当前位置: 首页 > news >正文

linux 驱动cc1101

cc110x.h

/*
 * File:   cc110x.h
 * Author: elinux
 *
 * Created on 2015年4月7日, 上午10:32
 */

#ifndef CC110X_H
#define    CC110X_H

#ifdef    __cplusplus
extern "C" {
#endif

#define     WRITE_BURST         0x40                        //连续写入
#define     READ_SINGLE         0x80                        //读  
#define     READ_BURST          0xC0                        //连续读  
#define     BYTES_IN_RXFIFO     0x7F                        //接收缓冲区的有效字节数  
#define     CRC_OK              0x80                        //CRC校验通过位标志  
#define CCxxx0_IOCFG2       0x00        // GDO2 output pin configuration  
#define CCxxx0_IOCFG1       0x01        // GDO1 output pin configuration  
#define CCxxx0_IOCFG0       0x02        // GDO0 output pin configuration  
#define CCxxx0_FIFOTHR      0x03        // RX FIFO and TX FIFO thresholds  
#define CCxxx0_SYNC1        0x04        // Sync word, high u8  
#define CCxxx0_SYNC0        0x05        // Sync word, low u8  
#define CCxxx0_PKTLEN       0x06        // Packet length  
#define CCxxx0_PKTCTRL1     0x07        // Packet automation control  
#define CCxxx0_PKTCTRL0     0x08        // Packet automation control  
#define CCxxx0_ADDR         0x09        // Device address  
#define CCxxx0_CHANNR       0x0A        // Channel number  
#define CCxxx0_FSCTRL1      0x0B        // Frequency synthesizer control  
#define CCxxx0_FSCTRL0      0x0C        // Frequency synthesizer control  
#define CCxxx0_FREQ2        0x0D        // Frequency control word, high u8  
#define CCxxx0_FREQ1        0x0E        // Frequency control word, middle u8  
#define CCxxx0_FREQ0        0x0F        // Frequency control word, low u8  
#define CCxxx0_MDMCFG4      0x10        // Modem configuration  
#define CCxxx0_MDMCFG3      0x11        // Modem configuration  
#define CCxxx0_MDMCFG2      0x12        // Modem configuration  
#define CCxxx0_MDMCFG1      0x13        // Modem configuration  
#define CCxxx0_MDMCFG0      0x14        // Modem configuration  
#define CCxxx0_DEVIATN      0x15        // Modem deviation setting  
#define CCxxx0_MCSM2        0x16        // Main Radio Control State Machine configuration  
#define CCxxx0_MCSM1        0x17        // Main Radio Control State Machine configuration  
#define CCxxx0_MCSM0        0x18        // Main Radio Control State Machine configuration  
#define CCxxx0_FOCCFG       0x19        // Frequency Offset Compensation configuration  
#define CCxxx0_BSCFG        0x1A        // Bit Synchronization configuration  
#define CCxxx0_AGCCTRL2     0x1B        // AGC control  
#define CCxxx0_AGCCTRL1     0x1C        // AGC control  
#define CCxxx0_AGCCTRL0     0x1D        // AGC control  
#define CCxxx0_WOREVT1      0x1E        // High u8 Event 0 timeout  
#define CCxxx0_WOREVT0      0x1F        // Low u8 Event 0 timeout  
#define CCxxx0_WORCTRL      0x20        // Wake On Radio control  
#define CCxxx0_FREND1       0x21        // Front end RX configuration  
#define CCxxx0_FREND0       0x22        // Front end TX configuration  
#define CCxxx0_FSCAL3       0x23        // Frequency synthesizer calibration  
#define CCxxx0_FSCAL2       0x24        // Frequency synthesizer calibration  
#define CCxxx0_FSCAL1       0x25        // Frequency synthesizer calibration  
#define CCxxx0_FSCAL0       0x26        // Frequency synthesizer calibration  
#define CCxxx0_RCCTRL1      0x27        // RC oscillator configuration  
#define CCxxx0_RCCTRL0      0x28        // RC oscillator configuration  
#define CCxxx0_FSTEST       0x29        // Frequency synthesizer calibration control  
#define CCxxx0_PTEST        0x2A        // Production test  
#define CCxxx0_AGCTEST      0x2B        // AGC test  
#define CCxxx0_TEST2        0x2C        // Various test settings  
#define CCxxx0_TEST1        0x2D        // Various test settings  
#define CCxxx0_TEST0        0x2E        // Various test settings  

    // Strobe commands  
#define CCxxx0_SRES         0x30        // Reset chip.  
#define CCxxx0_SFSTXON      0x31        // Enable and calibrate frequency synthesizer (if MCSM0.FS_AUTOCAL=1).  
    // If in RX/TX: Go to a wait state where only the synthesizer is  
    // running (for quick RX / TX turnaround).  
#define CCxxx0_SXOFF        0x32        // Turn off crystal oscillator.  
#define CCxxx0_SCAL         0x33        // Calibrate frequency synthesizer and turn it off  
    // (enables quick start).  
#define CCxxx0_SRX          0x34        // Enable RX. Perform calibration first if coming from IDLE and  
    // MCSM0.FS_AUTOCAL=1.  
#define CCxxx0_STX          0x35        // In IDLE state: Enable TX. Perform calibration first if  
    // MCSM0.FS_AUTOCAL=1. If in RX state and CCA is enabled:  
    // Only go to TX if channel is clear.  
#define CCxxx0_SIDLE        0x36        // Exit RX / TX, turn off frequency synthesizer and exit  
    // Wake-On-Radio mode if applicable.  
#define CCxxx0_SAFC         0x37        // Perform AFC adjustment of the frequency synthesizer  
#define CCxxx0_SWOR         0x38        // Start automatic RX polling sequence (Wake-on-Radio)  
#define CCxxx0_SPWD         0x39        // Enter power down mode when CSn goes high.  
#define CCxxx0_SFRX         0x3A        // Flush the RX FIFO buffer.  
#define CCxxx0_SFTX         0x3B        // Flush the TX FIFO buffer.  
#define CCxxx0_SWORRST      0x3C        // Reset real time clock.  
#define CCxxx0_SNOP         0x3D        // No operation. May be used to pad strobe commands to two  
    // u8s for simpler software.  

#define CCxxx0_PARTNUM      0x30  
#define CCxxx0_VERSION      0x31  
#define CCxxx0_FREQEST      0x32  
#define CCxxx0_LQI          0x33  
#define CCxxx0_RSSI         0x34  
#define CCxxx0_MARCSTATE    0x35  
#define CCxxx0_WORTIME1     0x36  
#define CCxxx0_WORTIME0     0x37  
#define CCxxx0_PKTSTATUS    0x38  
#define CCxxx0_VCO_VC_DAC   0x39  
#define CCxxx0_TXBYTES      0x3A  
#define CCxxx0_RXBYTES      0x3B  

#define CCxxx0_PATABLE      0x3E  

#define CCxxx0_TXFIFO       0x3F  
#define CCxxx0_RXFIFO       0x3F  
    
    #define CC1101_BUFLEN 16  


    // RF_SETTINGS is a data structure which contains all relevant CCxxx0 registers  

    typedef struct {
        u8 iocfg0; // GDO0 Output Pin Configuration  
        u8 fifothr; // RX FIFO and TX FIFO Thresholds  
        u8 pktctrl0; // Packet Automation Control  
        u8 fsctrl1; // Frequency Synthesizer Control  
        u8 freq2; // Frequency Control Word, High Byte  
        u8 freq1; // Frequency Control Word, Middle Byte  
        u8 freq0; // Frequency Control Word, Low Byte  
        u8 mdmcfg4; // Modem Configuration  
        u8 mdmcfg3; // Modem Configuration  
        u8 mdmcfg2; // Modem Configuration  
        u8 deviatn; // Modem Deviation Setting  
        u8 mcsm0; // Main Radio Control State Machine Configuration  
        u8 foccfg; // Frequency Offset Compensation Configuration  
        u8 worctrl; // Wake On Radio Control  
        u8 fscal3; // Frequency Synthesizer Calibration  
        u8 fscal2; // Frequency Synthesizer Calibration  
        u8 fscal1; // Frequency Synthesizer Calibration  
        u8 fscal0; // Frequency Synthesizer Calibration  
        u8 test2; // Various Test Settings  
        u8 test1; // Various Test Settings  
        u8 test0; // Various Test Settings  
    } RF_SETTINGS;
    
    /*
 * Some registers must be read back to modify.
 * To save time we cache them here in memory.
 */
struct cc110x_chip {
    struct spi_device     *spi;
            struct cdev cdev;
            dev_t devNo;
            int irqNo;
            int pin_rdy;
            wait_queue_head_t read_wait;
            volatile int rcv_flag;
            unsigned char cc1101_buf[CC1101_BUFLEN];
};

#ifdef    __cplusplus
}
#endif

