嵌入式Linux驱动笔记(十三)------spi设备之RFID-rc522驱动

来源:互联网 发布:苹果音频编辑软件 编辑:程序博客网 时间:2024/05/20 06:26

你好!这里是风筝的博客,

欢迎和我一起交流。

上一节讲了spi框架:通俗易懂式分析了解spi框架
现在我们写一下spi的设备驱动程序, rc522是一款刷卡模块,类似于学校食堂的刷卡机。

以kernel4.8.17为例:
之前我们给mach-smdk2440.c文件添加了:

&s3c_device_spi0,

现在我要把rc522设备接在2440的spi1接口上,所以我们应该修改为:

&s3c_device_spi1,

然后我们看下spi-s3c24xx.c的Makefile,里面:

obj-$(CONFIG_SPI_S3C24XX)               += spi-s3c24xx-hw.ospi-s3c24xx-hw-y                        := spi-s3c24xx.o

所以我们在menuconfig里,选上:Device Drivers —>[*] SPI support —> < M> Samsung S3C24XX series SPI
之前是作为M模块的,现在 选上编进内核。
make uImage,启动内核之后,发现:

s3c2410-spi s3c2410-spi.1: No platform data supplied
s3c2410-spi: probe of s3c2410-spi.1 failed with error -2

发现,没有platform 信息,我们看下&s3c_device_spi1,发现里面确实没有platform 信息,所以我们需要自己添加进去,修改为:

#include <linux/spi/s3c24xx.h>/*by kite 2017.9.13*/#include <linux/gpio.h>/*by kite 2017.9.13*/#include <mach/gpio-samsung.h>/*by kite 2017.9.13*/#include <mach/regs-gpio.h>/*by kite 2017.9.13*/#include <plat/gpio-cfg.h>/*by kite 2017.9.13*/static void s3c24xx_spi_cs(struct s3c2410_spi_info *spi, int cs, int pol)/*by kite 2017.9.13*/{    s3c_gpio_cfgpin(cs, S3C_GPIO_OUTPUT);    gpio_set_value(cs, pol);}static struct s3c2410_spi_info spi1_info={/*by kite 2017.9.13*/    .num_cs = 0xff ,/*最大片选数*/    .bus_num = 1,       .set_cs = s3c24xx_spi_cs, };struct platform_device s3c_device_spi1 = {    .name       = "s3c2410-spi",    .id     = 1,    .num_resources  = ARRAY_SIZE(s3c_spi1_resource),    .resource   = s3c_spi1_resource,    .dev        = {        .dma_mask       = &samsung_device_dma_mask,        .coherent_dma_mask  = DMA_BIT_MASK(32),        .platform_data      = &spi1_info,/*by kite 2017.9.13*/    }};

然后启动Kernel,发现:s3c2410-spi.1:No clock for device
定位错误代码在drivers/spi/spi-s3c24xx.c文件里的s3c24xx_spi_probe函数里:

hw->clk = devm_clk_get(&pdev->dev, "spi");    if (IS_ERR(hw->clk)) {        dev_err(&pdev->dev, "No clock for device\n");        err = PTR_ERR(hw->clk);        goto err_no_pdata;    }

其中devm_clk_get函数是对clk_get函数进行了封装:

struct clk *devm_clk_get(struct device *dev, const char *id){    struct clk **ptr, *clk;    ptr = devres_alloc(devm_clk_release, sizeof(*ptr), GFP_KERNEL);    if (!ptr)        return ERR_PTR(-ENOMEM);    clk = clk_get(dev, id);    if (!IS_ERR(clk)) {        *ptr = clk;        devres_add(dev, ptr);    } else {        devres_free(ptr);    }    return clk;}

这里可以看下这篇文章:详解clock时钟(CCF)框架及clk_get函数
这里我们clk_get失败了,我们知道,clk_get函数是从一个时钟list链表中以字符id名称来查找一个时钟clk结构体并且返回的,所以我们时钟链表里还未添加spi时钟:
在drivers/clk/samsung/clk-s3c2410.c文件里:

