参考自 Github 项目 ArduinoRadar 。原项目中 Processing 部分代码测试有疏漏,已修改并完成验证。
主要是通过超声波传感器测量目标距离,并借助舵机完成扫描巡视动作,最后通过 Processing 收集测量数据,并完成类似声纳显示器的图形绘制。
项目实物图如下:
Processing 绘制的类似监视器界面的动态图形如下:
一、准备材料
软件:
- Arduino IDE:编写 C 语言源代码并编译上传至 Ardunio 开发板。
- Processing:通过串口与 Arduino 开发板通信,获取实时数据并绘制类似监视器画面的动态图形。
硬件:
- Arduino Uno 或与之兼容的开发版:控制中心。
- 超声波传感器:测量目标距离。
- 舵机:承载超声波传感器,完成扫描动作。
二、连线示意图
线路连接示意图如下:
三、源代码
arduino C 程序源代码 radar.ino
:
#include <Servo.h>.
const int trigPin = 7;
const int echoPin = 8;
long duration;
int distance;
Servo myServo;
void setup() {
pinMode(trigPin, OUTPUT);
pinMode(echoPin, INPUT);
Serial.begin(9600);
myServo.attach(9);
}
void loop() {
for(int i=15;i<=165;i++){
myServo.write(i);
delay(30);
distance = calculateDistance();
Serial.print(i);
Serial.print(",");
Serial.print(distance);
Serial.print(".");
}
for(int i=165;i>15;i--){
myServo.write(i);
delay(30);
distance = calculateDistance();
Serial.print(i);
Serial.print(",");
Serial.print(distance);
Serial.print(".");
}
}
int calculateDistance() {
digitalWrite(trigPin, LOW);
delayMicroseconds(2);
digitalWrite(trigPin, HIGH);
delayMicroseconds(10);
digitalWrite(trigPin, LOW);
duration = pulseIn(echoPin, HIGH);
distance= duration*0.034/2;
return distance;
}
Processing 源代码 radar.pde
:
import processing.serial.*; // imports library for serial communication
import java.awt.event.KeyEvent; // imports library for reading the data from the serial port
import java.io.IOException;
String Port = "COM3"; //Arduino port
Serial myPort;
String angle="";
String distance="";
String data="";
String noObject;
float pixsDistance;
int iAngle, iDistance;
int index1=0;
int index2=0;
PFont orcFont;
void setup() {
size (1250, 650); //resolution
smooth();
myPort = new Serial(this, Port, 9600);
myPort.bufferUntil('.');
}
void draw() {
fill(98,245,31);
noStroke();
fill(0,4);
rect(0, 0, width, height-height*0.065);
fill(98,245,31);
drawRadar();
drawLine();
drawObject();
drawText();
}
void serialEvent (Serial myPort) {
data = myPort.readStringUntil('.');
data = data.substring(0,data.length()-1);
index1 = data.indexOf(",");
angle= data.substring(0, index1);
distance= data.substring(index1+1, data.length());
iAngle = int(angle);
iDistance = int(distance);
}
void drawRadar() {
pushMatrix();
translate(width/2,height-height*0.074);
noFill();
strokeWeight(2);
stroke(98,245,31);
arc(0,0,(width-width*0.0625),(width-width*0.0625),PI,TWO_PI);
arc(0,0,(width-width*0.27),(width-width*0.27),PI,TWO_PI);
arc(0,0,(width-width*0.479),(width-width*0.479),PI,TWO_PI);
arc(0,0,(width-width*0.687),(width-width*0.687),PI,TWO_PI);
line(-width/2,0,width/2,0);
line(0,0,(-width/2)*cos(radians(30)),(-width/2)*sin(radians(30)));
line(0,0,(-width/2)*cos(radians(60)),(-width/2)*sin(radians(60)));
line(0,0,(-width/2)*cos(radians(90)),(-width/2)*sin(radians(90)));
line(0,0,(-width/2)*cos(radians(120)),(-width/2)*sin(radians(120)));
line(0,0,(-width/2)*cos(radians(150)),(-width/2)*sin(radians(150)));
line((-width/2)*cos(radians(30)),0,width/2,0);
popMatrix();
}
void drawObject() {
pushMatrix();
translate(width/2,height-height*0.074);
strokeWeight(9);
stroke(255,10,10);
pixsDistance = iDistance*((height-height*0.1666)*0.025);
if(iDistance<40){ //range limit
line(pixsDistance*cos(radians(iAngle)),-pixsDistance*sin(radians(iAngle)),(width-width*0.505)*cos(radians(iAngle)),-(width-width*0.505)*sin(radians(iAngle)));
}
popMatrix();
}
void drawLine() {
pushMatrix();
strokeWeight(9);
stroke(30,250,60);
translate(width/2,height-height*0.074);
line(0,0,(height-height*0.12)*cos(radians(iAngle)),-(height-height*0.12)*sin(radians(iAngle)));
popMatrix();
}
void drawText() {
pushMatrix();
fill(0,0,0);
noStroke();
rect(0, height-height*0.0648, width, height);
fill(98,245,31);
textSize(15);
text("10cm",width-width*0.3854,height-height*0.0833);
text("20cm",width-width*0.281,height-height*0.0833);
text("30cm",width-width*0.177,height-height*0.0833);
text("40cm",width-width*0.0729,height-height*0.0833);
textSize(30);
text("Angle: " + iAngle +" °", width-width*0.48, height-height*0.0277);
text("Distance: ", width-width*0.26, height-height*0.0277);
if(iDistance<40) {
text(" " + iDistance +" cm", width-width*0.225, height-height*0.0277);
}
textSize(25);
fill(98,245,60);
translate((width-width*0.4994)+width/2*cos(radians(30)),(height-height*0.0907)-width/2*sin(radians(30)));
rotate(-radians(-60));
text("30°",0,0);
resetMatrix();
translate((width-width*0.503)+width/2*cos(radians(60)),(height-height*0.0888)-width/2*sin(radians(60)));
rotate(-radians(-30));
text("60°",0,0);
resetMatrix();
translate((width-width*0.507)+width/2*cos(radians(90)),(height-height*0.0833)-width/2*sin(radians(90)));
rotate(radians(0));
text("90°",0,0);
resetMatrix();
translate(width-width*0.513+width/2*cos(radians(120)),(height-height*0.07129)-width/2*sin(radians(120)));
rotate(radians(-30));
text("120°",0,0);
resetMatrix();
translate((width-width*0.5104)+width/2*cos(radians(150)),(height-height*0.0574)-width/2*sin(radians(150)));
rotate(radians(-60));
text("150°",0,0);
popMatrix();
}
注意 radar.pde
文件开头的 String Port = "COM3";
行代码,将 Port
变量的值 COM3
改为 Ardunio 开发板实际连接的串口号。