#endif    /* CC110X_H */

 

cc110x.c

 

#include <linux/platform_device.h>
#include <linux/delay.h>
#include <linux/ioport.h>
#include <linux/device.h>
#include <linux/gpio.h>
#include <linux/spi/spi.h>
#include <linux/freezer.h>
#include <linux/workqueue.h>
#include <linux/export.h>
#include "cc110x.h"
#include <linux/irq.h>
#include <linux/timer.h>


//*****************************************************************************************  
//SpiTxRxByte(struct cc11xx_chip *chip, u8 dat)
//*****************************************************************************************  

int SpiTxRxByte(struct cc11xx_chip *chip, u8 dat) {
    
    struct spi_message m;
    struct spi_transfer xfer;

    u8 w, r;
    int rc;

    spi_message_init(&m);

    memset(&xfer, 0, sizeof (xfer));

    w = dat;

    xfer.tx_buf = &w;
    xfer.rx_buf = &r;
    xfer.bits_per_word = 8;
    xfer.len = 1;
    spi_message_add_tail(&xfer, &m);

    rc = spi_sync(chip->spi, &m);

    if (rc) {
        dev_err(&chip->spi->dev, "VK32xx  write  error\n");
        return -EIO;
    }

    return r;
    
}

//*****************************************************************************************  
//RESET_CC1100
//*****************************************************************************************  