struct samsung_clock_alias s3c2410_common_aliases[] __initdata = {    ALIAS(PCLK_I2C, "s3c2410-i2c.0", "i2c"),    ALIAS(PCLK_ADC, NULL, "adc"),    ALIAS(PCLK_RTC, NULL, "rtc"),    ALIAS(PCLK_PWM, NULL, "timers"),    ALIAS(HCLK_LCD, NULL, "lcd"),    ALIAS(HCLK_USBD, NULL, "usb-device"),    ALIAS(HCLK_USBH, NULL, "usb-host"),    ALIAS(UCLK, NULL, "usb-bus-host"),    ALIAS(UCLK, NULL, "usb-bus-gadget"),    ALIAS(ARMCLK, NULL, "armclk"),    ALIAS(UCLK, NULL, "uclk"),    ALIAS(HCLK, NULL, "hclk"),    ALIAS(MPLL, NULL, "mpll"),    ALIAS(FCLK, NULL, "fclk"),    ALIAS(PCLK, NULL, "watchdog"),    ALIAS(PCLK_SDI, NULL, "sdi"),    ALIAS(HCLK_NAND, NULL, "nand"),    ALIAS(PCLK_I2S, NULL, "iis"),    ALIAS(PCLK_I2C, NULL, "i2c"),};

在数组最后一行添加:

    ALIAS(PCLK_SPI, NULL, "spi"),/*add by kite*/

然后编译好内核,启动后还发现:

WARNING: CPU: 0 PID: 1 at drivers/clk/clk.c:652 clk_core_enable+0x98/0xa4

有个警告,我们需要在drivers/spi/spi-s3c24xx.c文件里的s3c24xx_spi_probe函数里,在:

hw->clk = devm_clk_get(&pdev->dev, "spi");    if (IS_ERR(hw->clk)) {        dev_err(&pdev->dev, "No clock for device\n");        err = PTR_ERR(hw->clk);        goto err_no_pdata;    }

后面加上两句:

if (clk_prepare_enable(hw->clk)) {        printk("spi: clock failed :\n");    }

因为:“名称中含有prepare、unprepare字符串的API是内核后来才加入的,过去只有clk_enable和clk_disable。只有clk_enable和clk_disable带来的问题是,有时候,某些硬件的enable/disable clk可能引起睡眠使得enable/disable不能在原子上下文进行。加上prepare后,把过去的clk_enable分解成不可在原子上下文调用的clk_prepare(该函数可能睡眠)和可以在原子上下文调用的clk_enable。而clk_prepare_enable则同时完成prepare和enable的工作,当然也只能在可能睡眠的上下文调用该API。”

这样,改好后编译,就能成功注册spi-master,顺利启动内核了!

因为还没弄好设备树,现在只好老老实实写platform_device设备了:
rc522_dev.c文件:

#include <linux/module.h>#include <linux/version.h>#include <linux/init.h>#include <linux/kernel.h>#include <linux/device.h>#include <linux/platform_device.h>#include <linux/spi/spi.h>#include <linux/irq.h>#include <linux/interrupt.h>#include <linux/jiffies.h>#include <linux/delay.h>#include <linux/io.h>#include <linux/gpio.h>#include <mach/regs-gpio.h>#include <plat/gpio-cfg.h>#include <mach/gpio-samsung.h>static struct spi_board_info spi_info_rc522[] = {    {         .modalias = "rc522",  /* 对应的spi_driver名字也是"rc522" */         .max_speed_hz = 8000000,   /* max spi clock (SCK) speed in HZ */         .bus_num = 1,     /* 接在SPI CONTROLLER 1 */         .mode    = SPI_MODE_0,         .chip_select   = S3C2410_GPF(2), /* oled_cs, 它的含义由spi_master确定 */            },};static int spi_info_rc522_init(void){    spi_register_board_info(spi_info_rc522, ARRAY_SIZE(spi_info_rc522));    return 0;}static int spi_info_rc522_exit(void){    //spi_unregister_device();    return 0;}module_init(spi_info_rc522_init);module_exit(spi_info_rc522_exit);MODULE_LICENSE("GPL");MODULE_AUTHOR("kite");/*modinfo rc522.ko*/MODULE_DESCRIPTION("A spi-rc522 Module for testing module ");MODULE_VERSION("V1.0");

