一、设计要求

  1. 将环境中温湿度数值、环境的光照强度和烟雾的信息获取到开发板,显示在图形界面上。
  2. 当温度值高于阈值时,温度指示灯变红、蜂鸣器告警并且启动直流电机正转降温;当湿度值高于阈值时,湿度指示灯变红、蜂鸣器告警并且继电器吸合接通除湿电路;当光照度大于阈值时,光照度指示灯变红、蜂鸣器告警并且步进电机正转关闭窗帘;当检测到烟雾时,烟雾指示灯变红、蜂鸣器告警;报警声音的频率可通过图形界面进行设置。
  3. 温湿度告警阈值、光照度告警阈值可以通过界面进行设置并且保存到配置文件,系统重新上电后,读取配置文件的配置参数。
  4. 实验箱可通过UDP协议将温湿度、照度和烟雾数据传输到x86上的ubuntu上的图形界面显示,并且实验箱和x86上的ubuntu的可以通过图形界面进行文本信息的交流。
  5. 修改启动脚本,使系统上电后自动运行本次实验设计的图形界面。

二、实验原理

        该嵌入式 Linux 环境监测系统采用模块化设计,主要包含硬件采集、核心控制、设备执行、软件交互四大模块。

        硬件采集模块集成温湿度传感器、光敏电阻与烟雾传感器,负责实时感知环境参数变化,为系统提供原始数据。

        核心控制模块以粤嵌GEC6818开发板为载体,搭载Linux操作系统,通过编写设备驱动程序,实现对传感器数据的读取解析,同时运行QT应用程序进行数据处理与逻辑判断。

        设备执行模块由继电器、步进电机蜂鸣器和直流电机组成,根据核心控制模块的指令,继电器在光照强度高于设定的阈值时吸合,触点闭合,电路通断状态改变当光敏元件上的光照强度降低到一定阈值以下时,光敏元件的导通电流或电阻值恢复原状,继电器也会恢复到原来的状态步进电机可在检测光照强度高于阈值时启动,可以与窗帘联动,通过驱动拉开窗帘,使其参数值降低;蜂鸣器在环境参数超设定阈值时,触发声光报警直流电机在检测到烟雾和环境温度高于阈值时启动风扇,使其参数值降低;

        软件交互模块基于QT框架开发可视化界面,不仅能实时展示环境数据,还支持阈值参数设置,便于用户远程监控与管理系统,各模块协同工作实现环境监测与智能调控功能。

三、系统模块分析

3.1.1 环境监测模块

3.1.1.1  温湿度监测模块

        温湿度监测中,采用了DHT11温湿度传感器。VDD_IO为传感器供电,电容C67滤波保证电压稳定。R124作为上拉电阻,使数据传输引脚在空闲时保持高电平状态,R125则将传感器数据引脚连接至XEINT24_B引脚,以便与外部控制设备通信。工作时,微控制器先发送起始信号,传感器响应后,通过单总线传输40位包含温湿度整数、小数部分及校验和的数据,微控制器接收并校验数据,若准确无误,便对温湿度数据进行后续处理与应用,如显示或依据数据触发相关控制动作。