void RESET_CC1100(struct cc11xx_chip *chip) {
    
    SpiTxRxByte(chip, CCxxx0_SRES); //
}

//*****************************************************************************************  
//void halSpiWriteReg(INT8U addr, INT8U value)  
//*****************************************************************************************  

int halSpiWriteReg(struct cc11xx_chip *chip, u8 addr, u8 val) {
    struct spi_message m;
    struct spi_transfer xfer;

    u8 w[2];
    int rc;

    spi_message_init(&m);

    memset(&xfer, 0, sizeof (xfer));

    w[0] = addr;
    w[1] = val;

    xfer.tx_buf = &w[0];
     xfer.bits_per_word = 8;
   
    xfer.len = 2;
    spi_message_add_tail(&xfer, &m);

    rc = spi_sync(chip->spi, &m);

    if (rc) {
        dev_err(&chip->spi->dev, "cc1101  write  error\n");
        return -EIO;
    }

    return 0;
}

//*****************************************************************************************  
//halSpiWriteBurstReg
//*****************************************************************************************  

int halSpiWriteBurstReg(struct cc11xx_chip *chip, u8 addr, u8 *buffer, u8 cnt) {
    
    struct spi_message m;
    struct spi_transfer xfer;

    u8 w[cnt];
    int rc;

    spi_message_init(&m);

    memset(&xfer, 0, sizeof (xfer));
    
    for (i = 0; i < cnt; i++) {
        w[i] = buffer[i];
    }

    SpiTxRxByte(chip, addr | WRITE_BURST);
 
    xfer.tx_buf = &w[0];
     xfer.bits_per_word = 8;
    xfer.len = cnt;
    spi_message_add_tail(&xfer, &m);

    rc = spi_sync(chip->spi, &m);
    
    if (rc) {
        dev_err(&chip->spi->dev, "cc1101  write  burst mode error\n");
        return -EIO;
    }
    
    return 0;
}