里面就是注册spi_board_info板级设备信息,不过这里编写好后我发现会出个问题:

rc522_dev: Unknown symbol spi_register_board_info (err 0)
insmod: can’t insert ‘rc522_dev.ko’: unknown symbol in module or invalid parameter

也就是spi_register_board_info 函数没有导出内核符号到公共内核符号表,详情可以看这篇blog:http://blog.csdn.net/wuyongpeng0912/article/details/46739233。
所以我们在drivers/spi/spi.c文件里找到spi_register_board_info函数实现的地方,在后面加上一句:EXPORT_SYMBOL_GPL(spi_register_board_info);
重新编译即可。

然后继续看下platform_driver驱动:
rc522_drv.c文件:

编译好后又发现个问题,真是一波三折啊……

WARNING: CPU: 0 PID: 1037 at drivers/base/dd.c:347 driver_probe_device+0x114/0x318

同样是个警告,定位到drivers/base/dd.c文件里的really_probe里的一句:

WARN_ON(!list_empty(&dev->devres_head));

就是这里出了警告,WARN_ON是调用dump_stack,打印堆栈信息,只要list_empty返回0,也就是链表非空时,会warning打印堆栈。
我们看下s3c24xx_spi_probe函数有句:

hw->master->setup = s3c24xx_spi_setup;

s3c24xx_spi_setup函数里面有一句:

cs = devm_kzalloc(&spi->dev,                  sizeof(struct s3c24xx_spi_devstate),                  GFP_KERNEL);

devm_kzalloc函数里会加入 dev->devres_head的:

list_add_tail(&node->entry, &dev->devres_head);

所以这里,我们把devm_kzalloc修改为kzalloc即可:

        /*cs = devm_kzalloc(&spi->dev,                  sizeof(struct s3c24xx_spi_devstate),                  GFP_KERNEL);*/        cs = kzalloc(sizeof(struct s3c24xx_spi_devstate), GFP_KERNEL); /*by kite 2017.9.16*/

这里说下devm_kzalloc和kzalloc: devm_kzalloc()函数 和kzalloc()函数一样都是内核内存分配函数,但是devm_kzalloc()是跟设备(device)有关的,当设备(device)被detached或者驱动(driver)卸载(unloaded)时,内存会被自动释放。另外,当内存不在使用时,可以使用函数devm_kfree()释放。
而kzalloc()则需要手动释放(使用kfree()),但如果工程师检查不仔细,则有可能造成内存泄漏。

所以这里我们最好还要有kfree函数,如果你不打算释放spi_master的话,不写也没事。
在s3c24xx_spi_probe函数里,

hw->master->setup = s3c24xx_spi_setup;

下面添加一句:

hw->master->cleanup = s3c24xx_spi_cleanup;

同时实现s3c24xx_spi_cleanup函数:

static void s3c24xx_spi_cleanup(struct spi_device *spi)/*by kite 2017.9.16*/{    struct chip_data *chip = spi_get_ctldata(spi);    kfree(chip);    spi_set_ctldata(spi, NULL);    printk("spi_master has been rmmove ! \n");}

接下来就是rc522_drv.c文件:

#include <linux/init.h>#include <linux/fs.h>#include <linux/slab.h>#include <linux/module.h>#include <linux/kernel.h>#include <linux/device.h>#include <sound/core.h>#include <linux/spi/spi.h>#include <asm/uaccess.h>#include <linux/cdev.h>#include <mach/hardware.h>#include <mach/regs-gpio.h>#include <linux/gpio.h>#include <plat/gpio-cfg.h>#include <linux/delay.h>#include "rc522.h"#include <linux/gpio.h>#include <mach/regs-gpio.h>#include <plat/gpio-cfg.h>#include <mach/gpio-samsung.h>static volatile unsigned long *gpfcon;static volatile unsigned long *gpfdat;//f1#define SET_RC522RST *gpfdat |= (0x01<<(1));#define CLR_RC522RST *gpfdat &= ~(0x01<<(1));static struct spi_device *spi_dev;/* 1. 确定主设备号 */static int major;static struct cdev rc522_cdev;static struct class *cls;u8 ReadRawRC(u8   Address ){    unsigned char tx_buf[1];        unsigned char rx_buf[1];    tx_buf[0] = ((Address<<1)&0x7E)|0x80;//RC522 set    spi_write_then_read(spi_dev, tx_buf, 1, rx_buf, 1);    return rx_buf[0];}void WriteRawRC(u8   Address, u8   value){    u8   ucAddr[2];    ucAddr[0] = ((Address<<1)&0x7E);//RC522 set    ucAddr[1] = value;    spi_write(spi_dev, ucAddr, 2);}void ClearBitMask(u8   reg,u8   mask)  {    char   tmp = 0x0;    tmp = ReadRawRC(reg);    WriteRawRC(reg, tmp & ~mask);  // clear bit mask}void SetBitMask(u8   reg,u8   mask)  {    char   tmp = 0x0;    tmp = ReadRawRC(reg);    WriteRawRC(reg,tmp | mask);  // set bit mask}static int rc522_open(struct inode *inode, struct file *file)   {    u8   i;u8  Re=0;    printk("this is open \n");    /*复位*/    SET_RC522RST;    ndelay(10);    CLR_RC522RST;    ndelay(10);    SET_RC522RST;    ndelay(10);        WriteRawRC(CommandReg,PCD_RESETPHASE);    WriteRawRC(CommandReg,PCD_RESETPHASE);        ndelay(10);    WriteRawRC(ModeReg,0x3D);            //和Mifare卡通讯,CRC初始值0x6363    WriteRawRC(TReloadRegL,30);                   WriteRawRC(TReloadRegH,0);        WriteRawRC(TModeReg,0x8D);        WriteRawRC(TPrescalerReg,0x3E);     WriteRawRC(TxAutoReg,0x40);//必须要    /*关闭天线*/    ClearBitMask(TxControlReg, 0x03);//    mdelay(2);    /*开启天线*/    i = ReadRawRC(TxControlReg);     if (!(i & 0x03))        {            SetBitMask(TxControlReg, 0x03);        }    /*设置RC632的工作方式 */    ClearBitMask(Status2Reg,0x08);       WriteRawRC(ModeReg,0x3D);//3F       WriteRawRC(RxSelReg,0x86);//84       WriteRawRC(RFCfgReg,0x7F);   //4F    WriteRawRC(TReloadRegL,30);//tmoLength);// TReloadVal = 'h6a =tmoLength(dec)     WriteRawRC(TReloadRegH,0);       WriteRawRC(TModeReg,0x8D);    WriteRawRC(TPrescalerReg,0x3E);    ndelay(1000);       /*开启天线*/    i = ReadRawRC(TxControlReg);     if (!(i & 0x03))        {            SetBitMask(TxControlReg, 0x03);        }    return 0;}char PcdComMF522(u8   Command,                  u8 *pIn ,                  u8   InLenByte,                 u8 *pOut ,                  u8 *pOutLenBit){    char   status = MI_ERR;    u8   irqEn   = 0x00;    u8   waitFor = 0x00;    u8   lastBits;    u8   n;    u16   i;    switch (Command)    {        case PCD_AUTHENT:            irqEn   = 0x12;            waitFor = 0x10;            break;        case PCD_TRANSCEIVE:            irqEn   = 0x77;            waitFor = 0x30;            break;        default:            break;    }    WriteRawRC(ComIEnReg,irqEn|0x80);    ClearBitMask(ComIrqReg,0x80);   //清所有中断位    WriteRawRC(CommandReg,PCD_IDLE);    SetBitMask(FIFOLevelReg,0x80);      //清FIFO缓存    for (i=0; i<InLenByte; i++)    {   WriteRawRC(FIFODataReg, pIn [i]);    }    WriteRawRC(CommandReg, Command);          if (Command == PCD_TRANSCEIVE)    {    SetBitMask(BitFramingReg,0x80);  }  //开始传送    //i = 600;//根据时钟频率调整,操作M1卡最大等待时间25ms    i = 60;    do     {        n = ReadRawRC(ComIrqReg);        i--;mdelay(50);    }    while ((i!=0) && !(n&0x01) && !(n&waitFor));    ClearBitMask(BitFramingReg,0x80);    if (i!=0)    {            if(!(ReadRawRC(ErrorReg)&0x1B))        {            status = MI_OK;            if (n & irqEn & 0x01)            {   status = MI_NOTAGERR;   }            if (Command == PCD_TRANSCEIVE)            {                n = ReadRawRC(FIFOLevelReg);                lastBits = ReadRawRC(ControlReg) & 0x07;                if (lastBits)                {   *pOutLenBit = (n-1)*8 + lastBits;   }                else                {   *pOutLenBit = n*8;   }                if (n == 0)                {   n = 1;    }                if (n > MAXRLEN)                {   n = MAXRLEN;   }                for (i=0; i<n; i++)                {   pOut [i] = ReadRawRC(FIFODataReg);    }            }        }        else        {   status = MI_ERR;   }    }    SetBitMask(ControlReg,0x80);           // stop timer now    WriteRawRC(CommandReg,PCD_IDLE);     return status;}char PcdRequest(u8   req_code,u8 *pTagType){    char   status;      u8   unLen;    u8   ucComMF522Buf[MAXRLEN];     ClearBitMask(Status2Reg,0x08);    WriteRawRC(BitFramingReg,0x07);    SetBitMask(TxControlReg,0x03);    ucComMF522Buf[0] = req_code;    status = PcdComMF522(PCD_TRANSCEIVE,ucComMF522Buf,1,ucComMF522Buf,&unLen);    if ((status == MI_OK) && (unLen == 0x10))    {            *pTagType     = ucComMF522Buf[0];        *(pTagType+1) = ucComMF522Buf[1];    }    else    {          status = MI_ERR;      }    return status;}char PcdAnticoll(u8 *pSnr){    char   status;    u8   i,snr_check=0;    u8   unLen;    u8   ucComMF522Buf[MAXRLEN];       ClearBitMask(Status2Reg,0x08);    WriteRawRC(BitFramingReg,0x00);    ClearBitMask(CollReg,0x80);    ucComMF522Buf[0] = PICC_ANTICOLL1;    ucComMF522Buf[1] = 0x20;    status = PcdComMF522(PCD_TRANSCEIVE,ucComMF522Buf,2,ucComMF522Buf,&unLen);    if (status == MI_OK)    {        for (i=0; i<4; i++)        {               *(pSnr+i)  = ucComMF522Buf[i];            snr_check ^= ucComMF522Buf[i];        }        if (snr_check != ucComMF522Buf[i])        {              status = MI_ERR;            }    }    SetBitMask(CollReg,0x80);    return status;}static ssize_t rc522_read(struct file * file, char __user *buf, size_t count, loff_t *off){    u8 status;    u8 CT[2];//卡类型    u8 UID[4]; //卡号    status = PcdRequest(PICC_REQALL,CT);/*尋卡 输出为卡类型----CT卡类型*/    if(status==MI_OK)    {        printk(" find car ok \n");        status=MI_ERR;        status = PcdAnticoll(UID);/*防冲撞*/           if (status==MI_OK)//防衝撞成功        {            status=MI_ERR;              printk("The car id is %d%d%d%d \n" , UID[0],UID[1],UID[2],UID[3]);        }    }    else        printk("find car faid \n");    return 0;}static ssize_t rc522_write(struct file *file, const char __user *buf,size_t count, loff_t *ppos){    return 0;}static struct file_operations rc522_fops = {    .owner  = THIS_MODULE,    .open   = rc522_open,        .read   = rc522_read,     .write  = rc522_write,};static int spi_rc522_probe(struct spi_device *spi){    int res;    struct device *rc522_res;    dev_t devid;    s3c_gpio_cfgpin(S3C2410_GPG(2), S3C_GPIO_OUTPUT);//    spi_dev = spi;    /* 3. 告诉内核 */#if 0    major = register_chrdev(0, "hello", &hello_fops); /* (major,  0), (major, 1), ..., (major, 255)都对应hello_fops */#else /*仅仅是注册设备号*/    if (major) {        devid = MKDEV(major, 0);        register_chrdev_region(devid, 1, "rc522");  /* (major,0) 对应 pwm_fops, (major, 1~255)都不对应pwm_fops */    } else {        alloc_chrdev_region(&devid, 0, 1, "rc522"); /* (major,0) 对应 pwm_fops, (major, 1~255)都不对应pwm_fops */        major = MAJOR(devid);                         }    cdev_init(&rc522_cdev, &rc522_fops);    res=cdev_add(&rc522_cdev, devid, 1);    if(res)    {        printk("cdev_add failed\n");        unregister_chrdev_region(MKDEV(major, 0), 1);        return 0;    }#endif    cls = class_create(THIS_MODULE, "rc522");    rc522_res = device_create(cls, NULL, MKDEV(major, 0), NULL, "rc522"); /* /dev/xxx */    if (IS_ERR(rc522_res))     {        printk("device_create failed\n");        return 0;    }    gpfcon  = ioremap(0x56000050 , 8);    gpfdat  = gpfcon+1;    if (!gpfcon)    {        printk("ioremap failed\n");        return -EIO;    }    return 0;}static struct spi_driver spi_rc522_drv = {    .driver = {        .name   = "rc522",        .owner  = THIS_MODULE,    },    .probe      = spi_rc522_probe,    //.remove       = spi_rc522_remove,};static int spi_rc522_init(void){    return spi_register_driver(&spi_rc522_drv);}static void spi_rc522_exit(void){    spi_unregister_driver(&spi_rc522_drv);}module_init(spi_rc522_init);module_exit(spi_rc522_exit);MODULE_LICENSE("GPL");MODULE_AUTHOR("kite");/*modinfo my_keyboard.ko*/MODULE_DESCRIPTION("A spi-rc522 Module for testing module ");MODULE_VERSION("V1.0");

