Hello everyone. I thought it would be good to share with you all a project which me and my 9yo daughter and busy with.
The project involves building a small boat and have it sail autonomously from the north east UK coat (Northumberland) to Norway. The project is around 90% complete and we are currently doing some rigorous testing in local waters to test its performance and reliability.
The hull is based on an RC hull and has been adapted to our requirements. The boat in its entirety has the following specs:-
2x 23ah 12v batteries
2x 30w solar panels up top
40a esc
1000k brushless motor
35kg servo for steering rudder
Arduino UNO 1 is for navigation
Arduino UNO 2 is for communication
Rockblock 9603 for communication
plus various other sensors to implement some navigation / power control.
Before this project (started winter 23) I had zero experience of programming other than copy and pasting how to blink and LED with an UNO. Fast forward to this post and I have a working code of around 300 lines which steers and powers a boat from drop location set a set of waypoints !
Link to our facebook page -
NAVIGATION CODE
#include <TinyGPSPlus.h>
#include <Wire.h>
#include <LSM303.h>
#include <PWMServo.h>
#include <PID_v1.h>
#include <NeoSWSerial.h>
#include <avr/wdt.h>
#include <Adafruit_Sensor.h>
#include <Adafruit_BME280.h>
#include <Adafruit_AHRS.h>
#include <Adafruit_AHRS_FusionInterface.h>
#include <Adafruit_AHRS_Madgwick.h>
#include <Adafruit_AHRS_Mahony.h>
#include <Adafruit_AHRS_NXPFusion.h>
#include <Adafruit_Sensor_Set.h>
#include <Adafruit_Simple_AHRS.h>
// PID constants
double Kp = 2.00; // Proportional gain
double Ki = 0.12; // Integral gain
double Kd = 0.0; // Derivative gain
// PID variables
double previous_error = 0;
double integral = 0;
double derivative = 0;
double rudder_output = 0;
unsigned long previousMillis = 0; // will store last time GPS was printed
const long interval = 5000; // interval at which to print GPS
// TEMP and HUMIDITY
#define SEALEVELPRESSURE_HPA (1013.25)
// VOLTAGE
#define ANALOG_IN_PIN A0
// Floats for ADC voltage & Input voltage
float adc_voltage = 0.0;
float in_voltage = 0.0;
// Floats for resistor values in divider (in ohms)
float R1 = 30000.0;
float R2 = 7500.0;
// Float for Reference Voltage
float ref_voltage = 5.18;
// Integer for ADC value
int adc_value = 0;
///AMPS
int analogPin = A1; // Current sensor output
const int averageValue = 500;
long int sensorValue = 0; // variable to store the sensor value read
float voltage = 0.00;
float current = 0.00;
int battery_percent = 0;
// GPS
static const int RXPin = 7, TXPin = 6; //GPS TX & RX
NeoSWSerial ss(RXPin, TXPin); //GPS TX & RX
// Create objects
TinyGPSPlus gps;
LSM303 compass;
PWMServo rudder;
PWMServo esc;
Adafruit_BME280 bme;
// GPS buadrate
static const uint32_t GPSBaud = 9600;
// ESC inputs - 180 = full power etc
int full_power = 105;
//105 is about 1.1amp at cruise with average of 3kph
//108 is about UNKNOWNamp at cruise with average of 3.08kph
int reduced_power = 100;
// Define waypoints (latitude, longitude)
struct Waypoint {
double latitude;
double longitude;
};
Waypoint waypoints[] = {
{ 58.80532, 5.549003}, // 1
// { 55.3397, -1.59416 } // 2
};
int numWaypoints = sizeof(waypoints) / sizeof(Waypoint);
int currentWaypointIndex = 0;
void setup()
{
wdt_disable(); // Disable the watchdog and wait for more than 2 seconds */
Serial.begin(115200);
delay(3000);
Serial.print("Watchdog disabled"); //
wdt_enable(WDTO_4S); /* Enable the watchdog with a timeout of 4 seconds */
Serial.println("Watchdog enabled");
Serial.println("Project West Wind by Alan & Elise Thompson");
Serial.println("NeoSerial begin @ 115200");
ss.begin(GPSBaud);
Serial.println("GPS serial begin @ 9600");
Wire.begin();
Serial.println("Wire begin");
compass.init();
Serial.println("Compass initiated");
compass.enableDefault();
Serial.println("Compass enable default");
bme.begin(0x76);
Serial.println("Temperature and Humidity device initiated");
rudder.attach(SERVO_PIN_B);
Serial.println("rudder servo attched");
esc.attach(SERVO_PIN_A);
esc.write(90);
delay(3000);
Serial.println("esc attached");
wdt_reset(); /* Reset the watchdog */
compass.m_min = (LSM303::vector<int16_t>){ -629, -621, -422 };
compass.m_max = (LSM303::vector<int16_t>){ +594, +592, +519 }; //{ -629, -621, -422} max: { +594, +592, +519}
Serial.println("compass calibration data loaded");
}
void loop() {
unsigned long currentMillis = millis();
wdt_reset(); /* Reset the watchdog */
while (ss.available() > 0) {
gps.encode(ss.read());
}
if (gps.location.isUpdated()) {
wdt_reset(); /* Reset the watchdog */
}
// NAVIGATION FOMULAS
compass.read();
Waypoint currentWaypoint = waypoints[currentWaypointIndex];
double distanceToWaypoint = TinyGPSPlus::distanceBetween(gps.location.lat(), gps.location.lng(), currentWaypoint.latitude, currentWaypoint.longitude);
double courseToWaypoint = TinyGPSPlus::courseTo(gps.location.lat(), gps.location.lng(), currentWaypoint.latitude, currentWaypoint.longitude);
int heading = compass.heading();
int heading_error_INT = (heading - courseToWaypoint);
float heading_error = (heading_error_INT + 540) % 360 - 180; //int heading_error = (bearing-heading+540)%360 -180;
// Check if close to the current waypoint
if (distanceToWaypoint < 5) { // 5 meters threshold
if (currentWaypointIndex < numWaypoints - 1) {
currentWaypointIndex++;
} else {
currentWaypointIndex = 0;
}
}
for (int i = 0; i < averageValue; i++) {
sensorValue += analogRead(analogPin);
wdt_reset(); /* Reset the watchdog */
}
//System amps
sensorValue = sensorValue / averageValue;
voltage = sensorValue * 5.186 / 1024.0;
current = (voltage - 2.5) / 0.185;
//System voltage
int average_volts = 0;
for (int i = 0; i < 50; i++) {
average_volts = average_volts + analogRead(A0);
}
average_volts = average_volts / 50;
voltage = average_volts * (5.186 / 1024) * ((R1 + R2) / R2);
float R_internal = 0.4;
float corrected_voltage = voltage + (current * R_internal);
wdt_reset(); /* Reset the watchdog */
// BATTERY PERCENTAGE
float minVoltage = 11.9; // Minimum voltage
float maxVoltage = 12.7; // Maximum voltage
battery_percent = ((corrected_voltage - minVoltage) / 0.800) * 100;
battery_percent = constrain(battery_percent, 0, 100);
wdt_reset(); /* Reset the watchdog */
// PROPULSION
esc.write(corrected_voltage > 12.3 ? full_power : reduced_power);
// Calculate PID components
integral += heading_error;
derivative = heading_error - previous_error;
// Calculate the rudder output from the PID controller
rudder_output = (Kp * heading_error) + (Ki * integral) + (Kd * derivative);
wdt_reset(); /* Reset the watchdog */
// Map the PID output to the rudder servo range (e.g., 0 to 180 degrees)
int rudder_angle = map(rudder_output, -180, 180, 180, 0);
rudder_angle = constrain(rudder_angle, 60, 120); //able to set limits // possible sensitivy adjustment
rudder.write(rudder_angle);
// Save the current error for the next iteration
previous_error = heading_error;
wdt_reset(); /* Reset the watchdog */
// SERIAL PRINTS
if (currentMillis - previousMillis >= interval) {
// save the last time you printed GPS
previousMillis = currentMillis;
// Serial prints
if (gps.location.isValid()) {
Serial.print(gps.date.day());
Serial.print("-");
Serial.print(gps.date.month());
Serial.print("-");
Serial.print(gps.date.year());
Serial.print(",");
Serial.print(gps.time.hour() + 1); //DAYLIGHT SAVING DEPENDANT !!!
Serial.print(F(":"));
Serial.print(gps.time.minute());
Serial.print(F(":"));
Serial.print(gps.time.second());
Serial.print(",");
Serial.print(gps.location.lat(), 6);
Serial.print(",");
Serial.print(gps.location.lng(), 6);
Serial.print(",");
Serial.print(distanceToWaypoint / 1000);
} else {
Serial.print("gps not updated");
}
Serial.print(",");
Serial.print(currentWaypointIndex + 1);
Serial.print(",");
Serial.print((int)courseToWaypoint);
Serial.print(",");
Serial.print((int)heading);
Serial.print(",");
Serial.print((int)heading_error);
Serial.print(",");
Serial.print(gps.speed.kmph());
Serial.print(",");
Serial.print(current, 1);
Serial.print(",");
Serial.print(corrected_voltage, 1);
Serial.print(",");
Serial.print(battery_percent);
Serial.print(",");
Serial.print(map(compass.a.x, -22000, 22000, -90, 90));
Serial.print(",");
Serial.print(map(compass.a.y, -6000, 6000, -40, 20));
Serial.print(",");
Serial.print(bme.readTemperature(), 1);
Serial.print(",");
Serial.println(bme.readHumidity(), 0);
wdt_reset(); /* Reset the watchdog */
}
}
COMMUNICATION CODE
#include <SD.h>
#include <SPI.h>
#include <IridiumSBD.h>
#include "SoftwareSerial.h"
#include <avr/wdt.h>
unsigned long previousMillis = 0; // will store last time GPS was printed
// constants won't change:
const long interval = 1000 * 43200; // Interval to send IRIDIUM payload !!!!!!!
const int chipSelect = 4;
#define DIAGNOSTICS true // Change this to see diagnostics
SoftwareSerial IridiumSerial(7, 6);
IridiumSBD modem(IridiumSerial, 5);
void setup() {
wdt_disable(); // Disable the watchdog and wait for more than 2 seconds */
Serial.print("Watchdog disabled"); //
delay(3000);
wdt_enable(WDTO_4S); /* Enable the watchdog with a timeout of 4 seconds */
Serial.println("Watchdog enabled");
IridiumSerial.begin(19200);
Serial.begin(115200);
Serial.setTimeout(10);
wdt_reset(); /* Reset the watchdog */
if (!Serial) {
; // wait for serial port to connect. Needed for native USB port only
}
Serial.print("Initializing SD card...");
wdt_reset(); /* Reset the watchdog */
// see if the card is present and can be initialized:
if (!SD.begin(chipSelect)) {
Serial.println("Card failed, or not present");
wdt_reset(); /* Reset the watchdog */
// don't do anything more:
while (1)
;
}
Serial.println("card initialized.");
wdt_reset(); /* Reset the watchdog */
}
void loop() {
unsigned long loopStartTime = millis();
if (Serial.available() > 0) {
String str = Serial.readString();
str.trim();
wdt_reset(); /* Reset the watchdog */
File dataFile = SD.open("datalog.txt", FILE_WRITE);
//Print data on Serial Monitor
if (dataFile) {
dataFile.println(str);
Serial.println(str);
dataFile.close();
// Length (with one extra character for the null terminator)
int str_len = str.length() + 1;
// Prepare the character array (the buffer)
char char_array[str_len];
// Copy it over
str.toCharArray(char_array, str_len);
unsigned long currentMillis = millis();
while (currentMillis - previousMillis >= interval) {
// save the last time you printed GPS
previousMillis = currentMillis;
{
int signalQuality = -1;
int err;
while (!Serial)
;
// Start the serial port connected to the satellite modem
IridiumSerial.begin(19200);
// Begin satellite modem operation
Serial.println("Starting modem...");
err = modem.begin();
if (err != ISBD_SUCCESS) {
Serial.print("Begin failed: error ");
Serial.println(err);
if (err == ISBD_NO_MODEM_DETECTED)
Serial.println("No modem detected: check wiring.");
return;
}
// Example: Print the firmware revision
char version[12];
err = modem.getFirmwareVersion(version, sizeof(version));
if (err != ISBD_SUCCESS) {
Serial.print("FirmwareVersion failed: error ");
Serial.println(err);
return;
}
Serial.println("Sending the following line of data");
Serial.println(char_array);
Serial.print("Firmware Version is ");
Serial.print(version);
Serial.println(".");
// Example: Test the signal quality.
// This returns a number between 0 and 5.
// 2 or better is preferred.
err = modem.getSignalQuality(signalQuality);
if (err != ISBD_SUCCESS) {
Serial.print("SignalQuality failed: error ");
Serial.println(err);
return;
}
Serial.print("On a scale of 0 to 5, signal quality is currently ");
Serial.print(signalQuality);
Serial.println(".");
// Send the message
Serial.print("Trying to send the message. This might take several minutes.\r\n");
err = modem.sendSBDText(char_array);
if (err != ISBD_SUCCESS) {
Serial.print("sendSBDText failed: error ");
Serial.println(err);
if (err == ISBD_SENDRECEIVE_TIMEOUT)
Serial.println("Try again with a better view of the sky.");
}
else {
Serial.println("Hey, it worked!");
modem.sleep();
}
}
}
}
}
}
#if DIAGNOSTICS
void ISBDConsoleCallback(IridiumSBD *device, char c) {
Serial.write(c);
}
void ISBDDiagsCallback(IridiumSBD *device, char c) {
Serial.write(c);
}
#endif
Graph showing battery percentage over last 2hr run. ( code now adjust to show corrected voltage after during being under load. realise this is non inear but give better representation)
Uploading: BATTERY.JPG…
Map plot showing how well boat keep on course over a 271m route between 2 waypoints
Uploading: Capture.JPG…
Graph showing speed vs time. Fascinating to note the correlation between speed going with the tide and speed going against the tide
Uploading: SPEED.JPG…
While I have some data and graphs etc showing the boat working as expected I also feel like there is room for improvement and would appreciate any feedback on the code. Particularly around the Millis rollover subject as this is something I cant get my head around
I hope you enjoy the Facebook page and please give us a follow to help support us
Alan