本帖最后由 pig881 于 2016-4-22 16:37 编辑
#include <PID_v1.h>
//========== PID 参数 ======================================
double Setpoint=0, Input, Output;
double Kp=0.2, Ki=0, Kd=0.08; // Kp=0.1; Kp=0.1, Ki=0.05, Kd=0.001; Kp=0.2, Ki=0, Kd=0.08;
PID myPID(&Input, &Output, &Setpoint, Kp, Ki, Kd, DIRECT);
//========== End of PID 参数 ===================================
//============= 测速参数 ===================
int OUTL=2;
int OUTR=3;
volatile int scode_L = 0; //左轮编码器码盘脉冲计数值
volatile int scode_R =0; //右轮编码器码盘脉冲计数值
unsigned long old_time=0,new_time=0; // 总时间标记
unsigned long time1 = 0, time2 = 0; //左1,右2 轮 时间标记
double spdLft; //左轮电机每分钟(min)转速(r/min)
double spdRgt; //右轮电机每分钟(min)转速(r/min)
int val_left;//上位机控制字节,用于提供给左轮电机PWM功率值。
int val_right; //小车右轮电机的PWM功率值
int pwm;
//=============END OF 测速参数 ===================
//=================== MOTOR 马达驱动 参数 ===================
// motor A LEFT MOTOR
int dir1PinAL = 13;
int dir2PinAL = 12;
int speedPinAL = 10; //10脚 LEFT spped setter
// motor B RIGHT MOTOR
int dir1PinBR = 9;
int dir2PinBR = 8;
int speedPinBR = 6; // 6脚 RIGHT spped setter
//=================== end of MOTOR 马达驱动 参数 ===================
void setMotor()
{
//左边马达
pinMode(dir1PinAL,OUTPUT);
pinMode(dir2PinAL,OUTPUT);
pinMode(speedPinAL,OUTPUT);
//右边马达
pinMode(dir1PinBR,OUTPUT);
pinMode(dir2PinBR,OUTPUT);
pinMode(speedPinBR,OUTPUT);
}
//====================== END OF MOTOR 参数 ===============
void Code1();
void Code2();
void setup() {
setMotor();
Serial.begin(9600);
pwm=60; //=inString.toInt();
scode_L = 0; //恢复到编码器测速的初始状态
scode_R = 0;
old_time= millis();
attachInterrupt(0, Code1, FALLING);//小车左车轮电机的编码器脉冲中断函数
attachInterrupt(1, Code2, FALLING);//小车右车轮电机的编码器脉冲中断函数
Setpoint=0; //左右差为0 为目标
myPID.SetOutputLimits(-60,60); //输出限制
myPID.SetTunings(Kp,Ki,Kd);
myPID.SetSampleTime(1000);
myPID.SetMode(AUTOMATIC);
}
void loop() {
//======================= 测速代码 ==========================================
new_time=millis();
if(abs(new_time - old_time) >= 1000) // 如果计时时间已达1秒
{
detachInterrupt(0); // 关闭外部中断0
detachInterrupt(1); // 关闭外部中断1
//把每一秒钟编码器码盘计得的脉冲数,换算为当前转速值
//转速单位是每分钟多少转,即r/min。这个编码器码盘为12个齿。
spdLft =(float)scode_L*60/20;//小车左车轮电机转速
spdRgt =(float)scode_R*60/20; //小车右车轮电机转速
//val_right=(float)val_right+(rpm1-rpm2)*0.4;
Input=0.6*(spdLft-spdRgt); 这里我用的 0.6 X 左右速度差作为PID输入,我是根据一篇文章提示这么做 的 ,具体应该多少我也不懂
myPID.Compute();
val_right=pwm-Output;
val_left=pwm+Output;
testNum('n');
scode_L = 0; //恢复到编码器测速的初始状态
scode_R = 0;
old_time= millis();
attachInterrupt(0, Code1,FALLING); // 重新开放外部中断0
attachInterrupt(1, Code2,FALLING); // 重新开放外部中断1
}
//======================= END OF 测速代码 ==========================================
advance();
}
// 左侧车轮电机的编码器码盘计数中断子程序
void Code1()
{
//为了不计入噪音干扰脉冲,
//当2次中断之间的时间大于5ms时,计一次有效计数
if((millis()-time1)>5)
//当编码器码盘的OUTA脉冲信号下跳沿每中断一次,
scode_L += 1; // 编码器码盘计数加一
time1=millis();
}
// 右侧车轮电机的编码器码盘计数中断子程序
void Code2()
{
if((millis()-time2)>5)
//当编码器码盘的OUTA脉冲信号下跳沿每中断一次,
scode_R += 1; // 编码器码盘计数加一
time2=millis();
}
//子程序程序段
void advance()//小车前进
{
MOTORDRIVE(speedPinAL,dir1PinAL,dir2PinAL,val_left,0); //左边马达
MOTORDRIVE(speedPinBR,dir1PinBR,dir2PinBR,val_right,0); //右边马达
}
void back()//小车后退
{
MOTORDRIVE(speedPinAL,dir1PinAL,dir2PinAL,val_left,1); //左边马达
MOTORDRIVE(speedPinBR,dir1PinBR,dir2PinBR,val_right,1); //右边马达
}
void Stop()//小车停止
{
MOTORDRIVE(speedPinAL,dir1PinAL,dir2PinAL,0,1); //左边马达
MOTORDRIVE(speedPinBR,dir1PinBR,dir2PinBR,0,1); //右边马达
}
//============================= 马达驱动函数 ====================================================
// speedpin:速度引脚 dirPinA:电机极A , dirPinB:电机极B , mspeed:速度值 ,dir:1 正向 0 反向
void MOTORDRIVE(int speedpin,int dirPinA,int dirPinB,int mspeed,int dir)
{
analogWrite(speedpin,mspeed);
if (dir == 1) {
digitalWrite(dirPinA,LOW);
digitalWrite(dirPinB,HIGH);
}
else if(dir== 0) {//反转
digitalWrite(dirPinA,HIGH);
digitalWrite(dirPinB,LOW);
}
else {
analogWrite(speedpin,0);
}
}
//============================= end of 马达驱动函数 ====================================================
// ================== 显示函数 =============
void testNum(char a)
{
if(a=='n')
{
Serial.print("Input=");
Serial.println(Input);
Serial.print("Output=");
Serial.println(Output);
Serial.print("val_left=");
Serial.println(val_left);
Serial.print("val_right=");
Serial.println(val_right);
Serial.print("\t speeds left=");
Serial.println(spdLft);
Serial.print("\t speeds Right=");
Serial.println(spdRgt);
}
else if (a=='t')
{
Serial.print(spdLft);
Serial.print(",");
Serial.println(spdRgt);
Serial.print("\n");
}
delay(1000);
}
|