|
本帖最后由 xiao11duo9 于 2018-5-6 19:46 编辑
#include <MsTimer2.h>
#include <TimerOne.h>
int apin = 2; //定义引脚为D2 右前
int bpin = 3; //定义引脚为D3 右后
int cpin = 4; //定义引脚为D4 左后
int dpin = 5; //定义引脚为D5 左前
int sd_sum;
unsigned long rfduration=0;
unsigned long rrduration=0;
unsigned long lrduration=0;
unsigned long lfduration=0;
unsigned long rfdurationhigh=0;
unsigned long rrdurationhigh=0;
unsigned long lrdurationhigh=0;
unsigned long lfdurationhigh=0;
//2017.10.15 update
int flag1 = 0;
boolean _down1 = false;
int flag2 = 0;
boolean _down2 = false;
int flag3 = 0;
boolean _down3 = false;
int flag4 = 0;
boolean _down4 = false;
unsigned long count_100us=0; //因為 使用內部 timer2, timer2 的計數器 counter 與 timer0 的都只有 8 bit, 受限於 8-bit 配合 Prescaler 64, 無法做到真的剛好 1ms, 它所謂的 1ms 其實是 1.024ms;
int count_50ms=0;
int flag_100us=0;
unsigned long count1=0;
unsigned long count2=0;
unsigned long count3=0;
unsigned long count4=0;
void frequency_division() //分频子程序
{
count1++;
count2++;
count3++;
count4++;
flag_100us++;
}
void senddata()
{
if((rfduration != 0) && (rrduration != 0)&&(lfduration != 0) && (lrduration != 0)) //2018.5.3 update
{
Serial.write(0xEB);
Serial.write(0x90);//同步码
Serial.write(rfduration);//右前旋翼转速低字节
rfdurationhigh = rfduration >> 8;
Serial.write(rfdurationhigh);//右前旋翼转速高字节
Serial.write(rrduration);//右后旋翼转速低字节
rrdurationhigh = rrduration >> 8;
Serial.write(rrdurationhigh);//右后旋翼转速高字节
Serial.write(lrduration);//左后旋翼转速低字节
lrdurationhigh = lrduration >> 8;
Serial.write(lrdurationhigh);//左后旋翼转速高字节
Serial.write(lfduration);//左前旋翼转速低字节
lfdurationhigh = lfduration >> 8;
Serial.write(lfdurationhigh);//左前旋翼转速高字节
sd_sum = rfduration + rfdurationhigh + rrduration + rrdurationhigh + lrduration + lrdurationhigh + lfduration + lfdurationhigh; //字节和
Serial.write(sd_sum);//校验码
}
}
/*
void senddata() {
Serial.println(rfduration);//右前旋翼转速低字节
Serial.println(rrduration);//右后旋翼转速低字节
Serial.println(lrduration);//左后旋翼转速低字节
Serial.print(lfduration);//左前旋翼转速低字节
Serial.println(";");
}
*/
void setup()
{
Serial.begin(19200); //串口波特率为19200
pinMode(apin, INPUT); //设置2引脚为输入模式
pinMode(bpin, INPUT); //设置3引脚为输入模式
pinMode(cpin, INPUT); //设置4引脚为输入模式
pinMode(dpin, INPUT); //设置5引脚为输入模式
delay(500);
MsTimer2::set(100,senddata);//10hz发送速率
MsTimer2::start();
Timer1.initialize( 100 ); // 初始化,以 micro sec 為單位 100us计数
Timer1.attachInterrupt( frequency_division); // attach the servic e routine here
}
void loop()
{
if(flag_100us==1)
{
//读取电机1 rf 转速
if(digitalRead(apin) == HIGH)
{
flag1 = 1;
}
if((digitalRead(apin) == LOW) && (flag1 == 1))
{
_down1 = true; flag1 = 0;
}
if(_down1)
{
_down1 = false; //下面写希望检测到下降沿后执行的程序
rfduration=(600000/count1);//转速1(单位rpm)
count1=0;
}
//读取电机2 rr 转速
if(digitalRead(bpin) == HIGH)
flag2 = 1;
if((digitalRead(bpin) == LOW) && (flag2 == 1))
{
_down2 = true; flag2 = 0;
}
if(_down2)
{
_down2 = false;//下面写希望检测到下降沿后执行的程序
rrduration=(600000/count2);//转速2(单位rpm)
count2=0;
}
//读取电机3 lr 转速
if(digitalRead(cpin) == HIGH)
flag3 = 1;
if((digitalRead(cpin) == LOW) && (flag3 == 1))
{
_down3 = true; flag3 = 0;
}
if(_down3)
{
_down3 = false; //下面写希望检测到下降沿后执行的程序
lrduration=(600000/count3);//转速3(单位rpm)
count3=0;
}
//读取电机4 lf 转速
if(digitalRead(dpin) == HIGH)
flag4 = 1;
if((digitalRead(dpin) == LOW) && (flag4 == 1))
{
_down4 = true; flag4 = 0;
}
if(_down4)
{
_down4 = false; //下面写希望检测到下降沿后执行的程序
lfduration=(600000/count4);//转速4(单位rpm)
count4=0;
}
flag_100us=0;
}
}
|
|