diff --git a/remote_controler/remote_controler.ino b/remote_controler/remote_controler.ino index 87e9703..a99c378 100644 --- a/remote_controler/remote_controler.ino +++ b/remote_controler/remote_controler.ino @@ -1,31 +1,22 @@ //player1,remote controler #include -#include -#include -#include #include -RF24 radio(7,8);//端口可能要改 +//RF24 radio(7,8);//端口可能要改 +bool flag=false; SoftwareSerial sendingSerial(5,6); -String sending=""; -const int Rp=0,Rr=1,interval=20;//Rp,Rr 分别为两个遥杆的接口 +SoftwareSerial bluetoothSerial(7,8); +String sending="",received=""; +const int Rp=0,Rr=1,interval=100;//Rp,Rr 分别为两个遥杆的接口 long propeller=0,rudder=0,dist;//propeller为螺旋桨(0-1023,512为静止),rudder为舵(0-1023,512为静止) long sending_signal=0;//发送的信号 long response=0; -const byte addresser[6]={"00001"};//创建通信通道地址,6用来写,8用来读 +//const byte addresser[6]={"00001"};//创建通信通道地址,6用来写,8用来读 long time=0; void setup() { Serial.begin(9600); sendingSerial.begin(38400); - radio.begin(); - //radio.setChannel(115);//设置信道,115号通道 - radio.setDataRate(RF24_250KBPS); - radio.setRetries(3, 5); - radio.openWritingPipe(addresser); - radio.openReadingPipe(1,addresser); - radio.setPALevel(RF24_PA_MIN); - //Timer1.initialize(interval); - //Timer1.attachInterrupt(send); - radio.startListening(); + bluetoothSerial.begin(57600); + bluetoothSerial.listen(); } void send(){ @@ -41,10 +32,9 @@ void send(){ } void loop() { // put your main code here, to run repeatedly: - time=millis(); + //time=millis(); //Serial.println("send"); sending_signal=0; - radio.stopListening(); propeller=analogRead(Rp); rudder=analogRead(Rr); if(propeller>=1000)propeller=999; @@ -52,24 +42,23 @@ void loop() { sending_signal+=propeller; sending_signal+=rudder*1000; sending_signal+=1000000; - bool b=radio.write(&sending_signal,sizeof(sending_signal)); - Serial.println(b); - radio.startListening(); + sending=String(sending_signal); + bluetoothSerial.println(sending); + //Serial.println(sending); delay(interval); - //Serial.println("loop"); - if(radio.available()){ - Serial.print("response:"); - radio.read(&response,sizeof(response)); - Serial.println(response); - if(response%1000000==1){ - sending=String(response); - sendingSerial.print(sending); - sendingSerial.print('\n'); + while(bluetoothSerial.available()>0){ + //Serial.println("available!"); + if(bluetoothSerial.peek()!='\n'){//peek()查看当前字节是不是换行 + received+=(char)bluetoothSerial.read(); + //Serial.println(received); + //Serial.println("no \n"); } - else if(response==2000000){ - sending=String(response); - sendingSerial.print(sending); + else{ + bluetoothSerial.read();//把换行符读掉 + Serial.println(received); + sendingSerial.print(received); sendingSerial.print('\n'); + received=""; } } } diff --git a/remote_controler_board_2/remote_controler_board_2.ino b/remote_controler_board_2/remote_controler_board_2.ino index 28dc181..a09d7a9 100644 --- a/remote_controler_board_2/remote_controler_board_2.ino +++ b/remote_controler_board_2/remote_controler_board_2.ino @@ -77,6 +77,9 @@ void loop() { clr=true; } } + else{ + rec=false; + } received=""; } } diff --git a/ship/ship.ino b/ship/ship.ino index e52aa48..ea53ac9 100644 --- a/ship/ship.ino +++ b/ship/ship.ino @@ -1,8 +1,7 @@ #include -#include -#include #include "Arduino.h" #include "HardwareSerial.h" +#include #include #define trigPin 2 //超声波模块的Trig口 6# #define echoPin 5 //超声波模块的echo口 5# @@ -14,24 +13,22 @@ bool clr=false; int status=0; int clrtime=40; int x=0; - +const int interval=100; +String sending="",received=""; Servo MyServo; Servo RadarServo; -RF24 radio(7,8); +SoftwareSerial bluetoothSerial(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 propeller,rudder;//校验序列、读取内容和解码内容 long response=0; const byte addresses[6] = "00001"; //创建一个数组,建立接收机地址,或者说两个模块将用于通信的“管道” int calculateDistance() @@ -49,6 +46,8 @@ int calculateDistance() void setup() { Serial.begin(9600); + bluetoothSerial.begin(57600); + bluetoothSerial.listen(); MyServo.attach(4); RadarServo.attach(ServoPin); pinMode(trigPin,OUTPUT); @@ -61,11 +60,7 @@ void setup() 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); } @@ -74,71 +69,9 @@ long confirm(long x){ 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; + Serial.print("s: "); + Serial.println(status); if(status==0){ if(x<180){ x+=2; @@ -150,7 +83,14 @@ void loop() { //测距 distance = calculateDistance(); //send distance - response=1000000+x*1000+distance; + //response=1000000+x*1000+distance; + response=0; + response+=distance; + Serial.println(response); + response+=(long)x*1000; + Serial.println(response); + response+=1000000; + Serial.println(response); } else if(status==1){ if(x>0){ @@ -162,7 +102,14 @@ void loop() { RadarServo.write(x); //调整舵机角度 //测距 distance = calculateDistance(); - response=1000000+x*1000+distance; + //response=1000000+x*1000+distance; + response=0; + response+=distance; + Serial.println(response); + response+=(long)x*1000; + Serial.println(response); + response+=1000000; + Serial.println(response); //send distance } else if(status=2){ @@ -179,8 +126,86 @@ void loop() { //send clear response=2000000; } - radio.write(&response,sizeof(response)); + sending=String(response); + + Serial.print("x: "); + Serial.println(x); + Serial.print("d: "); + Serial.println(distance); + Serial.println(response); + Serial.println(sending); + bluetoothSerial.println(sending); + delay(interval); //delay(20-distance/17); Serial.println(distance); + while(bluetoothSerial.available()>0){ + //Serial.println("available!"); + if(bluetoothSerial.peek()!='\n'){//peek()查看当前字节是不是换行 + received+=(char)bluetoothSerial.read(); + //Serial.println(received); + //Serial.println("no \n"); + } + else{ + bluetoothSerial.read();//把换行符读掉 + //Serial.println(received); + //Serial.println(received.length()); + //content=toInt(received); + if(received[0]=='1'&&received.length()-1==7){ + propeller=received.substring(4).toInt(); + rudder=received.substring(1,4).toInt(); + 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); + } + } + received=""; + } + } }