第一次提交

This commit is contained in:
氧原子
2025-05-14 12:34:56 +08:00
parent 64518bf42d
commit 8b2d592220
14 changed files with 929 additions and 0 deletions

102
maze_code/maze_func_pid.cpp Normal file
View File

@@ -0,0 +1,102 @@
#include<iostream>
#include<string>
#include<vector>
#include"eyebot++.h"
#include"maze_func.h"
#include"maze_parameter.h"
using namespace std;
/*---对PID控制的积分部分I限幅---*/
void eI_xianfu(int eI_max)
{
if (err_sum >= eI_max) //如果err_sum大于限幅则直接让err_sum=限幅防止err_sum过大影响PID控制
{
err_sum = eI_max;
}
else if (err_sum <= -eI_max)
{
err_sum = -eI_max;
}
else
{
//此处为空;
}
}
/*---位置式PID算法---*/
void PID_AL()
{
err_sum += err; //积分累计误差值
eI_xianfu(eI_max); //积分部分限幅
err_diff = err - err_old; //微分部分误差值
/*---打印输出PID控制的各项参数1---*/
// cout << "本次误差:" << err << "\t" ;
// cout << "上次误差:" << err_old << "\t" ;
// cout << "误差累计:" << err_sum << "\t" ;
// cout << "误差变化:" << err_diff << "\t" ;
/*---打印结束---*/
err_old = err; //将误差幅值到上一次误差
Kpid = Kp*err + Ki*err_sum + Kd*err_diff; //PID控制算法输出的倍率
Kpid_speed = Kpid * Kpid_base;
/*---打印输出PID控制的各项参数2---*/
// cout << "PID输出值:" << Kpid << endl ;
/*---打印结束---*/
// VWSetSpeed(speed,Kpid*Kpid_base); //控制小车的行驶速度,角速度(模拟器可以用实物no)
MOTORDriveRaw(1,speed1);
MOTORDriveRaw(2,speed1+Kpid_speed);
}
/*---PID控制下的直线行驶---*/
void PIDStraight()
{
int DIST_move; //定义基础角速度和速度,和移动距离
int L_PSD, R_PSD, F_PSD; //定义左侧,右侧,前方的距离值
int x_1,x_2, y_1,y_2, phi_1,phi_2; //VWGetPosition的参数定义
speed1 = speed;
VWGetPosition(&x_1, &y_1, &phi_1); //获取机器人在移动前的x,y,phi值
MOTORDriveRaw(1,speed1);
MOTORDriveRaw(2,speed1);
do
{
F_PSD = PSDGetRaw(1); //读取前方和墙壁的距离
L_PSD = PSDGetRaw(2); //读取左侧和墙壁的距离
R_PSD = PSDGetRaw(3); //读取右侧和墙壁的距离
/*---打印输出PSD数值---*/
// cout << "PSD值L:" << L_PSD << " R:" << R_PSD << " F:" << F_PSD << "\t" ;
/*---打印结束---*/
if (100<L_PSD && L_PSD<180 && 100<R_PSD && R_PSD<180) //如果两侧都有墙的情况
{
err = L_PSD - R_PSD;
PID_AL();
}
else if (100<L_PSD && L_PSD<180) //只有左侧有墙的情况
{
err = L_PSD - DIST_wall;
PID_AL();
}
else if (100<R_PSD && R_PSD<180) //只有右侧有墙的情况
{
err = DIST_wall - R_PSD;
PID_AL();
}
else
{
L_PSD = L_PSD % DIST_cell;
R_PSD = R_PSD % DIST_cell;
err = L_PSD - R_PSD;
PID_AL();
}
VWGetPosition(&x_2, &y_2, &phi_2);
DIST_move = sqrt(pow(x_2-x_1,2) + pow(y_2-y_1,2));
if (DIST_move > (DIST_cell -50)) //当移动距离只剩下最后的50mm的时候降点速度
{
speed1 = speed2;
}
}while (DIST_move < DIST_cell && F_PSD > DIST_wall); //当移动到指定距离,或者检测到小车前方的距离小于检测距离的时候,停止运行
}