RC_Boat/ship/ship.ino

162 lines
3.9 KiB
Arduino
Raw Normal View History

2023-09-04 06:54:15 +00:00
#include<SPI.h>
#include<nRF24L01.h>
#include<RF24.h>
#include "Arduino.h"
#include "HardwareSerial.h"
#include<Servo.h>
Servo MyServo;
Servo RidaServo;
RF24 radio(7,8);
int count =0;
2023-09-04 13:42:44 +00:00
int IN1 =9;
int IN2 =10;
2023-09-04 06:54:15 +00:00
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-1023512为静止rudder为舵0-1023512为静止
//long s_propeller=0,s_rudder=0;//发送的信号
2023-09-04 13:42:44 +00:00
long propeller,rudder,content;//校验序列、读取内容和解码内容
2023-09-04 06:54:15 +00:00
const byte addresses[6] = "00001"; //创建一个数组,建立接收机地址,或者说两个模块将用于通信的“管道”
2023-09-04 13:42:44 +00:00
2023-09-04 06:54:15 +00:00
void setup()
{
2023-09-04 13:42:44 +00:00
Serial.begin(9600);
MyServo.attach(4);
RidaServo.attach(5);
pinMode(TrigPin,OUTPUT);
pinMode(EcoPin,INPUT);
pinMode(IN1,OUTPUT);
pinMode(IN2,OUTPUT);
pinMode(PWM,OUTPUT);
pinMode(A1,INPUT);
pinMode(A2,INPUT);
MyServo.write(angle);
2023-09-04 06:54:15 +00:00
radio.begin();
2023-09-04 13:42:44 +00:00
//radio.setChannel(114);
2023-09-04 06:54:15 +00:00
radio.openReadingPipe(1,addresses); //接收通道,
radio.openWritingPipe(addresses);//发送通道
radio.setPALevel(RF24_PA_HIGH); //设置功率放大器级别,将其设置为最小值
2023-09-04 13:42:44 +00:00
delay(1000);
MyServo.write(45);
}
long confirm(long x){
if(x>=1000000&&x<=2000000)return x%1000000;
else return -1;
2023-09-04 06:54:15 +00:00
}
void loop() {
2023-09-04 13:42:44 +00:00
radio.startListening();
// Serial.println("start listening!");
/*if(angle<=0){
2023-09-04 06:54:15 +00:00
dAngle=5;
}
else if(angle>=180){
dAngle=-5;
}
2023-09-04 13:42:44 +00:00
/*angle=angle+dAngle;
2023-09-04 06:54:15 +00:00
RidaServo.write(angle);
digitalWrite(TrigPin,LOW);
delayMicroseconds(8);
digitalWrite(TrigPin,HIGH);
delayMicroseconds(10);
digitalWrite(TrigPin,LOW);
dist=pulseIn(EcoPin,HIGH,58800)/58.8;
if(dist<=0.5){
dist=100.0;
}
if(dist/17<period){
delay(period-dist/17);
2023-09-04 13:42:44 +00:00
} */
2023-09-04 06:54:15 +00:00
radio.startListening();
2023-09-04 13:42:44 +00:00
// Serial.println("start listening!");
2023-09-04 06:54:15 +00:00
if(radio.available()>0){
2023-09-04 13:42:44 +00:00
radio.read(&content,sizeof(content));
2023-09-04 06:54:15 +00:00
Serial.println("The content is");
Serial.println(content);//调试
2023-09-04 13:42:44 +00:00
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);
2023-09-04 06:54:15 +00:00
}
2023-09-04 13:42:44 +00:00
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);
2023-09-04 06:54:15 +00:00
}
}
2023-09-04 13:42:44 +00:00
else if(rudder<=550||rudder>=449)
{
dj=0;
MyServo.write(45);
Serial.println("stop turing");
Serial.println(dj);
2023-09-04 06:54:15 +00:00
}
}
2023-09-04 13:42:44 +00:00
}
2023-09-04 06:54:15 +00:00
// radio.stopListening();
//radio.write(&dist,sizeof(dist));
// radio.write(&dj,sizeof(dj));
//radio.write(&z,sizeof(z));
//radio.startListening();
//delay(20);
/* if (radio.available()) { //判断是否有要接收的数据
radio.read(response,sizeof(response));
Serial.print(text);
Serial.println(response);
}*/
//delay(20); //延迟等待0.3秒
//text++;
}