硬件:
Arduino UNO
红外遥控接受接受模块
LCD12864 液晶显示屏
红外发射器
代码:
#include "InfraredRemote.h"
#include "LCD12864RSPI.h" //3,8,9 引脚
#define AR_SIZE( a ) sizeof( a ) / sizeof( a[0] )
unsigned char show0[]={0xBA, 0xEC,0xCD, 0xE2,0xD2, 0xA3,0xBF, 0xD8,0xB6, 0xE6,0xBB, 0xFA}; //红外遥控舵机
unsigned char show1[]={0xD2, 0xA3,0xBF, 0xD8,0xD6, 0xB8,0xC1, 0xEE,0x3A, 0x00}; //遥控指令:
unsigned char show2[]={0xD0, 0xFD,0xD7, 0xAA,0xBD, 0xC7,0xB6, 0xC8,0x3A, 0x00}; //旋转角度:
unsigned char show3[]={0x28, 0x00,0xB0, 0xB4,0x30, 0x00,0xB8, 0xB4,0xD4, 0xAD,0x29, 0x00}; //(按0复原)
#define PWM_pin 2 //舵机引脚
int pulsewidth = 0; //高电平时间
char d[3]; //定义年值存储数组,3位
void setup()
{
Serial.begin(9600);
pinMode(PWM_pin,OUTPUT);
pinMode(IR_IN,INPUT_PULLUP);//设置红外接收引脚为输入
Serial.flush(); //清除串口缓冲器内容函数。
timer1_init();//定时器初始化
startRun(0);
LCDA.Initialise();
delay(100);
LCDA.DisplayString(0,1,show0,AR_SIZE(show0));
LCDA.DisplayString(1,0,show1,AR_SIZE(show1));
LCDA.DisplayString(1,5," ",AR_SIZE(" "));
LCDA.DisplayString(2,0,show2,AR_SIZE(show1));
LCDA.DisplayString(2,5,"0",AR_SIZE("0"));
LCDA.DisplayString(3,1,show3,AR_SIZE(show3));
}
void loop()
{
remote_decode(); //译码
if( adrL_code == 0x45 ) {
LCDA.DisplayString(1,5," 1 ",AR_SIZE(" 1 "));
//Serial.println("1");
startRun(10);
} else if( adrL_code == 0x46) {
LCDA.DisplayString(1,5," 2 ",AR_SIZE(" 2 "));
//Serial.println("2");
startRun(20);
}else if( adrL_code == 0x47 ) {
LCDA.DisplayString(1,5," 3 ",AR_SIZE(" 3 "));
//Serial.println("3");
startRun(30);
} else if( adrL_code == 0x44 ) {
LCDA.DisplayString(1,5," 4 ",AR_SIZE(" 4 "));
//Serial.println("4");
startRun(40);
} else if( adrL_code == 0x40 ) {
LCDA.DisplayString(1,5," 5 ",AR_SIZE(" 5 "));
//Serial.println("5");
startRun(50);
} else if( adrL_code == 0x43 ) {
LCDA.DisplayString(1,5," 6 ",AR_SIZE(" 6 "));
//Serial.println("6");
startRun(60);
} else if( adrL_code == 0x07 ) {
LCDA.DisplayString(1,5," 7 ",AR_SIZE(" 7 "));
//Serial.println("7");
startRun(70);
} else if( adrL_code == 0x15) {
LCDA.DisplayString(1,5," 8 ",AR_SIZE(" 8 "));
//Serial.println("8");
startRun(80);
} else if( adrL_code == 0x09 ){
LCDA.DisplayString(1,5," 9 ",AR_SIZE(" 9 "));
//Serial.println("9");
startRun(90);
} else if( adrL_code == 0x19) {
LCDA.DisplayString(1,5," 0 ",AR_SIZE(" 0 "));
//Serial.println("0");
startRun(0);
} else if( adrL_code == 0x16) {
LCDA.DisplayString(1,5," * ",AR_SIZE(" * "));
//Serial.println("*");
startRun(100);
} else if( adrL_code == 0x0d) {
LCDA.DisplayString(1,5," # ",AR_SIZE(" # "));
//Serial.println("#");
startRun(110);
} else if( adrL_code == 0x18) {
LCDA.DisplayString(1,5," Up",AR_SIZE(" Up"));
//Serial.println("Up");
startRun(120);
} else if( adrL_code == 0x08 ){
LCDA.DisplayString(1,5," L ",AR_SIZE(" L "));
//Serial.println("left");
startRun(130);
} else if( adrL_code == 0x1C ){
LCDA.DisplayString(1,5," OK",AR_SIZE(" OK"));
//Serial.println(" OK ");
startRun(140);
} else if(adrL_code == 0x5A) {
LCDA.DisplayString(1,5," R ",AR_SIZE(" R "));
//Serial.println("Right");
startRun(150);
} else if( adrL_code == 0x52 ) {
LCDA.DisplayString(1,5," D ",AR_SIZE(" D "));
//Serial.println("Down");
startRun(160);
}
adrL_code = 0x00;
adrH_code = 0x00;
ir_code = 0x00;
}
void servopulse(int servopin, int myangle) /*定义一个脉冲函数,用来模拟方式产生PWM值*/
{
pulsewidth = (myangle * 11) + 500; //将角度转化为500-2480 的脉宽值
digitalWrite(servopin, HIGH); //将舵机接口电平置高
delayMicroseconds(pulsewidth);//延时脉宽值的微秒数
digitalWrite(servopin, LOW); //将舵机接口电平置低
delay(20 - pulsewidth / 1000); //延时周期内剩余时间
}
void startRun(int degree) {
if (degree >= 0 && degree <= 180) //判断收到数据值是否符合范围
{
//直接获取旋转角度
dtostrf(degree,3,0,d);
LCDA.DisplayString(2,5,(unsigned char *)d,AR_SIZE(d));
//Serial.print("moving servo to ");
//Serial.print(degree, DEC);
//Serial.println();
for (int i = 0; i <= 50; i++) //产生PWM个数,等效延时以保证能转到响应角度
{
servopulse(PWM_pin, degree); //模拟产生PWM
}
}
}
InfraredRemote.h
#ifndef __InfraredRemote__H__
#define __InfraredRemote__H__
#include <Arduino.h>
#define IR_IN 11 //红外接收
extern void timer1_init(void); //定时器初始化函数
extern char logic_value();//判断逻辑值“0”和“1”子函数
extern void pulse_deal();//接收地址码和命令码脉冲函数
extern void remote_decode(void);
extern void remote_deal(void);//执行译码结果函数
extern unsigned int ir_code;// 用户编码值
extern unsigned int adrL_code;//命令码
extern unsigned int adrH_code;//命令码反码
#endif
InfraredRemote.cpp
#include "InfraredRemote.h"
int Pulse_Width = 0;//存储脉宽
unsigned int ir_code = 0x00;// 用户编码值
unsigned int adrL_code = 0x00;//命令码
unsigned int adrH_code = 0x00;//命令码反码
void timer1_init(void)//定时器初始化函数
{
TCCR1A = 0X00;
TCCR1B = 0X05;//给定时器时钟源 //64us进行一次计数器累加
TCCR1C = 0X00;
TCNT1 = 0X00;
TIMSK1 = 0X00; //禁止定时器溢出中断
}
void remote_deal(void)//执行译码结果函数
{ //数据显示
Serial.print("\nir_code:");
Serial.println(ir_code,HEX);//16进制显示
Serial.print("adrL_code:");
Serial.println(adrL_code,HEX);//16进制显示
Serial.print("adrH_code:");
Serial.println(adrH_code,HEX);//16进制显示
}
char logic_value()//判断逻辑值“0”和“1”子函数
{
TCNT1 = 0X00;
while(!(digitalRead(IR_IN))); //低等待
Pulse_Width=TCNT1;
TCNT1=0;
if(Pulse_Width>=7&&Pulse_Width<=10)//低电平560us
{
while(digitalRead(IR_IN));//是高就等待
Pulse_Width=TCNT1;
TCNT1=0;
if(Pulse_Width>=7&&Pulse_Width<=10)//接着高电平560us
return 0;
else if(Pulse_Width>=25&&Pulse_Width<=27) //接着高电平1.7ms
return 1;
}
return -1;
}
void pulse_deal()//接收地址码和命令码脉冲函数
{
int i;
int j;
ir_code=0x00;// 清零
adrL_code=0x00;// 清零
adrH_code=0x00;// 清零
//解析遥控器编码中的用户编码值
for(i = 0 ; i < 16; i++)
{
if(logic_value() == 1) //是1
ir_code |= (1<<i);//保存键值
}
//解析遥控器编码中的命令码
for(i = 0 ; i < 8; i++)
{
if(logic_value() == 1) //是1
adrL_code |= (1<<i);//保存键值
}
//解析遥控器编码中的命令码反码
for(j = 0 ; j < 8; j++)
{
if(logic_value() == 1) //是1
adrH_code |= (1<<j);//保存键值
}
remote_deal();
}
void remote_decode(void)//译码函数
{
TCNT1=0X00;
while(digitalRead(IR_IN))//是高就等待
{
//if(TCNT1>=1563) //当高电平持续时间超过100ms,表明此时没有按键按下
//{
// ir_code=0x00ff;// 用户编码值
// adrL_code=0x00;//键码前一个字节值
// adrH_code=0x00;//键码后一个字节值
// return;
//}
}
//如果高电平持续时间不超过100ms
TCNT1=0X00;
while(!(digitalRead(IR_IN))); //低等待
Pulse_Width=TCNT1;
TCNT1=0;
if(Pulse_Width>=140&&Pulse_Width<=141)//9ms
{
while(digitalRead(IR_IN));//是高就等待
Pulse_Width=TCNT1;
TCNT1=0;
if(Pulse_Width>=68&&Pulse_Width<=72)//4.5ms
{
pulse_deal();
return;
}
else if(Pulse_Width>=34&&Pulse_Width<=36)//2.25ms
{
while(!(digitalRead(IR_IN)));//低等待
Pulse_Width=TCNT1;
TCNT1=0;
if(Pulse_Width>=7&&Pulse_Width<=10)//560us
{
return;
}
}
}
}
|