diff --git a/radar/radar.ino b/radar/radar.ino index 0416b35..25a1c5a 100644 --- a/radar/radar.ino +++ b/radar/radar.ino @@ -19,6 +19,9 @@ int Xmax = 160; //屏幕的横向像素数 int Xcent = Xmax / 2; //x中位 int base = 118; //基线高度 int scanline = 105; //雷达扫描线长度 +int outcircle=81; +int midcircle=54; +int incircle=27; Servo baseServo; Ucglib_ST7735_18x128x160_HWSPI ucg(/*cd=*/ 9, /*cs=*/ 10, /*reset=*/ 8); @@ -122,25 +125,25 @@ void fix() ucg.setColor(0, 40, 0); //画基线圆盘 ucg.drawDisc(Xcent, base+1, 3, UCG_DRAW_ALL); - ucg.drawCircle(Xcent, base+1, 115, UCG_DRAW_UPPER_LEFT); - ucg.drawCircle(Xcent, base+1, 115, UCG_DRAW_UPPER_RIGHT); - ucg.drawCircle(Xcent, base+1, 78, UCG_DRAW_UPPER_LEFT); - ucg.drawCircle(Xcent, base+1, 78, UCG_DRAW_UPPER_RIGHT); - ucg.drawCircle(Xcent, base+1, 40, UCG_DRAW_UPPER_LEFT); - ucg.drawCircle(Xcent, base+1, 40, UCG_DRAW_UPPER_RIGHT); + ucg.drawCircle(Xcent, base+1, outcircle, UCG_DRAW_UPPER_LEFT); + ucg.drawCircle(Xcent, base+1, outcircle, UCG_DRAW_UPPER_RIGHT); + ucg.drawCircle(Xcent, base+1, midcircle, UCG_DRAW_UPPER_LEFT); + ucg.drawCircle(Xcent, base+1, midcircle, UCG_DRAW_UPPER_RIGHT); + ucg.drawCircle(Xcent, base+1, incircle, UCG_DRAW_UPPER_LEFT); + ucg.drawCircle(Xcent, base+1, incircle, UCG_DRAW_UPPER_RIGHT); ucg.drawLine(0, base+1, Xmax,base+1); ucg.setColor(0, 120, 0); //画刻度表 - for(int i= 40;i < 140; i+=2) - { + // for(int i= 40;i < 140; i+=2) + // { - if (i % 10 == 0) - ucg.drawLine(105*cos(radians(i))+Xcent,base - 105*sin(radians(i)) , 113*cos(radians(i))+Xcent,base - 113*sin(radians(i))); - else + // if (i % 10 == 0) + // ucg.drawLine(105*cos(radians(i))+Xcent,base - 105*sin(radians(i)) , 113*cos(radians(i))+Xcent,base - 113*sin(radians(i))); + // else - ucg.drawLine(110*cos(radians(i))+Xcent,base - 110*sin(radians(i)) , 113*cos(radians(i))+Xcent,base - 113*sin(radians(i))); - } + // ucg.drawLine(110*cos(radians(i))+Xcent,base - 110*sin(radians(i)) , 113*cos(radians(i))+Xcent,base - 113*sin(radians(i))); + // } //画一些装饰性图案 ucg.setColor(0,200,0); @@ -172,6 +175,10 @@ void fix() ucg.drawTetragon(67,123,63,127,93,127,97,123); ucg.setColor(0,210,0); ucg.drawTetragon(72,123,68,127,88,127,92,123); + + // ucg.setColor(0,155, 0); + // ucg.setPrintPos(0,126); + // ucg.print("DEG: "); } @@ -189,16 +196,16 @@ void loop(void) baseServo.write(x); //调整舵机角度 //绘制雷达扫描线 - int f = x - 4; - ucg.setColor(0, 255, 0); - ucg.drawLine(Xcent, base, scanline*cos(radians(f))+Xcent,base - scanline*sin(radians(f))); - f+=2; - ucg.setColor(0, 128, 0); - ucg.drawLine(Xcent, base, scanline*cos(radians(f))+Xcent,base - scanline*sin(radians(f))); - f+=2; - ucg.setColor(0, 0, 0); - ucg.drawLine(Xcent, base, scanline*cos(radians(f))+Xcent,base - scanline*sin(radians(f))); - ucg.setColor(0,200, 0); + // int f = x - 4; + // ucg.setColor(0, 255, 0); + // ucg.drawLine(Xcent, base, scanline*cos(radians(f))+Xcent,base - scanline*sin(radians(f))); + // f+=2; + // ucg.setColor(0, 128, 0); + // ucg.drawLine(Xcent, base, scanline*cos(radians(f))+Xcent,base - scanline*sin(radians(f))); + // f+=2; + // ucg.setColor(0, 0, 0); + // ucg.drawLine(Xcent, base, scanline*cos(radians(f))+Xcent,base - scanline*sin(radians(f))); + // ucg.setColor(0,200, 0); //测距 distance = calculateDistance(); @@ -206,12 +213,12 @@ void loop(void) if (distance < 100) { ucg.setColor(255,0,0); - ucg.drawDisc(distance*cos(radians(x))+Xcent,-distance*sin(radians(x))+base, 1, UCG_DRAW_ALL); + ucg.drawDisc(0.8*distance*cos(radians(x))+Xcent,-0.8*distance*sin(radians(x))+base, 1, UCG_DRAW_ALL); } else { //超过1米以上的,用黄色画在边缘区域示意 ucg.setColor(255,255,0); - ucg.drawDisc(116*cos(radians(x))+Xcent,-116*sin(radians(x))+base, 1, UCG_DRAW_ALL); + ucg.drawDisc((outcircle-1)*cos(radians(x))+Xcent,-(outcircle-1)*sin(radians(x))+base, 1, UCG_DRAW_ALL); } @@ -221,23 +228,23 @@ void loop(void) Serial.println(distance); - if (x > 70 and x < 110) fix_font(); //扫描线和数字重合时,重绘数字 + //if (x > 70 and x < 110) fix_font(); //扫描线和数字重合时,重绘数字 - ucg.setColor(0,155, 0); - ucg.setPrintPos(0,126); - ucg.print("DEG: "); - ucg.setPrintPos(24,126); - ucg.print(x); - ucg.print(" "); - ucg.setPrintPos(125,126); - ucg.print(" "); - ucg.print(distance); - ucg.print("cm "); + // ucg.setColor(0,155, 0); + // ucg.setPrintPos(0,126); + // ucg.print("DEG: "); + //ucg.setPrintPos(24,126); + //ucg.print(x); + // ucg.print(" "); + //ucg.setPrintPos(125,126); + // ucg.print(" "); + //ucg.print(distance); + // ucg.print("cm "); } - //ucg.clearScreen(); //清屏 如果arduino供电不足,可能会引起白屏(显示信号中断)可以用 cls();函数代替 ucg.clearScreen(); + ucg.clearScreen(); //清屏 如果arduino供电不足,可能会引起白屏(显示信号中断)可以用 cls();函数代替 ucg.clearScreen(); delay(50); - cls(); //如有频繁白屏情况,可以使用该函数 。或者增加外部供电 + //cls(); //如有频繁白屏情况,可以使用该函数 。或者增加外部供电 fix(); fix_font(); //重绘屏幕背景元素 @@ -246,16 +253,16 @@ void loop(void) baseServo.write(x); //调整舵机角度 //绘制雷达扫描线 - int f = x + 4; - ucg.setColor(0, 255, 0); - ucg.drawLine(Xcent, base, scanline*cos(radians(f))+Xcent,base - scanline*sin(radians(f))); - f-=2; - ucg.setColor(0, 128, 0); - ucg.drawLine(Xcent, base, scanline*cos(radians(f))+Xcent,base - scanline*sin(radians(f))); - f-=2; - ucg.setColor(0, 0, 0); - ucg.drawLine(Xcent, base, scanline*cos(radians(f))+Xcent,base - scanline*sin(radians(f))); - ucg.setColor(0, 200, 0); + // int f = x + 4; + // ucg.setColor(0, 255, 0); + // ucg.drawLine(Xcent, base, scanline*cos(radians(f))+Xcent,base - scanline*sin(radians(f))); + // f-=2; + // ucg.setColor(0, 128, 0); + // ucg.drawLine(Xcent, base, scanline*cos(radians(f))+Xcent,base - scanline*sin(radians(f))); + // f-=2; + // ucg.setColor(0, 0, 0); + // ucg.drawLine(Xcent, base, scanline*cos(radians(f))+Xcent,base - scanline*sin(radians(f))); + // ucg.setColor(0, 200, 0); //测距 distance = calculateDistance(); @@ -263,12 +270,12 @@ void loop(void) if (distance < 100) { ucg.setColor(255,0,0); - ucg.drawDisc(distance*cos(radians(x))+Xcent,-distance*sin(radians(x))+base, 1, UCG_DRAW_ALL); + ucg.drawDisc(0.8*distance*cos(radians(x))+Xcent,-0.8*distance*sin(radians(x))+base, 1, UCG_DRAW_ALL); } else { //超过1米以上的,用黄色画在边缘区域示意 ucg.setColor(255,255,0); - ucg.drawDisc(116*cos(radians(x))+Xcent,-116*sin(radians(x))+base, 1, UCG_DRAW_ALL); + ucg.drawDisc((outcircle-1)*cos(radians(x))+Xcent,-(outcircle-1)*sin(radians(x))+base, 1, UCG_DRAW_ALL); } //调试代码,输出角度和测距值 @@ -276,23 +283,23 @@ void loop(void) Serial.print(" , "); Serial.println(distance); - if (x > 70 and x < 110) fix_font(); //扫描线和数字重合时,重绘数字 + //if (x > 70 and x < 110) fix_font(); //扫描线和数字重合时,重绘数字 - ucg.setColor(0,155, 0); - ucg.setPrintPos(0,126); - ucg.print("DEG: "); - ucg.setPrintPos(24,126); - ucg.print(x); - ucg.print(" "); - ucg.setPrintPos(125,126); - ucg.print(" "); - ucg.print(distance); - ucg.print("cm "); + // ucg.setColor(0,155, 0); + // ucg.setPrintPos(0,126); + // ucg.print("DEG: "); + // ucg.setPrintPos(24,126); + // ucg.print(x); + // ucg.print(" "); + //ucg.setPrintPos(125,126); + // ucg.print(" "); + //ucg.print(distance); + // ucg.print("cm "); } - //ucg.clearScreen(); // + ucg.clearScreen(); // delay(50); - cls(); + //cls(); } \ No newline at end of file diff --git a/remote_controler/remote_controler.ino b/remote_controler/remote_controler.ino index 617ebdb..48a1a3a 100644 --- a/remote_controler/remote_controler.ino +++ b/remote_controler/remote_controler.ino @@ -4,55 +4,41 @@ #include #include RF24 radio(7,8);//端口可能要改 -const int Rp=0,Rr=1,interval=20;//Rp,Rr 分别为两个遥杆的接口,间断20ms -long propeller=0,rudder=0;//propeller为螺旋桨(0-1023,512为静止),rudder为舵(0-1023,512为静止) -long s_propeller=0,s_rudder=0;//发送的信号 -long check_array[6]; +const int Rp=0,Rr=1,interval=20;//Rp,Rr 分别为两个遥杆的接口 +long propeller=0,rudder=0,dist;//propeller为螺旋桨(0-1023,512为静止),rudder为舵(0-1023,512为静止) +long sending_signal=0;//发送的信号 const byte addresser[6]={"00001"};//创建通信通道地址,6用来写,8用来读 void setup() { // put your setup code here, to run once: Serial.begin(9600); radio.begin(); //radio.setChannel(114);//设置信道,114号通道 - radio.openWritingPipe(addresser);//6 - radio.openReadingPipe(1,addresser);//8 + radio.openWritingPipe(addresser); + radio.openReadingPipe(1,addresser); radio.setPALevel(RF24_PA_HIGH); Timer1.initialize(interval); - Timer1.attachInterrupt(Send); + Timer1.attachInterrupt(send); } -void Send(){//发送信号函数 +void send(){ + sending_signal=0; radio.stopListening(); - Serial.println("stop listening!"); propeller=analogRead(Rp); rudder=analogRead(Rr); + if(propeller>=1000)propeller=999; + if(rudder>=1000)rudder=999; + sending_signal+=propeller; + sending_signal+=rudder*1000; + sending_signal+=1000000; + radio.write(&sending_signal,sizeof(sending_signal)); Serial.println(propeller); Serial.println(rudder); - propeller+=create_checknumber(propeller)*10000; - rudder+=create_checknumber(rudder)*10000; - propeller+=100000; - rudder+=200000; - radio.write(&propeller,sizeof(propeller)); - radio.write(&rudder,sizeof(rudder)); - Serial.print("propeller sent"); + Serial.print("propeller sent "); Serial.println(propeller); - Serial.print("rudder sent"); + Serial.print("rudder sent "); Serial.println(rudder); -} -long create_checknumber(long x){//创造校验码,校验码规则:个位×4,十位×3,百位×2,千位×1 - long add=0,sum=0; - while(x!=0){ - check_array[add]=x%10; - x/=10; - add++; - } - for(int i=0,j=4;i