Skip to content
Snippets Groups Projects
Verified Commit 69913cb6 authored by Thomas Lambert's avatar Thomas Lambert :helicopter:
Browse files

feat: add safety switch


Signed-off-by: Thomas Lambert's avatarThomas Lambert <t.lambert@uliege.be>
parent cd6ab628
No related branches found
No related tags found
No related merge requests found
......@@ -43,22 +43,28 @@ wing, which are measured using absolute magnetic rotary encoders.
### List of devices
| Device | Reference | Usage |
|----------------- | --------------- | --------------- |
| **BLDC** | [Plettenberg][plettenberg] Advance 30 <br />_(Discontinued by manufacturer)_ | Motor |
| **ESC** | [JETI SPIN 75 Pro Opto][jetispin] | Motor controller |
| **ESC Terminal** | [JETIBOX][jetibox] | Program ESC, motor telemetry |
| **PSU** | [Electroautomatik][elektro] PSI 8080 - 60 T (1500W) <br />_(Discontinued by manufacturer)_ | DC power supply |
| Device | Reference | Usage |
|------------------ | --------------- | --------------- |
| **BLDC** | [Plettenberg][plettenberg] Advance 30 <br />_(Discontinued by manufacturer)_ | Motor |
| **ESC** | [JETI SPIN 75 Pro Opto][jetispin] | Motor controller |
| **ESC Terminal** | [JETIBOX][jetibox] | Program ESC, motor telemetry |
| **PSU** | [Electroautomatik][elektro] PSI 8080 - 60 T (1500W) <br />_(Discontinued by manufacturer)_ | DC power supply |
| **Controller board** | [Arduino uno (Rev 3)][arduino] | Full setup control, data logging|
| **Encoders** | [Broadcom AEAT 6012][AEAT612] | Flapping angle measurement |
| **Others** | N/A | Potentiometers, switches, resistors, etc. |
| **Encoders** | [Broadcom AEAT 6012][AEAT612] | Flapping angle measurement |
| **Potentiometer** | N/A | Manual control of RPM in v1.x.x |
| **ON/OFF switch** | N/A | Safety: Prevent ESC from starting[^1] |
## Schematics
[plettenberg]: https://plettenbergmotors.com/
[serial-studio]: https://serial-studio.github.io/
[jetispin]: https://www.jetimodel.com/katalog/spin-75-pro-opto.htm
[jetibox]: https://www.jetimodel.com/katalog/jetibox.htm
[arduino]: https://store.arduino.cc/products/arduino-uno-rev3
[elektro]: https://elektroautomatik.de
[AEAT612]: https://docs.broadcom.com/doc/AV02-0188EN
[^1]: This is useful in monitoring mode, when the JETIBOX is attached to the ESC
for analysis. As long as the switch is OFF, the Arduino will bypass the
potentiometer and write 0 to the ESC. This prevent any accidental start of the
motor while the operator is looking into diagnostics.
[plettenberg]: <https://plettenbergmotors.com/>
[serial-studio]: <https://serial-studio.github.io/>
[jetispin]: <https://www.jetimodel.com/katalog/spin-75-pro-opto.htm>
[jetibox]: <https://www.jetimodel.com/katalog/jetibox.htm>
[arduino]: <https://store.arduino.cc/products/arduino-uno-rev3>
[elektro]: <https://elektroautomatik.de>
[AEAT612]: <https://docs.broadcom.com/doc/AV02-0188EN>
......@@ -21,9 +21,10 @@
// Include Servo library to generate the PWM signal to control the motors
#include <Servo.h>
// Declare ESC pins
byte servoPin1 = 9;
byte servoPin2 = 10;
// Declare pins
byte servoPin1 = 10; // ESC 1
byte servoPin2 = 9; // ESC 2
byte switchPin = 7; // ON/OFF switch (safety feature)
// Create servo objects to control the ESC
Servo ESC1;
......@@ -34,22 +35,35 @@ void setup() {
Serial.begin(9600);
ESC1.attach(servoPin1);
ESC2.attach(servoPin2);
pinMode(switchPin,INPUT);
delay(1000); // Ensure proper initialization
}
void loop() {
int potAnal = analogRead(A0); // read potentiometer value (between 0 and 1023)
// Read ON/OFF switch state
int switchState = digitalRead(switchPin);
String armed;
// Read and map potentiometer
int potAnal = analogRead(A0); // value between 0 and 1023
int potVal = map(potAnal, 0, 1023, 0, 180); // scale potentiometer value to use with servo lib
// [TEST] Write sine values for visualization in serial-studio
float freq = 10;
float angleL = sin(millis()*1000*freq);
float angleR = cos(millis()*1000*freq);;
float angleR = cos(millis()*1000*freq);
// Send values to ESCs (currently both receive the same input)
ESC1.write(potVal);
ESC2.write(potVal);
if (switchState == LOW){
armed = "OFF";
ESC1.write(0);
ESC2.write(0);
} else {
armed = "ON";
ESC1.write(potVal);
ESC2.write(potVal);
}
// Print all useful data to serial for processing in serial-studio
Serial.print("/*"); // Frame start sequence [/*]
......@@ -62,6 +76,8 @@ void loop() {
Serial.print(angleL); // %4, Left wing angle [deg]
Serial.print(",");
Serial.print(angleR); // %5, Right wing angle [deg]
Serial.print(",");
Serial.print(armed); // %6, Armed status
Serial.println("*/"); // Frame finish sequence [*/]
delay(50); // Reduce number of data to output
......
......@@ -17,6 +17,20 @@
"units": "s",
"value": "%1",
"widget": ""
},
{
"alarm": 0,
"fft": false,
"fftSamples": 1024,
"graph": false,
"led": false,
"log": false,
"max": 0,
"min": 0,
"title": "Ready",
"units": "",
"value": "%6",
"widget": ""
}
],
"title": "Runtime",
......@@ -33,7 +47,7 @@
"log": false,
"max": 0,
"min": 0,
"title": "Potentiometer tension",
"title": "Pot. tension",
"units": "V",
"value": "%2",
"widget": ""
......@@ -47,7 +61,7 @@
"log": false,
"max": 180,
"min": 0,
"title": "Potentiometer mapped",
"title": "Pot. val",
"units": "",
"value": "%3",
"widget": "gauge"
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment