【STM32】飞控设计

【一些入门知识】

1.飞行原理

 【垂直运动】

mg>F1+F2+F3+F4,此时做下降加速飞行
mg<F1+F2+F3+F4,此时做升高加速飞行
mg=F1+F2+F3+F4 ,此时垂直上保持匀速飞行。

 【偏航飞行】

ω 4 + ω 2 ≠ ω 1+ ω 3  就会产生水平旋转

 【俯仰飞行】

F1+F4<F2+F3 向前飞行
F1+F4>F2+F3 向后飞行

【横滚飞行】

F4+F3>F1+F2 向右飞行
F4+F3<F1+F2 向左飞行

 2.串级PID

3.飞控的控制系统

4.姿态解算

 一.硬件设计(简)

【主控】

1.电源:3.7V锂电池供电 - DCDC升压至5V -  LDO稳压3.3V

2.USB - 上位机

3.SPI - NRF24L01无线通讯

4.I2C - MPU6050陀螺仪

5.4个PWM

6.主控STM32F103C8T6

【遥控】

1.电源:3.7V锂电池供电 - LDO稳压3.3V

2.I2C - AT24CO2

3.4个ADC - 两个遥感

4.8个IO口 - 8个按键

5.SPI - NRF24L01无线通讯

6.主控STM32F103C8T6

二.主控程序

【MPU6050读取飞控三轴加速度、角速度 并且 卡尔曼滤波】

通过 MPU6050 寄存器手册:我们需要读取的三轴加速度和三轴角速度位于寄存器 0x3B~0X48,读取数据后,需要合成 16bit 的数据。
//从 0x3B 读取 6 个字节放到 buffer 里面
#define Acc_Read() i2cRead(0x68, 0X3B,6,buffer)//从 0x43 读取 6 个字节放到 buffer 里面
#define Gyro_Read() i2cRead(0x68, 0x43,6,&buffer[6])void MpuGetData(void) //读取陀螺仪数据加滤波
{uint8_t i;uint8_t buffer[12];Acc_Read();//读取加速度Gyro_Read();//读取角速度for(i=0;i<6;i++){//整合为 16bit,并减去水平静止校准值pMpu[i] = (((int16_t)buffer[i<<1] << 8) | buffer[(i<<1)+1])-MpuOffset[i];if(i < 3)//对加速度做卡尔曼滤波{{//卡尔曼滤波的数据初始化,这个 8192 是初始化默认 1 个 g 的加速度static struct _1_ekf_filter ekf[3] = {{0.02,0,0,0,0.001,0.543}{0.02,0, 0,0,0.001,0.543},{0.02,0, 0,0,0.001,0.543}};kalman_1(&ekf[i],(float)pMpu[i]); //调用一维卡尔曼滤波函数pMpu[i] = (int16_t)ekf[i].out;//卡尔曼滤波输出}}if(i > 2)//以下对角速度做一阶低通滤波{uint8_t k=i-3;const float factor = 0.15f; //滤波因素,因数越小,滤波力度越大static float last_mpuData[3];//滤波并保存滤波数据 last_mpuData[k] = last_mpuData[k] * (1 - factor) + pMpu[i] * factor; pMpu[i] = last_mpuData[k];//滤波输出}}
}

【遥控数据解析】