//*****************************************************************************************  
//halSpiStrobe
//*****************************************************************************************  

void halSpiStrobe(struct cc11xx_chip *chip,u8 strobe) {
 
    SpiTxRxByte(chip,strobe); //

}

//*****************************************************************************************  
//halSpiReadReg
//*****************************************************************************************  

u8 halSpiReadReg(struct cc11xx_chip *chip, u8 addr) {
 
    SpiTxRxByte(chip, addr | READ_SINGLE);
    return SpiTxRxByte(chip, 0);
}


//*****************************************************************************************  
//halSpiReadBurstReg
//*****************************************************************************************  

void halSpiReadBurstReg(struct cc11xx_chip *chip,u8 addr, u8 *buffer, u8 cnt) {
    struct spi_message m;
    struct spi_transfer xfer;

    u8 r[cnt],i;
    
    SpiTxRxByte(chip, addr | READ_BURST);
    
     spi_message_init(&m);
     
     for(i =0 ;i < cnt; i++)
            r[i]  = 0x00;
     
    memset(&xfer, 0, sizeof (xfer));
 
    xfer.rx_buf = &r[0];
     xfer.bits_per_word = 8;
    xfer.len = cnt;
    spi_message_add_tail(&xfer, &m);

    rc = spi_sync(chip->spi, &m);
    
    if (rc) {
        dev_err(&chip->spi->dev, "cc110x  write  error\n");
        return -EIO;
    }
    
     for (i = 0; i < cnt; i++) {
        buffer[i] = r[i];
    }
   
    return 0;
    
}


//*****************************************************************************************  
//u8 halSpiReadReg(INT8U addr)  
//*****************************************************************************************  

u8  halSpiReadStatus(struct cc11xx_chip *chip, u8 addr) {
    
    SpiTxRxByte(chip, addr | READ_BURST);
    return SpiTxRxByte(chip, 0);
 
}
//*****************************************************************************************  
//oid halRfWriteRfSettings(RF_SETTINGS *pRfSettings)  
//*****************************************************************************************  

