Linux设备驱动开发-SPI驱动开发详解(包含设备树处理详细过程)
基础知识及 SPI 相关结构体介绍
引脚:MISO(master 输入,slave 输出),MOSI(master 输出,slave 输入),片选引脚,SCK(时钟)
控制寄存器:可以设置这CPOL 和 CPHA两个参数,CPOL 代表 SCK 初始电平,CPHA 代表相位(第一/第二个时钟沿采集数据),
SPI 状态寄存器:分辨数据是否发送完了,使能中断
波特率寄存器:设置 SCK 频率
数据寄存器:连接移位器收发数据
驱动程序编写方法:Master 和 slave 都需要驱动程序,采用总线设备驱动模型编写,设备树->spi_dev,驱动程序->spi_driver
/ include / linux / spi / spi.h中定义了 spi_master,里面有 transfer 函数指针
/* Compatibility layer */
#define spi_master spi_controllerstruct spi_controller {struct device dev;struct list_head list;/* other than negative (== assign one dynamically), bus_num is fully* board-specific. usually that simplifies to being SOC-specific.* example: one SOC has three SPI controllers, numbered 0..2,* and one board's schematics might show it using SPI-2. software* would normally use bus_num=2 for that controller.*/s16 bus_num;/* chipselects will be integral to many controllers; some others* might use board-specific GPIOs.*/u16 num_chipselect;/* some SPI controllers pose alignment requirements on DMAable* buffers; let protocol drivers know about these requirements.*/u16 dma_alignment;/* spi_device.mode flags understood by this controller driver */u32 mode_bits;/* spi_device.mode flags override flags for this controller */u32 buswidth_override_bits;/* bitmask of supported bits_per_word for transfers */u32 bits_per_word_mask;
#define SPI_BPW_MASK(bits) BIT((bits) - 1)
#define SPI_BPW_RANGE_MASK(min, max) GENMASK((max) - 1, (min) - 1)/* limits on transfer speed */u32 min_speed_hz;u32 max_speed_hz;/* other constraints relevant to this driver */u16 flags;
#define SPI_CONTROLLER_HALF_DUPLEX BIT(0) /* can't do full duplex */
#define SPI_CONTROLLER_NO_RX BIT(1) /* can't do buffer read */
#define SPI_CONTROLLER_NO_TX BIT(2) /* can't do buffer write */
#define SPI_CONTROLLER_MUST_RX BIT(3) /* requires rx */
#define SPI_CONTROLLER_MUST_TX BIT(4) /* requires tx */#define SPI_MASTER_GPIO_SS BIT(5) /* GPIO CS must select slave *//* flag indicating if the allocation of this struct is devres-managed */bool devm_allocated;/* flag indicating this is an SPI slave controller */bool slave;/** on some hardware transfer / message size may be constrained* the limit may depend on device transfer settings*/size_t (*max_transfer_size)(struct spi_device *spi);size_t (*max_message_size)(struct spi_device *spi);/* I/O mutex */struct mutex io_mutex;/* Used to avoid adding the same CS twice */struct mutex add_lock;/* lock and mutex for SPI bus locking */spinlock_t bus_lock_spinlock;struct mutex bus_lock_mutex;/* flag indicating that the SPI bus is locked for exclusive use */bool bus_lock_flag;/* Setup mode and clock, etc (spi driver may call many times).** IMPORTANT: this may be called when transfers to another* device are active. DO NOT UPDATE SHARED REGISTERS in ways* which could break those transfers.*/int (*setup)(struct spi_device *spi);/** set_cs_timing() method is for SPI controllers that supports* configuring CS timing.** This hook allows SPI client drivers to request SPI controllers* to configure specific CS timing through spi_set_cs_timing() after* spi_setup().*/int (*set_cs_timing)(struct spi_device *spi);/* bidirectional bulk transfers** + The transfer() method may not sleep; its main role is* just to add the message to the queue.* + For now there's no remove-from-queue operation, or* any other request management* + To a given spi_device, message queueing is pure fifo** + The controller's main job is to process its message queue,* selecting a chip (for masters), then transferring data* + If there are multiple spi_device children, the i/o queue* arbitration algorithm is unspecified (round robin, fifo,* priority, reservations, preemption, etc)** + Chipselect stays active during the entire message* (unless modified by spi_transfer.cs_change != 0).* + The message transfers use clock and SPI mode parameters* previously established by setup() for this device*/int (*transfer)(struct spi_device *spi,struct spi_message *mesg);/* called on release() to free memory provided by spi_controller */void (*cleanup)(struct spi_device *spi);/** Used to enable core support for DMA handling, if can_dma()* exists and returns true then the transfer will be mapped* prior to transfer_one() being called. The driver should* not modify or store xfer and dma_tx and dma_rx must be set* while the device is prepared.*/bool (*can_dma)(struct spi_controller *ctlr,struct spi_device *spi,struct spi_transfer *xfer);struct device *dma_map_dev;/** These hooks are for drivers that want to use the generic* controller transfer queueing mechanism. If these are used, the* transfer() function above must NOT be specified by the driver.* Over time we expect SPI drivers to be phased over to this API.*/bool queued;struct kthread_worker *kworker;struct kthread_work pump_messages;spinlock_t queue_lock;struct list_head queue;struct spi_message *cur_msg;bool idling;bool busy;bool running;bool rt;bool auto_runtime_pm;bool cur_msg_prepared;bool cur_msg_mapped;char last_cs;bool last_cs_mode_high;bool fallback;struct completion xfer_completion;size_t max_dma_len;int (*prepare_transfer_hardware)(struct spi_controller *ctlr);int (*transfer_one_message)(struct spi_controller *ctlr,struct spi_message *mesg);int (*unprepare_transfer_hardware)(struct spi_controller *ctlr);int (*prepare_message)(struct spi_controller *ctlr,struct spi_message *message);int (*unprepare_message)(struct spi_controller *ctlr,struct spi_message *message);int (*slave_abort)(struct spi_controller *ctlr);/** These hooks are for drivers that use a generic implementation* of transfer_one_message() provided by the core.*/void (*set_cs)(struct spi_device *spi, bool enable);int (*transfer_one)(struct spi_controller *ctlr, struct spi_device *spi,struct spi_transfer *transfer);void (*handle_err)(struct spi_controller *ctlr,struct spi_message *message);/* Optimized handlers for SPI memory-like operations. */const struct spi_controller_mem_ops *mem_ops;const struct spi_controller_mem_caps *mem_caps;/* gpio chip select */struct gpio_desc **cs_gpiods;bool use_gpio_descriptors;s8 unused_native_cs;s8 max_native_cs;/* statistics */struct spi_statistics statistics;/* DMA channels for use with core dmaengine helpers */struct dma_chan *dma_tx;struct dma_chan *dma_rx;/* dummy data for full duplex devices */void *dummy_rx;void *dummy_tx;int (*fw_translate_cs)(struct spi_controller *ctlr, unsigned cs);/** Driver sets this field to indicate it is able to snapshot SPI* transfers (needed e.g. for reading the time of POSIX clocks)*/bool ptp_sts_supported;/* Interrupt enable state during PTP system timestamping */unsigned long irq_flags;
};
spi_device 结构体,可以看到这里结构体里面包含spi_controller,由设备树转换得到,其中bits_per_word 是每次传输的位数
struct spi_device {struct device dev;struct spi_controller *controller;struct spi_controller *master; /* compatibility layer */u32 max_speed_hz;u8 chip_select;u8 bits_per_word;bool rt;
#define SPI_NO_TX BIT(31) /* no transmit wire */
#define SPI_NO_RX BIT(30) /* no receive wire *//** All bits defined above should be covered by SPI_MODE_KERNEL_MASK.* The SPI_MODE_KERNEL_MASK has the SPI_MODE_USER_MASK counterpart,* which is defined in 'include/uapi/linux/spi/spi.h'.* The bits defined here are from bit 31 downwards, while in* SPI_MODE_USER_MASK are from 0 upwards.* These bits must not overlap. A static assert check should make sure of that.* If adding extra bits, make sure to decrease the bit index below as well.*/
#define SPI_MODE_KERNEL_MASK (~(BIT(30) - 1))u32 mode;int irq;void *controller_state;void *controller_data;char modalias[SPI_NAME_SIZE];const char *driver_override;struct gpio_desc *cs_gpiod; /* chip select gpio desc */struct spi_delay word_delay; /* inter-word delay *//* CS delays */struct spi_delay cs_setup;struct spi_delay cs_hold;struct spi_delay cs_inactive;/* the statistics */struct spi_statistics statistics;/** likely need more hooks for more protocol options affecting how* the controller talks to each chip, like:* - memory packing (12 bit samples into low bits, others zeroed)* - priority* - chipselect delays* - ...*/
};
spi_driver 结构体
struct spi_driver {const struct spi_device_id *id_table;int (*probe)(struct spi_device *spi);void (*remove)(struct spi_device *spi);void (*shutdown)(struct spi_device *spi);struct device_driver driver;
};
设备树结构:
spi{
spi master 配置(address-cell,size-cell,reg,interrupts,interrupt-parent,cs-gpios,compatible,spi-cpol,spi-cpha......)
slave{spi_device}
slave{spi_device}
}
设备树处理过程
首先根据spi 的compatible 属性找到 master 驱动,然后由 master 驱动解析子节点
看看内核的处理过程,设备树匹配之后 调用 probe 函数
/ drivers / spi / spi-gpio.c
static struct platform_driver spi_gpio_driver = {.driver = {.name = DRIVER_NAME,.of_match_table = of_match_ptr(spi_gpio_dt_ids),},.probe = spi_gpio_probe,
};
module_platform_driver(spi_gpio_driver);
首先设置 master 的参数
static int spi_gpio_probe(struct platform_device *pdev)
{int status;struct spi_master *master;struct spi_gpio *spi_gpio;struct device *dev = &pdev->dev;struct spi_bitbang *bb;master = devm_spi_alloc_master(dev, sizeof(*spi_gpio));if (!master)return -ENOMEM;if (pdev->dev.of_node)status = spi_gpio_probe_dt(pdev, master);elsestatus = spi_gpio_probe_pdata(pdev, master);if (status)return status;spi_gpio = spi_master_get_devdata(master);status = spi_gpio_request(dev, spi_gpio);if (status)return status;master->bits_per_word_mask = SPI_BPW_RANGE_MASK(1, 32);master->mode_bits = SPI_3WIRE | SPI_3WIRE_HIZ | SPI_CPHA | SPI_CPOL |SPI_CS_HIGH | SPI_LSB_FIRST;if (!spi_gpio->mosi) {/* HW configuration without MOSI pin** No setting SPI_MASTER_NO_RX here - if there is only* a MOSI pin connected the host can still do RX by* changing the direction of the line.*/master->flags = SPI_MASTER_NO_TX;}master->bus_num = pdev->id;master->setup = spi_gpio_setup;master->cleanup = spi_gpio_cleanup;bb = &spi_gpio->bitbang;bb->master = master;/** There is some additional business, apart from driving the CS GPIO* line, that we need to do on selection. This makes the local* callback for chipselect always get called.*/master->flags |= SPI_MASTER_GPIO_SS;bb->chipselect = spi_gpio_chipselect;bb->set_line_direction = spi_gpio_set_direction;if (master->flags & SPI_MASTER_NO_TX) {bb->txrx_word[SPI_MODE_0] = spi_gpio_spec_txrx_word_mode0;bb->txrx_word[SPI_MODE_1] = spi_gpio_spec_txrx_word_mode1;bb->txrx_word[SPI_MODE_2] = spi_gpio_spec_txrx_word_mode2;bb->txrx_word[SPI_MODE_3] = spi_gpio_spec_txrx_word_mode3;} else {bb->txrx_word[SPI_MODE_0] = spi_gpio_txrx_word_mode0;bb->txrx_word[SPI_MODE_1] = spi_gpio_txrx_word_mode1;bb->txrx_word[SPI_MODE_2] = spi_gpio_txrx_word_mode2;bb->txrx_word[SPI_MODE_3] = spi_gpio_txrx_word_mode3;}bb->setup_transfer = spi_bitbang_setup_transfer;status = spi_bitbang_init(&spi_gpio->bitbang);if (status)return status;return devm_spi_register_master(&pdev->dev, master);
}
/ include / linux / spi / spi.h
#define devm_spi_register_master(_dev, _ctlr) \devm_spi_register_controller(_dev, _ctlr)
/ drivers / spi / spi.c
/*** devm_spi_register_controller - register managed SPI master or slave* controller* @dev: device managing SPI controller* @ctlr: initialized controller, originally from spi_alloc_master() or* spi_alloc_slave()* Context: can sleep** Register a SPI device as with spi_register_controller() which will* automatically be unregistered and freed.** Return: zero on success, else a negative error code.*/
int devm_spi_register_controller(struct device *dev,struct spi_controller *ctlr)
{struct spi_controller **ptr;int ret;ptr = devres_alloc(devm_spi_unregister, sizeof(*ptr), GFP_KERNEL);if (!ptr)return -ENOMEM;ret = spi_register_controller(ctlr);if (!ret) {*ptr = ctlr;devres_add(dev, ptr);} else {devres_free(ptr);}return ret;
}
EXPORT_SYMBOL_GPL(devm_spi_register_controller);
注册 master
int spi_register_controller(struct spi_controller *ctlr)
{struct device *dev = ctlr->dev.parent;struct boardinfo *bi;int status;int id, first_dynamic;if (!dev)return -ENODEV;/** Make sure all necessary hooks are implemented before registering* the SPI controller.*/status = spi_controller_check_ops(ctlr);if (status)return status;if (ctlr->bus_num >= 0) {/* devices with a fixed bus num must check-in with the num */mutex_lock(&board_lock);id = idr_alloc(&spi_master_idr, ctlr, ctlr->bus_num,ctlr->bus_num + 1, GFP_KERNEL);mutex_unlock(&board_lock);if (WARN(id < 0, "couldn't get idr"))return id == -ENOSPC ? -EBUSY : id;ctlr->bus_num = id;} else if (ctlr->dev.of_node) {/* allocate dynamic bus number using Linux idr */id = of_alias_get_id(ctlr->dev.of_node, "spi");if (id >= 0) {ctlr->bus_num = id;mutex_lock(&board_lock);id = idr_alloc(&spi_master_idr, ctlr, ctlr->bus_num,ctlr->bus_num + 1, GFP_KERNEL);mutex_unlock(&board_lock);if (WARN(id < 0, "couldn't get idr"))return id == -ENOSPC ? -EBUSY : id;}}if (ctlr->bus_num < 0) {first_dynamic = of_alias_get_highest_id("spi");if (first_dynamic < 0)first_dynamic = 0;elsefirst_dynamic++;mutex_lock(&board_lock);id = idr_alloc(&spi_master_idr, ctlr, first_dynamic,0, GFP_KERNEL);mutex_unlock(&board_lock);if (WARN(id < 0, "couldn't get idr"))return id;ctlr->bus_num = id;}ctlr->bus_lock_flag = 0;init_completion(&ctlr->xfer_completion);if (!ctlr->max_dma_len)ctlr->max_dma_len = INT_MAX;/** Register the device, then userspace will see it.* Registration fails if the bus ID is in use.*/dev_set_name(&ctlr->dev, "spi%u", ctlr->bus_num);if (!spi_controller_is_slave(ctlr) && ctlr->use_gpio_descriptors) {status = spi_get_gpio_descs(ctlr);if (status)goto free_bus_id;/** A controller using GPIO descriptors always* supports SPI_CS_HIGH if need be.*/ctlr->mode_bits |= SPI_CS_HIGH;}/** Even if it's just one always-selected device, there must* be at least one chipselect.*/if (!ctlr->num_chipselect) {status = -EINVAL;goto free_bus_id;}/* setting last_cs to -1 means no chip selected */ctlr->last_cs = -1;status = device_add(&ctlr->dev);if (status < 0)goto free_bus_id;dev_dbg(dev, "registered %s %s\n",spi_controller_is_slave(ctlr) ? "slave" : "master",dev_name(&ctlr->dev));/** If we're using a queued driver, start the queue. Note that we don't* need the queueing logic if the driver is only supporting high-level* memory operations.*/if (ctlr->transfer) {dev_info(dev, "controller is unqueued, this is deprecated\n");} else if (ctlr->transfer_one || ctlr->transfer_one_message) {status = spi_controller_initialize_queue(ctlr);if (status) {device_del(&ctlr->dev);goto free_bus_id;}}/* add statistics */spin_lock_init(&ctlr->statistics.lock);mutex_lock(&board_lock);list_add_tail(&ctlr->list, &spi_controller_list);list_for_each_entry(bi, &board_list, list)spi_match_controller_to_boardinfo(ctlr, &bi->board_info);mutex_unlock(&board_lock);/* Register devices from the device tree and ACPI */of_register_spi_devices(ctlr);acpi_register_spi_devices(ctlr);return status;free_bus_id:mutex_lock(&board_lock);idr_remove(&spi_master_idr, ctlr->bus_num);mutex_unlock(&board_lock);return status;
}
EXPORT_SYMBOL_GPL(spi_register_controller);
可以看到这里遍历子节点然后区进行注册
static void of_register_spi_devices(struct spi_controller *ctlr)
{struct spi_device *spi;struct device_node *nc;if (!ctlr->dev.of_node)return;for_each_available_child_of_node(ctlr->dev.of_node, nc) {if (of_node_test_and_set_flag(nc, OF_POPULATED))continue;spi = of_register_spi_device(ctlr, nc);if (IS_ERR(spi)) {dev_warn(&ctlr->dev,"Failed to create SPI device for %pOF\n", nc);of_node_clear_flag(nc, OF_POPULATED);}}
}
static struct spi_device *
of_register_spi_device(struct spi_controller *ctlr, struct device_node *nc)
{struct spi_device *spi;int rc;/* Alloc an spi_device */spi = spi_alloc_device(ctlr);if (!spi) {dev_err(&ctlr->dev, "spi_device alloc error for %pOF\n", nc);rc = -ENOMEM;goto err_out;}/* Select device driver */rc = of_modalias_node(nc, spi->modalias,sizeof(spi->modalias));if (rc < 0) {dev_err(&ctlr->dev, "cannot find modalias for %pOF\n", nc);goto err_out;}rc = of_spi_parse_dt(ctlr, spi, nc);if (rc)goto err_out;/* Store a pointer to the node in the device structure */of_node_get(nc);spi->dev.of_node = nc;spi->dev.fwnode = of_fwnode_handle(nc);/* Register the new device */rc = spi_add_device(spi);if (rc) {dev_err(&ctlr->dev, "spi_device register error %pOF\n", nc);goto err_of_node_put;}return spi;err_of_node_put:of_node_put(nc);
err_out:spi_dev_put(spi);return ERR_PTR(rc);
}
spidev 驱动源码解析
insmod 之后会调用 init 函数
/ drivers / spi / spidev.c
这里面注册了一个字符设备驱动和 spi_driver
static int __init spidev_init(void)
{int status;/* Claim our 256 reserved device numbers. Then register a class* that will key udev/mdev to add/remove /dev nodes. Last, register* the driver which manages those device numbers.*/status = register_chrdev(SPIDEV_MAJOR, "spi", &spidev_fops);if (status < 0)return status;spidev_class = class_create(THIS_MODULE, "spidev");if (IS_ERR(spidev_class)) {unregister_chrdev(SPIDEV_MAJOR, spidev_spi_driver.driver.name);return PTR_ERR(spidev_class);}status = spi_register_driver(&spidev_spi_driver);if (status < 0) {class_destroy(spidev_class);unregister_chrdev(SPIDEV_MAJOR, spidev_spi_driver.driver.name);}return status;
}
module_init(spidev_init);
设备树匹配之后 probe 函数被调用
static struct spi_driver spidev_spi_driver = {.driver = {.name = "spidev",.of_match_table = spidev_dt_ids,.acpi_match_table = spidev_acpi_ids,},.probe = spidev_probe,.remove = spidev_remove,.id_table = spidev_spi_ids,/* NOTE: suspend/resume methods are not necessary here.* We don't do anything except pass the requests to/from* the underlying controller. The refrigerator handles* most issues; the controller driver handles the rest.*/
};
来看看 probe 函数,这里首先记录 spi 设备,然后找到一个次设备号并创建设备节点,创建之后可以在/dev/找到这个字符设备,用户访问时通过下面的device_list 找出spidev_data(有spi_device),spi_device 中又包含了 spi_master,这样就可以通过spi_master 读写设备了
static int spidev_probe(struct spi_device *spi)
{int (*match)(struct device *dev);struct spidev_data *spidev;int status;unsigned long minor;match = device_get_match_data(&spi->dev);if (match) {status = match(&spi->dev);if (status)return status;}/* Allocate driver data */spidev = kzalloc(sizeof(*spidev), GFP_KERNEL);if (!spidev)return -ENOMEM;/* Initialize the driver data */spidev->spi = spi;spin_lock_init(&spidev->spi_lock);mutex_init(&spidev->buf_lock);INIT_LIST_HEAD(&spidev->device_entry);/* If we can allocate a minor number, hook up this device.* Reusing minors is fine so long as udev or mdev is working.*/mutex_lock(&device_list_lock);minor = find_first_zero_bit(minors, N_SPI_MINORS);if (minor < N_SPI_MINORS) {struct device *dev;spidev->devt = MKDEV(SPIDEV_MAJOR, minor);dev = device_create(spidev_class, &spi->dev, spidev->devt,spidev, "spidev%d.%d",spi->master->bus_num, spi->chip_select);status = PTR_ERR_OR_ZERO(dev);} else {dev_dbg(&spi->dev, "no minor number available!\n");status = -ENODEV;}if (status == 0) {set_bit(minor, minors);list_add(&spidev->device_entry, &device_list);}mutex_unlock(&device_list_lock);spidev->speed_hz = spi->max_speed_hz;if (status == 0)spi_set_drvdata(spi, spidev);elsekfree(spidev);return status;
}
用户就使用这里字符设备驱动程序提供的接口去操作 spidev 了,其中 spi 读写操作的实现都在其中
static const struct file_operations spidev_fops = {.owner = THIS_MODULE,/* REVISIT switch to aio primitives, so that userspace* gets more complete API coverage. It'll simplify things* too, except for the locking.*/.write = spidev_write,.read = spidev_read,.unlocked_ioctl = spidev_ioctl,.compat_ioctl = spidev_compat_ioctl,.open = spidev_open,.release = spidev_release,.llseek = no_llseek,
};
内核应用程序参考代码
/ tools / spi / spidev_fdx.c
// SPDX-License-Identifier: GPL-2.0
#include <stdio.h>
#include <unistd.h>
#include <stdlib.h>
#include <fcntl.h>
#include <string.h>#include <sys/ioctl.h>
#include <sys/types.h>
#include <sys/stat.h>#include <linux/types.h>
#include <linux/spi/spidev.h>static int verbose;static void do_read(int fd, int len)
{unsigned char buf[32], *bp;int status;/* read at least 2 bytes, no more than 32 */if (len < 2)len = 2;else if (len > sizeof(buf))len = sizeof(buf);memset(buf, 0, sizeof buf);status = read(fd, buf, len);if (status < 0) {perror("read");return;}if (status != len) {fprintf(stderr, "short read\n");return;}printf("read(%2d, %2d): %02x %02x,", len, status,buf[0], buf[1]);status -= 2;bp = buf + 2;while (status-- > 0)printf(" %02x", *bp++);printf("\n");
}static void do_msg(int fd, int len)
{struct spi_ioc_transfer xfer[2];unsigned char buf[32], *bp;int status;memset(xfer, 0, sizeof xfer);memset(buf, 0, sizeof buf);if (len > sizeof buf)len = sizeof buf;buf[0] = 0xaa;xfer[0].tx_buf = (unsigned long)buf;xfer[0].len = 1;xfer[1].rx_buf = (unsigned long) buf;xfer[1].len = len;status = ioctl(fd, SPI_IOC_MESSAGE(2), xfer);if (status < 0) {perror("SPI_IOC_MESSAGE");return;}printf("response(%2d, %2d): ", len, status);for (bp = buf; len; len--)printf(" %02x", *bp++);printf("\n");
}static void dumpstat(const char *name, int fd)
{__u8 lsb, bits;__u32 mode, speed;if (ioctl(fd, SPI_IOC_RD_MODE32, &mode) < 0) {perror("SPI rd_mode");return;}if (ioctl(fd, SPI_IOC_RD_LSB_FIRST, &lsb) < 0) {perror("SPI rd_lsb_fist");return;}if (ioctl(fd, SPI_IOC_RD_BITS_PER_WORD, &bits) < 0) {perror("SPI bits_per_word");return;}if (ioctl(fd, SPI_IOC_RD_MAX_SPEED_HZ, &speed) < 0) {perror("SPI max_speed_hz");return;}printf("%s: spi mode 0x%x, %d bits %sper word, %d Hz max\n",name, mode, bits, lsb ? "(lsb first) " : "", speed);
}int main(int argc, char **argv)
{int c;int readcount = 0;int msglen = 0;int fd;const char *name;while ((c = getopt(argc, argv, "hm:r:v")) != EOF) {switch (c) {case 'm':msglen = atoi(optarg);if (msglen < 0)goto usage;continue;case 'r':readcount = atoi(optarg);if (readcount < 0)goto usage;continue;case 'v':verbose++;continue;case 'h':case '?':
usage:fprintf(stderr,"usage: %s [-h] [-m N] [-r N] /dev/spidevB.D\n",argv[0]);return 1;}}if ((optind + 1) != argc)goto usage;name = argv[optind];fd = open(name, O_RDWR);if (fd < 0) {perror("open");return 1;}dumpstat(name, fd);if (msglen)do_msg(fd, msglen);if (readcount)do_read(fd, readcount);close(fd);return 0;
}
spi 发送源码解析
/ drivers / spi / spidev.c
/* Write-only message with current device setup */
static ssize_t
spidev_write(struct file *filp, const char __user *buf,size_t count, loff_t *f_pos)
{struct spidev_data *spidev;ssize_t status;unsigned long missing;/* chipselect only toggles at start or end of operation */if (count > bufsiz)return -EMSGSIZE;spidev = filp->private_data;mutex_lock(&spidev->buf_lock);missing = copy_from_user(spidev->tx_buffer, buf, count);if (missing == 0)status = spidev_sync_write(spidev, count);elsestatus = -EFAULT;mutex_unlock(&spidev->buf_lock);return status;
}
static inline ssize_t
spidev_sync_write(struct spidev_data *spidev, size_t len)
{struct spi_transfer t = {.tx_buf = spidev->tx_buffer,.len = len,.speed_hz = spidev->speed_hz,};struct spi_message m;spi_message_init(&m);spi_message_add_tail(&t, &m);return spidev_sync(spidev, &m);
}
static ssize_t
spidev_sync(struct spidev_data *spidev, struct spi_message *message)
{int status;struct spi_device *spi;spin_lock_irq(&spidev->spi_lock);spi = spidev->spi;spin_unlock_irq(&spidev->spi_lock);if (spi == NULL)status = -ESHUTDOWN;elsestatus = spi_sync(spi, message);if (status == 0)status = message->actual_length;return status;
}
/ drivers / spi / spi.c
/*** spi_sync - blocking/synchronous SPI data transfers* @spi: device with which data will be exchanged* @message: describes the data transfers* Context: can sleep** This call may only be used from a context that may sleep. The sleep* is non-interruptible, and has no timeout. Low-overhead controller* drivers may DMA directly into and out of the message buffers.** Note that the SPI device's chip select is active during the message,* and then is normally disabled between messages. Drivers for some* frequently-used devices may want to minimize costs of selecting a chip,* by leaving it selected in anticipation that the next message will go* to the same chip. (That may increase power usage.)** Also, the caller is guaranteeing that the memory associated with the* message will not be freed before this call returns.** Return: zero on success, else a negative error code.*/
int spi_sync(struct spi_device *spi, struct spi_message *message)
{int ret;mutex_lock(&spi->controller->bus_lock_mutex);ret = __spi_sync(spi, message);mutex_unlock(&spi->controller->bus_lock_mutex);return ret;
}
EXPORT_SYMBOL_GPL(spi_sync);
注意这里有 __spi_queued_transfer (把消息放入队列,帮你管理,后面调用__spi_pump_messages 发送消息)和spi_async_locked(自己实现 transfer,自己管理) 两种传输方式
static int __spi_sync(struct spi_device *spi, struct spi_message *message)
{DECLARE_COMPLETION_ONSTACK(done);int status;struct spi_controller *ctlr = spi->controller;unsigned long flags;status = __spi_validate(spi, message);if (status != 0)return status;message->complete = spi_complete;message->context = &done;message->spi = spi;SPI_STATISTICS_INCREMENT_FIELD(&ctlr->statistics, spi_sync);SPI_STATISTICS_INCREMENT_FIELD(&spi->statistics, spi_sync);/** If we're not using the legacy transfer method then we will* try to transfer in the calling context so special case.* This code would be less tricky if we could remove the* support for driver implemented message queues.*/if (ctlr->transfer == spi_queued_transfer) {spin_lock_irqsave(&ctlr->bus_lock_spinlock, flags);trace_spi_message_submit(message);status = __spi_queued_transfer(spi, message, false);spin_unlock_irqrestore(&ctlr->bus_lock_spinlock, flags);} else {status = spi_async_locked(spi, message);}if (status == 0) {/* Push out the messages in the calling context if we can */if (ctlr->transfer == spi_queued_transfer) {SPI_STATISTICS_INCREMENT_FIELD(&ctlr->statistics,spi_sync_immediate);SPI_STATISTICS_INCREMENT_FIELD(&spi->statistics,spi_sync_immediate);__spi_pump_messages(ctlr, false);}wait_for_completion(&done);status = message->status;}message->context = NULL;return status;
}
先看 spi_async_locked
static int spi_async_locked(struct spi_device *spi, struct spi_message *message)
{struct spi_controller *ctlr = spi->controller;int ret;unsigned long flags;ret = __spi_validate(spi, message);if (ret != 0)return ret;spin_lock_irqsave(&ctlr->bus_lock_spinlock, flags);ret = __spi_async(spi, message);spin_unlock_irqrestore(&ctlr->bus_lock_spinlock, flags);return ret;
在这里可以看到需要自己提供 transfer 函数,需要自己管理队列,自己触发传输
static int __spi_async(struct spi_device *spi, struct spi_message *message)
{struct spi_controller *ctlr = spi->controller;struct spi_transfer *xfer;/** Some controllers do not support doing regular SPI transfers. Return* ENOTSUPP when this is the case.*/if (!ctlr->transfer)return -ENOTSUPP;message->spi = spi;SPI_STATISTICS_INCREMENT_FIELD(&ctlr->statistics, spi_async);SPI_STATISTICS_INCREMENT_FIELD(&spi->statistics, spi_async);trace_spi_message_submit(message);if (!ctlr->ptp_sts_supported) {list_for_each_entry(xfer, &message->transfers, transfer_list) {xfer->ptp_sts_word_pre = 0;ptp_read_system_prets(xfer->ptp_sts);}}return ctlr->transfer(spi, message);
}
来看看__spi_queued_transfer,如果 transfer 函数是内核提供的话就会调用这个函数
static int __spi_queued_transfer(struct spi_device *spi,struct spi_message *msg,bool need_pump)
{struct spi_controller *ctlr = spi->controller;unsigned long flags;spin_lock_irqsave(&ctlr->queue_lock, flags);if (!ctlr->running) {spin_unlock_irqrestore(&ctlr->queue_lock, flags);return -ESHUTDOWN;}msg->actual_length = 0;msg->status = -EINPROGRESS;list_add_tail(&msg->queue, &ctlr->queue);if (!ctlr->busy && need_pump)kthread_queue_work(ctlr->kworker, &ctlr->pump_messages);spin_unlock_irqrestore(&ctlr->queue_lock, flags);return 0;
}
来看看前面的__spi_pump_messages,这里调用transfer_one_message传输一个消息,就是循环发送消息中的所有 xfer
/*** __spi_pump_messages - function which processes spi message queue* @ctlr: controller to process queue for* @in_kthread: true if we are in the context of the message pump thread** This function checks if there is any spi message in the queue that* needs processing and if so call out to the driver to initialize hardware* and transfer each message.** Note that it is called both from the kthread itself and also from* inside spi_sync(); the queue extraction handling at the top of the* function should deal with this safely.*/
static void __spi_pump_messages(struct spi_controller *ctlr, bool in_kthread)
{struct spi_transfer *xfer;struct spi_message *msg;bool was_busy = false;unsigned long flags;int ret;/* Lock queue */spin_lock_irqsave(&ctlr->queue_lock, flags);/* Make sure we are not already running a message */if (ctlr->cur_msg) {spin_unlock_irqrestore(&ctlr->queue_lock, flags);return;}/* If another context is idling the device then defer */if (ctlr->idling) {kthread_queue_work(ctlr->kworker, &ctlr->pump_messages);spin_unlock_irqrestore(&ctlr->queue_lock, flags);return;}/* Check if the queue is idle */if (list_empty(&ctlr->queue) || !ctlr->running) {if (!ctlr->busy) {spin_unlock_irqrestore(&ctlr->queue_lock, flags);return;}/* Defer any non-atomic teardown to the thread */if (!in_kthread) {if (!ctlr->dummy_rx && !ctlr->dummy_tx &&!ctlr->unprepare_transfer_hardware) {spi_idle_runtime_pm(ctlr);ctlr->busy = false;trace_spi_controller_idle(ctlr);} else {kthread_queue_work(ctlr->kworker,&ctlr->pump_messages);}spin_unlock_irqrestore(&ctlr->queue_lock, flags);return;}ctlr->busy = false;ctlr->idling = true;spin_unlock_irqrestore(&ctlr->queue_lock, flags);kfree(ctlr->dummy_rx);ctlr->dummy_rx = NULL;kfree(ctlr->dummy_tx);ctlr->dummy_tx = NULL;if (ctlr->unprepare_transfer_hardware &&ctlr->unprepare_transfer_hardware(ctlr))dev_err(&ctlr->dev,"failed to unprepare transfer hardware\n");spi_idle_runtime_pm(ctlr);trace_spi_controller_idle(ctlr);spin_lock_irqsave(&ctlr->queue_lock, flags);ctlr->idling = false;spin_unlock_irqrestore(&ctlr->queue_lock, flags);return;}/* Extract head of queue */msg = list_first_entry(&ctlr->queue, struct spi_message, queue);ctlr->cur_msg = msg;list_del_init(&msg->queue);if (ctlr->busy)was_busy = true;elsectlr->busy = true;spin_unlock_irqrestore(&ctlr->queue_lock, flags);mutex_lock(&ctlr->io_mutex);if (!was_busy && ctlr->auto_runtime_pm) {ret = pm_runtime_resume_and_get(ctlr->dev.parent);if (ret < 0) {dev_err(&ctlr->dev, "Failed to power device: %d\n",ret);mutex_unlock(&ctlr->io_mutex);return;}}if (!was_busy)trace_spi_controller_busy(ctlr);if (!was_busy && ctlr->prepare_transfer_hardware) {ret = ctlr->prepare_transfer_hardware(ctlr);if (ret) {dev_err(&ctlr->dev,"failed to prepare transfer hardware: %d\n",ret);if (ctlr->auto_runtime_pm)pm_runtime_put(ctlr->dev.parent);msg->status = ret;spi_finalize_current_message(ctlr);mutex_unlock(&ctlr->io_mutex);return;}}trace_spi_message_start(msg);if (ctlr->prepare_message) {ret = ctlr->prepare_message(ctlr, msg);if (ret) {dev_err(&ctlr->dev, "failed to prepare message: %d\n",ret);msg->status = ret;spi_finalize_current_message(ctlr);goto out;}ctlr->cur_msg_prepared = true;}ret = spi_map_msg(ctlr, msg);if (ret) {msg->status = ret;spi_finalize_current_message(ctlr);goto out;}if (!ctlr->ptp_sts_supported && !ctlr->transfer_one) {list_for_each_entry(xfer, &msg->transfers, transfer_list) {xfer->ptp_sts_word_pre = 0;ptp_read_system_prets(xfer->ptp_sts);}}ret = ctlr->transfer_one_message(ctlr, msg);if (ret) {dev_err(&ctlr->dev,"failed to transfer one message from queue: %d\n",ret);goto out;}out:mutex_unlock(&ctlr->io_mutex);/* Prod the scheduler in case transfer_one() was busy waiting */if (!ret)cond_resched();
}
spi master 驱动分析
/ drivers / spi / spi-gpio.c
首先看 probe 函数,这里先分配一个 spi_master 结构体
static int spi_gpio_probe(struct platform_device *pdev)
{int status;struct spi_master *master;struct spi_gpio *spi_gpio;struct device *dev = &pdev->dev;struct spi_bitbang *bb;master = devm_spi_alloc_master(dev, sizeof(*spi_gpio));if (!master)return -ENOMEM;if (pdev->dev.of_node)status = spi_gpio_probe_dt(pdev, master);elsestatus = spi_gpio_probe_pdata(pdev, master);if (status)return status;spi_gpio = spi_master_get_devdata(master);status = spi_gpio_request(dev, spi_gpio);if (status)return status;master->bits_per_word_mask = SPI_BPW_RANGE_MASK(1, 32);master->mode_bits = SPI_3WIRE | SPI_3WIRE_HIZ | SPI_CPHA | SPI_CPOL |SPI_CS_HIGH | SPI_LSB_FIRST;if (!spi_gpio->mosi) {/* HW configuration without MOSI pin** No setting SPI_MASTER_NO_RX here - if there is only* a MOSI pin connected the host can still do RX by* changing the direction of the line.*/master->flags = SPI_MASTER_NO_TX;}master->bus_num = pdev->id;master->setup = spi_gpio_setup;master->cleanup = spi_gpio_cleanup;bb = &spi_gpio->bitbang;bb->master = master;/** There is some additional business, apart from driving the CS GPIO* line, that we need to do on selection. This makes the local* callback for chipselect always get called.*/master->flags |= SPI_MASTER_GPIO_SS;bb->chipselect = spi_gpio_chipselect;bb->set_line_direction = spi_gpio_set_direction;if (master->flags & SPI_MASTER_NO_TX) {bb->txrx_word[SPI_MODE_0] = spi_gpio_spec_txrx_word_mode0;bb->txrx_word[SPI_MODE_1] = spi_gpio_spec_txrx_word_mode1;bb->txrx_word[SPI_MODE_2] = spi_gpio_spec_txrx_word_mode2;bb->txrx_word[SPI_MODE_3] = spi_gpio_spec_txrx_word_mode3;} else {bb->txrx_word[SPI_MODE_0] = spi_gpio_txrx_word_mode0;bb->txrx_word[SPI_MODE_1] = spi_gpio_txrx_word_mode1;bb->txrx_word[SPI_MODE_2] = spi_gpio_txrx_word_mode2;bb->txrx_word[SPI_MODE_3] = spi_gpio_txrx_word_mode3;}bb->setup_transfer = spi_bitbang_setup_transfer;status = spi_bitbang_init(&spi_gpio->bitbang);if (status)return status;return devm_spi_register_master(&pdev->dev, master);
}
这里最核心的就是 bitbang对于 消息收发处理的设置
来看看 bitbang 怎么获取的
/ include / linux / spi / spi.h
#define spi_master_get_devdata(_ctlr) spi_controller_get_devdata(_ctlr)
static inline void *spi_controller_get_devdata(struct spi_controller *ctlr)
{return dev_get_drvdata(&ctlr->dev);
}
/ include / linux / device.h
static inline void *dev_get_drvdata(const struct device *dev)
{return dev->driver_data;
}
来看看 bitbang 的具体处理
/ drivers / spi / spi-gpio.c
/ drivers / spi / spi-bitbang.c
可以看到这里对txrx_bufs 进行了赋值,对transfer_one 也进行了赋值
int spi_bitbang_init(struct spi_bitbang *bitbang)
{struct spi_master *master = bitbang->master;bool custom_cs;if (!master)return -EINVAL;/** We only need the chipselect callback if we are actually using it.* If we just use GPIO descriptors, it is surplus. If the* SPI_MASTER_GPIO_SS flag is set, we always need to call the* driver-specific chipselect routine.*/custom_cs = (!master->use_gpio_descriptors ||(master->flags & SPI_MASTER_GPIO_SS));if (custom_cs && !bitbang->chipselect)return -EINVAL;mutex_init(&bitbang->lock);if (!master->mode_bits)master->mode_bits = SPI_CPOL | SPI_CPHA | bitbang->flags;if (master->transfer || master->transfer_one_message)return -EINVAL;master->prepare_transfer_hardware = spi_bitbang_prepare_hardware;master->unprepare_transfer_hardware = spi_bitbang_unprepare_hardware;master->transfer_one = spi_bitbang_transfer_one;/** When using GPIO descriptors, the ->set_cs() callback doesn't even* get called unless SPI_MASTER_GPIO_SS is set.*/if (custom_cs)master->set_cs = spi_bitbang_set_cs;if (!bitbang->txrx_bufs) {bitbang->use_dma = 0;bitbang->txrx_bufs = spi_bitbang_bufs;if (!master->setup) {if (!bitbang->setup_transfer)bitbang->setup_transfer =spi_bitbang_setup_transfer;master->setup = spi_bitbang_setup;master->cleanup = spi_bitbang_cleanup;}}return 0;
}
EXPORT_SYMBOL_GPL(spi_bitbang_init);
这里就是正真硬件相关读写了
static int spi_bitbang_bufs(struct spi_device *spi, struct spi_transfer *t)
{struct spi_bitbang_cs *cs = spi->controller_state;unsigned nsecs = cs->nsecs;struct spi_bitbang *bitbang;bitbang = spi_master_get_devdata(spi->master);if (bitbang->set_line_direction) {int err;err = bitbang->set_line_direction(spi, !!(t->tx_buf));if (err < 0)return err;}if (spi->mode & SPI_3WIRE) {unsigned flags;flags = t->tx_buf ? SPI_MASTER_NO_RX : SPI_MASTER_NO_TX;return cs->txrx_bufs(spi, cs->txrx_word, nsecs, t, flags);}return cs->txrx_bufs(spi, cs->txrx_word, nsecs, t, 0);
}
来看看spi_bitbang_transfer_one,可以看到这里面调用了txrx_bufs
static int spi_bitbang_transfer_one(struct spi_master *master,struct spi_device *spi,struct spi_transfer *transfer)
{struct spi_bitbang *bitbang = spi_master_get_devdata(master);int status = 0;if (bitbang->setup_transfer) {status = bitbang->setup_transfer(spi, transfer);if (status < 0)goto out;}if (transfer->len)status = bitbang->txrx_bufs(spi, transfer);if (status == transfer->len)status = 0;else if (status >= 0)status = -EREMOTEIO;out:spi_finalize_current_transfer(master);return status;
}
前面提到的transfer_one_message 是在 controller 队列初始化时赋值的
/ drivers / spi / spi.c
static int spi_controller_initialize_queue(struct spi_controller *ctlr)
{int ret;ctlr->transfer = spi_queued_transfer;if (!ctlr->transfer_one_message)ctlr->transfer_one_message = spi_transfer_one_message;/* Initialize and start queue */ret = spi_init_queue(ctlr);if (ret) {dev_err(&ctlr->dev, "problem initializing queue\n");goto err_init_queue;}ctlr->queued = true;ret = spi_start_queue(ctlr);if (ret) {dev_err(&ctlr->dev, "problem starting queue\n");goto err_start_queue;}return 0;err_start_queue:spi_destroy_queue(ctlr);
err_init_queue:return ret;
}
可以看到这里调用了transfer_one
/** spi_transfer_one_message - Default implementation of transfer_one_message()** This is a standard implementation of transfer_one_message() for* drivers which implement a transfer_one() operation. It provides* standard handling of delays and chip select management.*/
static int spi_transfer_one_message(struct spi_controller *ctlr,struct spi_message *msg)
{struct spi_transfer *xfer;bool keep_cs = false;int ret = 0;struct spi_statistics *statm = &ctlr->statistics;struct spi_statistics *stats = &msg->spi->statistics;spi_set_cs(msg->spi, true, false);SPI_STATISTICS_INCREMENT_FIELD(statm, messages);SPI_STATISTICS_INCREMENT_FIELD(stats, messages);list_for_each_entry(xfer, &msg->transfers, transfer_list) {trace_spi_transfer_start(msg, xfer);spi_statistics_add_transfer_stats(statm, xfer, ctlr);spi_statistics_add_transfer_stats(stats, xfer, ctlr);if (!ctlr->ptp_sts_supported) {xfer->ptp_sts_word_pre = 0;ptp_read_system_prets(xfer->ptp_sts);}if ((xfer->tx_buf || xfer->rx_buf) && xfer->len) {reinit_completion(&ctlr->xfer_completion);fallback_pio:ret = ctlr->transfer_one(ctlr, msg->spi, xfer);if (ret < 0) {if (ctlr->cur_msg_mapped &&(xfer->error & SPI_TRANS_FAIL_NO_START)) {__spi_unmap_msg(ctlr, msg);ctlr->fallback = true;xfer->error &= ~SPI_TRANS_FAIL_NO_START;goto fallback_pio;}SPI_STATISTICS_INCREMENT_FIELD(statm,errors);SPI_STATISTICS_INCREMENT_FIELD(stats,errors);dev_err(&msg->spi->dev,"SPI transfer failed: %d\n", ret);goto out;}if (ret > 0) {ret = spi_transfer_wait(ctlr, msg, xfer);if (ret < 0)msg->status = ret;}} else {if (xfer->len)dev_err(&msg->spi->dev,"Bufferless transfer has length %u\n",xfer->len);}if (!ctlr->ptp_sts_supported) {ptp_read_system_postts(xfer->ptp_sts);xfer->ptp_sts_word_post = xfer->len;}trace_spi_transfer_stop(msg, xfer);if (msg->status != -EINPROGRESS)goto out;spi_transfer_delay_exec(xfer);if (xfer->cs_change) {if (list_is_last(&xfer->transfer_list,&msg->transfers)) {keep_cs = true;} else {spi_set_cs(msg->spi, false, false);_spi_transfer_cs_change_delay(msg, xfer);spi_set_cs(msg->spi, true, false);}}msg->actual_length += xfer->len;}out:if (ret != 0 || !keep_cs)spi_set_cs(msg->spi, false, false);if (msg->status == -EINPROGRESS)msg->status = ret;if (msg->status && ctlr->handle_err)ctlr->handle_err(ctlr, msg);spi_finalize_current_message(ctlr);return ret;
}
spi slave 和 master 区别
master 是主动发送数据,slave 是被动接收数据(先填充数据,等待传输)
master 的 SS、SCK 是输出引脚,slave 的是输入引脚
slave 要使能接收中断,有数据来了会触发中断
相关文章:
Linux设备驱动开发-SPI驱动开发详解(包含设备树处理详细过程)
基础知识及 SPI 相关结构体介绍 引脚:MISO(master 输入,slave 输出),MOSI(master 输出,slave 输入),片选引脚,SCK(时钟) 控制寄存器&…...
物联网平台建设方案一
系统概述 构建物联网全域支撑服务能力,为实现学院涵盖物联网设备的全面感知、全域互联、全程智控、全域数字基底、全过程统筹管理奠定基础,为打造智能化提供坚实后台基石。 物联网平台向下接入各种传感器、终端和网关,向上通过开放的实施分…...
java23种设计模式-桥接模式
桥接模式(Bridge Pattern)学习笔记 🌟 定义 桥接模式属于结构型设计模式,将抽象部分与实现部分分离,使它们可以独立变化。通过组合代替继承的方式,解决多维度的扩展问题,防止类爆炸。 &#x…...
springboot实现文件上传到华为云的obs
一、前言 有时在项目中需要使用一些存储系统来存储文件,那么当项目要接入obs作为存储系统时,就会利用obs来进行文件的上传下载,具体实现如下。 二、如何通过obs实现文件的上传下载? 1.添加相关的obs的maven依赖。 <dependency…...
【红队利器】单文件一键结束火绒6.0
关于我们 4SecNet 团队专注于网络安全攻防研究,目前团队成员分布在国内多家顶级安全厂商的核心部门,包括安全研究领域、攻防实验室等,汇聚了行业内的顶尖技术力量。团队在病毒木马逆向分析、APT 追踪、破解技术、漏洞分析、红队工具开发等多个…...
DeepSeek 助力 Vue 开发:打造丝滑的滚动动画(Scroll Animations)
前言:哈喽,大家好,今天给大家分享一篇文章!并提供具体代码帮助大家深入理解,彻底掌握!创作不易,如果能帮助到大家或者给大家一些灵感和启发,欢迎收藏关注哦 💕 目录 Deep…...
Compose 动画,让页面动起来
Compose 动画,让页面动起来 概述高级别动画APIAnimatedVisibilityMutableTransitionStateModifier.animateEnterExit自定义Enter/Exit动画 AnimatedContentContentTransform自定义动画SizeTranstion定义大小动画定义子元素动画自定义Enter/Exit动画 CrossfadeModifi…...
Windows CMD 命令大全(Complete List of Windows CMD Commands)
Windows CMD 命令大全: Windows CMD 是 Windows 系统内置的命令行工具,用于执行各种命令和管理任务。 称为Command Prompt。它提供了一个通过键入命令来与计算机系统进行交互的方式,类似于早期的DOS操作系统。以下是 CMD 的基础知识和常用命…...
DeepSeek在MATLAB上的部署与应用
在科技飞速发展的当下,人工智能与编程语言的融合不断拓展着创新边界。DeepSeek作为一款备受瞩目的大语言模型,其在自然语言处理领域展现出强大的能力。而MATLAB,作为科学计算和工程领域广泛应用的专业软件,拥有丰富的工具包和高效…...
IP代理在网络数据挖掘中的关键作用(AI大模型数据采集版)
在当今人工智能飞速发展的时代,AI大模型的训练需要海量且多样化的数据。然而,在数据采集过程中,常常面临诸多挑战,而IP代理在其中发挥着至关重要的作用。 数据采集的多样性是影响AI大模型性能的关键因素。如果数据来源单一&#x…...
pandas数据的导出
数据导出 将数据导出到CSV文件 数据对象.to_csv(filepath,sep"",indexFalse,encoding)参数1:文件的路径参数2:分隔符,默认是 ,参数3:是否保留索引 默认 Ture参数4:文件编码代码 : # 将数据导出到CSV # 引用 pandas import pandas as pd # 定…...
Claude-3.7-Sonnet:Cursor 的新引擎,解锁编码与推理的未来
引言 claude-3.7-sonnet 是 Anthropic 最新发布的大型语言模型,于 2025 年 2 月 24 日推出,并已集成到 Cursor AI 平台中。Cursor 是一个 AI 驱动的集成开发环境(IDE),旨在通过 AI 增强开发者的生产力。claude-3.7-so…...
JavaScript函数-函数的两种声明方式
在JavaScript中,函数是构建复杂逻辑和实现代码重用的基本单元。了解如何正确地定义和使用函数对于任何JavaScript开发者来说都是至关重要的。本文将详细介绍JavaScript函数的两种主要声明方式:函数声明(Function Declaration)和函…...
微服务即时通信系统---(六)语音识别子服务
目录 功能设计 模块划分 业务接口/功能示意图 服务实现流程思想 服务代码实现 编写proto文件 服务端创建子类(SpeechRecognitionServiceImpl)完成RPC服务调用函数重写 SpeechRecognize(语音识别) 服务端完成语音识别子服务类(SpeechRecognitionServer) 注意 …...
【Java 8】Lambda表达式介绍
目录 1、Lambda简介 2、语法介绍 3、Lambda表达式示例 3.1、无参数的 Lambda 表达式 3.2、单个参数的 Lambda 表达式 3.3、多个参数的 Lambda 表达式 3.4、带语句块的 Lambda 表达式 4、Lambda使用场景 4.1、替代匿名内部类 4.2、集合操作 4.3、排序 4.4、函数式接口…...
2011-2019年各省电视节目综合人口覆盖率数据
2011-2019年各省电视节目综合人口覆盖率数据 1、时间:2011-2019年 2、来源:国家统计局、统计年鉴 3、指标:行政区划代码、地区、年份、电视节目综合人口覆盖率(%) 4、范围:31省 5、指标解释:电视节目综合人口覆盖…...
便捷高效的免费 PDF 文件处理帮手
软件介绍 今天要给大家推荐一款超实用的 PDF 工具箱。它的优势十分突出,完全免费且没有任何使用限制。 安装起来毫不费力,下载完成后,直接打开就能使用。软件界面简洁大方,操作便捷顺手。其核心功能涵盖三大板块:一…...
DeepSeek引领目标检测新趋势:如何通过知识蒸馏优化模型性能
目录 一、知识蒸馏是什么? 二、知识蒸馏在目标检测中的重要性 提升实时性 跨任务迁移学习 三、如何使用知识蒸馏优化目标检测? 训练教师模型 生成软标签 训练学生模型 调节温度参数 多教师蒸馏(可选) 四、案例分享 定…...
“深入解析 SQL Server 子查询:从基础到应用”
目录 引言什么是子查询? 子查询的定义子查询的类型 子查询的使用 标量子查询多行子查询多列子查询相关子查询 子查询的性能优化子查询的实际案例总结 引言 在 SQL Server 中,子查询是一种强大的工具,允许我们在一个查询中嵌套另一个查询&am…...
375_C++_cloud手机推送,添加人脸告警信息到任务队列中,UploadAlarmPush是典型的工厂模式应用,为什么使用工厂模式完成这部分代码
一:AlarmFaceInfo的应用 让我帮你解析这个lambda表达式的实现: // ...................... .h ...........................// struct RsMsgPushTask_S : public Task{AlarmType_E mainAlarmType;unsigned int subAlarmType;DateTime alarmTime...
Vue进阶之AI智能助手项目(二)——项目评审与架构设计
AI智能助手项目 基于Vue的最佳实践main.tsApp.vue主应用给子应用下发功能语言language,theme设置及appStore状态管理状态管理router路由index.tspermission.ts基于Vue的最佳实践 src目录概览 api 接口,基于接口可以做 状态处理,interceptorassets/public 静态资源component…...
LambdaQueryWrapper在Mybatis-plus中的应用
LambdaQueryWrapper 是 MyBatis-Plus 中非常强大的工具,用于构建类型安全的查询条件。它利用 Java 的 Lambda 表达式,使得查询条件的编写更加简洁和直观。 public R getAppArticleCategoryPage(ParameterObject Page page,ParameterObject AppArticleCa…...
DeepSeek AI人工智能该如何学习?
人工智能(Artificial Intelligence, AI)是当今科技领域的热门话题,它涵盖了机器学习、深度学习、自然语言处理、计算机视觉等多个子领域。 作为中国科技发展的核心方向之一,AI在国家战略规划中占据了重要地位,特别是在…...
element ui的select选择框
我们首先先试一下,这个东西怎么玩的 <el-select v-model"select" change"changeSelect"><el-option value"香蕉"></el-option><el-option value"菠萝"></el-option><el-option value&quo…...
解决Value of type ‘AVCodecContext‘ has no member ‘channels‘ 的问题
在 FFmpeg 7.1 中,AVCodecContext 的 channels 和 channel_layout 字段已经被移除,取而代之的是 AVChannelLayout 结构。因此,代码需要进行调整以适应新的 API。 以下是如何正确设置 AVCodecContext 和 AVCodecParameters 的方法。 1. 问题分析 在 FFmpeg 7.1 中: AVCode…...
【STM32H743IIT6】STM32H7的ADC时钟频率设置问题 —— 网上大多文章未注意到的要点!
前言 我使用的是定时器触发ADC采样。最近在想达到ADC的最高采样率的时候,发现一直却卡在1Msps上不去,直到在硬汉嵌入式的论坛里才发现了答案:[ADC] STM32H743/H750的Y版和V版芯片ADC的主频区别 这篇文章就详细的讲一下这个问题,这…...
GGUF 文件格式全解析
在机器学习领域,模型的存储和部署一直是关键环节。随着大语言模型 (LLM) 的广泛应用,如何高效地存储和加载这些复杂的模型成为一个亟待解决的问题。GGUF(GGML Universal Format)作为一种新兴的二进制文件格式,旨在解决…...
剑指offer - 面试题11 旋转数组的最小数字
题目链接:旋转数组的最小数字 第一种:正确写法(num[m]和nums[r]比较) class Solution { public:/*** 代码中的类名、方法名、参数名已经指定,请勿修改,直接返回方法规定的值即可** * param nums int整型v…...
JNA基础使用,调用C++返回结构体
C端 test.h文件 #pragma oncestruct RespInfo {char* path;char* content;int statusCode; };extern "C" { DLL_EXPORT void readInfo(char* path, RespInfo* respInfo); }test.cpp文件 #include "test.h"void readInfo(char* path, RespInfo* respInfo…...
Typora的Github主题美化
[!note] Typora的Github主题进行一些自己喜欢的修改,主要包括:字体、代码块、表格样式 美化前: 美化后: 一、字体更换 之前便看上了「中文网字计划」的「朱雀仿宋」字体,于是一直想更换字体,奈何自己拖延症…...
计算机网络模型-TCP/IP协议簇
目录 1. OSI 参考模型 2. TCP/IP 5层协议簇 3. 数据传输过程 4. OSI模型vsTCP/IP模型 5. 工作设备和协议 1. OSI 参考模型 OSI 参考模型 OSI 参考模型 7层参考协议:同层使用相同协议,下层为上层提供服务 再往每一层填网络协议的时候,表…...
ros进阶——强化学习倒立摆的PG算法实现
项目地址:https://github.com/chan-yuu/cartpole_ws git clone https://github.com/chan-yuu/cartpole_ws依赖安装: xterm等 python3.8 torch等上一节中我们定义了很多ros工具,在这里我们将进行验证。 对于launch_robot_test.py来说&#x…...
BUU41 [GYCTF2020]FlaskApp1【SSTI】
题目: 加密处没啥事,但是解密的地方提交{{7*7}}就会返回报错界面,顺便把代码也爆出来了 text_decode base64.b64decode(text.encode()) 先将字符串 text编码为字节对象,然后使用 base64.b64decode 函数对这个字节对象进行 Base…...
pandas读取数据
pandas读取数据 导入需要的包 import pandas as pd import numpy as np import warnings import oswarnings.filterwarnings(ignore)读取纯文本文件 pd.read_csv 使用默认的标题行、逗号分隔符 import pandas as pd fpath "./datas/ml-latest-small/ratings.csv" 使…...
React + TypeScript 全栈开发最佳实践
React TypeScript 全栈开发最佳实践 一、环境搭建与项目初始化 node.js和npm的安装请参考我的文章。 1.1 脚手架选择与工程创建 # 使用Vite 5.x创建ReactTS项目(2025年主流方案) npx create-vitelatest my-app --template react-ts cd my-app npm in…...
RK3399 Android7双WiFi功能实现
在Android系统里面,WiFi功能STA和AP模式是互斥的,而现在越来越多的WiFi模组或者芯片能支持并发模式,即STA+P2P、STA+STA或者STA+AP模式组合。不管是单WiFi并发,还是双WiFi模组,想让STA和AP两个模式同时运行,对于Android7来说,是需要修改到系统源码,才能让APP层用Androi…...
前端包管理工具进化论:npm vs yarn vs pnpm 深度对比
前端包管理工具进化论:npm vs yarn vs pnpm 深度对比 一、工具定位与核心差异二、功能特性对比三、优缺点深度解析四、性能实测对比(示例数据)五、选型建议六、未来趋势 一、工具定位与核心差异 npm (Node Package Manager) Node.js 官方捆绑…...
绕过information_schema与order by注入以及seacsmv9注入
一:information_schema绕过 1,、sys数据库包含了许多视图,这些视图整合了来自information_schema和performance_schema的数据,攻击者可以利用这些视图来获取数据库结构信息。 -- 获取所有数据库名 SELECT DISTINCT table_schema FROM sys.schema_table_…...
在LangFlow中集成OpenAI Compatible API类型的大语言模型
一、背景与核心价值 从Dify换到这个langflow真的时各种的不适应啊。 就比如这个OpenAI Compatible API,这不应该是基本操作嘛? 算了,服了,习惯了就好了。咱闲言少叙,正片开始: LangFlow作为LangChain的可视化开发工具,其最大优势在于无需编写代码即可构建复杂的大模型…...
PING命令TTL解析
在 ping 命令中,TTL(Time to Live,生存时间) 是 IP 数据包的核心字段之一,用于控制数据包在网络中的生命周期。以下是针对 TTL 的简明解析: 1. TTL 的核心作用 防循环机制:TTL 是一个计数器&a…...
Hadoop 基础原理
Hadoop 基础原理 基本介绍Hadoop 的必要性Hadoop 核心组件Hadoop 生态系统中的附加组件 HDFSHDFS 集群架构HDFS 读写流程HDFS 写流程HDFS 读流程 NameNode 持久化机制 MapReduce底层原理示例 Hadoop 是一个由 Apache 基金会开发的分布式系统基础架构,主要解决海量数…...
蓝桥杯单片机基础部分——1.5基础模块代码升级
前言 之前的蓝桥杯单片机基础部分——1、基础模块代码发现有的同学不太会使,这样的话就给他们都封装一下函数,额外封装一下蜂鸣器和继电器,这就全了,到时候的逻辑只要没问题就没啥事了 LED灯模块 现在,给这里封装一个…...
PyTorch常用函数总结(持续更新)
本文主要记录自己在用 PyTorch复现经典模型 过程中遇到的一些函数及用法,以期对 常见PyTorch函数 更加熟练~ 官方Docs:PyTorch documentation — PyTorch 2.6 documentation 目录 数据层面 torch.sign(tensor) torch.tensor(np.eye(3)[y]) torch.on…...
Docker 常用命令大全
一、启动类 1. 启动 docker systemctl start docker 2. 关闭 docker systemctl stop docker 3. 重新启动 docker systemctl restart docker 4. docker 设置自启动 systemctl enable docker 5. 查看 docker 运行状态 systemctl status docker 6. 查看 docker 版本号等信息 docke…...
单片机裸机编程:状态机与其他高效编程框架
在单片机裸机编程中,状态机是一种非常强大的工具,能够有效管理复杂的逻辑和任务切换。除了状态机,还有其他几种编程模式可以在不使用 RTOS 的情况下实现高效的程序设计。以下是一些常见的方法: 1. 状态机编程 状态机通过定义系统…...
TCP,http,WebSocket
TCP(Transmission Control Protocol,传输控制协议)和HTTP(HyperText Transfer Protocol,超文本传输协议)都是网络通信中的重要协议,但它们在网络协议栈的不同层次上工作,各自负责不同…...
gotool在线工具集
1. 包含各种 sql 处理 2. 包含 json 处理 3. 包含 图片处理 4. 跨平台传输 gotool...
HBuilder X中,uni-app、js的延时操作及定时器
完整源码下载 https://download.csdn.net/download/luckyext/90430165 在HBuilder X中,uni-app、js的延时操作及定时器可以用setTimeout和setInterval这两个函数来实现。 1.setTimeout函数用于在指定的毫秒数后执行一次函数。 例如, 2秒后弹出一个提…...
ow rank decomposition如何用于矩阵的分解
1. 什么是矩阵分解和低秩分解 矩阵分解是将一个矩阵表示为若干结构更简单或具有特定性质的矩阵的组合或乘积的过程。低秩分解(Low Rank Decomposition)是其中一种方法,旨在将原矩阵近似为两个或多个秩较低的矩阵的乘积,从而降低复…...
2.3做logstash实验
收集apache日志输出到es 在真实服务器安装logstash,httpd systemctl start httpd echo 666 > /var/www/html/index.html cat /usr/local/logstash/vendor/bundle/jruby/2.3.0/gems/logstash-patterns-core-4.1.2/patterns/httpd #系统内置变量 cd /usr/local/…...