void RC_Analy(void)  
{static uint16_t cnt;if(NRF24L01_RxPacket(RC_rxData)==SUCCESS){ 	uint8_t i;uint8_t CheckSum=0;uint16_t thr;cnt = 0;for(i=0;i<31;i++){CheckSum +=  RC_rxData[i]; //检查数据的数量是否是31个}if(RC_rxData[31]==CheckSum && RC_rxData[0]==0xAA && RC_rxData[1]==0xAF)  //如果接收到的遥控数据正确{Remote.roll = ((uint16_t)RC_rxData[4]<<8) | RC_rxData[5];  //通道1Remote.roll = LIMIT(Remote.roll,1000,2000);Remote.pitch = ((uint16_t)RC_rxData[6]<<8) | RC_rxData[7];  //通道2Remote.pitch = LIMIT(Remote.pitch,1000,2000);Remote.thr = 	((uint16_t)RC_rxData[8]<<8) | RC_rxData[9];   //通道3Remote.thr = 	LIMIT(Remote.thr,1000,2000);Remote.yaw =  ((uint16_t)RC_rxData[10]<<8) | RC_rxData[11];   //通道4Remote.yaw =  LIMIT(Remote.yaw,1000,2000);Remote.AUX1 =  ((uint16_t)RC_rxData[12]<<8) | RC_rxData[13];   //通道5  左上角按键都属于通道5  Remote.AUX1 =  LIMIT(Remote.AUX1,1000,2000);Remote.AUX2 =  ((uint16_t)RC_rxData[14]<<8) | RC_rxData[15];   //通道6  右上角按键都属于通道6 Remote.AUX2 =  LIMIT(Remote.AUX2,1000,2000);Remote.AUX3 =  ((uint16_t)RC_rxData[16]<<8) | RC_rxData[17];   //通道7  左下边按键都属于通道7 Remote.AUX3 =  LIMIT(Remote.AUX3,1000,2000);Remote.AUX4 =  ((uint16_t)RC_rxData[18]<<8) | RC_rxData[19];   //通道8  右下边按键都属于通道6  Remote.AUX4 = LIMIT(Remote.AUX4,1000,4000);	{const float roll_pitch_ratio = 0.04f;const float yaw_ratio =   0.3f;	pidPitch.desired =-(Remote.pitch-1500)*roll_pitch_ratio;	 //将遥杆值作为飞行角度的期望值pidRoll.desired = -(Remote.roll-1500)*roll_pitch_ratio;if(Remote.yaw>1820){pidYaw.desired -= yaw_ratio;	}else if(Remote.yaw <1180){pidYaw.desired += yaw_ratio;	}						}remote_unlock();}}
//如果3秒没收到遥控数据,则判断遥控信号丢失,飞控在任何时候停止飞行,避免伤人。
//意外情况,使用者可紧急关闭遥控电源,飞行器会在3秒后立即关闭,避免伤人。
//立即关闭遥控,如果在飞行中会直接掉落,可能会损坏飞行器。else{cnt++;if(cnt>500){cnt = 0;ALL_flag.unlock = 0; NRF24L01_init();}}
}

【PID控制器的设计】

void FlightPidControl(float dt)
{volatile static uint8_t status=WAITING_1;switch(status){		case WAITING_1: //等待解锁if(ALL_flag.unlock){status = READY_11;	}			break;case READY_11:  //准备进入控制pidRest(pPidObject,6); //批量复位PID数据,防止上次遗留的数据影响本次控制Angle.yaw = pidYaw.desired =  pidYaw.measured = 0;   //锁定偏航角status = PROCESS_31;break;			case PROCESS_31: //正式进入控制if(Angle.pitch<-50||Angle.pitch>50||Angle.roll<-50||Angle.roll>50)//倾斜检测,大角度判定为意外情况,则紧急上锁	if(Remote.thr>1200)//当油门的很低时不做倾斜检测ALL_flag.unlock = EMERGENT;//打入紧急情况pidRateX.measured = MPU6050.gyroX * Gyro_G; //内环测量值 角度/秒pidRateY.measured = MPU6050.gyroY * Gyro_G;pidRateZ.measured = MPU6050.gyroZ * Gyro_G;pidPitch.measured = Angle.pitch; //外环测量值 单位:角度pidRoll.measured = Angle.roll;pidYaw.measured = Angle.yaw;pidUpdate(&pidRoll,dt);    //调用PID处理函数来处理外环	横滚角PID		pidRateX.desired = pidRoll.out; //将外环的PID输出作为内环PID的期望值即为串级PIDpidUpdate(&pidRateX,dt);  //再调用内环pidUpdate(&pidPitch,dt);    //调用PID处理函数来处理外环	俯仰角PID	pidRateY.desired = pidPitch.out;  pidUpdate(&pidRateY,dt); //再调用内环CascadePID(&pidRateZ,&pidYaw,dt);	//也可以直接调用串级PID函数来处理break;case EXIT_255:  //退出控制pidRest(pPidObject,6);status = WAITING_1;//返回等待解锁break;default:status = EXIT_255;break;}if(ALL_flag.unlock == EMERGENT) //意外情况,请使用遥控紧急上锁,飞控就可以在任何情况下紧急中止飞行,锁定飞行器,退出PID控制status = EXIT_255;
}

【4路PWM电机驱动】

void TIM2_PWM_Config(void)
{TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;TIM_OCInitTypeDef TIM_OCInitStructure;GPIO_InitTypeDef GPIO_InitStructure;/* 使能 GPIOA 时钟时钟 */RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0 | GPIO_Pin_1 | GPIO_Pin_2 |GPIO_Pin_3;GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;GPIO_Init(GPIOA, &GPIO_InitStructure);/* 使能定时器 2 时钟 */RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE);/* Time base configuration */TIM_TimeBaseStructure.TIM_Period = 999; //定时器计数周期 0-999 1000TIM_TimeBaseStructure.TIM_Prescaler = 8; //设置预分频:8+1 分频 8K PWM 频率TIM_TimeBaseStructure.TIM_ClockDivision = 0; //设置时钟分频系数:不分频TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; //向上计数模式TIM_TimeBaseInit(TIM2, &TIM_TimeBaseStructure);/* PWM1 Mode configuration: Channel */TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1; //配置为 PWM 模式 1TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;TIM_OCInitStructure.TIM_Pulse = 0;//设置跳变值,当计数器计数到这个值时,电平发生跳变(即占空比) 初始值 0TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High;//当定时器计数值小于定时设定值时为高电平/* 使能通道 1 */TIM_OC1Init(TIM2, &TIM_OCInitStructure);TIM_OC1PreloadConfig(TIM2, TIM_OCPreload_Enable);/* 使能通道 2 */TIM_OC2Init(TIM2, &TIM_OCInitStructure);TIM_OC2PreloadConfig(TIM2, TIM_OCPreload_Enable);/* 使能通道 3 */TIM_OC3Init(TIM2, &TIM_OCInitStructure);TIM_OC3PreloadConfig(TIM2, TIM_OCPreload_Enable);
/* 使能通道 4 */TIM_OC4Init(TIM2, &TIM_OCInitStructure);TIM_OC4PreloadConfig(TIM2, TIM_OCPreload_Enable);TIM_ARRPreloadConfig(TIM2, ENABLE); // 使能 TIM2 重载寄存器 ARRTIM_Cmd(TIM2, ENABLE); //使能定时器 2
}

【解锁 - 启动步骤 - 电机动力分配】

void MotorControl(void)
{	volatile static uint8_t status=WAITING_1;if(ALL_flag.unlock == EMERGENT) //意外情况,请使用遥控紧急上锁,飞控就可以在任何情况下紧急中止飞行,锁定飞行器,退出PID控制status = EXIT_255;	switch(status){		case WAITING_1: //等待解锁	MOTOR1 = MOTOR2 = MOTOR3 = MOTOR4 = 0;  //如果锁定,则电机输出都为0if(ALL_flag.unlock){status = WAITING_2;}case WAITING_2: //解锁完成后判断使用者是否开始拨动遥杆进行飞行控制if(Remote.thr>1100){low_thr_cnt_quiet=0;low_thr_cnt=0;pidRest(pPidObject,6);status = PROCESS_31;}break;case PROCESS_31:{int16_t temp,thr;temp = Remote.thr -1000; //油门+定高输出值//油门比例规划thr = 250+0.45f * temp;if(temp<10) //自动关停判断{if(low_thr_cnt<1500)low_thr_cnt++;thr = thr-(low_thr_cnt*0.6);//油门摇杆值慢慢降为0 if(MPU6050.accZ<8500&&MPU6050.accZ>7800){low_thr_cnt++;if(low_thr_cnt>600)//1800ms{thr = 0;pidRest(pPidObject,6);MOTOR1 = MOTOR2 = MOTOR3 = MOTOR4 =0;status = WAITING_2;break;}}} else low_thr_cnt=0;MOTOR1 = MOTOR2 = MOTOR3 = MOTOR4 = LIMIT(thr,0,700); //留100给姿态控制//以下输出的脉冲分配取决于电机PWM分布与飞控坐标体系。请看飞控坐标体系图解,与四个电机PWM分布分布	
//           机头      
//   PWM3     ♂       PWM1
//      *             *
//      	*       *
//    		  *   *
//      	    *  
//    		  *   *
//         *        *
//      *             *
//    PWM4           PWM2			
//		pidRateX.out 横滚角串级PID输出 控制左右,可以看出1 2和3 4,左右两组电机同增同减
//      pidRateY.out 俯仰角串级PID输出 控制前后,可以看出2 3和1 4,前后两组电机同增同减
//		pidRateZ.out 横滚角串级PID输出 控制旋转,可以看出2 4和1 3,两组对角线电机同增同减	// 正负号取决于算法输出 比如输出是正的话  往前飞必然是尾巴两个电机增加,往右飞必然是左边两个电机增加		MOTOR1 +=    + pidRateX.out + pidRateY.out + pidRateZ.out;//; 姿态输出分配给各个电机的控制量MOTOR2 +=    + pidRateX.out - pidRateY.out - pidRateZ.out ;//;MOTOR3 +=    - pidRateX.out + pidRateY.out - pidRateZ.out;MOTOR4 +=    - pidRateX.out - pidRateY.out + pidRateZ.out;//;}	break;case EXIT_255:MOTOR1 = MOTOR2 = MOTOR3 = MOTOR4 = 0;  //如果锁定,则电机输出都为0status = WAITING_1;	break;default:break;}TIM2->CCR1 = LIMIT(MOTOR1,0,1000);  //更新PWMTIM2->CCR2 = LIMIT(MOTOR2,0,1000);TIM2->CCR3 = LIMIT(MOTOR3,0,1000);TIM2->CCR4 = LIMIT(MOTOR4,0,1000);
} 

【水平校准】

MPU6050 获取的数值要减去水平静止校准值才是真正的飞控可用数据
void MpuGetOffset(void) //校准
{int32_t buffer[6]={0};int16_t i;  uint8_t k=30;const int8_t MAX_GYRO_QUIET = 5;const int8_t MIN_GYRO_QUIET = -5;	
/*           wait for calm down    	                                                          */int16_t LastGyro[3] = {0};int16_t ErrorGyro[3];	/*           set offset initial to zero    		*/memset(MpuOffset,0,12);MpuOffset[2] = 8192;   //set offset from the 8192  TIM_ITConfig(  //使能或者失能指定的TIM中断TIM1,TIM_IT_Update ,DISABLE  //使能);	while(k--)//30次静止则判定飞行器处于静止状态{do{delay_ms(10);MpuGetData();for(i=0;i<3;i++){ErrorGyro[i] = pMpu[i+3] - LastGyro[i];LastGyro[i] = pMpu[i+3];	}			}while ((ErrorGyro[0] >  MAX_GYRO_QUIET )|| (ErrorGyro[0] < MIN_GYRO_QUIET)//标定静止||(ErrorGyro[1] > MAX_GYRO_QUIET )|| (ErrorGyro[1] < MIN_GYRO_QUIET)||(ErrorGyro[2] > MAX_GYRO_QUIET )|| (ErrorGyro[2] < MIN_GYRO_QUIET));}	/*           throw first 100  group data and make 256 group average as offset                    */	for(i=0;i<356;i++)//水平校准{		MpuGetData();if(100 <= i)//取256组数据进行平均{uint8_t k;for(k=0;k<6;k++){buffer[k] += pMpu[k];}}}for(i=0;i<6;i++){MpuOffset[i] = buffer[i]>>8;}TIM_ITConfig(  //使能或者失能指定的TIM中断TIM1, TIM_IT_Update ,ENABLE  //使能);FLASH_write(MpuOffset,6);//将数据写到FLASH中,一共有6个int16数据
}

三.遥控程序

摇杆ADC采集和转换

配置 4 路 ADC 采集遥控摇杆值。DMA 自动采集,转换完成后自动将 ADC 结果存于ADC_ConvertedValue 。
void ADC1_Mode_Config(void)
{DMA_InitTypeDef DMA_InitStructure;ADC_InitTypeDef ADC_InitStructure;/* DMA channel1 configuration */DMA_DeInit(DMA1_Channel1);DMA_InitStructure.DMA_PeripheralBaseAddr = ADC1_DR_Address; //ADC 结果寄存器地址DMA_InitStructure.DMA_MemoryBaseAddr = (u32)&ADC_ConvertedValue;//输入数组地址地址DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;DMA_InitStructure.DMA_BufferSize = 4;//转换 4 路DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;//外设地址固定DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable; //内存地址固定DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord; //半字(12bit ADC存放)DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord;DMA_InitStructure.DMA_Mode = DMA_Mode_Circular; //循环传输DMA_InitStructure.DMA_Priority = DMA_Priority_High;DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;DMA_Init(DMA1_Channel1, &DMA_InitStructure);/* Enable DMA channel1 */DMA_Cmd(DMA1_Channel1, ENABLE);/* ADC1 configuration */ADC_InitStructure.ADC_Mode = ADC_Mode_Independent; //独立 ADC 模式ADC_InitStructure.ADC_ScanConvMode = ENABLE ; //禁止扫描模式,扫描模式用于多通道采集ADC_InitStructure.ADC_ContinuousConvMode = ENABLE; //开启连续转换模式,即不停地进行 ADC 转换ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_None; //不使用外部触发转换ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right; //采集数据右对齐ADC_InitStructure.ADC_NbrOfChannel = 4; //4 路 ADC 通道ADC_Init(ADC1, &ADC_InitStructure);/*配置 ADC 时钟,为 PCLK2 的 8 分频,即 6MHz,ADC 频率最高不能超过 14MHz*/RCC_ADCCLKConfig(RCC_PCLK2_Div8); /*配置 ADC1 的通道 11 为 55. 5 个采样周期,序列为 1 */ ADC_RegularChannelConfig(ADC1, ADC_Channel_0, 1, ADC_SampleTime_55Cycles5);ADC_RegularChannelConfig(ADC1, ADC_Channel_1, 2, ADC_SampleTime_55Cycles5);ADC_RegularChannelConfig(ADC1, ADC_Channel_2, 3, ADC_SampleTime_55Cycles5);ADC_RegularChannelConfig(ADC1, ADC_Channel_3, 4, ADC_SampleTime_55Cycles5);/* 使能 DMA 外设*/ADC_DMACmd(ADC1, ENABLE);/*使能 ADC1 外设 */ADC_Cmd(ADC1, ENABLE);/*复位校准寄存器 */ ADC_ResetCalibration(ADC1);/*等待校准寄存器复位完成 */while(ADC_GetResetCalibrationStatus(ADC1));
/* ADC 校准 */ADC_StartCalibration(ADC1);
/* 等待校准完成*/while(ADC_GetCalibrationStatus(ADC1));
/* 软件启动 ADC 转换 */ ADC_SoftwareStartConvCmd(ADC1, ENABLE);
}
每 10ms 进行一次 ADC 数据的转换为航模遥控数据:
12bitADC(0~4096)*0.25 +1000   ≈  航模标准数据 1000~2000

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

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

相关文章

我的考研经历

当我写下这篇文章时&#xff0c;我已经从考研 的失败中走出来了&#xff0c;考研的整个过程都写在博客日志里面了&#xff0c;在整理并阅读考研的日志时&#xff0c;想写下一篇总结&#xff0c;也算是为了更好的吸取教训。 前期日志模板&#xff1a;时间安排的还算紧凑&#x…

【启明智显分享】Model系列工业级HMI芯片:开源RISC-V+RTOS实时系统,开放!高效!

前言 「Model系列」芯片是启明智显针对工业、行业以及车载产品市场推出的系列HMI芯片&#xff0c;主要应用于工业自动化、智能终端HMI、车载仪表盘、两轮车彩屏仪表、串口屏、智能中控、智能家居、充电桩显示屏、储能显示屏、工业触摸屏等领域。此系列具有高性能、低成本的特点…

C4D如何预览动画?C4D动画云渲染助力

C4D是一款功能丰富的3D设计软件&#xff0c;以其快速的预览渲染和多样的渲染插件而闻名&#xff0c;其卓越的渲染效果赢得了CG行业专业人士的广泛赞誉。尽管C4D的渲染功能十分强大&#xff0c;但对于初学者而言&#xff0c;其复杂的渲染设置可能会带来一些挑战。本文一起来看看…

最好用的邮箱管理软件推荐,邮箱管理软件哪个好?(干货篇)

在快节奏的工作与生活中&#xff0c;有效管理电子邮件成为提升个人与团队效率的关键。 面对海量信息流&#xff0c;一款好的邮箱管理软件不仅能够帮助我们高效地整理收件箱&#xff0c;还能确保重要邮件不会错过&#xff0c;同时提升通讯的便捷性和安全性。 本文将为您推荐几款…

Http协议JSON格式

1. 计算机网络 计算机网络是指将地理位置不同的具有独立功能的多台计算机及其外部设备&#xff0c;通过通信线路连接起来&#xff0c;在网络操作系统&#xff0c;网络管理软件及网络通信协议的管理和协调下&#xff0c;实现资源共享和信息传递的计算机系统。 思考:计算机网络…

【第三篇】SpringSecurity请求流程分析

简介 本篇文章主要分析一下SpringSecurity在系统启动的时候做了那些事情、第一次请求执行的流程是什么、以及SpringSecurity的认证流程是怎么样的,主要的过滤器有哪些? SpringSecurity初始化流程 1.加载配置文件web.xml 当Web服务启动的时候,会加载我们配置的web.xml文件…

【记录与感想】CS61b-21sp project0(2048游戏)

项目概述 本项目是cs61b课程开课以来的第一个项目&#xff0c;游戏本身非常简单。它在 44 的方格网格上进行&#xff0c;每个方格可以是空的&#xff0c;也可以包含一个带有整数&#xff08;大于或等于 2 的 2 的幂&#xff09;的图块。在第一步之前&#xff0c;应用程序会将一…

Python第二语言(十四、高阶基础)

目录 1. 闭包 1.1 使用闭包注意事项 1.2 小结 2. 装饰器&#xff1a;实际上也是一种闭包&#xff1b; 2.1 装饰器的写法&#xff08;闭包写法&#xff09; &#xff1a;基础写法&#xff0c;只是解释装饰器是怎么写的&#xff1b; 2.2 装饰器的语法糖写法&#xff1a;函数…

半导体笔记汇总

半导体笔记汇总 介于导体与绝缘体之间的材质就叫做半导体。半导体器件主要分三类&#xff1a;二极管、三极管、MOS管。 一、半导体理论基础 1、导体、半导体和绝缘体 我们根据物质的导电性能强弱将物质分为导体、半导体和绝缘体。电导率与电阻率互为倒数&#xff0c;下图中…

3d模型文件格式有那些,什么区别?---模大狮模型网

3D模型文件格式有很多种&#xff0c;每种格式都有其特点和应用场景。常见的3D模型文件格式包括OBJ、FBX、STL、3DS、DAE等&#xff0c;下面将逐一介绍这些格式的区别。 1. OBJ格式&#xff1a;OBJ是一种开放的3D模型文件格式&#xff0c;可以被几乎所有的3D软件所支持。OBJ格式…

小程序 UI 风格,构建美妙视觉

小程序 UI 风格&#xff0c;构建美妙视觉

【DIY飞控板PX4移植】BARO模块BMP388气压计的PCB硬件设计和PX4驱动配置

BARO模块BMP388气压计的PCB硬件设计和PX4驱动配置 BMP388简介硬件设计封装原理图PCB设计引脚选择问题 PX4驱动配置飞控板的配置文件夹结构default.px4board文件nuttx-config/nsh/defconfig文件nuttx-config/include/board.h文件src/board_config.h文件src/i2c.cpp文件init/rc.b…

安卓/iOS/Linux系统影音边下边播P2P传输解决方案

在当今的数字时代&#xff0c;IPTV 影音行业正经历着快速的发展和变革&#xff0c;但影音行业的流量带宽成本一直很高&#xff0c;有没有什么办法既能保证现有的用户观看体验&#xff0c;又能很好降低流量带宽成本呢? P2P技术可能是一个很好的选择&#xff0c;它不仅仅可以提…

Vue2+Element-ui后台系统常用js方法

el-dialog弹框关闭清空form表单并清空验证 cancelDialog(diaLog, formRef) {this[diaLog] falseif (formRef) {this.$refs[formRef].resetFields()} }页面使用&#xff1a; <el-dialog :visible.sync"addSubsidyDialog.dialog" close"cancelDialog(addSub…

大模型赛道有前景吗?普通人该如何入门大模型?(附AI大模型资源)

大模型赛道有前景吗&#xff1f; 这个问题&#xff0c;是个热门话题&#xff0c;但不是个好问题。 因为&#xff0c;它基于不同的提问人、提问意图&#xff0c;会有不同的答案。 对于一个职业发展初期的新人&#xff0c;提问的意图可能是&#xff1a;我要不要转行去大模型赛…

如何实现一个合格的分布式锁

1、概述 在多线程的环境下&#xff0c;为了保证一个代码块在同一时间只能由一个线程访问&#xff0c;Java中我们一般可以使用 synchronized 语法和 ReentrantLock 去保证&#xff0c;这实际上是本地锁的方式。而在如今分布式架构的热潮下&#xff0c;如何保证不同节点的线程同…

聚道云软件连接器:企业数字化转型新动力

在当今数字化浪潮中&#xff0c;企业如何高效整合内部资源、优化业务流程、提升客户满意度&#xff0c;已成为每个企业亟需解决的问题。该公司作为行业内的佼佼者&#xff0c;近期借助聚道云软件连接器成功实现了飞鱼CRM与金蝶云星辰的对接&#xff0c;开启了数字化转型的新篇章…

macOS Sequoia 将 Mac 生产力与智能化提升至全新高度

本文转载自 官方新闻&#xff1a;https://www.apple.com.cn/newsroom/2024/06/macos-sequoia-takes-productivity-and-intelligence-on-mac-to-new-heights/ 文章目录 1、借助 iPhone 镜像 直接在 Mac 上无线使用 iPhone2、Safari 浏览器迎来重大更新3、升级的游戏体验与备受瞩…

资源分享—2021版乡级制图规范符号库

汇总整理超图平台软件相关的各类资源&#xff08;包括但不限于符号库、地图模板、地理处理模型等&#xff09;&#xff0c;助力项目的高效制图、提高数据生产效率等业务。 本次分享新版国土空间规划【2021版乡级制图规范符号库】&#xff0c;提供SuperMap格式符号库下载。 符…

Python学习笔记8:入门知识(八)

前言 本篇是元组的知识点学习以及知识点的补充 元组 概念 不可变的列表&#xff0c;叫做元组。 在之前列表的特性中&#xff0c;我们就说过列表是可变的&#xff0c;但是在实际使用过程中&#xff0c;我们有时候仍然需要一系列不可变的元素&#xff0c;这个时候就需要元组出…