void halRfWriteRfSettings(struct cc11xx_chip *chip) {
    //*******************************rfSettingsSmart RF***********************************//  
    //*******************************Low data rate----2.4kbaud**************************************//  
    //*******************************Carrier frequency-----433.99MHz********************************//  
    RF_SETTINGS rfSettings = {
        0x06, // IOCFG0        GDO0 Output Pin Configuration  
        0x47, // FIFOTHR       RX FIFO and TX FIFO Thresholds  
        0x05, // PKTCTRL0      Packet Automation Control  
        0x06, // FSCTRL1       Frequency Synthesizer Control  
        0x10, // FREQ2         Frequency Control Word, High Byte  
        0xB1, // FREQ1         Frequency Control Word, Middle Byte  
        0x3B, // FREQ0         Frequency Control Word, Low Byte  
        0xF6, // MDMCFG4       Modem Configuration  
        0x83, // MDMCFG3       Modem Configuration  
        0x13, // MDMCFG2       Modem Configuration  
        0x15, // DEVIATN       Modem Deviation Setting  
        0x18, // MCSM0         Main Radio Control State Machine Configuration  
        0x16, // FOCCFG        Frequency Offset Compensation Configuration  
        0xFB, // WORCTRL       Wake On Radio Control  
        0xE9, // FSCAL3        Frequency Synthesizer Calibration  
        0x2A, // FSCAL2        Frequency Synthesizer Calibration  
        0x00, // FSCAL1        Frequency Synthesizer Calibration  
        0x1F, // FSCAL0        Frequency Synthesizer Calibration  
        0x81, // TEST2         Various Test Settings  
        0x35, // TEST1         Various Test Settings  
        0x09, // TEST0         Various Test Settings  
    };

    halSpiWriteReg(chip, CCxxx0_IOCFG0, rfSettings.iocfg0);
    halSpiWriteReg(chip, CCxxx0_FIFOTHR, rfSettings.fifothr);
    halSpiWriteReg(chip, CCxxx0_PKTCTRL0, rfSettings.pktctrl0);
    halSpiWriteReg(chip, CCxxx0_FSCTRL1, rfSettings.fsctrl1);
    halSpiWriteReg(chip, CCxxx0_FREQ2, rfSettings.freq2);
    halSpiWriteReg(chip, CCxxx0_FREQ1, rfSettings.freq1);
    halSpiWriteReg(chip, CCxxx0_FREQ0, rfSettings.freq0);
    halSpiWriteReg(chip, CCxxx0_MDMCFG4, rfSettings.mdmcfg4);
    halSpiWriteReg(chip,CCxxx0_MDMCFG3, rfSettings.mdmcfg3);
    halSpiWriteReg(chip, CCxxx0_MDMCFG2, rfSettings.mdmcfg2);
    halSpiWriteReg(chip, CCxxx0_DEVIATN, rfSettings.deviatn);
    halSpiWriteReg(chip, CCxxx0_MCSM0, rfSettings.mcsm0);
    halSpiWriteReg(chip, CCxxx0_FOCCFG, rfSettings.foccfg);
    halSpiWriteReg(chip, CCxxx0_WORCTRL, rfSettings.worctrl);
    halSpiWriteReg(chip, CCxxx0_FSCAL3, rfSettings.fscal3);
    halSpiWriteReg(chip, CCxxx0_FSCAL2, rfSettings.fscal2);
    halSpiWriteReg(chip, CCxxx0_FSCAL1, rfSettings.fscal1);
    halSpiWriteReg(chip, CCxxx0_FSCAL0, rfSettings.fscal0);
    halSpiWriteReg(chip, CCxxx0_TEST2, rfSettings.test2);
    halSpiWriteReg(chip, CCxxx0_TEST1, rfSettings.test1);
    halSpiWriteReg(chip, CCxxx0_TEST0, rfSettings.test0);
}
//*****************************************************************************************  
//halRfSendPacket
//*****************************************************************************************  

void halRfSendPacket(struct cc11xx_chip *chip, u8 *txBuffer, u8 size) {
    halSpiStrobe(chip,  CCxxx0_SIDLE);
    halSpiStrobe(chip,  CCxxx0_STX);
    halSpiWriteReg(chip, CCxxx0_TXFIFO, size);
    halSpiWriteBurstReg(chip, CCxxx0_TXFIFO, txBuffer, size);

    // Wait for GDO0 to be set -> sync transmitted  
    while (!gpio_get_value(chip->pin_rdy));
    // Wait for GDO0 to be cleared -> end of packet  
    while (gpio_get_value(chip->pin_rdy));
    halSpiStrobe(chip, CCxxx0_SFTX);
    halSpiStrobe(chip, CCxxx0_SIDLE);
    halSpiStrobe(chip, CCxxx0_SRX);
}

//************************************************************************************************//  
//halRfReceivePacket
//***********************************************************************************************//  

