#include #include #include #include "Arduino.h" #include "HardwareSerial.h" #include #define trigPin 2 //超声波模块的Trig口 6# #define echoPin 5 //超声波模块的echo口 5# #define ServoPin 3 //底座舵机端口 3# unsigned long time=0; bool increasing=true; bool clr=false; //0: increase 1: decrease 2: clr int status=0; int clrtime=40; int x=0; Servo MyServo; Servo RadarServo; RF24 radio(7,8); int count =0; int IN1 =9; int IN2 =10; int PWM=6; // int TrigPin=2; // int EcoPin=3; // int dAngle=5; int angle=90; int period=25; // float dist; long dj,z;//dj是舵机,z是螺旋桨转速 //long propeller=0,rudder=0;//propeller为螺旋桨(0-1023,512为静止),rudder为舵(0-1023,512为静止) //long s_propeller=0,s_rudder=0;//发送的信号 long propeller,rudder,content;//校验序列、读取内容和解码内容 long response=0; const byte addresses[6] = "00001"; //创建一个数组,建立接收机地址,或者说两个模块将用于通信的“管道” int calculateDistance() { long duration; digitalWrite(trigPin, LOW); delayMicroseconds(2); digitalWrite(trigPin, HIGH); delayMicroseconds(10); digitalWrite(trigPin, LOW); duration = pulseIn(echoPin, HIGH); return duration*0.034/2; } void setup() { Serial.begin(9600); MyServo.attach(4); RadarServo.attach(ServoPin); pinMode(trigPin,OUTPUT); pinMode(echoPin,INPUT); pinMode(IN1,OUTPUT); pinMode(IN2,OUTPUT); pinMode(PWM,OUTPUT); pinMode(A1,INPUT); pinMode(A2,INPUT); MyServo.write(angle); RadarServo.write(0); radio.begin(); //radio.setChannel(114); radio.openReadingPipe(1,addresses); //接收通道, radio.openWritingPipe(addresses);//发送通道 radio.setPALevel(RF24_PA_MIN); //设置功率放大器级别,将其设置为最小值 delay(1000); MyServo.write(45); } long confirm(long x){ if(x>=1000000&&x<=2000000)return x%1000000; else return -1; } void loop() { radio.startListening(); delay(20); if(radio.available()){ radio.read(&content,sizeof(content)); Serial.println("The content is"); Serial.println(content);//调试 content=confirm(content); if(content!=-1){ propeller=content%1000; rudder=(content-propeller)/1000; if(propeller>550||propeller<449){ if(propeller>550){ long zheng=0.568*propeller-312.4; digitalWrite(IN2,HIGH); digitalWrite(IN1,LOW); analogWrite(PWM,zheng); z=zheng; Serial.println("forward propelling"); Serial.println(z); } else if(propeller<449){ long fan=255-0.568*propeller; digitalWrite(IN1,HIGH); digitalWrite(IN2,LOW); analogWrite(PWM,fan); z=fan; Serial.println("back propelling"); Serial.println(z); } } else if(propeller<=550||propeller>=449){ z=0; analogWrite(PWM,0); Serial.println("stop propelling"); Serial.println(z); } Serial.println("inputing ruddering"); if(rudder>550||rudder<449) { if(rudder<449){ long fan1=0.1*rudder; MyServo.write(fan1); Serial.println("turn left"); dj=2*fan1-90; Serial.println(dj); } else if(rudder>550){ long zheng1=0.1*rudder-10.122; MyServo.write(zheng1); dj=2*zheng1-90; Serial.println("turn right"); Serial.println(dj); } } else if(rudder<=550||rudder>=449){ dj=0; MyServo.write(45); Serial.println("stop turing"); Serial.println(dj); } } } radio.stopListening(); int distance=0; if(status==0){ if(x<180){ x+=2; } else{ status=2; } RadarServo.write(x); //调整舵机角度 //测距 distance = calculateDistance(); //send distance response=1000000+x*1000+distance; } else if(status==1){ if(x>0){ x-=2; } else{ status=2; } RadarServo.write(x); //调整舵机角度 //测距 distance = calculateDistance(); response=1000000+x*1000+distance; //send distance } else if(status=2){ clrtime--; if(clrtime<=0){ clrtime=4; if(x>=180){ status=1; } else{ status=0; } } //send clear response=2000000; } radio.write(&response,sizeof(response)); //delay(20-distance/17); Serial.println(distance); }