I took quite a few hours to read the forum, I would still be grateful if anyone wanted to comment on my assumptions.
For three seasons, I used a simple RF remote control on the electric SUP to control the speed of the T200 thruster. I want to upgrade the system to two T200 thrusters and add some features.
see https://discuss.bluerobotics.com/t/new-sup-project-2x-t200/8977
I anticipate that the “loiter” functionality would allow me an electronic anchor and keep me in position at sea. It would no longer be limited to about 25m depth with a physical anchor.
I saw the course / heading lock function in the flight version. Is this also possible in the rover version? Namely, I would like the SUP to drive me straight during trolling fishing if I switched to this mode.
I also assume that regarding Mission Planner, a Bluetooth connection is possible between the smartphone and Ardupilot. It would be very helpful if I could sail above the planned isobath.
// kill switch not yet programmed / option a) stop all thrusters / option b) set loiter mode
// LOW, HIGH setups and PWM values may change according to actual needs / Arduino Nano is ready to test with Ardupilot
// valy, valx / values for x and y joystisk
#include <Servo.h>
Servo speed; // joystick speed
Servo direction; // joystick direction
Servo mode; // mode switch for Ardupilot
int x = 0; // analog pin za sped A0
int y = 1; // analog pin za direction A1
const int killswitch = 2; // digital pin connected to switch output D2
const int switch1 = 3; // digital pin connected to switch output D3
const int switch2 = 4; // digital pin connected to switch output D4
int PWM = 1500; // initial setup
#define WINDOW_SIZE 100 // joystick smoothing / set apropriate value together with delay at the end
int INDEX = 0;
int VALUE = 0;
int SUM = 0;
int READINGS[WINDOW_SIZE];
int AVERAGED = 0;
// ---------------------SETUP-------------------------------------------------------
void setup()
{
speed.attach(8); // speed Arduino pin D8
direction.attach(6); // direction Arduino pin D6
mode.attach(5); // izhod na ardupilot za mode select D5
speed.writeMicroseconds(1500);
direction.writeMicroseconds(1500);
mode.writeMicroseconds(1500);
pinMode(x, INPUT);
pinMode(y, INPUT);
digitalWrite(killswitch, HIGH); //
Serial.begin(115200);
pinMode(switch1, INPUT);
pinMode(switch2, INPUT);
digitalWrite(switch1, HIGH);
digitalWrite(switch2, HIGH);
Serial.print("Iniciliziram na 1500......");
delay (10000);
}
// --------------LOOP------------------------------------------------------------------
void loop()
{
// speed code
int valx; // variable to read the value from hitrost
valx = analogRead(x); // reads the value of the potentiometer value between 0 and 1023)
SUM = SUM - READINGS[INDEX]; // Remove the oldest entry from the sum
VALUE = analogRead(x); // Read the next sensor value
READINGS[INDEX] = VALUE; // Add the newest reading to the window
SUM = SUM + VALUE; // Add the newest reading to the sum
INDEX = (INDEX+1) % WINDOW_SIZE; // Increment the index, and wrap to 0 if it exceeds the window size
AVERAGED = SUM / WINDOW_SIZE; // Divide the sum of the window by the window size for the result
Serial.print(VALUE);
Serial.print(",");
Serial.println(AVERAGED);
delay(25);
valx = map(valx, 0, 1023, 1100, 1900); // scale it to use it with the servo value between 0 and 180)
if (valx > 1450 && valx < 1550) { // ignore values between 1450 and 1550 -> neutral 1500
valx = 1500;
}
speed.writeMicroseconds(valx); // sets the servo position according to the scaled value
// direction code
int valy; // variable to read the value from direction
valy = analogRead(y); // reads the value of the potentiometer value between 0 and 1023)
// smoothing subcode
SUM = SUM - READINGS[INDEX]; // Remove the oldest entry from the sum
VALUE = analogRead(y); // Read the next sensor value
READINGS[INDEX] = VALUE; // Add the newest reading to the window
SUM = SUM + VALUE; // Add the newest reading to the sum
INDEX = (INDEX+1) % WINDOW_SIZE; // Increment the index, and wrap to 0 if it exceeds the window size
AVERAGED = SUM / WINDOW_SIZE; // Divide the sum of the window by the window size for the result
Serial.print(VALUE);
Serial.print(",");
Serial.println(AVERAGED);
delay(25);
valy = map(valy, 0, 1023, 1100, 1900); // scale it to use it with the servo value between 0 and 180)
if (valy > 1450 && valy < 1550) { // če je vrednost med 1450 in 1550 potem je vrednost 1550, drugače po vhodu
valy = 1500;
}
direction.writeMicroseconds(valy); // sets the servo position according to the scaled value
// code mode 1
if (digitalRead(3) == HIGH && digitalRead(4) == HIGH) {
PWM = 1100;
mode.writeMicroseconds(PWM);
Serial.print("Mode PWM: ");
Serial.println(PWM);
}
// code mode 2
if (digitalRead(3) == HIGH && digitalRead(4) == LOW) {
PWM = 1500;
PWM = constrain(PWM, 1100, 1900);
mode.writeMicroseconds(PWM);
Serial.print("Mode PWM: ");
Serial.println(PWM);
}
// code mode 3
if (digitalRead(3) == LOW && digitalRead(4) == HIGH) {
PWM = 1900;
mode.writeMicroseconds(PWM);
Serial.print("Mode PWM: ");
Serial.println(PWM);
}
// serial prints debugging
Serial.print("vrednost speed: ");
Serial.println(valx);
Serial.print("vrednost direction: ");
Serial.println(valy);
Serial.print("Kill switch: ");
Serial.println(digitalRead(killswitch));
Serial.print("switch 1: ");
Serial.println(digitalRead(switch1));
Serial.print("switch 2: ");
Serial.println(digitalRead(switch2));
Serial.println("-----------------------------");
delay(100); // waits for the servo to get there
}
Loiter should work as you describe.
Acro mode will hold a heading.
Bluetooth telemetry works fine but I find WiFi to more reliable. Both short range of course. For longer range there are other telemetry radio options.
Finally, I have working code on PX4 and working skid steering on one x-y potentiometer joystick. I had to reprogram from PWM to PPM output.
// manjka še kill switch varnost
#include "PPMEncoder.h" //**
int x = 0; // analog pin za hitrost A0
int y = 1; // analog pin za smer A1
const int killswitch = 2; // digital pin connected to switch output D2
const int stikalo1 = 3; // digital pin connected to switch output D3
const int stikalo2 = 4; // digital pin connected to switch output D4
int PWM = 1500; // nastavitev za mode switch
#define OUTPUT_PPM 8
// ---------------------SETUP-------------------------------------------------------
void setup()
{
ppmEncoder.begin(OUTPUT_PPM, 5);
pinMode(x, INPUT);
pinMode(y, INPUT);
digitalWrite(killswitch, HIGH); // nastavitev inicialne vrednosti kill switcha
Serial.begin(115200);
pinMode(stikalo1, INPUT);
pinMode(stikalo2, INPUT);
digitalWrite(stikalo1, HIGH);
digitalWrite(stikalo2, HIGH);
Serial.print("Iniciliziram na 1500......");
delay (10000);
}
// --------------LOOP------------------------------------------------------------------
void loop()
{
// koda za hitrost // throttle code
int valx; // variable to read the value from hitrost
valx = analogRead(x); // reads the value of the potentiometer value between 0 and 1023)
valx = map(valx, 0, 1023, 1100, 1900); // scale it to use it with the servo value between 0 and 180)
if (valx > 1450 && valx < 1550) { // če je vrednost med 1450 in 1550 potem je vrednost 1550, drugače po vhodu
valx = 1500;
}
ppmEncoder.setChannel(2, valx);
// koda za smer // steering code
int valy; // variable to read the value from hitrost
valy = analogRead(y); // reads the value of the potentiometer value between 0 and 1023)
valy = map(valy, 0, 1023, 1100, 1900); // scale it to use it with the servo value between 0 and 180)
if (valy > 1450 && valy < 1550) { // če je vrednost med 1450 in 1550 potem je vrednost 1550, drugače po vhodu
valy = 1500;
}
// smer.writeMicroseconds(valy); // sets the servo position according to the scaled value
ppmEncoder.setChannel(0, valy);
ppmEncoder.setChannel(1, valy);
ppmEncoder.setChannel(3, valy);
// koda za mode 1 // mode code
if (digitalRead(3) == HIGH && digitalRead(4) == HIGH) {
PWM = 1500;
Serial.print("Mode PWM: ");
Serial.println(PWM);
ppmEncoder.setChannel(4, PWM);
}
// koda za mode 2 // mode code
if (digitalRead(3) == HIGH && digitalRead(4) == LOW) {
PWM = 1100;
PWM = constrain(PWM, 1100, 1900);
ppmEncoder.setChannel(4, PWM);
Serial.print("Mode PWM: ");
Serial.println(PWM);
}
// koda za mode 3 // mode code
if (digitalRead(3) == LOW && digitalRead(4) == HIGH) {
PWM = 1900;
ppmEncoder.setChannel(4, PWM);
Serial.print("Mode PWM: ");
Serial.println(PWM);
}
// izpisi serial
Serial.print("vrednost hitrost: ");
Serial.println(valx);
Serial.print("vrednost smer: ");
Serial.println(valy);
Serial.print("Kill switch: ");
Serial.println(digitalRead(killswitch));
Serial.print("Stikalo 1: ");
Serial.println(digitalRead(stikalo1));
Serial.print("Stikalo 2: ");
Serial.println("-----------------------------");
delay(5); // waits for the servo to get there
}
After flight controller switches to ARMED, the OLED display shows only the caption >>>> ARMED <<<<<.
Is it also possible in ARMED state to display the number of satellites, mode, EKF…?