u8 halRfReceivePacket(struct cc11xx_chip *chip,u8 *rxBuffer, u8 *length) {
    u8 status[2];
    u8 packetLength;
    u8 i = (*length)*4;

    halSpiStrobe(chip,CCxxx0_SIDLE);
    halSpiStrobe(chip,CCxxx0_SRX); //
    udelay(20);
    while (gpio_get_value(chip->pin_rdy)) {
        udelay(20);
        --i;
        if (i < 1)
            return 0;
    }
    if ((halSpiReadStatus(chip,CCxxx0_RXBYTES) & BYTES_IN_RXFIFO))
    {
        packetLength = halSpiReadReg(chip,CCxxx0_RXFIFO);
        if (packetLength <= *length) //
        {
            halSpiReadBurstReg(chip,CCxxx0_RXFIFO, rxBuffer, packetLength); //
            *length = packetLength; //

            // Read the 2 appended status bytes (status[0] = RSSI, status[1] = LQI)  
            halSpiReadBurstReg(chip,CCxxx0_RXFIFO, status, 2);
            halSpiStrobe(chip,CCxxx0_SFRX);
            return (status[1] & CRC_OK);
        }
        else {
            *length = packetLength;
            halSpiStrobe(chip,CCxxx0_SFRX); //
            return 0;
        }
    }
    else
        return 0;
}

/*
 **************************************************************************************
 *cc1101_rcv_interrupt(int irq, void *dev_id)
 **************************************************************************************
  */

static irqreturn_t cc1101_rcv_interrupt(int irq, void *dev_id) {
   
    struct cc110x_chip *chip = (struct cc110x_chip *)dev_id ;
    u8 count = CC1101_BUFLEN;
    int ret;
    
    printk(KERN_DEBUG "cc1101 handle interrupt!\n");

    ret = halRfReceivePacket(chip, chip->cc1101_buf, &count);
    if (0 != ret) {
        
        printk(KERN_DEBUG "cc1101 receiving .... start\n");
        printk(KERN_DEBUG "cc1101 receiving .... end\n");
        printk(KERN_DEBUG "cc1101 receiving %d bytes(s):%s\n", count, chip->cc1101_buf);
        
        chip->rcv_flag = 1;
        wake_up_interruptible(&chip->read_wait);
    }

    return IRQ_RETVAL(IRQ_HANDLED);
}

/*cc1101_open*/
int cc1101_open(struct inode *inode, struct file *filp) {
    struct cc110x_chip *chip;
    int ret;
    
    chip = container_of(inode->i_cdev, struct cc110x_chip, cdev);
    
    filp->private_data = chip;

    ret = request_irq(chip->irq, cc1101_rcv_interrupt,
            IRQ_TYPE_EDGE_FALLING,
            "cc1101",
            (void *) chip);
    
    if (ret) {
        printk(KERN_DEBUG "request_irq error!\n");
        return -EBUSY;
    }
    
    return 0;
}

/*写函数*/
static ssize_t cc1101_write(struct file *filp, const char __user *buf, size_t size, loff_t *ppos) {
    struct cc110x_chip *chip = filp->private_data;
    unsigned int count = size;
    int ret = 0;
 
    if (CC1101_BUFLEN != size) {
        printk(KERN_DEBUG "cc1101 write wrong len:%d\n", size);
        return -ENOMEM;
    }

    if (copy_from_user(chip->cc1101_buf, buf, count))
        ret = -EFAULT;
    else {
        ret = count;
        printk(KERN_DEBUG "kernel-space: cc1101 written %d bytes(s):%s\n",
                            count, chip->cc1101_buf);  
    }

    /* CC1101 */
    printk(KERN_DEBUG "kernel-space: cc1101 sending .... start\n");  
    halRfSendPacket(chip, chip->cc1101_buf, count);
    printk(KERN_DEBUG "kernel-space: cc1101 sending .... end\n");  

    return ret;
}

/* cc1101_waitqueue_read */
static ssize_t cc1101_waitqueue_read(struct file *filp, char __user *buf, size_t size, loff_t *ppos) {
    struct cc110x_chip *chip = filp->private_data;
    unsigned int count = size;
    int ret = 0;
    DECLARE_WAITQUEUE(wait, current);

    if (CC1101_BUFLEN != count) {
        printk(KERN_DEBUG "kernel-space: cc1101 read wrong len:%d\n", count);
        return -ENOMEM;
    }

    add_wait_queue(&chip->read_wait, &wait);

    if (0 == chip->rcv_flag) {
        if (filp->f_flags & O_NONBLOCK) {
            ret = -EAGAIN;
            goto out;
        }

        __set_current_state(TASK_INTERRUPTIBLE);
        schedule();
        if (signal_pending(current)) {
            ret = -ERESTARTSYS;
            goto out;
        }
    }

    /* 内核空间->用户空间 */
    copy_to_user(buf, chip->cc1101_buf, count);

    ret = count;

out:
    remove_wait_queue(&chip->read_wait, &wait);

    set_current_state(TASK_RUNNING);
    chip->rcv_flag = 0;
    return ret;
}

