Compare commits

...

7 Commits

Author SHA1 Message Date
38c49e4205 diagram 2025-04-01 11:41:13 +02:00
f4b257de8e diagram 2025-04-01 11:40:57 +02:00
3635e32259 mermaid test 2025-04-01 11:19:59 +02:00
fd037dbef2 new pcb and start programming 2025-04-01 10:54:43 +02:00
7d9ba29209 yeet 2025-04-01 10:54:29 +02:00
718cbe66d8 more clear docs 2025-04-01 10:54:25 +02:00
9a1ca56ac1 cleanup and removed debug code 2025-04-01 09:46:35 +02:00
5 changed files with 143 additions and 50 deletions

View File

@@ -71,6 +71,65 @@ During that time I used this code
```
It has an automatic arming sequence when the MCU starts with the esc and motor. But there is one small problem. I couldn't get the motor armed using this script even though I set the escpin to the correct pin. After inspecting the code a bit more I realized that escpin wasn't used anywhere and ledcChannel was the actual pin where the PWM signal would get generated. After I changed ledcChannel to the correct pin the motor armed and I could start if by sending the MCU "1".
??? Correct code
```cpp
const int potPin = 4;
// LEDC channel and timer configuration
const int ledcChannel = D2;
const int ledcTimer = 0;
const int pwmFreq = 50; // 50Hz frequency (20ms period)
const int pwmResolution = 16; // 16-bit resolution
// Pulse widths (in microseconds) for min and max throttle
const int minPulseWidth = 1200; // 1ms for min throttle
const int maxPulseWidth = 1940; // 2ms for max throttle
int incomingByte = 0;
// Function to convert pulse width to LEDC duty cycle
int pulseWidthToDutyCycle(int pulseWidth) {
int maxDuty = (1 << pwmResolution) - 1;
return (pulseWidth * maxDuty) / 20000; // Convert to 16-bit duty cycle
}
void setup() {
Serial.begin(115200);
// Set up the PWM signal on the escPin
ledcAttach(ledcChannel, pwmFreq, pwmResolution);
// Start the ESC calibration sequence
Serial.println("Starting ESC...");
// Step 2: Send minimum throttle (1ms pulse width)
Serial.println("Setting min throttle...");
ledcWrite(ledcChannel, pulseWidthToDutyCycle(minPulseWidth));
// At this point, the ESC should be calibrated
Serial.println("ESC calibration complete.");
delay(2000);
}
void loop() {
if (Serial.available() > 0) {
// read the incoming byte:
incomingByte = Serial.read();
}
//min 1100, max 1940
if (incomingByte == 48) {
ledcWrite(ledcChannel, pulseWidthToDutyCycle(1100));
Serial.println("low");
} else if (incomingByte == 49) {
ledcWrite(ledcChannel, pulseWidthToDutyCycle(1940));
Serial.println("high");
}
// Reset incomingByte after processing
// Small delay to allow for serial input processing
}
```
<video controls src="PXL_20250327_140301518(1)(1)(1).mp4" title="Title"></video>
In the loop section of the code is a method where it accepts serial communication back. Byte 49 represents ascii character 1 and byte 48 represents 0.
@@ -102,3 +161,7 @@ Here you can see it hit the maximum of the power supply (60watts). If it goes an
Here are the files to build the PSU yourself. I don't recommend building it without making a top lid. Otherwise you will have a very hard time assembling it.
Link to PSU: https://git.smikkelbakje.nl/Smikkelbakje/Labvoeding
## Power
Right now I'm facing the issue of powering the motors. My power supply can't handle the current draw from my motors. So I needed something that could output a lot of power while staying stable. That's where li-po batteries luckily come in. I have a bit of experience with handling them. The maximum amount of voltage I can put on my motors is 6S but the Electronic speed controllers can only go up to 4S. So that's what I'm going for. For now I will keep trying to test with my current power supply.

View File

@@ -1,16 +0,0 @@
# How to keep a drone upright
using accelerometers always try to keep them at 0
except if you press a button then the desired pitch changes.
https://www.reddit.com/r/diydrones/comments/1cm8ykx/how_is_stable_flight_possible/
https://github.com/lobodol/drone-flight-controller
https://github.com/liourej/CodeDroneDIY
https://electronoobs.com/eng_robotica_tut9_2_2.php
https://www.youtube.com/watch?v=4vpgjjYizVU

View File

@@ -125,6 +125,53 @@ This is the result of the board.
![alt text](image-6.jpg)
After some weeks I changed the design to this. Because I noticed the esp-C3 doesn't have enough analog pins for my joysticks so I asked Henk if I could use one of their esp-S3's because it had a lot more analog pins.
![alt text](image-9.png)
ESP S3
![alt text](image-10.png)
ESP C3
![alt text](image-8.png)
New design
This new design also saves a lot on material because the legs don't have to be cut out so I can almost make twice as many boards with the same material.
![alt text](image-11.png)
I've also send this board to JLCPCB for FR04 fabrication. Because I had issues where my FR-1 copper would just let got when moving the joysticks around. I wanted the controller to be super reliable and durable so that's why I ordered them from JLCPCB
## Programming
For the drone I will be using the [dRehmFlight VTOL program](https://github.com/nickrehm/dRehmFlight). In the [programming week](../Assignments/week_4_programming/programming.md) I already modified it to support the BNO085 and made the bridge between my handheld controller and the flight controller using ESPNow. For further support I still had some bugs to squash and some other features to implement for compatibility with my system.
```mermaid
classDiagram
namespace Drone {
class ESPC6 Thread 1{
+Control Motors
+keep drone in the air
+Receive communication from controller
Flightcontroller()
}
class MatrixControllerThread2 {
}
}
namespace Controller {
class ESPC3 {
+Read joystick data
+Clean joystick data
+Send joystick data to the drone
Handheld Controller()
}
}
ESPC3 --> ESPC6 Thread 1 : Send data to flight controller using ESPNOW
```
I've already gotten the motors to spin in week 10
## BOM (bill of materials)

View File

@@ -6,6 +6,7 @@
int normalizePot(int pin, int minValue);
int mapPot(int normalizedValue);
int analogReadMultiPlexer(int addressA, int addressB, int addressC, int addressD, int pin);
void espNow();
const int MAXPWMVALUE = 1000;
const int MINPWMVALUE = 2000;
@@ -25,28 +26,7 @@ esp_now_peer_info_t peerInfo; // create a class object of the ESPNow class
void setup()
{
// Set device as a Wi-Fi Station
WiFi.mode(WIFI_STA);
// Init ESP-NOW
if (esp_now_init() != ESP_OK)
{
Serial.println("Error initializing ESP-NOW");
return;
}
// Register peer
memcpy(peerInfo.peer_addr, broadcastAddress, 6);
peerInfo.channel = 0;
peerInfo.encrypt = false;
// Add peer
if (esp_now_add_peer(&peerInfo) != ESP_OK)
{
Serial.println("Failed to add peer");
return;
}
espNow();
Serial.begin(9600);
pinMode(D3, OUTPUT);
@@ -60,11 +40,13 @@ void setup()
void loop()
{
Serial.println(analogReadMultiPlexer(0, 0, 0, 0, A0)); // call normalizePot and put the output into mapPot then print it
Serial.print("X:" + String(myData.PWMCH2));
Serial.println(" Y:" + String(myData.PWMCH1));
// Set values to send
myData.PWMCH1 = mapPot(analogReadMultiPlexer(0, 0, 0, 0, A0));
myData.PWMCH2 = 1000; // test values
myData.PWMCH2 = mapPot(analogReadMultiPlexer(1, 0, 0, 0, A0)); // test values
myData.PWMCH3 = 1000;
myData.PWMCH4 = 1000;
@@ -78,7 +60,7 @@ void loop()
{
// Serial.println("Error sending the data");
}
delay(10);
delay(10); //delay to avoid hammering the radio and to save power/heat
}
int mapPot(int normalizedValue)
@@ -103,9 +85,28 @@ int normalizePot(int pin, int minValue) // normalize the pot value to a range of
int analogReadMultiPlexer(int addressA, int addressB, int addressC, int addressD, int pin)
{
digitalWrite(D3, LOW);
digitalWrite(D6, LOW);
digitalWrite(D7, LOW);
digitalWrite(D9, LOW);
digitalWrite(D8, LOW);
digitalWrite(D6, addressA);
digitalWrite(D7, addressB);
digitalWrite(D9, addressC);
digitalWrite(D8, addressD);
return analogRead(pin);
}
}
void espNow(){ // Set device as a Wi-Fi Station
WiFi.mode(WIFI_STA);
// Init ESP-NOW
if (esp_now_init() != ESP_OK)
{
Serial.println("Error initializing ESP-NOW");
return;
}
// Register peer
memcpy(peerInfo.peer_addr, broadcastAddress, 6);
peerInfo.channel = 0;
peerInfo.encrypt = false;
// Add peer
if (esp_now_add_peer(&peerInfo) != ESP_OK)
{
Serial.println("Failed to add peer");
return;
}}

View File

@@ -279,7 +279,6 @@ bool sbusLostFrame;
DSM1024 DSM;
#endif
#if defined USE_ESPNow
// Structure example to receive data
// Must match the sender structure
typedef struct struct_message
{
@@ -288,9 +287,7 @@ typedef struct struct_message
int PWMCH3 = 1500;
int PWMCH4 = 1500;
} struct_message;
// Create a struct_message called myData
struct_message myData;
struct_message myData; //Initialise struct as myData
#endif
// IMU:
@@ -1332,6 +1329,7 @@ void controlRATE()
void scaleCommands()
{
//TODO: Rewrite this mess with LEDC and use internal ESP pwm clocks
// DESCRIPTION: Scale normalized actuator commands to values for ESC/Servo protocol
/*
* mX_command_scaled variables from the mixer function are scaled to 125-250us for OneShot125 protocol. sX_command_scaled variables from