Now the code for the topside controller.
This is incomplete, but it works. You will have to modify it to read your game controller instead of my analogue joystick. You may find the Arduino Joystick library useful for that.
You'll also have to install the EasyTransfer library, and the NewLiquidCrystal library by fmalpardita if you plan to use I2C liquid crystal displays.
Code: Select all
// ///////////////////// //
// //
// ROV Console //
// Bennachie 20/08/19 //
// //
// ///////////////////// //
// This code was designed for the fmalpardita library (NewLiquidCrystal)
#include <EasyTransfer.h>
#include <Wire.h>
#define baudRate 115200 // Serial port baud rate
#include <LiquidCrystal_I2C.h>
#define I2C_ADDR 0x27 //Address for LCD display. Usually is 0x27 or 0x32.
LiquidCrystal_I2C lcd(I2C_ADDR,2,1,0,4,5,6,7); //Set up library to talk to LCD.
//Create two objects for EasyTransfer.
EasyTransfer ETin, ETout;
struct RECEIVE_DATA_STRUCTURE{
//Put your variable definitions here for the data you want to RECEIVE
//THIS MUST BE EXACTLY THE SAME ON THE OTHER ARDUINO
int16_t heading;
int16_t depth;
int16_t battery;
};
struct SEND_DATA_STRUCTURE{
//Put your variable definitions here for the data you want to SEND
//THIS MUST BE EXACTLY THE SAME ON THE OTHER ARDUINO
int16_t portvert;
int16_t stbdvert;
int16_t portfwd;
int16_t stbdfwd;
int16_t portaft;
int16_t stbdaft;
int16_t lights;
int16_t pan;
int16_t tilt;
};
//Give a name to the group of data
RECEIVE_DATA_STRUCTURE rxdata;
SEND_DATA_STRUCTURE txdata;
//Declare global variables
int slider = 511;
int xaxis = 511;
int yaxis = 511;
int zaxis = 511;
int portfwd1;
int stbdfwd1;
int portaft1;
int stbdaft1;
int16_t portvert;
int16_t stbdvert;
int16_t portfwd;
int16_t stbdfwd;
int16_t portaft;
int16_t stbdaft;
int16_t lights = 0;
int16_t pan = 89;
int16_t tilt = 89;
int lowval = 44;
int midval = 89;
int highval = 179;
float ptspeed = 2;
void setup(){
Serial.begin(115200);
//start the EasyTransfer library, pass in the data details and the name of the serial port. Can be Serial, Serial1, Serial2, etc.
ETin.begin(details(rxdata), &Serial);
ETout.begin(details(txdata), &Serial);
//Set up pins to read buttons on joystick
pinMode(A4,INPUT_PULLUP);
pinMode(A5,INPUT_PULLUP);
pinMode(A6,INPUT_PULLUP);
pinMode(A7,INPUT_PULLUP);
pinMode(A8,INPUT_PULLUP);
pinMode(A9,INPUT_PULLUP);
pinMode(A10,INPUT_PULLUP);
pinMode(A11,INPUT_PULLUP);
pinMode(A12,INPUT_PULLUP);
pinMode(A13,INPUT_PULLUP);
pinMode(A14,INPUT_PULLUP);
//Set pin for on board indicator LED
pinMode(13, OUTPUT);
//Initialise the LCD
lcd.begin (16, 2);
lcd.setBacklightPin(3,POSITIVE);
//lcd.setBacklight(HIGH); // NOTE: You can turn the backlight off by setting it to LOW instead of HIGH
lcd.setBacklight(LOW);
//Print a splash screen on the LCD
lcd.clear(); // clean screen and sets cursor to (0,0)
Serial.begin(baudRate);
lcd.setBacklight(HIGH); //turn on backlight
lcd.setCursor(0, 0); //First line
lcd.print("Console_1");
lcd.setCursor(0, 1); //Second line
lcd.print("Console 19/07/19");
delay(2000);
lcd.clear();
}
void loop(){
//Read values from the joystick axes
slider = analogRead(A3);
xaxis = analogRead(A0);
yaxis = analogRead(A1);
zaxis = analogRead(A2);
//Scale the verts
portvert = (map(slider, 0, 1023, 0, 179));
stbdvert = (map(slider, 0, 1023, 0, 179));
//send vert values out to EasyTransfer
txdata.portvert = portvert;
txdata.stbdvert = stbdvert;
//Calculate value for portaft
portaft1 = (((zaxis) - (xaxis) - (yaxis)) + 1023);
if (portaft1 >= 1023){
portaft1 = 1023;
}
if (portaft1 <= 0){
portaft1 = 0;
}
//Calculate value for stbdaft
stbdaft1 = (((xaxis) - (yaxis) - (zaxis)) + 1023);
if (stbdaft1 >= 1023){
stbdaft1 = 1023;
}
if (stbdaft1 <= 0 ){
stbdaft1 = 0;
}
//Calculate value for portfwd
portfwd1 = (((xaxis) - (yaxis) + (zaxis)));
if (portfwd1 >= 1023){
portfwd1 = 1023;
}
if (portfwd1 <= 0){
portfwd1 = 0;
}
//Calculate value for stbdfwd
stbdfwd1 = (2048 - ((xaxis) + (yaxis) + (zaxis)));
if (stbdfwd1 >= 1023){
stbdfwd1 = 1023;
}
if (stbdfwd1 <= 0){
stbdfwd1 = 0;
}
//Scale vectored thrusters according to power setting switch
//First, scale to MID
portaft = map(portaft1, 0, 1023, 44, 133);
stbdaft = map(stbdaft1, 0, 1023, 44, 133);
portfwd = map(portfwd1, 0, 1023, 44, 133);
stbdfwd = map(stbdfwd1, 0, 1023, 44, 133);
//If HIGH switch on, scale to HIGH
if (digitalRead(A9) == LOW) {
portaft = map(portaft1, 0, 1023, 0, 179);
stbdaft = map(stbdaft1, 0, 1023, 0, 179);
portfwd = map(portfwd1, 0, 1023, 0, 179);
stbdfwd = map(stbdfwd1, 0, 1023, 0, 179);
}
//If LOW switch on, scale to LOW
if (digitalRead(A8) == LOW) {
portaft = map(portaft1, 0, 1023, 66, 112);
stbdaft = map(stbdaft1, 0, 1023, 66, 112);
portfwd = map(portfwd1, 0, 1023, 66, 112);
stbdfwd = map(stbdfwd1, 0, 1023, 66, 112);
}
//Send vectored values out to EasyTransfer
txdata.portaft = portaft;
txdata.stbdaft = stbdaft;
txdata.portfwd = portfwd;
txdata.stbdfwd = stbdfwd;
//Set pan & tilt values, speed controlled by ptspeed value
if(digitalRead(A4) == LOW) {
pan = pan - ptspeed;
}
if(pan <=0){
pan = 0;
}
if(digitalRead(A5) == LOW) {
pan = pan + ptspeed;
}
if(pan >=179){
pan = 179;
}
if(digitalRead(A6) == LOW) {
tilt = tilt - ptspeed;
}
if(tilt <=0){
tilt = 0;
}
if(digitalRead(A7) == LOW) {
tilt = tilt + ptspeed;
}
if(tilt >=179){
tilt = 179;
}
//Centre P&T if trigger pulled
if(digitalRead(A13) == LOW) {
pan = 89;
tilt = 89;
}
txdata.pan = pan;
txdata.tilt = tilt;
//Send pan & tilt values to EasyTransfer
txdata.pan = pan;
txdata.tilt = tilt;
//Print sensor values to LCD
lcd.clear();
lcd.setCursor(0,0);
lcd.print("H:");
lcd.setCursor(2,0);
lcd.print(rxdata.heading);
lcd.setCursor(0,1);
lcd.print("D:");
lcd.setCursor(2,1);
lcd.print(rxdata.depth);
lcd.setCursor(8,0);
lcd.print("B:");
lcd.setCursor(10,0);
lcd.print(rxdata.battery);
//Read lights pin and send the value to EasyTransfer
if(!digitalRead(A10))
txdata.lights = HIGH;
else
txdata.lights = LOW;
//Read lights pin and set on board LED accordingly
if(!digitalRead(A10))
digitalWrite(13, HIGH);
else
digitalWrite(13, LOW);
//Send all the EasyTransfer data out of the port
ETout.sendData();
//There's a loop here so that we run the receive function more often then the
//transmit function. This is important due to the slight differences in
//the clock speed of different Arduinos. If we didn't do this, messages
//would build up in the buffer and appear to cause a delay.
for(int i=0; i<5; i++){
//remember, you could use an if() here to check for new data, this time it's not needed.
ETin.receiveData();
//delay
delay(10);
}
//delay to slow loop
//delay(10);
}