/*
 * poll
 */
static unsigned int cc1101_poll(struct file *filp, poll_table *wait) {
     struct cc110x_chip *chip = filp->private_data;
    unsigned int mask = 0;

    poll_wait(filp, &chip->read_wait, wait);

    if (1 == chip->rcv_flag) {
        mask |= POLLIN | POLLRDNORM;
        printk(KERN_DEBUG "kernel-space: cc1101_poll rcv_flag = 1!\n");
    }

    return mask;
}

static int cc1101_close(struct inode *inode, struct file *filp) {
    struct cc110x_chip *chip = filp->private_data;
    
    free_irq(chip->irq, chip);

    printk("kernel-space: cc1101_close!\n");
    return 0;
}

struct file_operations cc1101_fops = {
    .owner = THIS_MODULE,
    .open = cc1101_open,
    .release = cc1101_close,
    .write = cc1101_write,
    .read = cc1101_waitqueue_read,
    .poll = cc1101_poll,
};

//cc1101_setup
static int cc1101_setup(struct cc11xx_chip *chip) {
    
    u8 tbl[8] = {0x60, 0x60, 0x60, 0x60, 0x60, 0x60, 0x60, 0x60};
    
    RESET_CC1100(chip);
    
    halRfWriteRfSettings(chip);
    
    halSpiWriteBurstReg(chip, CCxxx0_PATABLE, tbl, 8);

    return 0;
}

/*cc1101_probe
*
*/

struct class *cc1101_class;

static int __devinit cc1101_probe(struct spi_device *spi) {
    struct cc110x_chip *chip;
    int ret;

    chip = kzalloc(sizeof (struct vk32xx_chip), GFP_KERNEL);
    if (!chip)
        return -ENOMEM;

    spi_set_drvdata(spi, chip);
    chip->spi = spi;
    chip->irqNo = spi->irq;

    spi_setup(spi);

    ret = alloc_chrdev_region(&chip->devNo, 0, 1, "cc1101");
    if (ret)
        return  ret;

    init_waitqueue_head(&chip->read_wait);
    cdev_init(&chip->cdev, &cc1101_fops);

    chip->cdev.owner = THIS_MODULE;
    chip->cdev.ops = &cc1101_fops;

    ret = cdev_add(&chip->cdev, chip->devNo, 1);
    
    if(ret)
    {
         unregister_chrdev_region(chip->devNo, 1);   
         return ret;
    }
    
     cc1101_class = class_create(THIS_MODULE, "cc1101");
        
     device_create(cc1101_class,
                  NULL,
                  chip->devNo,      
                  NULL,
                  "%s",
                  "cc1101");
     
     //setup cc1101
    cc1101_setup(chip);
    
     printk(KERN_DEBUG "cc1101 init success!\n");  

    return 0;  

}

static int __devexit cc1101_remove(struct spi_device *spi) {
    struct cc110x_chip *chip = spi_get_drvdata(spi);

    if (chip == NULL) {
        return -ENODEV;
    }
    
    unregister_chrdev_region(chip->devNo, 1);
    cdev_del(&chip->cdev);   
    
    device_destroy(cc1101_class, chip->devNo);  
    
    class_destroy(cc1101_class);
    
    kfree(chip);
    
   spi_set_drvdata(spi, NULL);
   
    return 0;
}

/* Spi driver data */
static struct spi_driver cc1101_spi_driver = {
    .driver =
    {
        .name = "cc1101",
        .bus = &spi_bus_type,
        .owner = THIS_MODULE,
    },
    .probe = cc1101_probe,
    .remove = __devexit_p(cc1101_remove),
};

