本文主要是介绍电赛2024年H题智能小车基于MSPM0G3507主控MCU(利用8路灰度加上MPU6050的解决方式),希望对大家解决编程问题提供一定的参考价值,需要的开发者们随着小编来一起学习吧!
一.前言
前段时间,激烈的电赛刚刚结束,很荣幸啊,也是十分的不甘心,本次的湖北赛区H题只拿到了一个省二,看最终的排名,在H题中我们离省一也就差几名。但是整个比赛已经过去了,现在不甘与不舍,也没有任何意义了,只有接收这一现实了。
当时我们整个比赛要求一二三都完美完成,要求四能够十分稳定的跑下来但是跑完四圈得花1分30秒,大概是跑十次才死一两次的样子(毕竟比赛,谁也没办法保证车能够百分百的完美跑完发挥一)。后面也想过提升速度,但是结果都是不尽人意,要么速度提上去了,但是稳定性不强,要么稳定性可以,速度提不上去,最终也来到了四天三夜的最后一天,当时我和另外两个队友商量,觉得稳定还是最主要,所有就抛弃了速度快但是不稳定的所有结果,就留下了最稳定的一个。但是最后直到测试的时候帮我三个人看懵了,看别人武大的发挥一跑完只花了30多秒,当时我们十分紧张的。他们一个发挥一有两个模式,一个是速度慢,但是非常稳定,一个是跑起来不怎么稳定,就车身刚好在线上的那种,但是速度出奇的快。看到这里我三个人直接是慌了,不知道该 这么进行下一步了。
好在我们三个人十分快速的调制状态,我们 三个人互相鼓励着不管别人怎么样,做好自己就行了,然后我们一项一项的保证每一项最后测试的时候都是一次过的,这也证明我们整个解决方案是十分稳定的。但是今年这个题目光稳定是不够的,或者说是最基础的。最后也十分遗憾的没有拿到省一,只拿了一个省二。
二.具体硬件组成
本项目由微处理器MSPM0G3507,编码器电机驱动,8路灰度传感器指示线巡线单元,MPU6050六轴传感器无线直行单元,OLED显示人机互动单元,红色LED及蜂鸣器声光提示单元构成。系统运行由两部分组成:自动行驶小车的无指示线直行控制部分和有指示线弯道行驶的实时转向控制部分,小车的无指示线直行控制部分,由MPU6050六轴传感器获得小车姿态的偏航角,通过获得的实时偏航角,编码器的实际值,构成双反馈串行PID实时监控调制小车实际运行轨迹的目的。指示线弯道行驶控制部分,由8路灰度传感器获得小车在指示线上实时运动方位,输出模拟量,通过模拟量和编码器脉冲值构成串行闭环PID实时控制小车投影位于指示线方位的目的。具体的实物图如下:
俯视图
左视图
俯视图
具体的实物连接图就如上所示了,其实本项目对硬件部分的要求不高,只要能够搭建起来,跑的时候结构稳定,不跑几次容易螺丝松动那种问题,基本就行了,而且本项目对灰度,mpu6050安装的位置不是十分的严格,不管装在那个地方都能够将其做出来的。
三.理论分析部分
整个项目的准备工作做完之后(硬件搭好了)就开始想着该如何实现,第一个就是有线的时候怎么走?第二个是无线的时候如何走直线?
首先解决第一个问题:有线的时候直接利用灰度返回的模拟量,得到小车的一个大概位置,也就是偏线的左边还是右边,这样就可以反馈给主控芯片了,主控芯片收到实时反馈之后就要进行处理,也就是用到pid实时调控(如果小车偏左就减少pwm让其回到中心)利用一个10ms定时器去计算实际的小车位置和目标位置(直线的正中心)的差值然后把差值补偿给小车这样就可以达到一个动态平衡的一个状态。也就解决了巡线的理论问题。
其次就是解决没有线走直线的问题,这个就用到MPU6050陀螺仪了,这里理论上是和上面的一样的,只不过不同的一点是上面利用灰度反射黑线来识别小车的位置,而这里是利用六轴陀螺仪作为参考形成一个闭环串行的pid调制过程。这里实际上只用到一个个轴也就是水平面的x轴,偏航角和其角速度。
这里两个部分的处理都是有编码器进行速度反馈调制的,也就是第一个环,然后加上后面的两种方式最后就可以达到有线巡线行驶,无线直线行驶。具体的mpu6050和灰度的利用这里就不细讲。
四.代码实现
电机部分
#include "motor.h"
int PWM_MAX =8000;
int PWM_MIN =-8000;void Limit(int *motoA,int *motoB)
{if(*motoA>PWM_MAX)*motoA=PWM_MAX;if(*motoA<PWM_MIN)*motoA=PWM_MIN;if(*motoB>PWM_MAX)*motoB=PWM_MAX;if(*motoB<PWM_MIN)*motoB=PWM_MIN;
}int abs(int p)
{int q;q=p>0?p:(-p);return q;
}void Load(int moto1,int moto2)
{//1.研究正负号,对应正反转if(moto1<0) AIN1_OUT(1),AIN2_OUT(0);//正转else AIN1_OUT(0),AIN2_OUT(1);//反转//2.研究PWM值DL_TimerG_setCaptureCompareValue(PWM_A_INST ,abs(moto1),GPIO_PWM_A_C0_IDX);if(moto2<0)BIN1_OUT(1),BIN2_OUT(0);else BIN1_OUT(0),BIN2_OUT(1); //2.研究PWM值DL_TimerG_setCaptureCompareValue(PWM_B_INST ,abs(moto2),GPIO_PWM_B_C0_IDX);
}
pid调制
#include "control.h"PID_Velocit_TypeDef L_pid, R_pid;
PID_Turn_TypeDef Turn_pid;
void PID_Init(void)
{
L_pid.Kp=80;
L_pid.Kd=0;
L_pid.Ki=0.03;
L_pid.Err=0;
L_pid.Err_Last=0;
L_pid.Integral=0;
L_pid.PID_out=0;
L_pid.Target=0;
R_pid.Kp=75;
R_pid.Kd=0;
R_pid.Ki=0.03;
R_pid.Err=0;
R_pid.Err_Last=0;
R_pid.Integral=0;
R_pid.PID_out=0;
R_pid.Target=0;
}
void PID_turn_Init(PID_Turn_TypeDef *PID)
{
PID->Kp=-5;
PID->Kd=-10;
PID->Ki=0;
PID->Err=0;
PID->Err_Last=0;
PID->Integral=0;
PID->PID_out=0;
PID->Target=0;
}float pid_Velocity(PID_Velocit_TypeDef *PID,float CurrentValue)
{PID->Err = PID->Target - CurrentValue;PID->Integral += PID->Err; /*积分限幅*/if(PID->Integral > 2000){PID->Integral = 2000;}if(PID->Integral < -2000){PID->Integral = -2000;} PID->PID_out = PID->Kp * PID->Err /*比例*/+ PID->Ki * PID->Integral /*积分*/+ PID->Kd * (PID->Err - PID->Err_Last); /*微分*/PID->Err_Last = PID->Err;return PID->PID_out;
}float pid_Turn(PID_Turn_TypeDef *PID,float CurrentValue)
{PID->Err = PID->Target - CurrentValue;PID->Integral += PID->Err; /*积分限幅*/if(PID->Integral > 2000){PID->Integral = 2000;}if(PID->Integral < -2000){PID->Integral = -2000;} PID->PID_out = PID->Kp * PID->Err /*比例*/+ PID->Ki * PID->Integral /*积分*/+ PID->Kd * (PID->Err - PID->Err_Last); /*微分*/PID->Err_Last = PID->Err;return PID->PID_out;
}
void set_Velocity_Target(PID_Velocit_TypeDef *PID,float target)
{PID->Target = target;
}void set_Turn_Target(PID_Turn_TypeDef *PID,float target)
{PID->Target = target;}
灰度部分
#include "gw.h"
#include "delay.h"__STATIC_INLINE uint8_t DL_GPIO_readPin(GPIO_Regs* gpio, uint32_t pin)
{ // 假设pin是一个只设置了单个位的位掩码 // 检查该引脚在DIN31_0寄存器中是否被设置 if (gpio->DIN31_0 & pin) { return 1; // 或 (uint8_t)Bit_SET,如果Bit_SET已定义 } else { return 0; // 或 (uint8_t)Bit_RESET,如果Bit_RESET已定义 }
}uint8_t gw_gray_serial_read(int gpio_clk,int gpio_dat)
{uint8_t ret = 0;uint8_t i;for (i = 0; i < 8; ++i){/* 输出时钟下降沿 */DL_GPIO_clearPins(SW_SPI_PORT, gpio_clk);delay_us(5); //有外部上拉源(4k ~ 10k电阻) 可不加此行ret |= DL_GPIO_readPin(SW_SPI_PORT, gpio_dat) << i;/* 输出时钟上升沿,让传感器更新数据*/DL_GPIO_setPins(SW_SPI_PORT, gpio_clk);/* 延迟需要在5us左右 */delay_us(5);}return ret;
}void track(void)
{if(distance==0xe7) //1110 0111 黑零白一 识别黑线在中央{error=0;}else if(distance==0xef) //1110 1111 稍偏右{error=5; }else if(distance==0xf7) //1111 0111 稍偏左{error=-5; }else if(distance==0xcf) //1100 1111 中度偏右{error=10; }else if(distance==0xf3) //1111 0011 中度偏左{error=-10; }else if(distance==0xdf) //1101 1111 高度偏右{error=15;}else if(distance==0xfb) //1111 1011 高度偏左{error=-15; }else if(distance==0x9f) //1001 1111 高2度偏右{error=20; }else if(distance==0xf9) //1111 1001 高2度偏左{error=-20; }else if(distance==0xbf) //1011 1111 高3度偏右{error=25; }else if(distance==0xfd) //1111 1101 高三度偏左{error=-25; }else if(distance==0x3f) //0011 1111 高4度偏右{error=30; }else if(distance==0xfc) //1111 1100 高4度偏左{error=-30; }else if(distance==0x7f) //0111 1111 高五度偏右{error=35; } else if(distance==0xfd) //1111 1110 高六度偏左{error=-35; }else if (distance==0xff) //0000000 走到终点了{error=100;}
}
mpu6050部分
#include "bsp_mpu6050.h"
#include "stdio.h"
#include "delay.h"
enum I2cControllerStatus {I2C_STATUS_IDLE = 0,I2C_STATUS_TX_STARTED,I2C_STATUS_TX_INPROGRESS,I2C_STATUS_TX_COMPLETE,I2C_STATUS_RX_STARTED,I2C_STATUS_RX_INPROGRESS,I2C_STATUS_RX_COMPLETE,I2C_STATUS_ERROR,
} gI2cControllerStatus;uint32_t gTxLen, gTxCount, gRxCount, gRxLen;
uint8_t gTxPacket[128];
uint8_t gRxPacket[128];char MPU6050_WriteReg(uint8_t addr,uint8_t regaddr,uint8_t num,uint8_t *regdata)
{uint16_t i;gI2cControllerStatus = I2C_STATUS_IDLE;gTxLen = num+1;gTxPacket[0] = regaddr;for(i=1; i<=num; i++){gTxPacket[i] = (uint8_t)regdata[i-1];}gTxCount = DL_I2C_fillControllerTXFIFO(I2C_MPU6050_INST, &gTxPacket[0], gTxLen);if (gTxCount < gTxLen) {DL_I2C_enableInterrupt(I2C_MPU6050_INST, DL_I2C_INTERRUPT_CONTROLLER_TXFIFO_TRIGGER);} else {DL_I2C_disableInterrupt(I2C_MPU6050_INST, DL_I2C_INTERRUPT_CONTROLLER_TXFIFO_TRIGGER);}gI2cControllerStatus = I2C_STATUS_TX_STARTED;while (!(DL_I2C_getControllerStatus(I2C_MPU6050_INST) & DL_I2C_CONTROLLER_STATUS_IDLE));DL_I2C_startControllerTransfer(I2C_MPU6050_INST, addr, DL_I2C_CONTROLLER_DIRECTION_TX, gTxLen);while ((gI2cControllerStatus != I2C_STATUS_TX_COMPLETE) && (gI2cControllerStatus != I2C_STATUS_ERROR));while (DL_I2C_getControllerStatus(I2C_MPU6050_INST) & DL_I2C_CONTROLLER_STATUS_BUSY_BUS);while (!(DL_I2C_getControllerStatus(I2C_MPU6050_INST) & DL_I2C_CONTROLLER_STATUS_IDLE));delay_cycles(1000);return 0;
}char MPU6050_ReadData(uint8_t addr, uint8_t regaddr,uint8_t num,uint8_t* Read)
{uint8_t data[2], i;data[0] = regaddr;gI2cControllerStatus = I2C_STATUS_IDLE;DL_I2C_fillControllerTXFIFO(I2C_MPU6050_INST, &data[0], 1);DL_I2C_disableInterrupt(I2C_MPU6050_INST, DL_I2C_INTERRUPT_CONTROLLER_TXFIFO_TRIGGER);gI2cControllerStatus = I2C_STATUS_TX_STARTED;while (!(DL_I2C_getControllerStatus(I2C_MPU6050_INST) & DL_I2C_CONTROLLER_STATUS_IDLE));DL_I2C_startControllerTransfer(I2C_MPU6050_INST, addr, DL_I2C_CONTROLLER_DIRECTION_TX, 1);while ((gI2cControllerStatus != I2C_STATUS_TX_COMPLETE) && (gI2cControllerStatus != I2C_STATUS_ERROR));while (DL_I2C_getControllerStatus(I2C_MPU6050_INST) & DL_I2C_CONTROLLER_STATUS_BUSY_BUS);while (!(DL_I2C_getControllerStatus(I2C_MPU6050_INST) & DL_I2C_CONTROLLER_STATUS_IDLE));// delay_cycles(1000);gRxLen = num;gRxCount = 0;gI2cControllerStatus = I2C_STATUS_RX_STARTED;DL_I2C_startControllerTransfer(I2C_MPU6050_INST, addr, DL_I2C_CONTROLLER_DIRECTION_RX, gRxLen);while (gI2cControllerStatus != I2C_STATUS_RX_COMPLETE);while (DL_I2C_getControllerStatus(I2C_MPU6050_INST) &DL_I2C_CONTROLLER_STATUS_BUSY_BUS);for(i=0; i<num; i++){Read[i] = gRxPacket[i];}return 0;
}/******************************************************************* 函 数 名 称:MPU_Set_Gyro_Fsr* 函 数 说 明:设置MPU6050陀螺仪传感器满量程范围* 函 数 形 参:fsr:0,±250dps;1,±500dps;2,±1000dps;3,±2000dps* 函 数 返 回:0,设置成功 其他,设置失败* 作 者:LC* 备 注:无
******************************************************************/
uint8_t MPU_Set_Gyro_Fsr(uint8_t fsr)
{uint8_t tmp[2];tmp[0] = fsr<<3;return MPU6050_WriteReg(0x68,MPU_GYRO_CFG_REG,1,tmp); //设置陀螺仪满量程范围
} /******************************************************************* 函 数 名 称:MPU_Set_Accel_Fsr* 函 数 说 明:设置MPU6050加速度传感器满量程范围* 函 数 形 参:fsr:0,±2g;1,±4g;2,±8g;3,±16g* 函 数 返 回:0,设置成功 其他,设置失败* 作 者:LC* 备 注:无
******************************************************************/
uint8_t MPU_Set_Accel_Fsr(uint8_t fsr)
{uint8_t tmp[2];tmp[0] = fsr<<3;return MPU6050_WriteReg(0x68,MPU_ACCEL_CFG_REG,1,tmp); //设置加速度传感器满量程范围
}/******************************************************************* 函 数 名 称:MPU_Set_LPF* 函 数 说 明:设置MPU6050的数字低通滤波器* 函 数 形 参:lpf:数字低通滤波频率(Hz)* 函 数 返 回:0,设置成功 其他,设置失败* 作 者:LC* 备 注:无
******************************************************************/
uint8_t MPU_Set_LPF(uint16_t lpf)
{uint8_t data=0;uint8_t tmp[2];if(lpf>=188)data=1;else if(lpf>=98)data=2;else if(lpf>=42)data=3;else if(lpf>=20)data=4;else if(lpf>=10)data=5;else data=6; tmp[0] = data;return data=MPU6050_WriteReg(0x68,MPU_CFG_REG,1,tmp);//设置数字低通滤波器
}
/******************************************************************* 函 数 名 称:MPU_Set_Rate* 函 数 说 明:设置MPU6050的采样率(假定Fs=1KHz)* 函 数 形 参:rate:4~1000(Hz) 初始化中rate取50* 函 数 返 回:0,设置成功 其他,设置失败* 作 者:LC* 备 注:无
******************************************************************/
uint8_t MPU_Set_Rate(uint16_t rate)
{uint8_t data;uint8_t tmp[2];if(rate>1000)rate=1000;if(rate<4)rate=4;data=1000/rate-1;tmp[0] = data;data=MPU6050_WriteReg(0x68,MPU_SAMPLE_RATE_REG,1,tmp); //设置数字低通滤波器return MPU_Set_LPF(rate/2); //自动设置LPF为采样率的一半
}/******************************************************************* 函 数 名 称:MPU6050ReadGyro* 函 数 说 明:读取陀螺仪数据* 函 数 形 参:陀螺仪数据存储地址 * 函 数 返 回:无* 作 者:LC* 备 注:无
******************************************************************/
void MPU6050ReadGyro(short *gyroData)
{uint8_t buf[6];uint8_t reg = 0;//MPU6050_GYRO_OUT = MPU6050陀螺仪数据寄存器地址//陀螺仪数据输出寄存器总共由6个寄存器组成,//输出X/Y/Z三个轴的陀螺仪传感器数据,高字节在前,低字节在后。//每一个轴16位,按顺序为xyzreg = MPU6050_ReadData(0x68,MPU6050_GYRO_OUT,6,buf);if( reg == 0 ){gyroData[0] = (buf[0] << 8) | buf[1];gyroData[1] = (buf[2] << 8) | buf[3];gyroData[2] = (buf[4] << 8) | buf[5];}
}/******************************************************************* 函 数 名 称:MPU6050ReadAcc* 函 数 说 明:读取加速度数据* 函 数 形 参:加速度数据存储地址 * 函 数 返 回:无* 作 者:LC* 备 注:无
******************************************************************/
void MPU6050ReadAcc(short *accData)
{uint8_t buf[6];uint8_t reg = 0;//MPU6050_ACC_OUT = MPU6050加速度数据寄存器地址//加速度传感器数据输出寄存器总共由6个寄存器组成,//输出X/Y/Z三个轴的加速度传感器值,高字节在前,低字节在后。reg = MPU6050_ReadData(0x68, MPU6050_ACC_OUT, 6, buf);if( reg == 0){accData[0] = (buf[0] << 8) | buf[1];accData[1] = (buf[2] << 8) | buf[3];accData[2] = (buf[4] << 8) | buf[5];}
}/******************************************************************* 函 数 名 称:MPU6050_GetTemp* 函 数 说 明:读取MPU6050上的温度* 函 数 形 参:无* 函 数 返 回:温度值单位为℃* 作 者:LC* 备 注:温度换算公式为:Temperature = 36.53 + regval/340
******************************************************************/
float MPU6050_GetTemp(void)
{short temp3;uint8_t buf[2];float Temperature = 0;MPU6050_ReadData(0x68,MPU6050_RA_TEMP_OUT_H,2,buf); temp3= (buf[0] << 8) | buf[1]; Temperature=((double) temp3/340.0)+36.53;return Temperature;
}/******************************************************************* 函 数 名 称:MPU6050ReadID* 函 数 说 明:读取MPU6050的器件地址* 函 数 形 参:无* 函 数 返 回:0=检测不到MPU6050 1=能检测到MPU6050* 作 者:LC* 备 注:无
******************************************************************/
uint8_t MPU6050ReadID(void)
{unsigned char Re[2] = {0};//器件ID寄存器 = 0x75printf("mpu=%d\r\n",MPU6050_ReadData(0x68,0X75,1,Re)); //读器件地址if (Re[0] != 0x68) {printf("检测不到 MPU6050 模块");return 1;} else{printf("MPU6050 ID = %x\r\n",Re[0]);return 0;}return 0;
}/******************************************************************* 函 数 名 称:MPU6050_Init* 函 数 说 明:MPU6050初始化* 函 数 形 参:无* 函 数 返 回:0成功 1没有检测到MPU6050* 作 者:LC* 备 注:无
******************************************************************/
char MPU6050_Init(void)
{uint8_t tmp[2];delay_ms(10);//复位6050tmp[0] = 0x80;MPU6050_WriteReg(0x68,MPU6050_RA_PWR_MGMT_1, 1, tmp);delay_ms(100);//电源管理寄存器//选择X轴陀螺作为参考PLL的时钟源,设置CLKSEL=001tmp[0] = 0x00;MPU6050_WriteReg(0x68,MPU6050_RA_PWR_MGMT_1,1, tmp);MPU_Set_Gyro_Fsr(3); //陀螺仪传感器,±2000dpsMPU_Set_Accel_Fsr(0); //加速度传感器,±2gMPU_Set_Rate(50); MPU6050_WriteReg(0x68,MPU_INT_EN_REG , 1,tmp); //关闭所有中断MPU6050_WriteReg(0x68,MPU_USER_CTRL_REG,1,tmp); //I2C主模式关闭MPU6050_WriteReg(0x68,MPU_FIFO_EN_REG,1,tmp); //关闭FIFOtmp[0] = 0x80;MPU6050_WriteReg(0x68,MPU_INTBP_CFG_REG,1,tmp); //INT引脚低电平有效if( MPU6050ReadID() == 0 )//检查是否有6050{ tmp[0] = 0x01;MPU6050_WriteReg(0x68,MPU6050_RA_PWR_MGMT_1, 1,tmp);//设置CLKSEL,PLL X轴为参考tmp[0] = 0x00;MPU6050_WriteReg(0x68,MPU_PWR_MGMT2_REG, 1,tmp);//加速度与陀螺仪都工作MPU_Set_Rate(50); return 1;}return 0;
}void I2C_MPU6050_INST_IRQHandler(void)
{switch (DL_I2C_getPendingInterrupt(I2C_MPU6050_INST)) {case DL_I2C_IIDX_CONTROLLER_RX_DONE:gI2cControllerStatus = I2C_STATUS_RX_COMPLETE;break;case DL_I2C_IIDX_CONTROLLER_TX_DONE:DL_I2C_disableInterrupt(I2C_MPU6050_INST, DL_I2C_INTERRUPT_CONTROLLER_TXFIFO_TRIGGER);gI2cControllerStatus = I2C_STATUS_TX_COMPLETE;break;case DL_I2C_IIDX_CONTROLLER_RXFIFO_TRIGGER:gI2cControllerStatus = I2C_STATUS_RX_INPROGRESS;/* Receive all bytes from target */while (DL_I2C_isControllerRXFIFOEmpty(I2C_MPU6050_INST) != true) {if (gRxCount < gRxLen) {gRxPacket[gRxCount++] =DL_I2C_receiveControllerData(I2C_MPU6050_INST);} else {/* Ignore and remove from FIFO if the buffer is full */DL_I2C_receiveControllerData(I2C_MPU6050_INST);}}break;case DL_I2C_IIDX_CONTROLLER_TXFIFO_TRIGGER:gI2cControllerStatus = I2C_STATUS_TX_INPROGRESS;/* Fill TX FIFO with next bytes to send */if (gTxCount < gTxLen) {gTxCount += DL_I2C_fillControllerTXFIFO(I2C_MPU6050_INST, &gTxPacket[gTxCount], gTxLen - gTxCount);}break;/* Not used for this example */case DL_I2C_IIDX_CONTROLLER_ARBITRATION_LOST:case DL_I2C_IIDX_CONTROLLER_NACK:if ((gI2cControllerStatus == I2C_STATUS_RX_STARTED) ||(gI2cControllerStatus == I2C_STATUS_TX_STARTED)) {/* NACK interrupt if I2C Target is disconnected */gI2cControllerStatus = I2C_STATUS_ERROR;}case DL_I2C_IIDX_CONTROLLER_RXFIFO_FULL:case DL_I2C_IIDX_CONTROLLER_TXFIFO_EMPTY:case DL_I2C_IIDX_CONTROLLER_START:case DL_I2C_IIDX_CONTROLLER_STOP:case DL_I2C_IIDX_CONTROLLER_EVENT1_DMA_DONE:case DL_I2C_IIDX_CONTROLLER_EVENT2_DMA_DONE:default:break;}
}
五.总结
最后我觉得这个项目最重要的部分还是陀螺仪的精准度,如果一个陀螺仪的精准度高,这个项目就十分简单了,像mpu6050这种陀螺仪精准度就稍微差了一点,他有个最严重的问题就是温漂,偏航角会随着温度变化为变化,这一点在跑发挥项一的时候十分关键的,因为这个只差基督就会导致车子跑偏,导致无法完成 整个项目。如果条件足够的话建议可以换一个好一点的陀螺仪,然后就是灰度如果没有条件同样也可以换成红外。以上就是本次项目的一些小建议。
这篇关于电赛2024年H题智能小车基于MSPM0G3507主控MCU(利用8路灰度加上MPU6050的解决方式)的文章就介绍到这儿,希望我们推荐的文章对编程师们有所帮助!