直流无刷电机控制(FOC):电流模式
目录
概述
1 系统框架结构
1.1 硬件模块介绍
1.2 硬件实物图
1.3 引脚接口定义
2 代码实现
2.1 软件架构
2.2 电流检测函数
3 电流环功能实现
3.1 代码实现
3.2 测试代码实现
4 测试
概述
本文主要介绍基于DengFOC的库函数,实现直流无刷电机控制(FOC)的电流环控制。笔者详细介绍了电流环采样电流时用到的函数。DengFOC的软件架构,电流环模式实现的原理等内容。
源代码下载地址:
dengfoctestdemo资源-CSDN文库
1 系统框架结构
1.1 硬件模块介绍
系统硬件框架结构功能如下:
电机模块: 2208直流无刷电机(数量:1)
编码器: 选用AS5600编码器,用于获取当前电机转动的角度,其通过I2C接口与MCU进行通信
驱动板(FOC): 通过接收到MCU传送的PWM芯片,直接作用到MOS管上,以驱动直流无刷电机工作。
主控模块:使用ESP32 ( ESP32-WROOM-32E)
电流检测功能: 使用MCU ADC功能检测INA240的输出电压值
1.2 硬件实物图
1.3 引脚接口定义
1) 电机驱动板与电机之间的接口
2)编码器与MCU接口
3)电流检测
2 代码实现
2.1 软件架构
2.2 电流检测函数
1)源代码介绍
代码12行: 定义参考电压值
代码13行: ADC的最大值(12bit )
代码16: 计算比率
代码25~26行: 定义ADC的端口
代码28行: 分流电阻
代码29行: 电流放大倍数
代码31行: 电流放大的比率
代码55~59行: 获取ADC的count值
代码61~66行: 配置ADC的端口模式
代码69~91行: 获取ADC的均值
代码93~99行: 读电流参数初始化
代码104~109行: 获取电流值
2)源代码文件
编写InlineCurrent.c文件的内容
#include <Arduino.h>
#include "InlineCurrent.h"// - shunt_resistor - 分流电阻值
// - gain - 电流检测运算放大器增益
// - phA - A 相 adc 引脚
// - phB - B 相 adc 引脚
// - phC - C 相 adc 引脚(可选)#define _ADC_VOLTAGE 3.3f //ADC 电压
#define _ADC_RESOLUTION 4095.0f //ADC 分辨率// ADC 计数到电压转换比率求解
#define _ADC_CONV ( (_ADC_VOLTAGE) / (_ADC_RESOLUTION) )#define NOT_SET -12345.0
#define _isset(a) ( (a) != (NOT_SET) )CurrSense::CurrSense(int Mot_Num)
{if(Mot_Num==0){pinA = 39;pinB = 36;//int pinC;_shunt_resistor = 0.01;amp_gain = 50;volts_to_amps_ratio = 1.0f /_shunt_resistor / amp_gain; // volts to amps// gains for each phasegain_a = volts_to_amps_ratio*-1;gain_b = volts_to_amps_ratio*-1;gain_c = volts_to_amps_ratio;}if(Mot_Num==1){pinA = 35;pinB = 34;//int pinC;_shunt_resistor = 0.01;amp_gain = 50;volts_to_amps_ratio = 1.0f /_shunt_resistor / amp_gain; // volts to amps// gains for each phasegain_a = volts_to_amps_ratio*-1;gain_b = volts_to_amps_ratio*-1;gain_c = volts_to_amps_ratio;}
}
float CurrSense::readADCVoltageInline(const int pinA)
{uint32_t raw_adc = analogRead(pinA);return raw_adc * _ADC_CONV;
}void CurrSense::configureADCInline(const int pinA,const int pinB, const int pinC)
{pinMode(pinA, INPUT);pinMode(pinB, INPUT);if( _isset(pinC) ) pinMode(pinC, INPUT);
}// 查找 ADC 零偏移量的函数
void CurrSense::calibrateOffsets()
{const int calibration_rounds = 1000;// 查找0电流时候的电压offset_ia = 0;offset_ib = 0;offset_ic = 0;// 读数1000次for (int i = 0; i < calibration_rounds; i++) {offset_ia += readADCVoltageInline(pinA);offset_ib += readADCVoltageInline(pinB);if(_isset(pinC)) offset_ic += readADCVoltageInline(pinC);delay(1);}// 求平均,得到误差offset_ia = offset_ia / calibration_rounds;offset_ib = offset_ib / calibration_rounds;if(_isset(pinC)) offset_ic = offset_ic / calibration_rounds;
}void CurrSense::init()
{// 配置函数configureADCInline(pinA,pinB,pinC);// 校准calibrateOffsets();
}// 读取全部三相电流void CurrSense::getPhaseCurrents()
{current_a = (readADCVoltageInline(pinA) - offset_ia)*gain_a;// ampscurrent_b = (readADCVoltageInline(pinB) - offset_ib)*gain_b;// ampscurrent_c = (!_isset(pinC)) ? 0 : (readADCVoltageInline(pinC) - offset_ic)*gain_c; // amps
}
编写InlineCurrent.h文件的内容
#include <Arduino.h>class CurrSense
{public:CurrSense(int Mot_Num);float readADCVoltageInline(const int pinA);void configureADCInline(const int pinA,const int pinB, const int pinC);void calibrateOffsets();void init();void getPhaseCurrents();float current_a,current_b,current_c;int pinA;int pinB;int pinC;float offset_ia;float offset_ib;float offset_ic;float _shunt_resistor;float amp_gain;float volts_to_amps_ratio;float gain_a;float gain_b;float gain_c;private:int _Mot_Num;
};
3 电流环功能实现
3.1 代码实现
代码29行: 设置电流环的PID参数
代码36行: 创建电流环的Obj
代码57~63行: 设置电流环参数PID函数
代码271~278行: 获取电流数据函数
代码283~293行: 获取IQ电流值
代码295~300行: 电流滤波函数
dengFOC.c 源文件内容:
#include <Arduino.h>
#include "AS5600.h"
#include "lowpass_filter.h"
#include "pid.h"
#include "InlineCurrent.h" //引入在线电流检测#define _1_SQRT3 0.57735026919f
#define _2_SQRT3 1.15470053838f
//低通滤波初始化
LowPassFilter M0_Vel_Flt = LowPassFilter(0.01); // Tf = 10ms //M0速度环
LowPassFilter M0_Curr_Flt = LowPassFilter(0.05); // Tf = 5ms //M0电流环#define _constrain(amt,low,high) ((amt)<(low)?(low):((amt)>(high)?(high):(amt)))
float voltage_power_supply;
float Ualpha,Ubeta=0,Ua=0,Ub=0,Uc=0;#define _3PI_2 4.71238898038f
float zero_electric_angle=0;int PP=1,DIR=1;
int pwmA = 32;
int pwmB = 33;
int pwmC = 25;//PID
PIDController vel_loop_M0 = PIDController{.P = 2, .I = 0, .D = 0, .ramp = 100000, .limit = voltage_power_supply/2};
PIDController angle_loop_M0 = PIDController{.P = 2, .I = 0, .D = 0, .ramp = 100000, .limit = 100};PIDController current_loop_M0 = PIDController{.P = 1.2, .I = 0, .D = 0, .ramp = 100000, .limit = 12.6};//AS5600
Sensor_AS5600 S0=Sensor_AS5600(0);
TwoWire S0_I2C = TwoWire(0);//初始化电流闭环
CurrSense CS_M0= CurrSense(0);//=================PID 设置函数=================
//速度PID
void DFOC_M0_SET_VEL_PID(float P,float I,float D,float ramp) //M0角度环PID设置
{vel_loop_M0.P=P;vel_loop_M0.I=I;vel_loop_M0.D=D;vel_loop_M0.output_ramp=ramp;
}//角度PID
void DFOC_M0_SET_ANGLE_PID(float P,float I,float D,float ramp) //M0角度环PID设置
{angle_loop_M0.P=P;angle_loop_M0.I=I;angle_loop_M0.D=D;angle_loop_M0.output_ramp=ramp;
}void DFOC_M0_SET_CURRENT_PID(float P,float I,float D,float ramp) //M0电流环PID设置
{current_loop_M0.P=P;current_loop_M0.I=I;current_loop_M0.D=D;current_loop_M0.output_ramp=ramp;
}//M0速度PID接口
float DFOC_M0_VEL_PID(float error) //M0速度环
{return vel_loop_M0(error);}//M0角度PID接口
float DFOC_M0_ANGLE_PID(float error)
{return angle_loop_M0(error);
}//初始变量及函数定义
#define _constrain(amt,low,high) ((amt)<(low)?(low):((amt)>(high)?(high):(amt)))
//宏定义实现的一个约束函数,用于限制一个值的范围。
//具体来说,该宏定义的名称为 _constrain,接受三个参数 amt、low 和 high,分别表示要限制的值、最小值和最大值。该宏定义的实现使用了三元运算符,根据 amt 是否小于 low 或大于 high,返回其中的最大或最小值,或者返回原值。
//换句话说,如果 amt 小于 low,则返回 low;如果 amt 大于 high,则返回 high;否则返回 amt。这样,_constrain(amt, low, high) 就会将 amt 约束在 [low, high] 的范围内。1// 归一化角度到 [0,2PI]
float _normalizeAngle(float angle)
{float a = fmod(angle, 2*PI); //取余运算可以用于归一化,列出特殊值例子算便知return a >= 0 ? a : (a + 2*PI); //三目运算符。格式:condition ? expr1 : expr2 //其中,condition 是要求值的条件表达式,如果条件成立,则返回 expr1 的值,否则返回 expr2 的值。可以将三目运算符视为 if-else 语句的简化形式。//fmod 函数的余数的符号与除数相同。因此,当 angle 的值为负数时,余数的符号将与 _2PI 的符号相反。也就是说,如果 angle 的值小于 0 且 _2PI 的值为正数,则 fmod(angle, _2PI) 的余数将为负数。//例如,当 angle 的值为 -PI/2,_2PI 的值为 2PI 时,fmod(angle, _2PI) 将返回一个负数。在这种情况下,可以通过将负数的余数加上 _2PI 来将角度归一化到 [0, 2PI] 的范围内,以确保角度的值始终为正数。
}// 设置PWM到控制器输出
void setPwm(float Ua, float Ub, float Uc)
{// 限制上限Ua = _constrain(Ua, 0.0f, voltage_power_supply);Ub = _constrain(Ub, 0.0f, voltage_power_supply);Uc = _constrain(Uc, 0.0f, voltage_power_supply);// 计算占空比// 限制占空比从0到1float dc_a = _constrain(Ua / voltage_power_supply, 0.0f , 1.0f );float dc_b = _constrain(Ub / voltage_power_supply, 0.0f , 1.0f );float dc_c = _constrain(Uc / voltage_power_supply, 0.0f , 1.0f );//写入PWM到PWM 0 1 2 通道ledcWrite(0, dc_a*255);ledcWrite(1, dc_b*255);ledcWrite(2, dc_c*255);
}void setTorque(float Uq,float angle_el)
{S0.Sensor_update(); //更新传感器数值Uq=_constrain(Uq,-(voltage_power_supply)/2,(voltage_power_supply)/2);float Ud=0;angle_el = _normalizeAngle(angle_el);// 帕克逆变换Ualpha = -Uq*sin(angle_el); Ubeta = Uq*cos(angle_el); // 克拉克逆变换Ua = Ualpha + voltage_power_supply/2;Ub = (sqrt(3)*Ubeta-Ualpha)/2 + voltage_power_supply/2;Uc = (-Ualpha-sqrt(3)*Ubeta)/2 + voltage_power_supply/2;setPwm(Ua,Ub,Uc);
}void DFOC_Vbus(float power_supply)
{voltage_power_supply=power_supply;pinMode(pwmA, OUTPUT);pinMode(pwmB, OUTPUT);pinMode(pwmC, OUTPUT);ledcSetup(0, 30000, 8); //pwm频道, 频率, 精度ledcSetup(1, 30000, 8); //pwm频道, 频率, 精度ledcSetup(2, 30000, 8); //pwm频道, 频率, 精度ledcAttachPin(pwmA, 0);ledcAttachPin(pwmB, 1);ledcAttachPin(pwmC, 2);Serial.println("完成PWM初始化设置");//AS5600S0_I2C.begin(19,18, 400000UL);S0.Sensor_init(&S0_I2C); //初始化编码器0Serial.println("编码器加载完毕");//PID 加载vel_loop_M0 = PIDController{.P = 2, .I = 0, .D = 0, .ramp = 100000, .limit = voltage_power_supply/2};//初始化电流传感器CS_M0.init();}float _electricalAngle()
{return _normalizeAngle((float)(DIR * PP) * S0.getMechanicalAngle()-zero_electric_angle);
}void DFOC_alignSensor(int _PP,int _DIR)
{ PP=_PP;DIR=_DIR;setTorque(3, _3PI_2); //起劲delay(1000);S0.Sensor_update(); //更新角度,方便下面电角度读取zero_electric_angle=_electricalAngle();setTorque(0, _3PI_2); //松劲(解除校准)Serial.print("0电角度:");Serial.println(zero_electric_angle);
}float DFOC_M0_Angle()
{return DIR*S0.getAngle();
}//无滤波
//float DFOC_M0_Velocity()
//{
// return DIR*S0.getVelocity();
//}//有滤波
float DFOC_M0_Velocity()
{//获取速度数据并滤波float vel_M0_ori=S0.getVelocity();float vel_M0_flit=M0_Vel_Flt(DIR*vel_M0_ori);return vel_M0_flit; //考虑方向
}//==============串口接收==============
float motor_target;
int commaPosition;
String serialReceiveUserCommand() {// a string to hold incoming datastatic String received_chars;String command = "";while (Serial.available()) {// get the new byte:char inChar = (char)Serial.read();// add it to the string buffer:received_chars += inChar;// end of user inputif (inChar == '\n') {// execute the user commandcommand = received_chars;commaPosition = command.indexOf('\n');//检测字符串中的逗号if(commaPosition != -1)//如果有逗号存在就向下执行{motor_target = command.substring(0,commaPosition).toDouble(); //电机角度Serial.println(motor_target);}// reset the command buffer received_chars = "";}}return command;
}float serial_motor_target()
{return motor_target;
}//================简易接口函数================
void DFOC_M0_set_Velocity_Angle(float Target)
{setTorque(DFOC_M0_VEL_PID(DFOC_M0_ANGLE_PID((Target-DFOC_M0_Angle())*180/PI)),_electricalAngle()); //角度闭环
}void DFOC_M0_setVelocity(float Target)
{setTorque(DFOC_M0_VEL_PID((serial_motor_target()-DFOC_M0_Velocity())*180/PI),_electricalAngle()); //速度闭环
}void DFOC_M0_set_Force_Angle(float Target) //力位
{setTorque(DFOC_M0_ANGLE_PID((Target-DFOC_M0_Angle())*180/PI),_electricalAngle());
}void DFOC_M0_setTorque(float Target)
{setTorque(Target,_electricalAngle());
}void runFOC()
{//====传感器更新====// S0.Sensor_update();CS_M0.getPhaseCurrents();//====传感器更新====
}//=========================电流读取=========================//通过Ia,Ib,Ic计算Iq,Id(目前仅输出Iq)
float cal_Iq_Id(float current_a,float current_b,float angle_el)
{float I_alpha=current_a;float I_beta = _1_SQRT3 * current_a + _2_SQRT3 * current_b;float ct = cos(angle_el);float st = sin(angle_el);//float I_d = I_alpha * ct + I_beta * st;float I_q = I_beta * ct - I_alpha * st;return I_q;
}float DFOC_M0_Current()
{ float I_q_M0_ori=cal_Iq_Id(CS_M0.current_a,CS_M0.current_b,_electricalAngle());float I_q_M0_flit=M0_Curr_Flt(I_q_M0_ori);return I_q_M0_flit;
}
dengFOC.h 源文件内容:
//灯哥开源,遵循GNU协议,转载请著名版权!
//GNU开源协议(GNU General Public License, GPL)是一种自由软件许可协议,保障用户能够自由地使用、研究、分享和修改软件。
//该协议的主要特点是,要求任何修改或衍生的作品必须以相同的方式公开发布,即必须开源。此外,该协议也要求在使用或分发软件时,必须保留版权信息和许可协议。GNU开源协议是自由软件基金会(FSF)制定和维护的一种协议,常用于GNU计划的软件和其他自由软件中。
//仅在DengFOC官方硬件上测试过,欢迎硬件购买/支持作者,淘宝搜索店铺:灯哥开源
//你的支持将是接下来做视频和持续开源的经费,灯哥在这里先谢谢大家了
//函数声明void setPwm(float Ua, float Ub, float Uc);
float setTorque(float Uq,float angle_el);
float _normalizeAngle(float angle);
void DFOC_Vbus(float power_supply);
void DFOC_alignSensor(int _PP,int _DIR);
float _electricalAngle();float serial_motor_target();
String serialReceiveUserCommand();
//传感器读取
float DFOC_M0_Velocity();
float DFOC_M0_Angle();
//PID
void DFOC_M0_SET_ANGLE_PID(float P,float I,float D,float ramp);
void DFOC_M0_SET_VEL_PID(float P,float I,float D,float ramp);
float DFOC_M0_VEL_PID(float error);
float DFOC_M0_ANGLE_PID(float error);
void DFOC_M0_SET_CURRENT_PID(float P,float I,float D,float ramp);//接口函数
void DFOC_M0_set_Velocity_Angle(float Target);
void DFOC_M0_setVelocity(float Target);
void DFOC_M0_set_Force_Angle(float Target);
void DFOC_M0_setTorque(float Target);float DFOC_M0_Current();
float cal_Iq_Id(float current_a,float current_b,float angle_el);void runFOC();
3.2 测试代码实现
代码37行: 设置供电电压
代码38行: 设置电极数和编码器的方向
代码57行: 获取电流参数
代码58行: 设置PID参数
代码59行:设置执行单元
源代码如下:
/* USER CODE BEGIN Header */
/**
******************************************************************************
* File Name : foc_function_test.c
* Description : FOC 闭环各种模式测试
******************************************************************************
* @attention
*
* COPYRIGHT: Copyright (c) 2025 tangmingfei2013@126.com * CREATED BY: Alan.tang
* DATE: JAN 7th, 2025
* 参考代码: Deng FOC
*
******************************************************************************
*/
/* USER CODE END Header */#include "DengFOC.h"
const int LED_PIN = 2;int Sensor_DIR=-1; //传感器方向
int Motor_PP=7; //电机极对数
float Sensor_Vel;/*0: 电流模式 1: 速度模式2: 位置模式
*/
#define SELECT_MODE 0void setup()
{pinMode(LED_PIN, OUTPUT);digitalWrite(LED_PIN, LOW);digitalWrite(LED_PIN, HIGH);// put your setup code here, to run once:Serial.begin(115200);DFOC_Vbus(11.6); //设定驱动器供电电压DFOC_alignSensor(Motor_PP,Sensor_DIR);#if SELECT_MODE == 0// 设置电流模式闭环PIDDFOC_M0_SET_CURRENT_PID(5,200,0,100000);#elif SELECT_MODE == 1// 设置速度闭环PIDDFOC_M0_SET_VEL_PID(0.01,0.00,0,0);#elif SELECT_MODE == 2//设置位置模式闭环PIDDFOC_M0_SET_VEL_PID(0.01,0.00,0,0);DFOC_M0_SET_ANGLE_PID(0.5,0,0,0);
#endif }void postion_Mode_test( void )
{//设置速度DFOC_M0_set_Velocity_Angle(serial_motor_target());
}void velocity_Mode_test( void )
{//设置速度DFOC_M0_setVelocity(serial_motor_target());
}void current_Mode_test( void )
{static int count=0;// 电流模式runFOC();DFOC_M0_setTorque(serial_motor_target());count++;if(count>30){count=0;Serial.printf("%0.2f \n", DFOC_M0_Current());}
}void loop()
{
#if SELECT_MODE == 0current_Mode_test();
#elif SELECT_MODE == 1velocity_Mode_test();
#elif SELECT_MODE == 2postion_Mode_test();
#endif//接收串口serialReceiveUserCommand();
}
4 测试
1) 设置电流值为0时,电流的输出波形
2)设置电流为2
3)设置电流值为-2
测试视频如下:
直流无刷电机控制(FOC):电流模式测试视频
相关文章:

直流无刷电机控制(FOC):电流模式
目录 概述 1 系统框架结构 1.1 硬件模块介绍 1.2 硬件实物图 1.3 引脚接口定义 2 代码实现 2.1 软件架构 2.2 电流检测函数 3 电流环功能实现 3.1 代码实现 3.2 测试代码实现 4 测试 概述 本文主要介绍基于DengFOC的库函数,实现直流无刷电机控制&#x…...

73.矩阵置零 python
矩阵置零 题目题目描述示例 1:示例 2:提示: 题解思路分析Python 实现代码代码解释提交结果 题目 题目描述 给定一个 m x n 的矩阵,如果一个元素为 0 ,则将其所在行和列的所有元素都设为 0 。请使用 原地 算法。 示例…...
垃圾收集算法
分代收集理论 分代收集理论,建立在两个分代假说之上。 弱分代假说:绝大多数对象都是朝圣夕灭的。 强分代假说:熬过越多次垃圾收集的过程的对象就越难以消亡。 这两个分代假说奠定了垃圾收集器的一致设计原则:收集器应该将Java…...
SQL-leetcode-262. 行程和用户
262. 行程和用户 表:Trips --------------------- | Column Name | Type | --------------------- | id | int | | client_id | int | | driver_id | int | | city_id | int | | status | enum | | request_at | varchar | --------------------- id 是这张表的主键…...