温度检测的驱动代码如下:
//头文件来源于linux内核源码
#include <linux/kernel.h>
#include <linux/module.h>
#include <linux/cdev.h>
#include <linux/fs.h>
#include <linux/errno.h>
#include <linux/uaccess.h>
#include <linux/device.h>
#include <linux/io.h>
#include <linux/gpio.h>		//函数声明
#include "cfg_type.h" 	 	//端口宏定义
#include <linux/ioport.h>	//IO相关
#include <linux/delay.h> 	//延时函数
#include <linux/time.h>
#include "led_cmd.h"
//1.定义一个字符设备
static struct cdev dht11_cdev;
static unsigned int dht11_major = 0; //主设备号;0--动态;>0--静态
static unsigned int dht11_minor = 0; //次设备号
static dev_t dht11_dev_num; 		   //设备号
static struct class *dht11_class;
static struct device *dht11_device;
#define DHT_DATA (??????)
static int gec6818_dht11_open(struct inode *inode, struct file *filp)
{gpio_set_value(DHT_DATA, 1);printk("dht11 driver is openning\n");	//应用程序打开驱动文件时打印return 0;
}static int gec6818_dht11_release(struct inode *inode, struct file *filp)
{gpio_set_value(DHT_DATA, 1);printk("dht11 driver is closing\n");//应用程序关闭驱动文件时打印return 0;
}
static unsigned char get_byte(void)
{int i=0, k=0;int ret_data = 0;for(k=0; k<8; k++){i=0;//复位计数值while(!gpio_get_value(DHT_DATA))//等待总线拉高跳出{i++;udelay(1);if(i > 120){printk("DTH11  high timeout error\n");break;}}udelay(22);ret_data <<= 1;//逐渐将数据移到最高位if(gpio_get_value(DHT_DATA))ret_data |= 0x01;//接收最高位放在第一位 1 只取1,0初始化已经填充i=0;//复位计数值while(gpio_get_value(DHT_DATA))//等待总线拉低跳出{i++;udelay(1);if(i > 200){printk("DTH11  low level timeout error\n");break;}}		}return ret_data;
}static long gec6818_dht11_ioctl(struct file *filp, unsigned int cmd, unsigned long arg)
{int ret, i=0 ; unsigned long flags;//中断保存unsigned char dth11_data[5]={0};//数据组unsigned char checksum = 0;//校验和if(cmd == GEC6818_GET_DHTDATA){local_irq_save(flags);//关闭中断ret =gpio_direction_output(DHT_DATA, 0);//设置输出if(ret != 0)printk("gpio_direction_output DHT_DATA error\n");gpio_set_value(DHT_DATA, 0);//主机拉低18msmsleep(20);ret =gpio_direction_input(DHT_DATA);//设置输入 if(ret != 0){printk("gpio_direction_input DHT_DATA error\n");local_irq_restore(flags); //恢复中断return ret;}udelay(10);if(gpio_get_value(DHT_DATA))//如果响应会拉低总线电平{printk("DTH11  timeout error\n");local_irq_restore(flags); //恢复中断return -EAGAIN;//超时重试}i = 0;while(!gpio_get_value(DHT_DATA))//等待总线拉高跳出{i++;udelay(1);if(i > 160){printk("DTH11  high timeout error\n");local_irq_restore(flags);//恢复中断 return -EAGAIN;//超时重试}}i = 0;while(gpio_get_value(DHT_DATA))//等待总线拉低跳出{i++;udelay(1);if(i > 160){printk("DTH11  low level timeout error\n");local_irq_restore(flags); //恢复中断return -EAGAIN;//超时重试}}for(i = 0; i<5; i++)dth11_data[i] = get_byte();		
checksum = dth11_data[0] + dth11_data[1] + dth11_data[2] + dth11_data[3];//统计校验和if(checksum != dth11_data[4])//判断校验和{printk("DTH11  checksum error\n");return -EAGAIN;	//超时重试}local_irq_restore(flags);//恢复中断}elsereturn -ENOIOCTLCMD;//无效命令	printk("th_data = %hhd  temp_data = %hhd\n", dth11_data[0], dth11_data[2]);ret = copy_to_user(((unsigned char *)arg)+2,&dth11_data[0],2);		if( ret != 0 )return -EFAULT;ret = copy_to_user((unsigned char *)arg,&dth11_data[2],2)if( ret != 0 )return -EFAULT;return 0;
}static const struct file_operations gec6818_dht11_fops = {.owner = THIS_MODULE,.unlocked_ioctl = gec6818_dht11_ioctl,.open = gec6818_dht11_open,.release = gec6818_dht11_release,
};//驱动的安装函数
static int __init gec6818_dht11_init(void)
{int ret;//2.申请设备号(静态注册 or 动态分配)if(dht11_major == 0){ret=alloc_chrdev_region(&dht11_dev_num,dht11_minor,1,"dht11_device");	}else{dht11_dev_num = MKDEV(dht11_major,dht11_minor);ret = register_chrdev_region(dht11_dev_num, 1, "dht11_device");}if(ret < 0){printk("can not get dht11 device number\n");return ret; //返回错误的原因}//4.初始化cdevcdev_init(&dht11_cdev, &gec6818_dht11_fops);//5.将初始化好的cdev加入内核ret = cdev_add(&dht11_cdev, dht11_dev_num, 1);if(ret < 0){printk("cdev add error\n");goto cdev_add_err;}//6.创建classdht11_class = class_create(THIS_MODULE, "dht11_class");if(IS_ERR(dht11_class)){ret =PTR_ERR(dht11_class);printk("dht11 driver class create error\n");goto class_create_err;}	//7.创建devicedht11_device = device_create(dht11_class, NULL,//设备名称dht11_dev_num, NULL, "dht11_dev");//dev/dht11_drvif(IS_ERR(dht11_device)){ret =PTR_ERR(dht11_device);printk("dht11 driver device create error\n");goto device_create_err;}if(gpio_request(DHT_DATA,"DHT_DATA") !=0)//申请物理内存区printk("gpio_request DHT_DATA error\n");		ret =gpio_direction_output(DHT_DATA, 1);//设置输出if(ret != 0){printk("gpio_direction_output DHT_DATA error\n");gpio_free(DHT_DATA);goto device_create_err;}printk(KERN_INFO "gec6818_dht11_init\n");return 0;//出错处理
device_create_err:class_destroy(dht11_class);
class_create_err:cdev_del(&dht11_cdev);
cdev_add_err:	unregister_chrdev_region(dht11_dev_num, 1);return ret;
}//驱动的卸载函数
static void __exit gec6818_dht11_exit(void)
{gpio_free(DHT_DATA);device_destroy(dht11_class, dht11_dev_num);class_destroy(dht11_class);cdev_del(&dht11_cdev);unregister_chrdev_region(dht11_dev_num, 1);printk(KERN_INFO "gec6818_dht11_exit\n");	
}module_init(gec6818_dht11_init);//入口函数
module_exit(gec6818_dht11_exit);//出口函数MODULE_AUTHOR("sugar@NNLG.com");
MODULE_DESCRIPTION("dht11 driver for GEC6818");
MODULE_LICENSE("GPL"); //符合GPL协议
MODULE_VERSION("V1.0");

 

3.1.1.2  光照强度监测模块

        光照强度监测中,采用了光照传感器,光照传感器CS1利用光电效应,其等效电阻随光照强度变化而改变 。CS1与R117、R116组成分压电路,光照强度改变会使R116两端电压变化,该模拟电压信号经XadcAIN3引脚传输至ADC模块 ,转换为数字信号后被微控制器等处理单元接收,依据预设转换关系换算出实际光照强度值,以此实现对光照强度的检测。

光照强度监测的驱动代码如下:
#include <linux/init.h>
#include <linux/kernel.h>
#include <linux/module.h>
#include <linux/fs.h>
#include <linux/cdev.h>
#include <linux/uaccess.h>
#include <linux/device.h>#include <linux/io.h>
#include <linux/gpio.h>
#include <cfg_type.h>
#include <linux/miscdevice.h>
#include <linux/ioctl.h>#define GEC6818_ADC_IN0	_IOR('A',  0, unsigned long)
#define GEC6818_ADC_IN1	_IOR('A',  1, unsigned long)
#define GEC6818_ADC_IN2	_IOR('A',  2, unsigned long) //光敏电阻
#define GEC6818_ADC_IN3	_IOR('A',  3, unsigned long) static void __iomem		*adc_base_va;		//adc的虚拟地址基址
static void __iomem		*adccon_va;		
static void __iomem		*adcdat_va;	
static void __iomem		*prescalercon_va;
static int  gec6818_adc_open (struct inode * inode, struct file *file)
{printk("gec6818_adc_open \n");return 0;
}
static int  gec6818_adc_release (struct inode * inode, struct file *file)
{printk("gec6818_adc_release \n");return 0;
}static long gec6818_adc_ioctl (struct file *filp, unsigned int cmd, unsigned long args)
{unsigned long adc_val=0,adc_vol=0; int rt=0;//adc通道选择#define switch(cmd){case GEC6818_ADC_IN0:iowrite32(ioread32(adccon_va)&(~(7<<3)),adccon_va);break;case GEC6818_ADC_IN1:{iowrite32(ioread32(adccon_va)&(~(7<<3)),adccon_va);iowrite32(ioread32(adccon_va)|(1<<3),adccon_va);}break;		case GEC6818_ADC_IN2:{iowrite32(ioread32(adccon_va)&(~(7<<3)),adccon_va);iowrite32(ioread32(adccon_va)|(2<<3),adccon_va);}break;case GEC6818_ADC_IN3:{iowrite32(ioread32(adccon_va)&(~(7<<3)),adccon_va);iowrite32(ioread32(adccon_va)|(3<<3),adccon_va);}break;	default:printk("IOCTLCMD failed\n");return -ENOIOCTLCMD;}//将电源开启iowrite32(ioread32(adccon_va)&(~(1<<2)),adccon_va);//预分频值=199+1,ADC的工作频率=200MHz/(199+1)=1MHziowrite32(ioread32(prescalercon_va)&(~(0x3FF<<0)),prescalercon_va);iowrite32(ioread32(prescalercon_va)|(199<<0),prescalercon_va);//预分频值使能iowrite32(ioread32(prescalercon_va)|(1<<15),prescalercon_va);//ADC使能//iowrite32(ioread32(adccon_va)&(~(1<<0)),adccon_va);iowrite32(ioread32(adccon_va)|(1<<0),adccon_va);//等待AD转换结束while(ioread32(adccon_va)&(1<<0));//读取12bit数据adc_val = ioread32(adcdat_va)&0xFFF;//关闭CLKIN时钟输入iowrite32(ioread32(prescalercon_va)&(~(1<<15)),prescalercon_va);//关闭ADC电源iowrite32(ioread32(adccon_va)|(1<<2),adccon_va);//将AD转换的结果值 换算为 电压值adc_vol = adc_val*1800/4095;rt = copy_to_user((void *)args,&adc_vol,4);if(rt != 0)return -EFAULT;return 0;
}
static ssize_t gec6818_adc_read (struct file *file, char __user *buf, size_t len, loff_t * offs)
{return 0;
}static const struct file_operations gec6818_adc_fops = {.owner 			= THIS_MODULE,.unlocked_ioctl = gec6818_adc_ioctl,.open 			= gec6818_adc_open,.release 		= gec6818_adc_release,.read 			= gec6818_adc_read,
};static struct miscdevice gec6818_adc_miscdev = {.minor		= MISC_DYNAMIC_MINOR,	//MISC_DYNAMIC_MINOR,动态分配次设备号.name		= "adc_drv",		//设备名称,/dev/adc_drv	.fops		= &gec6818_adc_fops,	//文件操作集
};
//入口函数
static int __init gec6818_adc_init(void)
{int rt=0;// struct resource *adc_res=NULL;//混杂设备的注册rt = misc_register(&gec6818_adc_miscdev);if (rt) {printk("misc_register fail\n");return rt;}//IO内存动态映射,得到物理地址相应的虚拟地址adc_base_va = ioremap(0xC0053000,0x14);if(adc_base_va == NULL){printk("ioremap 0xC0053000,0x14 fail\n");goto fail_ioremap_adc;		}	//得到每个寄存器的虚拟地址adccon_va 		= adc_base_va+0x00;adcdat_va 		= adc_base_va+0x04;	prescalercon_va = adc_base_va+0x10;	printk("gec6818 adc init\n");return 0;fail_ioremap_adc:misc_deregister(&gec6818_adc_miscdev);return rt;
}
//出口函数
static void __exit gec6818_adc_exit(void)
{	iounmap(adc_base_va);misc_deregister(&gec6818_adc_miscdev);printk("gec6818 adc exit\n");
}
//驱动程序的入口:insmod led_drv.ko调用module_init,module_init又会去调用gec6818_adc_init。
module_init(gec6818_adc_init);//驱动程序的出口:rmsmod led_drv调用module_exit,module_exit又会去调用gec6818_adc_exit。
module_exit(gec6818_adc_exit)//模块描述
MODULE_AUTHOR("sugar@NNLG");			    //作者信息
MODULE_DESCRIPTION("gec6818 adc driver");		//模块功能说明
MODULE_LICENSE("GPL");							//许可证:驱动遵循GPL协议

3.1.1.3  烟雾浓度监测模块

        该烟雾检测模块原理图中,采用了MQ-2烟雾传感器,MQ-2烟雾传感器利用气敏特性,其电阻值会随周围烟雾浓度变化而改变。VDD_5V为电路供电R100与MQ-2组成分压电路,烟雾浓度变化时,分压值也随之改变。该模拟信号经R101输入到LM393电压比较器与R99(可调电阻)设定的基准电压对比,当烟雾浓度达到一定程度,比较器输出电平翻转,通过XEINT22_B引脚将信号传输给主控单元,同时D16发光二极管亮起,实现烟雾检测与指示;C57、C60、C61等电容起到滤波作用,确保电路稳定工作。

烟雾浓度监测的驱动代码如下:
#include <linux/module.h>
#include <linux/kernel.h>
#include <linux/fs.h>
#include <linux/init.h>
#include <linux/delay.h>
#include <linux/poll.h>
#include <linux/sched.h>
#include <linux/irq.h>
#include <asm/irq.h>
#include <asm/io.h>
#include <linux/interrupt.h>
#include <asm/uaccess.h>
#include <linux/platform_device.h>
#include <linux/cdev.h>
#include <linux/miscdevice.h>
#include <linux/gpio.h>
#include <linux/types.h>
#include <linux/moduleparam.h>
#include <linux/slab.h>
#include <linux/ioctl.h>
#include <linux/cdev.h>
#include <linux/delay.h>
#include <linux/gpio.h>
#include <cfg_type.h>#define DEVICE_NAME		"gec_gas_drv"                  //设备名称
//烟雾结构体
struct gas_desc {int gpio;int number;char *name;	struct timer_list timer;
};//烟雾设备的管脚,编号,名字
static struct gas_desc gas[] = {{ ?????, 0, "gas0" },
};//初始值
static volatile char gas_values[] = {'0'
};
//等待队列
static DECLARE_WAIT_QUEUE_HEAD(gas_waitq);
static volatile int ev_press = 0;  //进入休眠的条件//烟雾的次数
static void gec6818_gas_timer(unsigned long _data)
{struct gas_desc *bdata = (struct gas_desc *)_data;int down;int number;unsigned tmp;tmp = gpio_get_value(bdata->gpio);/* active low */    //检测到烟雾,比较器输出低电平down = !tmp;//printk(KERN_DEBUG "KEY %d: %08x\n", bdata->number, down);number = bdata->number;//前后两次状态不一样 才认为是检测到一次烟雾if (down !=(gas_values[number] & 1)) {gas_values[number] = '0' + down;   // +'0' 将数字转换为charev_press = 1;//将等待队列中的进程变为可运行态,具体进程什么时候被执行,取决于调度程序;wake_up_interruptible(&gas_waitq);}
}
//烟雾中断
static irqreturn_t gas_interrupt(int irq, void *dev_id)
{struct gas_desc *bdata = (struct gas_desc *)dev_id;mod_timer(&bdata->timer, jiffies + msecs_to_jiffies(40));return IRQ_HANDLED;
}//打开设备
static int gec6818_gas_open(struct inode *inode, struct file *file)
{int irq;int i;int err = 0;//中断申请for (i = 0; i < ARRAY_SIZE(gas); i++) {if (!gas[i].gpio)continue;gpio_free(gas[i].gpio);setup_timer(&gas[i].timer, gec6818_gas_timer,(unsigned long)&gas[i]);irq = gpio_to_irq(gas[i].gpio);   //IRQ_TYPE_EDGE_BOTH双边沿触发err = request_irq(irq, gas_interrupt, IRQ_TYPE_EDGE_BOTH, gas[i].name, (void *)&gas[i]);if (err)break;}//出现错误,中断释放if (err) {i--;for (; i >= 0; i--) {if (!gas[i].gpio)continue;irq = gpio_to_irq(gas[i].gpio);disable_irq(irq);free_irq(irq, (void *)&gas[i]);del_timer_sync(&gas[i].timer);}return -EBUSY;}ev_press = 1;return 0;
}
//关闭中断
static int gec6818_gas_close(struct inode *inode, struct file *file)
{int irq, i;for (i = 0; i < ARRAY_SIZE(gas); i++) {if (!gas[i].gpio)continue;irq = gpio_to_irq(gas[i].gpio);free_irq(irq, (void *)&gas[i]);del_timer_sync(&gas[i].timer);}return 0;
}
//烟雾数据读取
static int gec6818_gas_read(struct file *filp, char __user *buff,size_t count, loff_t *offp)
{//printk("**********cin***************\n");unsigned long err;if (!ev_press) {if (filp->f_flags & O_NONBLOCK)return -EAGAIN;else   //当ev_press为非0时,立马返回,不会休眠,当为0时,线程加入等待队列链表中,然后线程进入休眠状态。wait_event_interruptible(gad_waitq, ev_press); //进入}ev_press = 0;err = copy_to_user((void *)buff,(const void *)(&gas_values),min(siaeof(gas_values),count));//printk("**********cout***************\n");return err ? -EFAULT : min(sizeof(gas_values), count);
}
//烟雾头部,Poll方法只是做一个登记 真正的阻塞发生在select.c 中的 do_select函数
static unsigned int gec6818_gas_poll( struct file *file,struct poll_table_struct *wait)
{unsigned int mask = 0;//把等待队列添加到poll_tablepoll_wait(file, &gas_waitq, wait);if (ev_press)    //if (有数据可读)mask |= POLLIN | POLLRDNORM; return mask;   //返回掩码
}
//文件操作集
static struct file_operations dev_fops = {.owner		= THIS_MODULE,.open		= gec6818_gas_open,.release	= gec6818_gas_close, .read		= gec6818_gas_read,.poll		= gec6818_gas_poll,
};
//杂项设备
static struct miscdevice misc = {.minor		= MISC_DYNAMIC_MINOR,.name		= DEVICE_NAME,.fops		= &dev_fops,
};
//驱动的初始化函数--->从内核中申请资源(内核、中断、设备号、锁....)
static int __init button_dev_init(void)
{int ret;ret = misc_deregister(&misc);printk(DEVICE_NAME"\tinitialized\n");return ret;
}
//驱动退出函数 --->将申请的资源还给内核
static void __exit button_dev_exit(void)
{misc_deregister(&misc);
}
module_init(button_dev_init);                       //驱动的入口函数会调用一个用户的初始化函数
module_exit(button_dev_exit);				        //驱动的出口函数会调用一个用户的退出函数//驱动的描述信息: #modinfo  *.ko , 驱动的描述信息并不是必需的。
MODULE_AUTHOR("sugar@nnlg");                         //驱动的作者
MODULE_DESCRIPTION("Gas of driver");                //驱动的描述
MODULE_LICENSE("GPL");                              //遵循的协议

 

3.1.2 智能调控模块

3.1.2.1 温度调控       

        温度调控中,由直流电机驱动风扇降低环境。LG9110是直流电机驱动芯片,由VDD_5V供电。微控制器通过XEINT20_B和XEINT21_B引脚向LG9110的IA和IB引脚输入控制信号,不同的电平组合能够控制芯片内部的电路通断,进而控制输出引脚OA和OB的电平状态,以此实现对直流电机正转、反转、停止等状态的控制。当检测到环境温度过高,微控制器输出相应信号使电机正转,带动风扇运转,加速空气流动来降低温度;C62和C63电容组成滤波电路,能稳定电源电压,减少电源波动对电机驱动芯片和电机的影响,确保电机稳定运行。

直流电机驱动代码如下所示:
#include <linux/kernel.h>
#include <linux/module.h>
#include <linux/miscdevice.h>
#include <linux/fs.h>
#include <linux/types.h>
#include <linux/moduleparam.h>
#include <linux/slab.h>
#include <linux/ioctl.h>
#include <linux/cdev.h>
#include <linux/delay.h>
#include <linux/gpio.h>
#include <mach/gpio.h>
#include <mach/platform.h>
#include <asm/gpio.h>#define DEVICE_NAME      "dc_motor"            //设备名字      
//电机管脚
static int motor_gpios[] = {(????),//电机管脚,需要自己修改(????),//电机管脚,需要自己修改
};#define MOTOR_NUM		ARRAY_SIZE(motor_gpios) //电机的数量
//电机初始化
static void motor_init(void)
{gpio_set_value(motor_gpios[0], 0);gpio_set_value(motor_gpios[1], 0);
}
//电机正传
static void motor_foreward(void)
{gpio_set_value(motor_gpios[0],1);gpio_set_value(motor_gpios[1],0);
}//电机反转
static void motor_rollback(void)
{gpio_set_value(motor_gpios[1],1);gpio_set_value(motor_gpios[0],0);
}
//电机设备打开
static int gec6818_motor_open(struct inode *inode, struct file *filp)
{printk(DEVICE_NAME ":open\n");motor_init();return 0;
}
//电机控制程序
static long gec6818_motor_ioctl(struct file *filp, unsigned int cmd,unsigned long arg)
{switch(cmd) {case 0:if (arg > MOTOR_NUM) {return -EINVAL;}motor_init();printk("Motor Stop.\n");break;case 1:if (arg > MOTOR_NUM) {return -EINVAL;}motor_rollback();printk("Motor Rollback.\n");break;case 4:if (arg > MOTOR_NUM) {return -EINVAL;}		motor_foreward();printk("Motor Foreward.\n");break;default:return -EINVAL;}return 0;
}
//文件操作集
static struct file_operations gec6818_motor_dev_fops = {.owner			= THIS_MODULE,.unlocked_ioctl	= gec6818_motor_ioctl,.open = gec6818_motor_open
};
//杂项设备
static struct miscdevice gec6818_motor_dev = {.minor			= MISC_DYNAMIC_MINOR,.name			= DEVICE_NAME,.fops			= &gec6818_motor_dev_fops,
};//驱动的初始化函数--->从内核中申请资源(内核、中断、设备号、锁....)
static int __init gec6818_motor_dev_init(void)
{int ret;int i;for (i = 0; i < MOTOR_NUM; i++) {ret = gpio_request(motor_gpios[i], "MOTOR");if (ret) {printk("%s: request GPIO %d for MOTOR failed, ret = %d\n", DEVICE_NAME,motor_gpios[i], ret);return ret;}gpio_direction_output(motor_gpios[i],0);}gpio_set_value(motor_gpios[0], 0);gpio_set_value(motor_gpios[1], 0);ret = misc_register(&gec6818_motor_dev);printk(DEVICE_NAME"\tinitialized\n");return ret;
}//驱动退出函数 --->将申请的资源还给内核
static void __exit gec6818_motor_dev_exit(void) 
{int i;for (i = 0; i < MOTOR_NUM; i++) {gpio_free(motor_gpios[i]);}misc_deregister(&gec6818_motor_dev);
}
module_init(gec6818_motor_dev_init);  //驱动的入口函数会调用一个用户的初始化函数
module_exit(gec6818_motor_dev_exit);  //驱动的出口函数会调用一个用户的退出函数
//驱动的描述信息: #modinfo  *.ko , 驱动的描述信息并不是必需的。
MODULE_AUTHOR("sugar@NNLG");                         //驱动的作者
MODULE_DESCRIPTION("Dc_Motor of driver");           //驱动的描述
MODULE_LICENSE("GPL");                              //遵循的协议

 

3.1.2.2 光照强度调控

        光照强度的调控中,采用步进电机对超过阈值的光照强度进行控制。VDD_5V为电路供电,C58和C59组成滤波电路,稳定电源电压。ULN2003A是达林顿管阵列,起电流放大作用。微控制器通过XEINT16_B、XEINT17_B、XEINT18_B、XEINT19_B引脚输出控制信号,输入到 ULN2003A 的对应引脚,经放大后从其1C-7C引脚输出,通过BA-BD线路驱动步进电机转动。步进电机可连接如百叶窗等装置,通过转动改变百叶窗叶片角度或位置,进而控制进入室内或检测区域的光线量,达到调节光照强度的目的。

直流电机驱动代码如下所示:
#include <linux/module.h>       /* Needed by all modules */
#include <linux/kernel.h>       /* Needed for KERN_ALERT */
#include <linux/init.h>
#include <asm/uaccess.h>
#include <linux/fs.h>
#include <linux/types.h>
#include <linux/cdev.h>
#include <linux/ioport.h>
#include <asm/io.h>
#include <linux/wait.h>
#include <mach/irqs.h>
#include <linux/gpio.h>
#include <asm/gpio.h>
#include <asm/delay.h>
#include <linux/clk.h>
#include <mach/gpio.h>
#include <mach/soc.h>
#include <mach/platform.h>
#include <linux/interrupt.h>
#include <linux/irq.h>
#include <linux/delay.h>
#include <linux/device.h>
#include <linux/gpio.h>
#define DEVICE_NAME     "stepmotor" //设备名字
#define BUF_SIZE 	1024        //Buf的大小static char tmpbuf[BUF_SIZE];
static unsigned int StepMajor=0;
static unsigned int StepMinor=0;
static struct cdev *step_cdev;
static dev_t dev;
struct class *my_class;
//结构体步进电机
struct stepmotor_des {int io_port;char *name;
} ;
//步进电机的管脚和名字
struct stepmotor_des  step_motor[] = {??????//定义管脚和名字,需要查看原理图修改
};
#define  SIZE   ARRAY_SIZE(step_motor) //大小
//字符设备打开
static int step_chardev_open(struct inode *inode,struct file *file)
{// 4 9 3 5int i;//管脚申请for(i=0;i<SIZE;i++){gpio_request( step_motor[i].io_port,step_motor[i].name );gpio_direction_output( step_motor[i].io_port,0 );}printk("open major=%d, minor=%d\n", imajor(inode), iminor(inode));return 0;
}
//字符设备释放
static int step_chardev_release(struct inode *inode,struct file *file)
{int i;for(i=0;i<SIZE;i++){gpio_free(step_motor[i].io_port);}//printk("close major=%d, minor=%d\n", imajor(inode), iminor(inode));return 0;
}
//字符设备读值
static ssize_t step_chardev_read(struct file *file,char __user *buf,size_t const count,loff_t *offset)
{if(count < BUF_SIZE){if(copy_to_user(buf,tmpbuf,count)){printk("copy to user fail \n");return -EFAULT;}}else{printk("read size must be less than %d\n", BUF_SIZE);return -EINVAL;}*offset += count;return count;
}
//字符设备写值
static ssize_t step_chardev_write(struct file *file, const char __user *buf,size_t const count,loff_t *offset)
{if(count < BUF_SIZE){if(copy_from_user(tmpbuf,buf,count)){printk("copy from user fail \n");return -EFAULT;}}else{printk("size must be less than %d\n", BUF_SIZE);return -EINVAL;}*offset += count;return count;
}
//字符设备ied的正传
void step_motor_forward(int speed)
{gpio_direction_output( step_moter[0].io_port,1);gpio_direction_output( step_moter[1].io_port,0);gpio_direction_output( step_moter[2].io_port,0);gpio_direction_output( step_moter[3].io_port,0);mdelay(speed);gpio_direction_output( step_moter[0].io_port,0);gpio_direction_output( step_moter[1].io_port,1);mdelay(speed);gpio_direction_output(step_moter[1].io_port,0);gpio_direction_output( step_moter[2].io_port,1);mdelay(speed);gpio_direction_output(step_moter[2].io_port,0);gpio_direction_output( step_moter[3].io_port,1);mdelay(speed);	
}
字符设备
void step_motor_backward(int speed)
{gpio_direction_output( step_motor[0].io_port,1);gpio_direction_output( step_motor[1].io_port,0);gpio_direction_output( step_motor[2].io_port,0);gpio_direction_output( step_motor[3].io_port,0);mdelay(speed);gpio_direction_output( step_motor[0].io_port,1);gpio_direction_output( step_motor[3].io_port,1);mdelay(speed);gpio_direction_output( step_motor[3].io_port,0);gpio_direction_output( step_motor[2].io_port,1);mdelay(speed);gpio_direction_output( step_motor[2].io_port,0);gpio_direction_output( step_motor[1].io_port,1);mdelay(speed);	
}//字符设备控制函数
static long step_chardev_ioctl(struct file *filep, unsigned int cmd, unsigned long arg)
{printk("test-ioctl: param %u %lu\n", cmd, arg);switch(cmd){case 1:{step_motor_forward(arg);break;}case 2:{step_motor_backward(arg);break;}case 3:{step_motor_backward(arg);break;}default:printk(" Unkown key");break;}return 0;
}
文件操作集
static struct file_operations chardev_fops={.owner = THIS_MODULE,.open = step_chardev_open,.release = step_chardev_release,.read = step_chardev_read,.write = step_chardev_write,.unlocked_ioctl = step_chardev_ioctl,//.ioctl = step_chardev_ioctl,
};//驱动的初始化函数--->从内核中申请资源(内核、中断、设备号、锁....)
static int  __init  step_motor_init(void)
{	int result;if(StepMajor){dev=MKDEV(StepMajor,StepMinor);result=register_chrdev_region(dev,1,DEVICE_NAME);} else {result=register_chrdev_region(dev,1,DEVICE_NAME);StepMajor=MAJOR(dev);dev=MKDEV(StepMajor,StepMinor);}if(result<0){printk(KERN_WARNING"LED: cannot get major %d \n",StepMajor);return result;}step_cdev=cdev_alloc();cdev_init(step_cdev,&chardev_fops);step_cdev->owner=THIS_MODULE;result=cdev_add(step_cdev,dev,1);if(result)printk("<1>Error %d while register led device!\n",result);my_class = class_create(THIS_MODULE,DEVICE_NAME);if(IS_ERR(my_class)){printk("Failed to create class \n");return -1;}device_create(my_class,NULL,dev,NULL,DEVICE_NAME);	return 0;
}
//驱动退出函数 --->将申请的资源还给内核
static void __exit  step_motor_exit(void)
{unregister_chrdev_region(MKDEV(StepMajor,StepMinor),1);cdev_del(step_cdev);	device_destroy(my_class,MKDEV(StepMajor,StepMinor));class_destroy(my_class);	
}module_init(step_motor_init); //驱动的入口函数会调用一个用户的初始化函数
module_exit(step_motor_exit); //驱动的出口函数会调用一个用户的退出函数
//驱动的描述信息: #modinfo  *.ko , 驱动的描述信息并不是必需的。
MODULE_AUTHOR("SUGAR@NNLG");                         //驱动的作者
MODULE_DESCRIPTION("Step_Motor of driver");         //驱动的描述
MODULE_LICENSE("GPL");                              //遵循的协议

 

3.1.2.3 负载调控

        负载调控中,在环境变量超过阈值时,采用继电器吸合,改变电路连接状态,切断负载的供电。在该电路中,VDD_5V为电源,C64和C65起到滤波作用,稳定电源电压。当环境变量(如温度、烟雾浓度等 )超过阈值,微控制器通过 XEINT23_B引脚输出信号,经R107限流后输入到三极管Q1(8050)的基极,使Q1导通。此时继电器U22(HK4100)的线圈得电,继电器吸合,改变电路连接状态,切断负载(通过USBJACK连接的设备)的供电。D17(1N4004)为续流二极管,防止继电器线圈断电时产生的反向电动势损坏元件。D18(LED-B)可用于指示继电器工作状态。

3.1.3 状态指示与报警监测模块

3.1.3.1 发光小灯状态指示

        发光小灯用于指示温度、湿度、光照强度和烟雾浓度是否超过阈值,对应灯亮起,表示该参数值超过阈值。

        温度指示灯在ADC模块中,通过ADC通道(如XadcAIN1、XadcAIN2、XadcAIN3)检测温度传感器信号,并通过GPIO控制LED;湿度指示灯在ADC模块中,与DHT11传感器相关,通过XEINT24_B或XEINT26等GPIO控制LED;光照强度指示灯在 LIGHT SENSOR部分,通过XadcAIN1或 XadcAIN2检测光照,LED连接到VDD_IO 或 VDD18V;烟雾浓度指示灯在MQ-2模块或通过ADC检测烟雾传感器信号,LED控制信号可连接到XEINT27或XEINT29。

发光指示灯驱动代码如下所示:
#include <linux/fs.h>
#include <linux/module.h>
#include <linux/kernel.h>
#include <linux/init.h>
#include <linux/platform_device.h>
#include <linux/miscdevice.h>
#include <linux/gpio.h>
#include "led_cmd.h"
#include <linux/io.h>#define DEVICE_NAME		"led4"                //设备名字
struct resource *myLedRes;
unsigned int led_gpio[4];
//led_open 函数
static int led_open(struct inode *inode, struct file *filp)
{printk(DEVICE_NAME ":open!!!\n");return 0;
}
//LED 控制函数
static long gec6818_leds_ioctl(struct file *filp, unsigned int cmd,unsigned long arg)
{#if 1printk("led_num = %d \n", LED_NUM);if(_IOC_TYPE(cmd) != LED_MAGIC) return - EINVAL;if(_IOC_NR(cmd) > LED_MAX_NR) return - EINVAL; gpio_set_value(led_gpio[_IOC_NR(cmd)], arg);printk(DEVICE_NAME": %d %lu\n", _IOC_NR(cmd), arg);#endif//printk("xxxx %lu, %d xxxxx \n", cmd, arg);return 0;
}
//文件操作集
static struct file_operations led_fops = {.owner  = THIS_MODULE,.open = led_open,.unlocked_ioctl = gec6818_leds_ioctl,
};
//杂项设备
static struct miscdevice misc = {.minor		= MISC_DYNAMIC_MINOR, //杂项设备主设备号10 ,自动分配次设备号.name		= DEVICE_NAME,    //生成设备文件的名字.fops		= &led_fops,
};
//device  和 driver 匹配成功后,会自动调用该函数
//*dev -->与该platform driver匹配的platform device
static int __devinit gec6818_led_probe(struct platform_device *pdev)
{int i, ret;for(i=0; i< 4; i++){myLedRes = platform_get_resource(pdev, IORESOURCE_MEM,i);if(myLedRes == NULL){printk("<0>""Error while get the myLedRes %i\n",i);return -EBUSY;}else{led_gpio[i] = myLedRes->start;ret = gpio_request(led_gpio[i],"led_gpio");if(ret <0 ){printk("fail to request led gpio \n");return ret;}gpio_direction_output(led_gpio[i], 0);}}ret = misc_register(&misc);   //注册杂项设备pr_err(DEVICE_NAME"\tinitialized\n");return ret;
}
static int __devexit gec6818_led_remove(struct platform_device *dev)
{int i;//释放管脚for (i = 0; i < LED_NUM; i++){gpio_free(led_gpio[i]);}misc_deregister(&misc);return 0;
}
static struct platform_driver gec6818_led_driver = {.probe  = gec6818_led_probe,.remove = __devexit_p(gec6818_led_remove),.driver = {.owner = THIS_MODULE,.name  = "led4_driver",	  //buttons_driver必须和设备的名字一致。},	
};
//驱动的初始化函数--->从内核中申请资源
static int __init led_dev_init(void)
{int ret;ret = platform_driver_register(&gec6818_led_driver);return ret;
}
//驱动退出函数 --->将申请的资源还给内核
static void __exit led_dev_exit(void)
{platform_driver_unregister(&gec6818_led_driver);
}
module_init(led_dev_init);                       //驱动的入口函数会调用一个用户的初始化函数
module_exit(led_dev_exit);                       //驱动的出口函数会调用一个用户的退出函数
//驱动的描述信息: #modinfo  *.ko , 驱动的描述信息并不是必需的。
MODULE_AUTHOR("sugar@NNLG");                         //驱动的作者
MODULE_DESCRIPTION("led of driver");            //驱动的描述
MODULE_LICENSE("GPL");                              //遵循的协议
MODULE_VERSION("v1.0");

编译过程省略。

3.1.3.1 报警监测

        报警检测中,采用蜂鸣器,通过PWN脉冲宽度调制技术实现报警功能。VDD_5V为蜂鸣器Buzzer1提供工作电源。微控制器输出的PWM信号通过PWM2引脚,经电阻R117(1KΩ)限流后输入到三极管Q3(型号9014)的基极。当PWM信号为高电平时,三极管Q3导通,使得电源电压能够施加到蜂鸣器两端,蜂鸣器得电发声;当PWM信号为低电平时,三极管Q3截止,蜂鸣器失电停止发声 。通过改变PWM信号的频率和占空比,可控制蜂鸣器发出不同频率和响度的声音,从而实现不同模式的报警功能。

蜂鸣器驱动代码如下所示:
#include <linux/module.h>
#include <linux/kernel.h>
#include <linux/cdev.h>
#include <linux/uaccess.h>
#include <linux/fs.h>
#include <linux/ioport.h>
#include <linux/miscdevice.h>
#include <linux/ioctl.h>
#include <linux/delay.h>
#include <linux/gpio.h>
#include <cfg_type.h>
#include <linux/platform_device.h>
#include <linux/err.h>
#include <linux/io.h>
#include <linux/init.h>
#include <linux/pwm.h>
#include <linux/slab.h>
#include <mach/platform.h>
#include <mach/devices.h>
#include <mach/soc.h>
#include "led_cmd.h"
#define DEVICE_NAME				"pwm"
#define NS_IN_1HZ				(1000000000UL)
#define BUZZER_PWM_ID			2
#define BUZZER_PMW_GPIO			(????)static struct pwm_device *pwm2buzzer;
static struct semaphore lock;
static void pwm_set_freq(unsigned long freq) {int period_ns = NS_IN_1HZ / freq;pwm_config(pwm2buzzer, period_ns / 2, period_ns);pwm_enable(pwm2buzzer);
}
static void pwm_stop(void) {pwm_config(pwm2buzzer, 0, NS_IN_1HZ / 100);pwm_disable(pwm2buzzer);
}
static int gec6818_pwm_open(struct inode *inode, struct file *file) {if (!down_trylock(&lock))return 0;elsereturn -EBUSY;
}
static int gec6818_pwm_close(struct inode *inode, struct file *file) {up(&lock);return 0;
}
static long gec6818_pwm_ioctl(struct file *filep, unsigned int cmd,unsigned long arg)
{//if(_IOC_TYPE(cmd) != PWM_MAGIC) return - EINVAL;//if(_IOC_NR(cmd) > PWM_MAX_NR) return - EINVAL; switch ( ????) {    //根据命令序列号控制蜂鸣器的状态case BUZZER_IOCTL_SET_FREQ:if (arg == 0)return -EINVAL;pwm_set_freq(arg);break;case BUZZER_IOCTL_STOP:default:pwm_stop();break;}return 0;
}
static struct file_operations gec6818_pwm_ops = {.owner			= THIS_MODULE,.open			= gec6818_pwm_open,.release		= gec6818_pwm_close, .unlocked_ioctl	= gec6818_pwm_ioctl,
};
static struct miscdevice gec6818_misc_dev = {.minor = MISC_DYNAMIC_MINOR,.name = DEVICE_NAME,.fops = &gec6818_pwm_ops,
};
static int __init gec6818_pwm_dev_init(void) {int ret;ret = gpio_request(BUZZER_PMW_GPIO, DEVICE_NAME);if (ret) {printk("request GPIO %d for pwm failed\n", BUZZER_PMW_GPIO);return ret;}gpio_direction_output(BUZZER_PMW_GPIO, 0);pwm2buzzer = pwm_request(BUZZER_PMW_ID, DEVICE_NAME);if (IS_ERR(pwm2buzzer)) {printk("request pwm %d for %s failed\n", BUZZER_PWM_ID, DEVICE_NAME);return -ENODEV;}pwm_stop();gpio_free(BUZZER_PMW_GPIO);//init_MUTEX(&lock);sema_init(&lock,1);  //ret = misc_register(&gec6818_misc_dev);printk(DEVICE_NAME "\tinitialized\n");return ret;
}
static void __exit gec6818_pwm_dev_exit(void) {pwm_stop();misc_deregister(&gec6818_misc_dev);
}
module_init(gec6818_pwm_dev_init);
module_exit(gec6818_pwm_dev_exit);MODULE_LICENSE("GPL");
MODULE_AUTHOR("GEC Inc.");
MODULE_DESCRIPTION("S5PV6818 PWM Driver");

 四、QT页面设计

4.1 新建项目工程

1、点击菜单:File→New File or Project→Qt→Qt Desinger Form Class→Choose。

2、关联一个UI设计文件Dialog with Buttons Bottom→Next。

3、在Qt项目中选择类名:在Class name中输入类名→Next。

4、双击.ui结尾的文件,进入界面设计编辑器,通过布局管理、属性编辑、信号与槽连接的步骤实现进行多个UI界面的设计。

4.2 界面跳转

        Qt界面跳转可通过多种方式实现:

        多窗口切换:创建独立窗口实例,通过show()和hide()方法控制显示/隐藏(如主窗口与对话框切换),支持窗口间传参和状态保持。

       QStackedWidget:在同一窗口内管理多个页面,通过setCurrentIndex()按索引切换,适合向导或多步骤界面,轻量级且无需频繁创建/销毁窗口。

        QTabWidget:以选项卡形式组织页面,用户点击选项卡标签切换,界面直观,适合分类展示内容。
这些方式灵活适配不同场景,通过合理选择可实现流畅的用户界面导航。

        在本次环境系统设计中,通过loginDlg类的on_loginBtn_clicked槽函数中实现界面跳转。当用户点击登录按钮,若用户名输入框内容(去除首尾空格后)为“star”且密码输入框内容为“123456”,则创建Led窗口实例,设置其固定大小为 800×480,显示该窗口并关闭当前登录窗口;若用户名或密码错误,弹出警告消息框提示错误,清空用户名和密码输入框内容,并将光标移至用户名输入框具体代码参数设置。

4.3 信号与槽的关联

        在Qt中,信号与槽是对象间通信的核心机制,信号由对象状态改变时自动发出(如按钮点击),槽是接收信号的函数(如自定义处理函数或 Lambda 表达式)。通过QObject::connect()函数可手动关联信号与槽,格式为connect(信号发送者,&发送者类::信号,信号接收者,&接收者类::槽),也可通过Qt Designer实现自动关联(槽名需遵循on_对象名_信号名()规则。信号与槽的参数类型需匹配,支持参数过滤(槽可只接收部分信号参数),这种机制实现了组件间的松耦合,使代码结构清晰且易于维护。如下图3-37,在登陆界面的ui文件下对“告警值:”使用go to slot,能够跳转到对应的槽函数,快速关联信号与槽,实现组件的交互逻辑。

4.4 驱动程序的调用

        在Qt中通过“pen()函数调用驱动程序:首先需要包含对应的“<fcntl.h><unistd.h>头文件,然后使用open(/dev/设备名, O_RDWR)以读写模式打开设备文件并获取文件描述符(若返回值小于0则打开失败),接着通过read()write()ioctl()函数进行数据读写或设备控制,操作完成后使用close()关闭文件描述符,同时需注意权限问题、进行错误处理,复杂场景下可将操作放入独立线程避免阻塞UI

        例如对直流电机驱动程序的调用,首先通过open函数以读写模式(O_RDWR)打开直流电机设备文件/dev/dc_motor ,尝试获取对直流电机驱动程序的访问权限。文件描述符fd用于后续对设备的操作。当open函数返回的fd小于 0 ,即设备文件打开失败时,使用perror打印错误信息,然后通过exit(1)终止程序。接着,使用ioctl函数对已打开的直流电机设备进行控制。通过传入不同的flag值(4 代表正转、1 代表反转、0 代表停止 ),向驱动程序传递控制指令。最后,使用close函数关闭之前打开的设备文件描述符fd,释放系统资源。

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。
如若转载,请注明出处:http://www.pswp.cn/bicheng/85484.shtml
繁体地址,请注明出处:http://hk.pswp.cn/bicheng/85484.shtml
英文地址,请注明出处:http://en.pswp.cn/bicheng/85484.shtml

如若内容造成侵权/违法违规/事实不符,请联系英文站点网进行投诉反馈email:809451989@qq.com,一经查实,立即删除!

相关文章

c++中std::transform详解和应用代码示例

std::transform 是 C 标准库中非常常用的算法之一&#xff0c;属于 <algorithm> 头文件。它的作用是将一个&#xff08;或两个&#xff09;序列中的元素通过某个函数进行变换&#xff0c;并将结果输出到另一个序列中。 一、std::transform 作用总结 std::transform 支持…

Yolov5 使用

1.开发背景 在已有的 Conda 环境下实现目标检测标定。 2.开发需求 实现演示例子的图片标定。 3.开发环境 Ubuntu20.04 Conda Yolov5 4.实现步骤 4.1 安装环境 # 创建环境 python 版本建议 3.9 以上 conda create -n yolov5 python3.9# 进入环境 conda activate yolov5# …

资深Java工程师的面试题目(四)性能优化

以下是针对Java性能优化的面试题&#xff0c;涵盖前后端技术栈的常见优化方式&#xff0c;适合评估候选人对性能调优的理解和实际应用能力&#xff1a; 1. JVM性能调优 题目: 请说明JVM垃圾回收&#xff08;GC&#xff09;的常见类型及其适用场景&#xff0c;并描述如何通过J…

火山引擎TTS使用体验

文章目录 前言1. 简介1.1 能力体验1.2 功能特性1.3 音色列表1.4 收费情况 2. 开启服务2.1 创建应用2.3 使用服务介绍 3.Websocket接入演示3.1 编写demo3.2 代码解释3.4运行demo 4. 参考链接 前言 语音合成TTS&#xff08;text to Speech&#xff09;是我觉得后续开发产品所不可…

Django中使用流式响应,自己也能实现ChatGPT的效果

最近在研究ChatGPT的时候&#xff0c;想通过openai提供的接口使国内用户也可以无限制访问&#xff0c;于是打算基于django开发一款应用。页面的渲染也得想ChatGPT一样采用流式响应&#xff0c;django中StreamingHttpResponse是支持流式响应的一种方式。 django 代码 class Ch…

Python Redis 简介

Redis 是一个高性能的内存键值数据库&#xff0c;支持多种数据结构&#xff08;字符串、列表、哈希、集合等&#xff09;&#xff0c;常用于缓存、消息队列和实时数据处理。Python 通过 redis-py 库与 Redis 交互。 核心功能 内存存储&#xff1a;数据存储在内存中&#xff0c…

mac安装whistle代理抓包工具(支持mock)

工具地址&#xff1a;https://wproxy.org/whistle/ 1、 安装nodejs环境 参考方法&#xff1a;https://github.com/nvm-sh/nvm 1&#xff09;安装 curl -o- https://raw.githubusercontent.com/nvm-sh/nvm/v0.40.3/install.sh | bash如图&#xff0c;安装成功 2&#xff09;…

基于 mydumper 实现 MySQL 定期全量备份、恢复方案

一、Mydumper 工具介绍 mydumper 是一款社区开源的逻辑备份工具,由 C 语言编写,与 MySQL 官方提供的 mysqldump 相比,它具有更高的性能和更多的功能,例如: • 支持多线程导出数据,速度更快; • 支持一致性备份; • 支持将导出文件压缩,节约空间; • 支持多线程恢复;…

C++中,std::async 一个用于异步编程的工具

在C中&#xff0c;std::async 是一个用于异步编程的工具&#xff0c;它允许你在一个单独的线程中执行任务&#xff0c;并返回一个 std::future 对象&#xff0c;通过这个对象可以获取任务的结果或者检查任务的状态。 基本用法1 lambda 表达式 #include <iostream> #incl…

【Linux驱动开发 ---- 4_驱动开发框架和 API】

Linux驱动开发 ---- 4_驱动开发框架和 API 目录 Linux驱动开发 ---- 4_驱动开发框架和 API&#x1f3af; 目标&#xff1a;&#x1f4cc; 1. Linux 设备模型&#xff08;Linux Device Model&#xff09;**设备模型的核心概念**&#xff1a; &#x1f4cc; 2. 设备树&#xff08…

实景VR展厅建设流程

实景VR展厅&#xff1a;建设流程、用途、案例与未来发展 随着虚拟现实&#xff08;VR&#xff09;技术的发展&#xff0c;实景VR展厅作为一种创新的展示方式&#xff0c;正在各个领域得到广泛应用。实景VR展厅提供沉浸式的体验&#xff0c;丰富展示内容和形式&#xff0c;为观…

android下拉栏添加媒体音量调节

参考下拉栏的屏幕亮度调节&#xff0c;添加媒体音量调节。 平台信息&#xff1a; MSM8909.LA.3.1.2_AOSP PLATFORM_VERSION9 BUILD_IDPKQ1.190903.001 效果图 布局文件与音量图标 Index: frameworks/base/packages/SystemUI/res/layout/quick_settings_media_volume_dialog.x…

VS Code 配置ROS2开发环境常见问题记录

1、ctrlshiftp后找不到C/C: Edit configurations 安装或重装C插件。 参考链接&#xff1a; 搜索C/C: Edit configurations显示no matching command问题https://www.cnblogs.com/hunghau/p/17195622.html 2、ROS2 API无法转到定义 &#xff08;1&#xff09;在c_cpp_proper…

Docker Desktop搭建RocketMQ的完整教程

Docker Desktop搭建RocketMQ图文教程 1. 准备工作 已安装Docker Desktop&#xff08;本地安装方法参考上一节教程&#xff09;。需部署三个组件&#xff1a;NameServer、Broker、Console&#xff08;管理界面&#xff09;。 2. 创建目录和文件 在任意盘&#xff08;如D盘&am…

算法35天|1049. 最后一块石头的重量 II、 494. 目标和、 474.一和零

1049. 最后一块石头的重量 II 题目 思路与解法 class Solution { public:int lastStoneWeightII(vector<int>& stones) {int sum 0;for(int i0;i<stones.size();i){sum stones[i];}// 问题转换为&#xff1a;// 先求得&#xff0c;背包容量为target时&#x…

AWS S3拒绝非https的请求访问

问题 aws s3桶&#xff0c;安全要求必须强制使用ssl加密访问&#xff0c;即https。需要添加一个策略拒绝所有不是https的访问s3桶请求。 解决 在对于桶添加相关拒绝策略即可。如下&#xff1a; {"Version": "2012-10-17","Statement": [{&qu…

GitLab CVE-2025-4278 安全漏洞解决方案

本分分享极狐GitLab 补丁版本 18.0.2, 17.11.4, 17.10.8 的详细内容。这几个版本包含重要的缺陷和安全修复代码&#xff0c;我们强烈建议所有私有化部署用户应该立即升级到上述的某一个版本。对于极狐GitLab SaaS&#xff0c;技术团队已经进行了升级&#xff0c;无需用户采取任…

Async、await是什么?跟promise有什么区别?使用的好处是什么

Async/Await 与 Promise 的深度解析 一、基本概念 1. Promise Promise 是 ES6 引入的异步编程解决方案&#xff0c;表示一个异步操作的最终完成&#xff08;或失败&#xff09;及其结果值。 function fetchData() {return new Promise((resolve, reject) > {setTimeout(…

MySQL数据库中所有表的空间占用与行数统计

查看某个数据库中所有表的空间与行数统计 SELECT TABLE_NAME AS 表名,TABLE_ROWS AS 行数,ROUND(DATA_LENGTH / 1024 / 1024, 2) AS 数据大小(MB),ROUND(INDEX_LENGTH / 1024 / 1024, 2) AS 索引大小(MB),ROUND((DATA_LENGTH INDEX_LENGTH) / 1024 / 1024, 2) AS 总占用空间(…

el-upload 点击上传按钮前先判断条件满足再弹选择文件框

解决思路&#xff1a; 先写一个上传按钮&#xff0c;点击上传按钮后判断条件是否满足&#xff0c;满足则显示上传组件并使用ref来控制点击事件&#xff0c;隐藏自身。 注&#xff1a;上传成功或者上传失败时或者上传前判断条件添加不满足return将this.isShow true 代码部分…