static int __init cc1101_init(void) {
    return spi_register_driver(&cc11xx_spi_driver);
}

static void __exit cc1101_exit(void) {
      spi_unregister_driver(&cc11xx_spi_driver);
}

module_init(cc1101_init);
module_exit(cc1101_exit);

MODULE_LICENSE("GPL");
MODULE_AUTHOR("hawk hunter");
MODULE_DESCRIPTION("cc1101 control");

 

相关文章:

  • (Repost) Getting Genode with TrustZone on the i.MX
  • [数分提高]2014-2015-2第5教学周第1次课
  • 【每天进步一点】毒药和老鼠的研究
  • linux下安装Python-2.7.9
  • 一条简单的sql在11g和12c中的不同
  • 关于mongodb在mac下的手动安装,非homwbrew安装(小白请进)
  • EcShop二次开发学习方法
  • 国庆后的特训
  • 梦游记-梦中游记
  • PHP-内核学习(一、变量)
  • 【cs229-Lecture18】线性二次型调节控制
  • 转:windows 下 netsh 实现 端口映射(端口转发)
  • assign, retain, weak, strong, copy,unsafe_unretain
  • java 反射
  • MSF溢出实战教程
  • 【159天】尚学堂高琪Java300集视频精华笔记(128)
  • 【JavaScript】通过闭包创建具有私有属性的实例对象
  • AzureCon上微软宣布了哪些容器相关的重磅消息
  • Debian下无root权限使用Python访问Oracle
  • Git的一些常用操作
  • HTTP传输编码增加了传输量,只为解决这一个问题 | 实用 HTTP
  • javascript从右向左截取指定位数字符的3种方法
  • js写一个简单的选项卡
  • python 装饰器(一)
  • SegmentFault 社区上线小程序开发频道,助力小程序开发者生态
  • Webpack入门之遇到的那些坑,系列示例Demo
  • 编写符合Python风格的对象
  • 读懂package.json -- 依赖管理
  • 精彩代码 vue.js
  • 七牛云 DV OV EV SSL 证书上线,限时折扣低至 6.75 折!
  • 浅析微信支付:申请退款、退款回调接口、查询退款
  • 使用Envoy 作Sidecar Proxy的微服务模式-4.Prometheus的指标收集
  • #QT(串口助手-界面)
  • #我与Java虚拟机的故事#连载18:JAVA成长之路
  • $分析了六十多年间100万字的政府工作报告,我看到了这样的变迁
  • (笔试题)分解质因式
  • (二)构建dubbo分布式平台-平台功能导图
  • (附源码)springboot金融新闻信息服务系统 毕业设计651450
  • (附源码)ssm高校社团管理系统 毕业设计 234162
  • (更新)A股上市公司华证ESG评级得分稳健性校验ESG得分年均值中位数(2009-2023年.12)
  • (经验分享)作为一名普通本科计算机专业学生,我大学四年到底走了多少弯路
  • (十) 初识 Docker file
  • (一)ClickHouse 中的 `MaterializedMySQL` 数据库引擎的使用方法、设置、特性和限制。
  • (转)chrome浏览器收藏夹(书签)的导出与导入
  • (转)VC++中ondraw在什么时候调用的
  • .net core 客户端缓存、服务器端响应缓存、服务器内存缓存
  • .NET Core、DNX、DNU、DNVM、MVC6学习资料
  • .Net MVC + EF搭建学生管理系统
  • .NET 解决重复提交问题
  • .net6解除文件上传限制。Multipart body length limit 16384 exceeded
  • .net6使用Sejil可视化日志
  • [ C++ ] STL_vector -- 迭代器失效问题
  • [AutoSar]BSW_Memory_Stack_004 创建一个简单NV block并调试
  • [CF703D]Mishka and Interesting sum/[BZOJ5476]位运算
  • [ffmpeg] av_opt_set 解析