Hey guys, I'm new to the forum.
I would like to present my project here and ask for opinions and suggestions for improvements. I am building an ROV to explore underground siphons "in caves".
I build underwater ROV that has one Arduino Uno in ROV and another Arduino Due as a ground station. Bothe Arduinos are connected via cable (shielded twisted pair, with neutral buoyancy,150m).
It has 5 thrusters, 3 for going Up/Down and title. 2 for Forward/Backward and turn Left/Right.
Arduino Due read values from 2 joysticks and send data to Arduino Uno. Arduino Uno send PWM signal to thrusters and every 5 seconds read data from sensors (temperature, pressure, compass,...) and send it to Arduino Due. Arduino Due represent sensors data on a 3.5" TFT display.
This is a rough description of how it works.
The communication between the Arduino controllers works but the response time is poor. More than about half a second delay.
- Should I replace the microcontrollers with better ones or just improve the code?
- Schematic diagram Schematic_diagram_ROV_2025_V3
Arduino Due / ground station / Code:
#include <Adafruit_GFX.h> // Core graphics library
#include <MCUFRIEND_kbv.h> // Hardware-specific library
MCUFRIEND_kbv tft;
#define BLACK 0x0000
#define WHITE 0xFFFF
#define BLUE 0x001F
#define RED 0xF800
#define GREEN 0x07E0
#define CYAN 0x07FF
#define MAGENTA 0xF81F
#define YELLOW 0xFFE0
#define joy_X1_pin A6
#define joy_Y1_pin A7
#define joy_sel1_pin 53
#define joy_X2_pin A8
#define joy_Y2_pin A9
#define joy_sel2_pin 52
int joy_X1_value = 512, joy_Y1_value = 512, joy_sel1_value = 1, joy_X2_value = 512, joy_Y2_value = 512, joy_sel2_value = 1, joy_sel1_state = 1, joy_sel2_state = 1, joyMin = 510, joyMax = 750;
int escValue1 = 1500, escValue2 = 1500, escValue3 = 1500, escValue4 = 1500, escValue5 = 1500;
float pressure = 0, temperature = 0, acceleration_x = 0, acceleration_y = 0, acceleration_z = 0, gyro_x = 0, gyro_y = 0, gyro_z = 0;
int hours = 0, minutes = 0, seconds = 0;
float angleDeg = 0;
char timeString[9];
int moveCompassX = 80;
int moveCompassY = 0;
int compassCenterX; // X coordinate of the compass center
int compassCenterY; // Y coordinate of the compass center
int compassRadius; // Radius of the compass
bool switch_read_flag = 0;
void setup() {
Serial.begin(9600);
Serial1.begin(9600);
Serial.println(" ");
Serial1.println(" ");
uint16_t ID = tft.readID();
tft.begin(ID);
tft.setRotation(2); // Adjust rotation as needed
tft.fillScreen(BLACK);
// Set text size, color, and background color
tft.setTextSize(2);
tft.setTextColor(WHITE, BLACK);
// Get the screen's width and height
int screenWidth = tft.width();
int screenHeight = tft.height();
// Calculate the center of the screen for the compass
compassCenterX = (screenWidth / 2) + moveCompassX;
compassCenterY = screenHeight / 2 + moveCompassY;
// Set the radius of the compass to be slightly smaller than half the screen's width or height
compassRadius = min(screenWidth, screenHeight) / 5;
pinMode(joy_sel1_pin, INPUT_PULLUP);
pinMode(joy_sel2_pin, INPUT_PULLUP);
}
void loop() {
joy_X1_value = analogRead(joy_X1_pin);
joy_Y1_value = analogRead(joy_Y1_pin);
joy_sel1_value = digitalRead(joy_sel1_pin);
joy_X2_value = analogRead(joy_X2_pin);
joy_Y2_value = analogRead(joy_Y2_pin);
joy_sel2_value = digitalRead(joy_sel2_pin);
if( (joy_X1_value < joyMin) || (joy_X1_value > joyMax) || (joy_X2_value < joyMin) || (joy_X2_value > joyMax) || (joy_Y1_value < joyMin) || (joy_Y1_value > joyMax) || (joy_Y2_value < joyMin) || (joy_Y2_value > joyMax) || (digitalRead(joy_sel1_pin)==0) || (digitalRead(joy_sel2_pin)==0) )
{
if(digitalRead(joy_sel1_pin)==0)
{
while(digitalRead(joy_sel1_pin)==0);
joy_sel1_state = !joy_sel1_state;
}
if(digitalRead(joy_sel2_pin)==0)
{
while(digitalRead(joy_sel2_pin)==0);
joy_sel2_state = !joy_sel2_state;
}
if( (joy_Y2_value < joyMin) || (joy_Y2_value > joyMax) ) // former X1, now Y2
{
escValue1 = map(joy_Y2_value, 0, 1023, 1100, 1900);
escValue2 = map(joy_Y2_value, 0, 1023, 1100, 1900);
escValue3 = map(joy_Y2_value, 0, 1023, 1900, 1100);
escValue4 = 1500;
escValue5 = 1500;
}
if( (joy_X2_value < joyMin) || (joy_X2_value > joyMax) )
{
escValue1 = map(joy_X2_value, 0, 1023, 1100, 1900);
escValue2 = map(joy_X2_value, 0, 1023, 1100, 1900);
escValue3 = map(joy_X2_value, 0, 1023, 1100, 1900);
escValue4 = 1500;
escValue5 = 1500;
}
if( (joy_Y1_value < joyMin) || (joy_Y1_value > joyMax) )
{
escValue4 = map(joy_Y1_value, 0, 1023, 1900, 1100);
escValue5 = map(joy_Y1_value, 0, 1023, 1100, 1900);
escValue1 = 1500;
escValue2 = 1500;
escValue3 = 1500;
}
if( (joy_X1_value < joyMin) || (joy_X1_value > joyMax) ) // former Y2, now X1
{
escValue4 = map(joy_X1_value, 0, 1023, 1900, 1100);
escValue5 = map(joy_X1_value, 0, 1023, 1900, 1100);
escValue1 = 1500;
escValue2 = 1500;
escValue3 = 1500;
}
// Convert data to a string to send via RS485
String data = String("<") +
String(escValue1) + "," +
String(escValue2) + "," +
String(escValue3) + "," +
String(escValue4) + "," +
String(escValue5) + "," +
String(joy_sel1_state) + "," +
String(joy_sel2_state) +
String(">");
// Send data over RS485
Serial1.println(data);
}
else
{
escValue1 = 1500;
escValue2 = 1500;
escValue3 = 1500;
escValue4 = 1500;
escValue5 = 1500;
}
// Check if data is available to read
if (Serial1.available()) {
// Read the data from RS485
String data = readStringUntilDelimiter(); // Read the string from Arduino2
if (data.length() > 0) {
Serial.print("Received data: ");
Serial.println(data);
// Process the received data (split and convert if needed)
// Example of splitting the data (assuming it's in the format "temperature,pressure,acceleration_x,acceleration_y,acceleration_z,gyro_x,gyro_y,gyro_z,hours,minutes,seconds")
if(switch_read_flag == 0)
{
int index = 0;
String values[6];
while (index < 6) {
int commaIndex = data.indexOf(',');
if (commaIndex == -1) {
values[index] = data;
break;
}
values[index] = data.substring(0, commaIndex);
data = data.substring(commaIndex + 1);
index++;
}
// Convert strings to float or int as appropriate
temperature = values[0].toFloat();
pressure = values[1].toFloat();
acceleration_x = values[2].toFloat();
acceleration_y = values[3].toFloat();
acceleration_z = values[4].toFloat();
angleDeg = values[5].toFloat();
// Print the received values
Serial.print("Received temperature: ");
Serial.println(temperature);
Serial.print("Received pressure: ");
Serial.println(pressure);
Serial.print("Received acceleration_x: ");
Serial.print(acceleration_x);
Serial.print(", Received acceleration_y: ");
Serial.print(acceleration_y);
Serial.print(", Received acceleration_z: ");
Serial.println(acceleration_z);
Serial.print("Received Angle: ");
Serial.println(angleDeg);
// Print on LCD
// tft.fillScreen(BLACK);
// Display temperature
tft.setTextColor(WHITE, BLACK);
tft.setCursor(10, 10);
tft.print("Temperature: ");
tft.fillRect(160, 10, 100, 20, BLACK);
tft.setTextColor(YELLOW, BLACK);
tft.print(temperature);
// Display pressure
tft.setTextColor(WHITE, BLACK);
tft.setCursor(10, 40);
tft.print("Pressure: ");
tft.fillRect(120, 40, 100, 20, BLACK);
tft.setTextColor(YELLOW, BLACK);
tft.print(pressure);
// Display acceleration
tft.setTextColor(WHITE, BLACK);
tft.setCursor(10, 70);
tft.print("AccelX: ");
tft.fillRect(100, 70, 100, 20, BLACK);
tft.setTextColor(YELLOW, BLACK);
tft.print(acceleration_x);
tft.setTextColor(WHITE, BLACK);
tft.setCursor(10, 100);
tft.print("AccelY: ");
tft.fillRect(100, 100, 100, 20, BLACK);
tft.setTextColor(YELLOW, BLACK);
tft.print(acceleration_y);
tft.setTextColor(WHITE, BLACK);
tft.setCursor(10, 130);
tft.print("AccelZ: ");
tft.fillRect(100, 130, 100, 20, BLACK);
tft.setTextColor(YELLOW, BLACK);
tft.print(acceleration_z);
// Clear the old compass needle
tft.fillCircle(compassCenterX, compassCenterY, compassRadius - 1, BLACK); // Black to clear the inside
// Draw the compass circle again (in case the needle overlaps the circle)
tft.drawCircle(compassCenterX, compassCenterY, compassRadius, WHITE); // White circle
// Draw the direction letters around the compass again
drawDirectionLetters();
// Calculate the end point of the needle (arrow's tip) based on the angle
int needleLength = compassRadius - 1;
float angleRad = radians(angleDeg); // Convert angle to radians
int needleX = compassCenterX + needleLength * cos(angleRad);
int needleY = compassCenterY - needleLength * sin(angleRad); // Y-axis is inverted on the screen
// Calculate the two points for the arrowhead
int arrowSize = 5; // Size of the arrowhead
float leftAngleRad = radians(angleDeg + 150); // 150 degrees to the left of the needle
float rightAngleRad = radians(angleDeg - 150); // 150 degrees to the right of the needle
int arrowLeftX = compassCenterX + (needleLength - arrowSize) * cos(angleRad) + arrowSize * cos(leftAngleRad);
int arrowLeftY = compassCenterY - (needleLength - arrowSize) * sin(angleRad) - arrowSize * sin(leftAngleRad);
int arrowRightX = compassCenterX + (needleLength - arrowSize) * cos(angleRad) + arrowSize * cos(rightAngleRad);
int arrowRightY = compassCenterY - (needleLength - arrowSize) * sin(angleRad) - arrowSize * sin(rightAngleRad);
// Draw the needle as an arrow
tft.drawLine(compassCenterX, compassCenterY, needleX, needleY, WHITE);
tft.fillTriangle(needleX, needleY, arrowLeftX, arrowLeftY, arrowRightX, arrowRightY, WHITE);
switch_read_flag = 1;
}
else if(switch_read_flag == 1)
{
int index = 0;
String values[6];
while (index < 6) {
int commaIndex = data.indexOf(',');
if (commaIndex == -1) {
values[index] = data;
break;
}
values[index] = data.substring(0, commaIndex);
data = data.substring(commaIndex + 1);
index++;
}
gyro_x = values[0].toFloat();
gyro_y = values[1].toFloat();
gyro_z = values[2].toFloat();
hours = values[3].toInt();
minutes = values[4].toInt();
seconds = values[5].toInt();
// Print the received values
Serial.print("Received gyro_x: ");
Serial.print(gyro_x);
Serial.print(", Received gyro_y: ");
Serial.print(gyro_y);
Serial.print(", Received gyro_z: ");
Serial.println(gyro_z);
sprintf(timeString, "%02d:%02d:%02d", hours, minutes, seconds);
Serial.print("received time: ");
Serial.println(timeString);
Serial.println("*************************");
// Print on LCD
// Display gyroscope data
tft.setTextColor(WHITE, BLACK);
tft.setCursor(10, 160);
tft.print("GyroX: ");
tft.fillRect(90, 160, 100, 20, BLACK);
tft.setTextColor(YELLOW, BLACK);
tft.print(gyro_x);
tft.setTextColor(WHITE, BLACK);
tft.setCursor(10, 190);
tft.print("GyroY: ");
tft.fillRect(90, 190, 100, 20, BLACK);
tft.setTextColor(YELLOW, BLACK);
tft.print(gyro_y);
tft.setTextColor(WHITE, BLACK);
tft.setCursor(10, 220);
tft.print("GyroZ: ");
tft.fillRect(90, 220, 100, 20, BLACK);
tft.setTextColor(YELLOW, BLACK);
tft.print(gyro_z);
// Display time
tft.setTextColor(WHITE, BLACK);
tft.setCursor(10, 250);
tft.print("Time: ");
tft.fillRect(70, 250, 130, 20, BLACK);
tft.setTextColor(YELLOW, BLACK);
tft.print(timeString);
switch_read_flag = 0;
}
}
}
delay(100);
}
// Function to read a string until the end delimiter
String readStringUntilDelimiter() {
String receivedString = "";
char incomingByte;
bool startReadingFlag = 0;
char start_delimiter;
char end_delimiter;
if(switch_read_flag == 0)
{
start_delimiter = '<';
end_delimiter = '>';
}
if(switch_read_flag == 1)
{
start_delimiter = '[';
end_delimiter = ']';
}
while (Serial1.available() > 0) {
incomingByte = Serial1.read();
// Check for start delimiter
if (incomingByte == start_delimiter) {
receivedString = "";
startReadingFlag = 1;
}
else if(startReadingFlag == 1)
{
if (incomingByte == end_delimiter) {
return receivedString;
}
else {
receivedString += incomingByte;
}
}
}
return ""; // Return empty string if no valid message is found
}
void drawDirectionLetters() {
// Set text color and size
tft.setTextColor(WHITE); // White color
tft.setTextSize(2); // Text size
// Position the letters around the compass
tft.setCursor(compassCenterX - 10, compassCenterY - compassRadius - 20);
tft.print("N"); // North
tft.setCursor(compassCenterX + compassRadius + 10, compassCenterY - 10);
tft.print("E"); // East
tft.setCursor(compassCenterX - 10, compassCenterY + compassRadius + 10);
tft.print("S"); // South
tft.setCursor(compassCenterX - compassRadius - 15, compassCenterY - 10);
tft.print("W"); // West
}
Arduino Uno / ROV / Code:
#include <OneWire.h>
#include <DallasTemperature.h>
#include "RTClib.h"
#include <Servo.h>
#include <Adafruit_MPU6050.h>
#include <Adafruit_Sensor.h>
#include <QMC5883L.h>
#include <Wire.h>
#define escPin1 9
#define escPin2 10
#define escPin3 6
#define escPin4 3
#define escPin5 5
#define relay1 7
#define relay2 8
#define ONE_WIRE_BUS 11
#define PRESSURE_SENSOR_PIN A3
// Setup a oneWire instance to communicate with any OneWire devices
OneWire oneWire(ONE_WIRE_BUS);
QMC5883L compass;
// Define the Servo objects for the ESCs
Servo esc1, esc2, esc3, esc4, esc5;
// Pass our oneWire reference to Dallas Temperature sensor
DallasTemperature sensors(&oneWire);
RTC_DS3231 rtc;
Adafruit_MPU6050 mpu;
int escValue1 = 1500, escValue2 = 1500, escValue3 = 1500, escValue4 = 1500, escValue5 = 1500, sel1 = 1, sel2 = 1, angleDeg = 0;
float pressure = 0, temperature = 0, acceleration_x = 0, acceleration_y = 0, acceleration_z = 0, gyro_x = 0, gyro_y = 0, gyro_z = 0, hours = 0, minutes = 0, seconds = 0;
unsigned int currentTime = 0;
unsigned int previousTime = 0;
unsigned int timeDelay = 500; // Send sensor data to Arduino Due every 500mS (0.5 Seconds)
void setup(void)
{
// Start serial communication for debugging purposes
Serial.begin(9600);
pinMode(relay1, OUTPUT);
pinMode(relay2, OUTPUT);
Wire.begin();
compass.init();
compass.setSamplingRate(50);
sensors.begin();
if (! rtc.begin()) {
Serial.println("Couldn't find RTC");
Serial.flush();
abort();
}
rtc.adjust(DateTime(F(__DATE__), F(__TIME__)));
// Attach the ESCs to the corresponding pins
esc1.attach(escPin1);
esc2.attach(escPin2);
esc3.attach(escPin3);
esc4.attach(escPin4);
esc5.attach(escPin5);
delay(100);
esc1.writeMicroseconds(1500);
delay(100);
esc2.writeMicroseconds(1500);
delay(100);
esc3.writeMicroseconds(1500);
delay(100);
esc4.writeMicroseconds(1500);
delay(100);
esc5.writeMicroseconds(1500);
delay(100);
// Try to initialize MPU6050!
if (!mpu.begin(0x69)) {
Serial.println("Failed to find MPU6050 chip");
while (1) {
delay(10);
}
}
Serial.println("MPU6050 Found!");
mpu.setAccelerometerRange(MPU6050_RANGE_8_G);
mpu.setGyroRange(MPU6050_RANGE_2000_DEG);
mpu.setFilterBandwidth(MPU6050_BAND_21_HZ);
Serial.println("");
delay(100);
}
void loop(void){
currentTime = millis();
if( (currentTime-previousTime) > timeDelay )
{
// Call sensors.requestTemperatures() to issue a global temperature and Requests to all devices on the bus
sensors.requestTemperatures();
temperature = sensors.getTempCByIndex(0);
pressure = analogRead(PRESSURE_SENSOR_PIN); //get ADC value
// convert ADC into pressure (bar)
pressure = 0.0689475729*0.169921875*pressure; // pressure = (PSI-to-bar-constant)*(174/1024)*(ADC)
/* Get MPU6050 readings */
sensors_event_t a, g, temp;
mpu.getEvent(&a, &g, &temp);
acceleration_x = a.acceleration.x;
acceleration_y = a.acceleration.y;
acceleration_z = a.acceleration.z;
gyro_x = g.gyro.x;
gyro_y = g.gyro.y;
gyro_z = g.gyro.z;
DateTime now = rtc.now();
hours = now.hour();
minutes = now.minute();
seconds = now.second();
angleDeg = compass.readHeading();
// Convert data to a string to send via RS485
String data1 = String("<") +
String(temperature, 2) + "," +
String(pressure, 2) + "," +
String(acceleration_x, 2) + "," +
String(acceleration_y, 2) + "," +
String(acceleration_z, 2) + "," +
String(angleDeg) +
String(">");
Serial.println(data1);
delay(200);
String data2 = String("[") +
String(gyro_x, 2) + "," +
String(gyro_y, 2) + "," +
String(gyro_z, 2) + "," +
String(hours) + "," +
String(minutes) + "," +
String(seconds) +
String("]");
Serial.println(data2);
delay(100);
previousTime = currentTime;
}
// Check if data is available to read
if (Serial.available()) {
// Read the data from RS485
String data = readStringUntilDelimiter(); // Read the string from Arduino2
if (data.length() > 0) {
Serial.print("Received data: ");
Serial.println(data);
// Process the received data (split and convert if needed)
// Example of splitting the data (assuming it's in the format "temperature,pressure,acceleration_x,acceleration_y,acceleration_z,gyro_x,gyro_y,gyro_z,hours,minutes,seconds")
int index = 0;
String values[7];
while (index < 7) {
int commaIndex = data.indexOf(',');
if (commaIndex == -1) {
values[index] = data;
break;
}
values[index] = data.substring(0, commaIndex);
data = data.substring(commaIndex + 1);
index++;
}
// Convert strings to float or int as appropriate
escValue1 = values[0].toInt();
escValue2 = values[1].toInt();
escValue3 = values[2].toInt();
escValue4 = values[3].toInt();
escValue5 = values[4].toInt();
sel1 = values[5].toInt();
sel2 = values[6].toInt();
// Print the received values
Serial.print("Received escValue1: ");
Serial.println(escValue1);
Serial.print("Received escValue2: ");
Serial.println(escValue2);
Serial.print("Received escValue3: ");
Serial.println(escValue3);
Serial.print("Received escValue4: ");
Serial.println(escValue4);
Serial.print("Received escValue5: ");
Serial.println(escValue5);
Serial.print("Received sel1: ");
Serial.println(sel1);
Serial.print("Received sel2: ");
Serial.println(sel2);
Serial.println("*************************");
}
esc1.writeMicroseconds(escValue1);
esc2.writeMicroseconds(escValue2);
esc3.writeMicroseconds(escValue3);
esc4.writeMicroseconds(escValue4);
esc5.writeMicroseconds(escValue5);
digitalWrite(relay1, sel1);
digitalWrite(relay2, sel2);
}
else
{
esc1.writeMicroseconds(1500); // Stop M1
esc2.writeMicroseconds(1500); // Stop M2
esc3.writeMicroseconds(1500); // Stop M3
esc4.writeMicroseconds(1500); // Stop M4
esc5.writeMicroseconds(1500); // Stop M5
}
delay(50);
}
// Function to read a string until the end delimiter
String readStringUntilDelimiter() {
String receivedString = "";
char incomingByte;
bool startReadingFlag = 0;
while (Serial.available() > 0) {
incomingByte = Serial.read();
// Check for start delimiter
if (incomingByte == '<') {
receivedString = "";
startReadingFlag = 1;
}
else if(startReadingFlag == 1)
{
if (incomingByte == '>') {
return receivedString;
}
else {
receivedString += incomingByte;
}
}
}
return ""; // Return empty string if no valid message is found
}
I apologize, the schematic is the final version, and the code has not been updated yet. I am still improving it. The difference is in the potentiometer and LED control.
Older version of ROV and ground station
ROV during test
New, upgraded ground station