太原理工大学软件设计与体系结构 --javaEE
这个是简答题的内容 选择题的一些老师会给你们题库,一些注意的点我会做出文档在这个网址 项目目录预览 - TYUT复习资料:复习资料 - GitCode 希望大家可以给我一些打赏 什么是Spring的IOC和DI IOC 是一种设计思想,它将对象的创建和对象之间的依赖关系…...

Leetcode 139. 单词拆分 动态规划
原题链接:Leetcode 139. 单词拆分 递归,超时 class Solution { public:bool isfind(string s,map<string,int>& mp){for(auto x:mp){string wordx.first;if(sword) return true;int nword.size();if(n>s.size()) continue;string s1s.subs…...

python异常机制
异常是什么? 软件程序在运行过程中,非常可能遇到刚刚提到的这些问题,我们称之为异常,英文是Exception,意思是例外。遇到这些例外情况,或者交异常,我们怎么让写的程序做出合理的处理,…...
运行爬虫时可能遇到哪些常见问题?
在运行Python爬虫时,可能会遇到以下一些常见问题及相应的解决方法: 1. 请求频繁被封 IP 问题描述:爬虫请求频繁时,网站可能会识别到异常行为并封禁 IP,从而导致后续请求失败。解决方法: 使用代理…...

BGP与CN2的区别 详解两者在网络传输中的应用与优势
在现代互联网环境中,选择合适的网络传输协议和解决方案对于企业的业务运行至关重要。BGP(Border Gateway Protocol)和CN2(China Telecom Next Carrier Network)是两种广泛应用的网络技术,但它们的设计理念、…...

Spring 项目 基于 Tomcat容器进行部署
文章目录 一、前置知识二、项目部署1. 将写好的 Spring 项目先打包成 war 包2. 查看项目工件(Artifact)是否存在3. 配置 Tomcat3.1 添加一个本地 Tomcat 容器3.2 将项目部署到 Tomcat 4. 运行项目 尽管市场上许多新项目都已经转向 Spring Boot࿰…...
“负载均衡”出站的功能、原理与场景案例
在企业日常网络中,外网访问速度不稳定是一个常见问题。特别是多条外网线路并行时,不合理的流量分配会导致资源浪费甚至网络拥堵。而出站负载均衡,正是解决这一问题的关键技术。 作为一种先进的网络流量管理技术,其核心是优化企业内…...

02-51单片机数码管与矩阵键盘
一、数码管模块 1.数码管介绍 如图所示为一个数码管的结构图: 说明: 数码管上下各有五个引脚,其中上下中间的两个引脚是联通的,一般为数码管的公共端,分为共阴极或共阳极;其它八个引脚分别对应八个二极管…...

不同方式获取音频时长 - python 实现
DataBall 助力快速掌握数据集的信息和使用方式,会员享有 百种数据集,持续增加中。 需要更多数据资源和技术解决方案,知识星球: “DataBall - X 数据球(free)” -------------------------------------------------------------…...

【python A* pygame 格式化 自定义起点、终点、障碍】
- pip install pygame test.py(chatgpt版本) 空格键:运行 A* 算法。CtrlC 键:清空路径。CtrlS 键:保存当前地图到 map.json 文件。CtrlL 键:从 map.json 文件加载地图。 import pygame import json from queue import PriorityQ…...
12_Redis发布订阅
1.Redis发布订阅介绍 1.1 基本概念 Redis的发布订阅(Pub/Sub)是一种消息通信模式,允许消息的发布者(Publisher)将消息发布到一个或多个频道(Channel),订阅者(Subscriber)通过订阅这些频道来接收消息。 发布者(Publisher):发送消息的一方,使用PUBLISH命令将消息…...

归并排序:数据排序的高效之道
🧑 博主简介:CSDN博客专家,历代文学网(PC端可以访问:https://literature.sinhy.com/#/literature?__c1000,移动端可微信小程序搜索“历代文学”)总架构师,15年工作经验,…...

【redis初阶】浅谈分布式系统
目录 一、常见概念 1.1 基本概念 2.2 评价指标(Metric) 二、架构演进 2.1 单机架构 2.2 应用数据分离架构 2.3 应用服务集群架构 2.4 读写分离/主从分离架构 2.5 引入缓存 ⸺ 冷热分离架构 2.6 数据库分库分表 2.7 业务拆分 ⸺ 引入微服务 redis学习&…...

CatLog的使用
一 CatLog的简介 1.1 作用 CAT(Central Application Tracking) 是基于 Java 开发的实时应用监控平台,为美团点评提供了全面的实时监控告警服务。 1.2 组成部分 1.2.1 Transaction 1.Transaction 适合记录跨越系统边界的程序访问行为&a…...
头歌python实验:网络安全应用实践-恶意流量检测
第1关:re 库的使用 本关任务:编写一个能正则匹配出 ip 地址的小程序。 re 的主要功能函数 常用的功能函数包括: compile、search、match、split、findall(finditer)、sub(subn)。 re.search 函数 re.search 扫描整个字符串并返回第一个成功的匹配。 函数语法: re…...

大模型WebUI:Gradio全解11——Chatbots:融合大模型的多模态聊天机器人(2)
大模型WebUI:Gradio全解11——Chatbots:融合大模型的聊天机器人(2) 前言本篇摘要11. Chatbot:融合大模型的多模态聊天机器人11.2 使用流行的LLM库和API11.2.1 Llama Index11.2.2 LangChain11.2.3 OpenAI1. 基本用法2. …...

龙虎榜——20250610
上证指数放量收阴线,个股多数下跌,盘中受消息影响大幅波动。 深证指数放量收阴线形成顶分型,指数短线有调整的需求,大概需要一两天。 2025年6月10日龙虎榜行业方向分析 1. 金融科技 代表标的:御银股份、雄帝科技 驱动…...
<6>-MySQL表的增删查改
目录 一,create(创建表) 二,retrieve(查询表) 1,select列 2,where条件 三,update(更新表) 四,delete(删除表…...

【Oracle APEX开发小技巧12】
有如下需求: 有一个问题反馈页面,要实现在apex页面展示能直观看到反馈时间超过7天未处理的数据,方便管理员及时处理反馈。 我的方法:直接将逻辑写在SQL中,这样可以直接在页面展示 完整代码: SELECTSF.FE…...
【AI学习】三、AI算法中的向量
在人工智能(AI)算法中,向量(Vector)是一种将现实世界中的数据(如图像、文本、音频等)转化为计算机可处理的数值型特征表示的工具。它是连接人类认知(如语义、视觉特征)与…...

UR 协作机器人「三剑客」:精密轻量担当(UR7e)、全能协作主力(UR12e)、重型任务专家(UR15)
UR协作机器人正以其卓越性能在现代制造业自动化中扮演重要角色。UR7e、UR12e和UR15通过创新技术和精准设计满足了不同行业的多样化需求。其中,UR15以其速度、精度及人工智能准备能力成为自动化领域的重要突破。UR7e和UR12e则在负载规格和市场定位上不断优化…...
聊一聊接口测试的意义有哪些?
目录 一、隔离性 & 早期测试 二、保障系统集成质量 三、验证业务逻辑的核心层 四、提升测试效率与覆盖度 五、系统稳定性的守护者 六、驱动团队协作与契约管理 七、性能与扩展性的前置评估 八、持续交付的核心支撑 接口测试的意义可以从四个维度展开,首…...

html css js网页制作成品——HTML+CSS榴莲商城网页设计(4页)附源码
目录 一、👨🎓网站题目 二、✍️网站描述 三、📚网站介绍 四、🌐网站效果 五、🪓 代码实现 🧱HTML 六、🥇 如何让学习不再盲目 七、🎁更多干货 一、👨…...

排序算法总结(C++)
目录 一、稳定性二、排序算法选择、冒泡、插入排序归并排序随机快速排序堆排序基数排序计数排序 三、总结 一、稳定性 排序算法的稳定性是指:同样大小的样本 **(同样大小的数据)**在排序之后不会改变原始的相对次序。 稳定性对基础类型对象…...

push [特殊字符] present
push 🆚 present 前言present和dismiss特点代码演示 push和pop特点代码演示 前言 在 iOS 开发中,push 和 present 是两种不同的视图控制器切换方式,它们有着显著的区别。 present和dismiss 特点 在当前控制器上方新建视图层级需要手动调用…...
MySQL 部分重点知识篇
一、数据库对象 1. 主键 定义 :主键是用于唯一标识表中每一行记录的字段或字段组合。它具有唯一性和非空性特点。 作用 :确保数据的完整性,便于数据的查询和管理。 示例 :在学生信息表中,学号可以作为主键ÿ…...