rc522.h:

#ifndef __RC522_H#define __RC522_H       ///////////////////////////////////////////////////////////////////////MF522命令字/////////////////////////////////////////////////////////////////////#define PCD_IDLE              0x00               //取消当前命令#define PCD_AUTHENT           0x0E               //验证密钥#define PCD_RECEIVE           0x08               //接收数据#define PCD_TRANSMIT          0x04               //发送数据#define PCD_TRANSCEIVE        0x0C               //发送并接收数据#define PCD_RESETPHASE        0x0F               //复位#define PCD_CALCCRC           0x03               //CRC计算///////////////////////////////////////////////////////////////////////Mifare_One卡片命令字/////////////////////////////////////////////////////////////////////#define PICC_REQIDL           0x26               //寻天线区内未进入休眠状态//读取完卡后还会再次读取#define PICC_REQALL           0x52               //寻天线区内全部卡//读取完卡后会等待卡离开开线作用范围,直到再次进入#define PICC_ANTICOLL1        0x93               //防冲撞#define PICC_ANTICOLL2        0x95               //防冲撞#define PICC_AUTHENT1A        0x60               //验证A密钥#define PICC_AUTHENT1B        0x61               //验证B密钥#define PICC_READ             0x30               //读块#define PICC_WRITE            0xA0               //写块#define PICC_DECREMENT        0xC0               //扣款#define PICC_INCREMENT        0xC1               //充值#define PICC_RESTORE          0xC2               //调块数据到缓冲区#define PICC_TRANSFER         0xB0               //保存缓冲区中数据#define PICC_HALT             0x50               //休眠///////////////////////////////////////////////////////////////////////MF522 FIFO长度定义/////////////////////////////////////////////////////////////////////#define DEF_FIFO_LENGTH       64                 //FIFO size=64byte#define MAXRLEN  18///////////////////////////////////////////////////////////////////////MF522寄存器定义/////////////////////////////////////////////////////////////////////// PAGE 0#define     RFU00                 0x00    #define     CommandReg            0x01    #define     ComIEnReg             0x02    #define     DivlEnReg             0x03    #define     ComIrqReg             0x04    #define     DivIrqReg             0x05#define     ErrorReg              0x06    #define     Status1Reg            0x07    #define     Status2Reg            0x08    #define     FIFODataReg           0x09#define     FIFOLevelReg          0x0A#define     WaterLevelReg         0x0B#define     ControlReg            0x0C#define     BitFramingReg         0x0D#define     CollReg               0x0E#define     RFU0F                 0x0F// PAGE 1     #define     RFU10                 0x10#define     ModeReg               0x11#define     TxModeReg             0x12#define     RxModeReg             0x13#define     TxControlReg          0x14#define     TxAutoReg             0x15#define     TxSelReg              0x16#define     RxSelReg              0x17#define     RxThresholdReg        0x18#define     DemodReg              0x19#define     RFU1A                 0x1A#define     RFU1B                 0x1B#define     MifareReg             0x1C#define     RFU1D                 0x1D#define     RFU1E                 0x1E#define     SerialSpeedReg        0x1F// PAGE 2    #define     RFU20                 0x20  #define     CRCResultRegM         0x21#define     CRCResultRegL         0x22#define     RFU23                 0x23#define     ModWidthReg           0x24#define     RFU25                 0x25#define     RFCfgReg              0x26#define     GsNReg                0x27#define     CWGsCfgReg            0x28#define     ModGsCfgReg           0x29#define     TModeReg              0x2A#define     TPrescalerReg         0x2B#define     TReloadRegH           0x2C#define     TReloadRegL           0x2D#define     TCounterValueRegH     0x2E#define     TCounterValueRegL     0x2F// PAGE 3      #define     RFU30                 0x30#define     TestSel1Reg           0x31#define     TestSel2Reg           0x32#define     TestPinEnReg          0x33#define     TestPinValueReg       0x34#define     TestBusReg            0x35#define     AutoTestReg           0x36#define     VersionReg            0x37#define     AnalogTestReg         0x38#define     TestDAC1Reg           0x39  #define     TestDAC2Reg           0x3A   #define     TestADCReg            0x3B   #define     RFU3C                 0x3C   #define     RFU3D                 0x3D   #define     RFU3E                 0x3E   #define     RFU3F                 0x3F///////////////////////////////////////////////////////////////////////和MF522通讯时返回的错误代码/////////////////////////////////////////////////////////////////////#define     MI_OK                 0#define     MI_NOTAGERR           (1)#define     MI_ERR                (2)#define SHAQU1  0X01#define KUAI4   0X04#define KUAI7   0X07#define REGCARD 0xa1#define CONSUME 0xa2#define READCARD    0xa3#define ADDMONEY    0xa4#endif 

这样,当我们cat rc522设备时,就会读出我们卡的id了

原创粉丝点击