我在使用光电编码器测车轮转速的时候出现了问题。当我的行驶速度超过40cm/s的时候,arduino上计算出的速度开始和真实值不相符,并且会出现负数的现象。
下面是我的代码
#include <FlexiTimer2.h>
/*
* 测速原理
脉冲数/(编码器分辨率*时间)
A脉冲为下降沿,B脉冲为高电平,方向为正;
A脉冲为下降沿,B脉冲为低电平,方向为负。
*/
#include <PinChangeInt.h> //额外中断头文件
#define PinA1 2 //外部中断0
#define PinA2 12 //外部中断1
#define PinB1 3 //编码器的OUT_B信号连接到数字端口8
#define PinB2 13 //编码器2的B信号口
#define PinA3 14 //后轮1的A口
#define PinA4 A1 //后轮2的A口
#define PinB3 15
#define PinB4 A2
#define rev_itr_pin 4
#define rev_sgn_pin 5
#define l_acc_pin 6 //车速控制驱动直接移到这个板子上了
#define r_acc_pin 7
//变量初始化
const double sampTime = 100; // 定时器周期100ms,采样频率10Hz,这个值必须是实际值的一半,因为在ctcmode下会自动有一个scaler 2.
volatile long time1;
volatile long time2;
volatile long time3;
volatile long time4;
volatile long time5;
volatile long time6;
volatile long time7;
volatile long time8;
volatile int num = 0;//采样周期内圈数,由Z相中断计数
volatile double count1 = 0; // 脉冲数计数器,由A相计数
volatile double count2 = 0;
volatile double count3 = 0;
volatile double count4 = 0;
int tmp = 0; //暂存编码器计数脉冲数值
volatile double spdVal1 = 0; //采样周期内,返回的速度计算结果cm/s
volatile double distance1 = 0;
volatile double rotation1 = 0;
volatile double spdVal2 = 0; //采样周期内,返回的速度计算结果
volatile double distance2 = 0;
volatile double rotation2 = 0;
volatile double spdVal3 = 0;
volatile double spdVal4 = 0;
const double D = 9*25.4/10; //轮子的直径,单位cm
const double pi = 3.141592654;//圆周率
volatile bool state_a1 = false;
volatile bool state_a2 = false;
volatile bool state_b1 = false;
volatile bool state_b2 = false;
volatile bool state_a3 = false;
volatile bool state_a4 = false;
volatile bool state_b3 = false;
volatile bool state_b4 = false;
volatile bool Direction = HIGH;//default is moving forward
//PID parameters
volatile double spdInput = 0;//输入速度cm/s
volatile double err_l = 0;//当前左轮误差
volatile double err_r = 0;//当前右轮误差
volatile double err_lHis = spdInput;//历史左轮误差
volatile double err_rHis = spdInput;//历史右轮误差
volatile double isum_l = 0;//左轮积分值
volatile double isum_r = 0;//右轮积分值
volatile double dsum_l = 0;//左轮微分值
volatile double dsum_r = 0;//右轮微分值
volatile double spdOutput_l = 0;//左轮输出速度
volatile double spdOutput_r = 0;//右轮输出速度
volatile double PIDOutput_l = 0;//左轮调整速度
volatile double PIDOutput_r = 0;//右轮调整速度
volatile int topSpeedTime_l = 0;//左轮最高速度时间
volatile int topSpeedTime_r = 0;//右轮最高速度时间
const double kp_l = 10;
const double ki_l = 1;
const double kd_l = 5;
const double kp_r = 10;
const double ki_r = 1;
const double kd_r = 5;
const double reduction = 0.18;
//Z相零位中断子程序
//void Set_state(){
// tmp = count; //暂存当前A相计数
// count = 0; //脉冲计数归零
// num += 1;
//}
// 编码器B相脉冲计数中断子程序
void Encode_A1()
{
//为了不计入噪音干扰脉冲,
//当2次中断之间的时间大于0.002ms时,计一次有效计数,下面的数字是实际频率的一半sampletime同理,原因是在CTCmode下频率其实要在prescaler的基础上再除个2.
if ((micros() - time1) > 2)
{
//当编码器码盘的OUTA脉冲信号下跳沿每中断一次,
// Test transition
state_a1 = digitalRead(PinB1) == HIGH;
// and adjust counter + if A leads B
count1 += state_a1 ? +1 : -1;
}
time1 == micros();
}
void Encode_B1()
{
//为了不计入噪音干扰脉冲,
//当2次中断之间的时间大于0.01ms时,计一次有效计数,下面的数字是实际频率的一半sampletime同理,原因是在CTCmode下频率其实要在prescaler的基础上再除个2.
if ((micros() - time2) > 2)
{
//当编码器码盘的OUTA脉冲信号下跳沿每中断一次,
// Test transition
state_b1 = digitalRead(PinA1) == HIGH;
// and adjust counter + if B follows A
count1 += state_b1 ? +1 : -1;
}
time2 == micros();
}
void Encode_A2()
{
//为了不计入噪音干扰脉冲,
//当2次中断之间的时间大于0.01ms时,计一次有效计数,下面的数字是实际频率的一半sampletime同理,原因是在CTCmode下频率其实要在prescaler的基础上再除个2.
if ((micros() - time3) > 2)
{
//当编码器码盘的OUTA脉冲信号下跳沿每中断一次,
// Test transition
state_a2 = digitalRead(PinB2) == LOW;
// and adjust counter + if A leads B
count2 += state_a2 ? +1 : -1;
}
time3 == micros();
}
void Encode_B2()
{
//为了不计入噪音干扰脉冲,
//当2次中断之间的时间大于0.01ms时,计一次有效计数,下面的数字是实际频率的一半sampletime同理,原因是在CTCmode下频率其实要在prescaler的基础上再除个2.
if ((micros() - time4) > 2)
{
//当编码器码盘的OUTA脉冲信号下跳沿每中断一次,
// Test transition
state_b2 = digitalRead(PinA2) == LOW;
// and adjust counter + if B follows A
count2 += state_b2 ? +1 : -1;
}
time4 == micros();
}
void Encode_A3()
{
//为了不计入噪音干扰脉冲,
//当2次中断之间的时间大于0.002ms时,计一次有效计数,下面的数字是实际频率的一半sampletime同理,原因是在CTCmode下频率其实要在prescaler的基础上再除个2.
if ((micros() - time5) > 2)
{
//当编码器码盘的OUTA脉冲信号下跳沿每中断一次,
// Test transition
state_a3 = digitalRead(PinB3) == LOW;
// and adjust counter + if A leads B
count3 += state_a3 ? +1 : -1;
}
time5 == micros();
}
void Encode_B3()
{
//为了不计入噪音干扰脉冲,
//当2次中断之间的时间大于0.01ms时,计一次有效计数,下面的数字是实际频率的一半sampletime同理,原因是在CTCmode下频率其实要在prescaler的基础上再除个2.
if ((micros() - time6) > 2)
{
//当编码器码盘的OUTA脉冲信号下跳沿每中断一次,
// Test transition
state_b3 = digitalRead(PinA3) == HIGH;
// and adjust counter + if B follows A
count3 += state_b3 ? +1 : -1;
}
time6 == micros();
}
void Encode_A4()
{
//为了不计入噪音干扰脉冲,
//当2次中断之间的时间大于0.002ms时,计一次有效计数,下面的数字是实际频率的一半sampletime同理,原因是在CTCmode下频率其实要在prescaler的基础上再除个2.
if ((micros() - time7) > 2)
{
//当编码器码盘的OUTA脉冲信号下跳沿每中断一次,
// Test transition
state_a4 = digitalRead(PinB4) == HIGH;
// and adjust counter + if A leads B
count4 += state_a4 ? +1 : -1;
}
time7 == micros();
}
void Encode_B4()
{
//为了不计入噪音干扰脉冲,
//当2次中断之间的时间大于0.01ms时,计一次有效计数,下面的数字是实际频率的一半sampletime同理,原因是在CTCmode下频率其实要在prescaler的基础上再除个2.
if ((micros() - time8) > 2)
{
//当编码器码盘的OUTA脉冲信号下跳沿每中断一次,
// Test transition
state_b4 = digitalRead(PinB4) == LOW;
// and adjust counter + if B follows A
count4 += state_b4 ? +1 : -1;
}
time8 == micros();
}
int spdTrans(double data){
double InSpeed = data;
int OutSpeed = int(map(InSpeed, 0 , 1000, 50, 255));
return OutSpeed;
}
// 编码器转速计算中断子程序
void PIDSpeed()
{
spdVal1 = (count1/600)/(sampTime/500)*reduction*pi*D;//这里除500也是由于速度其实是2倍
//distance1 += (count1/1200) * pi * D;
//rotation1 += (count1/1200)*360;
//Serial.println(rotation1);
Serial.println(count1);
Serial.print("The right w_speed is: ");Serial.print(spdVal1); Serial.println("cm/s.");
count1=0;
spdVal2 = (count2/600)/(sampTime/500)*reduction*pi*D;//这里除500也是由于速度其实是2倍
//distance2 += (count2/1200) * pi * D;
//rotation2 += (count2/1200);
Serial.println(count2);
Serial.print("The left w_speed is: ");Serial.print(spdVal2); Serial.println("cm/s.");
count2=0;
spdVal3 = (count3/2000)/(sampTime/500)*reduction*pi*D;
spdVal4 = (count4/2000)/(sampTime/500)*reduction*pi*D;
count3 = 0;
count4 = 0;
//Serial.print("left speed: "); Serial.println(spdVal3);
//Serial.print("right speed: "); Serial.println(spdVal4);
if(spdInput != 0){
Direction = (spdInput>0)?HIGH:LOW;
digitalWrite(rev_sgn_pin,Direction);
spdOutput_l = (spdInput>0)?600:-600;
spdOutput_r = (spdInput>0)?600:-600;
if(abs(spdVal1) >= 10 && abs(spdVal2) >= 10){
err_l = spdInput-spdVal1;//设定速度-当前速度
err_r = spdInput-spdVal2;
isum_l += err_l*0.1;//积分值
isum_r += err_r*0.1;
dsum_l = err_l-err_lHis;//微分
dsum_r = err_r-err_rHis;
PIDOutput_l = kp_l*err_l+ki_l*isum_l+kd_l*dsum_l;//计算变化值
PIDOutput_r = kp_r*err_r+ki_r*isum_r+kd_r*dsum_r;
spdOutput_l += PIDOutput_l;
spdOutput_r += PIDOutput_r;//换算成速度
if(spdOutput_l < 0 && spdOutput_r < 0){
Direction = LOW;
digitalWrite(rev_sgn_pin, Direction);
}else{
Direction = HIGH;
digitalWrite(rev_sgn_pin, Direction);
}
//Serial.println(spdOutput_r);
//极限速度限制
if(spdOutput_l >= 1000 || spdOutput_l <= -1000){
analogWrite(l_acc_pin,255);
if(PIDOutput_l > 0){
isum_l -= err_l*0.1;//停止增加积分器
if(Direction = LOW){
spdOutput_l = -1000;
}else{
spdOutput_l = 1000;
}
topSpeedTime_l++;
}
}else{
int l_out = spdTrans(abs(spdOutput_l));
analogWrite(l_acc_pin,l_out);
//Serial.println(l_out);
topSpeedTime_l = 0;
}
if(spdOutput_r >= 1000 || spdOutput_r <= -1000){
analogWrite(r_acc_pin,255);
if(PIDOutput_r > 0){
isum_r -= err_r*0.1;
if(Direction = LOW){
spdOutput_r = -1000;
}else{
spdOutput_r = 1000;
}
topSpeedTime_r++;
}
}else{
int r_out = spdTrans(abs(spdOutput_r));
analogWrite(r_acc_pin,r_out);
topSpeedTime_r = 0;
}
err_l = err_lHis;//保存本次误差,下次使用
err_r = err_rHis;
if(topSpeedTime_l > 30 || topSpeedTime_r > 30){
Serial.println("speed safty lock initiate!");
err_l = 0;
err_r = 0;
spdInput = 0;
err_lHis = 0;
err_rHis = 0;
isum_l = 0;
isum_r = 0;
spdOutput_l = 0;
spdOutput_r = 0;
}
}else{
analogWrite(r_acc_pin,180);
analogWrite(l_acc_pin,180);
}
Serial.println(spdOutput_r);
Serial.println(spdOutput_l);
}else{
analogWrite(r_acc_pin,0);
analogWrite(l_acc_pin,0);
}
}
void changeDir()
{
Serial.println("r 1");
}
void setup()
{
pinMode(PinA1, INPUT_PULLUP);//因为编码器信号为欧姆龙E6B2-CWZ6C,为开漏输出,因此需要上拉电阻,此处采用arduino的内部上拉输入模式,置高
pinMode(PinB1, INPUT_PULLUP);//同上
pinMode(PinA2, INPUT_PULLUP);//同上
pinMode(PinB2, INPUT_PULLUP);
pinMode(PinA3, INPUT_PULLUP);
pinMode(PinB3, INPUT_PULLUP);
pinMode(PinA4, INPUT_PULLUP);
pinMode(PinB4, INPUT_PULLUP);
pinMode(l_acc_pin, OUTPUT);
pinMode(r_acc_pin, OUTPUT);
attachInterrupt(0, Encode_A1, RISING);//触发脉冲中断函数:执行Encode函数,捕捉A相信号,并判断A、B相先后顺序
//attachInterrupt(1, Encode_B1, RISING);
attachPinChangeInterrupt(PinA2, Encode_A2, RISING);
//attachPinChangeInterrupt(PinB2, Encode_B2, RISING);
attachPinChangeInterrupt(PinA3, Encode_A3, RISING);
//attachPinChangeInterrupt(PinB3, Encode_B3, RISING);
attachPinChangeInterrupt(PinA4, Encode_A4, RISING);
//attachPinChangeInterrupt(PinB4, Encode_B4, RISING);
//attachPinChangeInterrupt(rev_itr_pin, changeDir, CHANGE);
// attachInterrupt(1, Set_state , FALLING);//用于在捕捉到Z的零信号时,进行状态置零
FlexiTimer2::set(sampTime,PIDSpeed); //设置计时器参数以及终端子程序
FlexiTimer2::start();
Serial.begin (9600);
}
void loop()
{
while(Serial.available()>0){
if(Serial.read() == 'v'){
spdInput = Serial.parseInt();
Serial.println("speed input");
Serial.println(spdInput);
}
}
}
起初我认为是因为count的值溢出了所以导致数据变为负数,因此我尝试提高取样频率,这样count的清零更快,自然能够接受的最高速度也会更快。但是无论我怎样更改取样频率,能够读取的最高速度都不会发生变化,我尝试将arduino从nano换成mega2560来提高板子的运算速度但是也没有得到解决。
所以我分析既然开始发生错误的速度和程序没有太大关系,那问题应该是出现在硬件和逻辑上。有可能是编码器输出波形的速度太快arduino无法正确读取,也有可能是我的程序内哪些值没有清零或者哪些函数运算速度太慢导致高频时出错。
我的出错速度大概在编码器各相2500pulse/s的时候,编码器使用的是600pulse的增量式编码器和1000pulse的。
有没有做类似应用的兄弟遇到过这种问题,又是如何解决的呢?我不想给编码器加一个减速装置,这样成本太高了。
是不是中断的问题,使用板子自带的外部中断试试