Compare commits

...

20 Commits

Author SHA1 Message Date
774f7f41d6 extra notes 2025-06-23 10:01:50 +02:00
2a585ff318 fix wrong information in research 2025-06-23 09:56:40 +02:00
e700818a2f edit flowchart 2025-06-17 12:41:03 +02:00
6be2d84f05 3d files 2025-06-17 11:51:20 +02:00
d943d6239e fix image tag 2025-06-10 13:34:46 +02:00
7a4b75c0a3 3d printing 2025-06-10 13:33:25 +02:00
a46ad186db schedule 2025-06-07 16:43:41 +02:00
7b3c164c6d docs 2025-06-04 16:35:06 +02:00
9da84bb7a8 fix accidentally overwritten image 2025-06-04 16:33:51 +02:00
1009a14673 docs 2025-06-04 16:26:30 +02:00
2d1a6ae1f6 stable flight in theory been achieved 2025-06-03 12:26:06 +02:00
d099aac466 fix controller so middle of joystick is actually 1500 now 2025-06-03 11:36:33 +02:00
c4c56efb7a typos 2025-06-02 15:52:28 +02:00
e975e5a93b BOM 2025-06-02 15:10:52 +02:00
e43a469647 docs 2025-06-02 10:33:53 +02:00
f156423f8b change video links 2025-06-02 10:19:17 +02:00
f892d78745 docs motor burnout 2025-06-02 09:55:00 +02:00
5adf888713 code update and presentation stuff 2025-05-28 12:23:32 +02:00
2dd30990bc added useless boot sequence 2025-05-27 15:29:12 +02:00
5104f71dc6 fix scrollingtext function for matrix controller 2025-05-27 14:50:37 +02:00
24 changed files with 675 additions and 259 deletions

View File

@@ -1,7 +1,7 @@
# FR-1 Trace lengths
## The experiment
For the experiment, I used FR-1 that has a thickness of 35µm. On there I will mill 4 trace sizes (0.4 mm, 0,6 mm, 0,8 mm and 1 mm) and they all have the same length of 7.5 cms. The traces are seperated by 1 Cm.
For the experiment, I used FR-1 that has a thickness of 35µm. On there I will mill 4 trace sizes (0.4 mm, 0,6 mm, 0,8 mm and 1 mm) and they all have the same length of 7.5 cms. The traces are separated by 1 Cm.
![alt text](FR-1-Traces.jpg)
@@ -26,26 +26,29 @@ The capacitance of a PCB trace is the amount of energy it can hold. It works lik
The capacitance is determined by the amount of copper is in the trace. So length, width and the thickness. When working with low frequency signals the capacitance is not super important.
But when working with higher speed frequencies the capacitance can actually mess up the signal integrity.
## Heat generation
Heat within traces is generated by the current flowing through it. Not the wattage. A good example of the is train lines. These run on 230.000 volts on thin wires while being able to supply multiple trains. The higher the voltage the easier it is the transport a higher amount of wattage.
## Results
the power. So I grabbed an old robot with 4 stepper motors attached but I could not get them to draw more than 30 watts. So that is why the maximum in this test is 30 watts. I also had a hard time finding a way to measure the temperature of the traces because we only had a heat gun here and the laser was not the place it was actually measuring. So 0,4 mm is not measured properly.
the power. So I grabbed an old robot with 4 stepper motors attached but I could not get them to draw more than 1.6 Amperage. So that is why the maximum in this test is 1.6 Amperage. I also had a hard time finding a way to measure the temperature of the traces because we only had a heat gun here and the laser was not the place it was actually measuring. So 0,4 mm is not measured properly.
| Trace Width Trace | Resistance | Maximum safe wattage | Burn out wattage |
| :---------------- | ---------- | -------------------- | ---------------- |
| 0,4mm | 3,1Ω | 15 | 20 |
| 0,6mm 2 | 2 | 22 | 26 |
| 0,8mm | 2Ω | 27 | ?? |
| 1mm | 1,85Ω | ?? | ?? |
| | | | |
| Trace Width Trace | Resistance | Maximum safe Current in Ampere | Burn out Ampere |
| :---------------- | ---------- | ------------------------------ | --------------- |
| 0,4mm | 3.1Ω | 0.7 | 0.85 |
| 0,6mm | 2.7Ω | 0.9 | 1.05 |
| 0,8mm | 2Ω | 1.6 | ?? |
| 1mm | 1.85Ω | ?? | ?? |
| | | | |
* The 0,4 mm trace was the first one I tested. I started with 15 watts for a few seconds. After that I increased the wattage to 20 watts and the trace instantly exploded and burned so I could not get temperature readings there.
* The 0,4 mm trace was the first one I tested. I started with 0.7 amps for a few seconds. After that I increased the wattage to 0.85 amps and the trace instantly exploded and burned so I could not get temperature readings there.
* The 0,6 mm trace it held up well up to 27 watts where it started getting burn marks within a 5-10 seconds. The temperature rose to 50 degrees celsius. At 29 watts the pcb burned out at 68 degrees celsius.
* The 0,6 mm trace it held up well up to 0.9 amps where it started getting burn marks within a 5-10 seconds. The temperature rose to 50 degrees celsius. At 1.05 amps the pcb burned out at 68 degrees celsius.
* When testing the 0,8 mm trace I hit a roof with how much power I could consume with the robot. I could only get up to 30 watts and I did not manage to break the trace after powering it for a few minutes. The maximum I found before it started discoloring was 24 watts at 54 degrees celsius. This was measured after it was left on for 2 minutes.
* When testing the 0,8 mm trace I hit a roof with how much power I could consume with the robot. I could only get up to 1.6 amps and I did not manage to break the trace after powering it for a few minutes. The maximum I found before it started discoloring was 24 watts at 54 degrees celsius. This was measured after it was left on for 2 minutes.
* I could not get to the 1mm trace because the robot could not draw more than 30 watts. So thats why these are not filled in the table.
* I could not get to the 1mm trace because the robot could not draw more than 1.6 Amperage. So thats why these are not filled in the table.
## Extra notes on temperature

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

BIN
docs/final_project/arm.stl Normal file

Binary file not shown.

Binary file not shown.

View File

@@ -1,29 +1,29 @@
# Final project
## Introduction
I wanted to combine 2 random objects that interest me into one project. A drone and a jumbotron. So im gonna make a drone with multiple screens on it that could for example be used for traffic control or entertainment purposes.
I wanted to combine 2 random objects that interest me into one project. A drone and a jumbotron. So im gonna make a drone with multiple screens on it that could for example be used for traffic control or entertainment purposes. There is no real reason why I chose to make this beside it looking and sounding fun to design and build.
## What does the drone do?
The drone needs to be able to fly for at least 20 minutes. It needs 2 screens on both side so it can display images or video. I wanna program the drone myself so I know how drones work and how they keep themselves upright.
## Drone Requirements
### basic requirements
* 2 screens
* Speakers
* 20 min flight time
* custom microcontroller pcb that controls the drones and screens
* 50 meter range from controller
??? Drone Requirements
### basic requirements
* 2 screens
* Speakers
* 20 min flight time
* custom micro controller pcb that controls the drones and screens
* 50 meter range from controller
### Sensors
* GPS
* IMU/rotation sensor
* Read voltage from battery know battery percentage
### Sensors
* GPS
* IMU/rotation sensor
* Read voltage from battery know battery percentage
### Requirements when far ahead
* Docking station
* Automatic docking
* Automatic pathing
* Design own electronic speed controllers
### Requirements when far ahead
* Docking station
* Automatic docking
* Automatic pathing
* Design own electronic speed controllers
## Images
@@ -50,19 +50,19 @@ When designing the drone I wanted to do everything parametric. So im going to tr
### Designing the drone parametrically
Designing parametrically is very hard because every constraint needs to be perfect. Otherwise when changing lengths the design will fold into itself like this.
![alt text](../assets/assets_week_2/fusion360/image.jpg)
I've spend one day getting the constraints perfect for the sketch so it scales well with everything. And this is the result of that. When I change one parameter in the variable menu the entire body scales with it. This is the final result of my design. I've made the body myself and I've imported the components from grabcad. So I had more time for blender and Onshape and so I could visualize it better.
I've spend one day getting the constraints perfect for the sketch so it scales well with everything. And this is the result of that. When I change one parameter in the variable menu the entire body scales with it. This is the final result of my design. I've made the body myself and I've imported the components from GrabCad. So I had more time for blender and Onshape and so I could visualize it better.
![alt text](../assets/assets_week_2/fusion360/image-18.jpg)
### Rendering
I've also made a render of the drone to visualize it for other people. Making this was kind of a pain because blender is a gigantic program. You can see my [docs](../Assignments/week_2_computer_aided_design_(cad)/drone_designing.md) to see where I struggled. This is my final result of the render. I've wished it looked nicer but I didn't have enough time to dive deeper into blender.
<video controls src="../assets/assets_week_2/blender/droneRender.mp4" title="Title"></video>
<video controls src="../../assets/assets_week_2/blender/droneRender.mp4" title="Title"></video>
## Feedback from Bas and Henk
I've gotten some feedback on my design and about the use of screens. Maybe I should only use speakers or use LED matrixes. After thinking about it I think im going to give LED matrixes a spin.
## Drone electronics
For the drone I will need a lot of electronics. But I will also need a pcb for inside the drone so I don't have any loose connections. The main board needs a couple of components. Something to step down the voltage from the big battery or I will use two separate batteries one for the motors one for the control board. I will also need a sensor to know the position of the drone and a microcontroller. I also need a lot of power to power the screens so that will also be something interesting.
For the drone I will need a lot of electronics. But I will also need a pcb for inside the drone so I don't have any loose connections. The main board needs a couple of components. Something to step down the voltage from the big battery or I will use two separate batteries one for the motors one for the control board. I will also need a sensor to know the position of the drone and a micro controller. I also need a lot of power to power the screens so that will also be something interesting.
### Components
* MCU
@@ -74,14 +74,14 @@ For the drone I will need a lot of electronics. But I will also need a pcb for i
### Drone remote electronics
I'm also building the remote for the drone
* Potslider for the throttle
* Potentiometer slider for the throttle
* Joystick for left-right-forward-backwards
* battery
* screen to see status of drone
* LED (mandatory)
#### Joystick
I really wanna use a joystick for this project because having 2 potmeters under each other looks a bit weird.
I really wanna use a joystick for this project because having 2 potentiometers under each other looks a bit weird.
### KiCad
The first thing I did was import the design rules for our milling machine. I used the file from the lecture to import it from because there we set everything up together.
@@ -143,13 +143,15 @@ For the drone I will be using the [dRehmFlight VTOL program](https://github.com/
```mermaid
classDiagram
namespace Drone {
class ESPC6 Thread 1{
class ESPC6{
+Control Motors
+keep drone in the air
+Receive communication from controller
Flightcontroller()
}
class MatrixControllerThread2 {
class MatrixControllerRP2040 {
+Receive communication from ESPC6 for Matrix data
ShowMatrix()
}
@@ -164,13 +166,15 @@ namespace Controller {
}
}
ESPC3 --> ESPC6 Thread 1 : Send data to flight controller using ESPNOW
ESPC3 --> ESPC6 : Send data to flight controller using ESPNOW
ESPC6 --> MatrixControllerRP2040 : Serial communication
```
Now that I am in week 15 this has changed. The change is on the drone are going to be 2 mcu's. One for the matrixes and one for the flight controller. So they are both separate systems and can't interfere with each other.
![alt text](image-30.jpg)
I've already gotten the motors to spin in [week 10](../Assignments/week_10_output_devices/output_devices.md) using the script in there. Now I also need to modify the original VTOL driver so my ESC's can properly understand it's instructions.
I have already gotten the motors to spin in [week 10](../Assignments/week_10_output_devices/output_devices.md) using the script in there. Now I also need to modify the original VTOL driver so my ESC's can properly understand it's instructions.
There's one specific function I need to change.
??? Old code
@@ -179,7 +183,7 @@ There's one specific function I need to change.
{
// DESCRIPTION: Send pulses to motor pins, oneshot125 protocol
/*
* My crude implimentation of OneShot125 protocol which sends 125 - 250us pulses to the ESCs (mXPin). The pulselengths being
* My crude implementation of OneShot125 protocol which sends 125 - 250us pulses to the ESCs (mXPin). The pulse lengths being
* sent are mX_command_PWM, computed in scaleCommands(). This may be replaced by something more efficient in the future.
*/
int wentLow = 0;
@@ -243,7 +247,7 @@ There's one specific function I need to change.
}
}
```
What this function does is generate PWM values in software which is super inefficient. The esp32C6 according to it's datasheet supports 6 seperate PWM clocks in hardware.
What this function does is generate PWM values in software which is super inefficient. The esp32C6 according to it's datasheet supports 6 separate PWM clocks in hardware.
![alt text](image-pc-4.jpg)
So I wanna use these to reduce the overhead and so the loop doesn't have to run 20 times a second but faster making the drone respond faster. To use these I need to use this library.
Right link: [https://docs.espressif.com/projects/arduino-esp32/en/latest/api/ledc.html](https://docs.espressif.com/projects/arduino-esp32/en/latest/api/ledc.html)
@@ -261,12 +265,12 @@ So I really needed 2 functions of the library.
## Generative design
Online I saw a lot of organic designs that where created by generative design.
![alt text](image-12.jpg)
Credits: [formlabs](https://formlabs.com/eu/blog/generative-design/)
Credits: [FormLabs](https://formlabs.com/eu/blog/generative-design/)
I wanted to do this myself for the drone arms. So I started messing around in the generative design tab of my drone arm model.
![alt text](image-13.jpg)
I've already designed the base of the arm. What generative design does is either add or remove material based on parameters you give it.
I've already prepared my model by created some parts as seperate bodies. So I can preserve them during the generation process.
I've already prepared my model by created some parts as separate bodies. So I can preserve them during the generation process.
When creating a Study you need to assign which parts to groups.
![alt text](image-14.jpg)
@@ -284,7 +288,7 @@ So after assigning everything this is my result.
After that you can open the Objectives tab to see what you wanna do and set more limits.
![alt text](image-16.jpg)
The only things I understand from this menu is the Objectives and the Displacement. The objective is straight foward and the Displacement is the amount of millimeters it is allowed to fluctuate from the original design in said direction.
The only things I understand from this menu is the Objectives and the Displacement. The objective is straight forward and the Displacement is the amount of millimeters it is allowed to fluctuate from the original design in said direction.
Now it's time to add the loads on the part. So the amount weight and force the part needs to be able to handle.
For that there's a keybind `L`
@@ -344,8 +348,13 @@ Now I needed to make the same holes through the case itself in the same location
From this tab I can edit the body with all the references in place. So I could use the holes in the drone arm as reference for my cuts for in the drone body.
![alt text](image-pc-7.jpg)
## 3D printing
I chose to fully 3D print my drone due to it's complex shape and time constraints. I still had a lot of work from university to do. We got encouraged to do compositing but that is super hard with the current design. However it would have been better since it is often lighter and more durable while being a lot more eco friendly. For 3D printing I am planning on using PLA because it has a lower carbon footprint than ABS and it releases less toxic fumes.
![alt text](image343.jpg)
## Burnout!
### Part 1
One of my motors during testing burned out completely when it was attached to the printed arm. I think the cause for this is overheating due to a propellor that's too big.
![alt text](image-27.jpg)
@@ -359,6 +368,13 @@ Another thing that also could be the issue is that my ESC was surging above 40 A
I think the main reason was heat and the coating on the motors evaporating causing a chain reaction.
### Part 2
This time it was completely my fault for not paying attention to the wires when connecting them to the right terminals. I had all other motors taped off like this but I forgot to do that for one motor I was testing.
![alt text](imag1.jpg)
<video controls src="../PXL_20250528_093723437(1)(1).mp4" title="Title"></video>
## Cables
The drone needs lots of cables to get power to the places where they need to be. I first started out by laying out everything that needed to be connected.
@@ -408,7 +424,7 @@ I tested the power consumption on the matrix by setting the brightness to 100 an
![alt text](image-38.jpg)
The result of this is that a single matrix consumed 3,8 amps at 5 volt. With 4 ESC's providing a total of 12 amps at 5 volts I should be easily able to power the mcu's and the matrixes.
## Assembly
Here I started assembly of the drone. I printed the motor arms and screwed all the motors into them and soldered pogo pins to each to connect them to the esc's. Unfortanetly I don't know how to connect them yet because the wires aren't labeled. 2 motors need to spin left and the other 2 right for stability.
Here I started assembly of the drone. I printed the motor arms and screwed all the motors into them and soldered pogo pins to each to connect them to the esc's. Unfortunately I don't know how to connect them yet because the wires aren't labeled. 2 motors need to spin left and the other 2 right for stability.
![alt text](image-43.jpg)
I also saw during assembly that the drone body warped a bit but that isn't going to ruin the fun. It will still fly.
![alt text](image-44.jpg)
@@ -426,55 +442,94 @@ I accidentally killed an esp C6 due to short in between the PWM output pin of th
Later on I realized I also killed my IMU. Because there wasn't any resistance between the 3v3 and the GND
## Stripped screws
Quick tip. When tightening screws do not do it at an angle otherwise you may strip the screw or dislodge the heated insert. Learned that the hard way. ;-;
And when doing heated inserts make sure to do a couple of extra wall layers. So the heated insert can latch onto the plastic.
![alt text](imag2.jpg)
## TODO
* [ ] Matrix panel subsystem
* [x] Rewrite PWM esc control system in driver
* [ ] Does it fly?
* [ ] Does it fly? (No it didn't)
* [x] Power distribution system (for matrixes and mcu's)
* [x] Test physical controller
## Testing the drone(V1)
The first test of the drone went horribly wrong. This was a first test with analog control with not stabilization feedback from the IMU to see if it would come off the ground. Sadly it did not go as expected.
<video controls src="../PXL_20250604_121528011(1).mp4" title="Title"></video>
### What went wrong
* The drone was not balanced
* The drone was a bit too heavy
* The drone didn't have good footing to the ground
* Motors recalibrating themselves at some startups (Last startup that didn't happen)
* The drone arm was too weak to resist the impact of the motors
* The batteries weren't fastened inside the drone
### Improvements for next design
* Proper legs so the drone doesn't fall over during takeoff
* Lighter design while being as strong as possible with the least amount of material
* A power switch because everything instantly starts once it gets power and that could be dangerous with extremely fast spinning propellors.
* Fastened batteries
![alt text](imaged.jpg)
### The damage
![alt text](imaged-1.jpg)
One matrix board got a few ripped of leds and capacitors but I think I am able to repair that.
![alt text](imaged-2.jpg)
2 ESC's and motors got completely tangled wires. I expect them to still work since they where still spinning after the impact.
3/4 arms got ripped off due to the crash.
![alt text](imaged-3.jpg)
![alt text](imaged-4.jpg)
Luckily we placed cardboard under the drone incase something would happen. The propellors completely mauled the cardboard away where it hit.
Now that the drone is ripped into several pieces I will be abandoning this design and start from scratch on a second design. From this point on I can only go up.
## BOM (bill of materials)
### Drone
#### Parts
| item | price | link |
| :-------------------- | ------- | --------------------------------------------------------------------------------------- |
| 700 grams of filament | € 14 | Any PLA |
| Matrix panel * 2 | € 17,78 | https://aliexpress.com/item/4001296811800.html |
| BLDC ESC * 4 | € 26,76 | https://aliexpress.com/item/1005006947824850.html |
| BLDC Motor 1500KV | € 34,39 | https://aliexpress.com/item/1005006859037930.html |
| 4S Li-Po * 2 | € 15,86 | https://hobbyking.com/en_us/turnigy-nano-tech-plus-1400mah-4s-70c-lipo-pack-w-xt60.html |
| Propellors 7040 | € 6,99 | https://aliexpress.com/item/1005008125599756.html |
| XT-60 connectors | € 1,40 | https://aliexpress.com/item/1005007228544590.html |
| Wiring 26 AWG | € 1,63 | https://aliexpress.com/item/1005007213319794.html |
| seeed XIAO RP2040 | $ 3,99 | https://www.seeedstudio.com/XIAO-RP2040-v1-0-p-5026.html |
| seeed XIAO ESP-C6 | $ 5,20 | https://www.seeedstudio.com/Seeed-Studio-XIAO-ESP32C6-p-5884.html |
| smd male header pins | € 2,99 | https://aliexpress.com/item/32796117265.html |
| M4 screws and nuts | | https://aliexpress.com/item/4001072025844.html |
| M4 Threaded inserts | | https://aliexpress.com/item/1005003582355741.html |
| | | |
| item | price | link |
| :-------------------- | ------- | -------------------------------------------------------------------------------------------------------- |
| 700 grams of filament | € 14 | Any PLA |
| Matrix panel * 2 | € 17,78 | [https://aliexpress.com/item/4001296811800.html](https://aliexpress.com/item/4001296811800.html ) |
| BLDC ESC * 4 | € 26,76 | [https://aliexpress.com/item/1005006947824850.html](https://aliexpress.com/item/1005006947824850.html ) |
| BLDC Motor 1500KV | € 34,39 | [https://aliexpress.com/item/1005006859037930.html](https://aliexpress.com/item/1005006859037930.html) |
| 4S Li-Po * 2 | € 15,86 | [https://hobbyking.com/en_us/turnigy-nano-tech-plus-1400mah-4s-70c-lipo-pack-w-xt60.html](https://hobbyking.com/en_us/turnigy-nano-tech-plus-1400mah-4s-70c-lipo-pack-w-xt60.html) |
| Propellors 7040 | € 6,99 | [https://aliexpress.com/item/1005008125599756.html](https://aliexpress.com/item/1005008125599756.html) |
| XT-60 connectors | € 1,40 | [https://aliexpress.com/item/1005007228544590.html](https://aliexpress.com/item/1005007228544590.html) |
| Wiring 26 AWG | € 1,63 | [https://aliexpress.com/item/1005007213319794.html](https://aliexpress.com/item/1005007213319794.html) |
| seeed XIAO RP2040 | $ 3,99 | [https://www.seeedstudio.com/XIAO-RP2040-v1-0-p-5026.html](https://www.seeedstudio.com/XIAO-RP2040-v1-0-p-5026.html) |
| seeed XIAO ESP-C6 | $ 5,20 | [https://www.seeedstudio.com/Seeed-Studio-XIAO-ESP32C6-p-5884.html](https://www.seeedstudio.com/Seeed-Studio-XIAO-ESP32C6-p-5884.html) |
| smd male header pins | € 2,99 | [https://aliexpress.com/item/32796117265.html](https://aliexpress.com/item/32796117265.html) |
| M4 screws and nuts | | [https://aliexpress.com/item/4001072025844.html](https://aliexpress.com/item/4001072025844.html) |
| M4 Threaded inserts | | [https://aliexpress.com/item/1005003582355741.html](https://aliexpress.com/item/1005003582355741.html) |
| | | |
#### Files
* [Drone main body F3D]
* [Drone arm F3D]
* [Drone main body STL]
* [Drone main arm STL]
* [Drone side panel STL]
* [Drone PCB's KiCad]
* [Drone Software]
* [Matrix Software]
* [Drone main body F3Z](DroneMain.f3z)
* [Drone arm F3D]("New DroneArm v5.f3d")
* [Drone main body STL](DroneMainBody.stl)
* [Drone main arm STL](arm.stl)
* [Drone side panel STL](SidePanel.stl)
* [Drone PCB's KiCad](drone_control_board.zip)
* [Drone Software]()
* [Matrix Software]()
### Drone controller
#### Parts
| item | price | link |
| :-------------------- | ------- | ---------------------------------------------------------------------------------- |
| XIAO ESP-C3 | $ 4,99 | https://www.seeedstudio.com/seeed-xiao-esp32c3-p-5431.html |
| Hall effect joysticks | € 11,99 | https://aliexpress.com/item/1005007462081151.html |
| Analog Multiplexer IC | $ 0,57 | https://www.digikey.com/en/products/detail/texas-instruments/CD74HC4067M96/1507236 |
| XIAO ESP-C3 | $ 4,99 | [https://www.seeedstudio.com/seeed-xiao-esp32c3-p-5431.html](https://www.seeedstudio.com/seeed-xiao-esp32c3-p-5431.html) |
| Hall effect joysticks | € 11,99 | [https://aliexpress.com/item/1005007462081151.html](https://aliexpress.com/item/1005007462081151.html) |
| Analog Multiplexer IC | $ 0,57 | [https://www.digikey.com/en/products/detail/texas-instruments/CD74HC4067M96/1507236](https://www.digikey.com/en/products/detail/texas-instruments/CD74HC4067M96/1507236) |
| | | |
#### Files
* [Handheld controller pcb](Drone%20controller.zip)
* [Handheld controller PCB](Drone%20controller.zip)

Binary file not shown.

After

Width:  |  Height:  |  Size: 130 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 97 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 80 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 86 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 109 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 76 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 79 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 76 KiB

View File

@@ -27,4 +27,34 @@ Im also busy with a project with connecting 4 led matrixes together so I can sho
For this project I wanna build a traffic drone that can be used as temporary traffic signs or can be used at festivals to quickly display information.
### What software/hardware am I using
For this project I'm using a mix of manjaro and windows. I use Windows for Fusion360 since I can't install it on manjaro and I use manjaro for the rest of my stuff since I daily drive it. I use visual studio code as my editor.
For this project I'm using a mix of manjaro and windows. I use Windows for Fusion360 since I can't install it on manjaro and I use manjaro for the rest of my stuff since I daily drive it. I use visual studio code as my editor.
## Schedule
| Date | Deadline |
| ------ | -------------------------------------------------------------------------- |
| Jan 29 | principles and practices, presentations, introductions, project management |
| Feb 5 | computer-aided design |
| Feb 12 | computer-controlled cutting |
| Feb 19 | embedded programming |
| Feb 26 | 3D scanning and printing |
| Mar 5 | electronics design |
| Mar 12 | computer-controlled machining |
| Mar 19 | electronics production |
| Mar 26 | input devices |
| Apr 2 | output devices + Intermediate assessment |
| Apr 9 | networking and communications |
| Apr 16 | mechanical design, machine design |
| Apr 30 | molding and casting |
| May 7 | interface and application programming |
| May 11 | Research paper version 1 |
| May 13 | Drone revision 2 done |
| May 14 | system integration |
| May 28 | applications and implications + Last version research paper |
| Jun 5 | Drone flight day |
| Jun 6 | Presentation |
| Jun 9 | final assignment presentations |
| Jun 10 | Portfolio version 1 |
| Jun 21 | Portfolio last version |
| Jun 24 | Finals Assessment |

BIN
docs/presentation.mp4 Normal file

Binary file not shown.

View File

@@ -38,9 +38,12 @@
// lines are arranged in columns, progressive order. The shield uses
// 800 KHz (v2) pixels that expect GRB color data.
void scrollingText(String text, int speed);
void scrollingText(String text, int speed, int color);
void playGif(const uint16_t* gifData[], int frameCount, int frameDelay);
void displayFullScreenBMP(const uint16_t* bitmap);
void bootSequence();
void matrixSerialLoop();
void matrixSerialSetup();
Adafruit_NeoMatrix matrix = Adafruit_NeoMatrix(32, 8, PIN,
NEO_MATRIX_BOTTOM + NEO_MATRIX_RIGHT +
@@ -48,35 +51,53 @@ Adafruit_NeoMatrix matrix = Adafruit_NeoMatrix(32, 8, PIN,
NEO_GRB + NEO_KHZ800);
const uint16_t colors[] = {
matrix.Color(255, 0, 0), matrix.Color(0, 255, 0), matrix.Color(0, 0, 255) };
matrix.Color(255, 0, 0), matrix.Color(0, 255, 0), matrix.Color(0, 0, 255) }; //RGB
void setup() {
matrix.begin();
matrix.setTextWrap(false);
matrix.setBrightness(40);
matrix.setTextColor(colors[0]);
matrix.setBrightness(25);
matrix.setTextColor(matrix.Color(255, 255, 255));
matrixSerialSetup();
Serial.begin(9600);
// bootSequence();
}
int x = matrix.width();
int pass = 0;
void loop() {
displayFullScreenBMP(EEP);
matrix.fillScreen(0);
matrix.setCursor(0, 0);
matrix.setTextColor(matrix.Color(255, 0, 255));
matrix.print("Outch");
matrix.show();
}
void scrollingText(String text, int speed) {
matrix.fillScreen(0);
matrix.setCursor(x, 0);
matrix.print(text);
if(--x < -(text.length() * 6)) {
x = matrix.width();
if(++pass >= 3) pass = 0;
matrix.setTextColor(colors[pass]);
void scrollingText(String text, int speed, int color) {
// Save original position and color state
int textX = matrix.width();
int textPass = 0;
matrix.setTextColor(color);
// Calculate the total scroll distance needed for the text to completely scroll through
// We want to scroll until the text has fully entered from the right AND fully exited to the left
int textWidth = text.length() * 6; // Approx 6 pixels per character
int totalScrollDistance = matrix.width() + textWidth;
// Continue scrolling until the text has completely passed through
for (int i = 0; i < totalScrollDistance; i++) {
matrix.fillScreen(0);
matrix.setCursor(textX, 0);
matrix.print(text);
matrix.show();
// Move text position one pixel to the left
textX--;
delay(speed);
}
matrix.show();
delay(speed);
}
void playGif(const uint16_t* gifData[], int frameCount, int frameDelay) {
@@ -104,4 +125,41 @@ void displayFullScreenBMP(const uint16_t* bitmap) {
int height = matrix.height();
matrix.drawRGBBitmap(0, 0, bitmap, width, height);
matrix.show();
}
void bootSequence() {
//just display something cool on startup. This is hardcoded asf
matrix.fillScreen(0);
matrix.setCursor(5, 0);
matrix.setTextColor(matrix.Color(0, 0, 255));
matrix.print("Boot");
matrix.show();
delay(5000);
}
void matrixSerialSetup(){
Serial1.begin(115200);
}
void matrixSerialLoop() {
if (Serial1.available()) {
String command = Serial1.readStringUntil('\n');
command.trim(); // Remove any trailing newline or spaces
Serial.println("Received command: " + command);
if (command.startsWith("scroll:")) {
String text = command.substring(7); // Get the text after "scroll:"
scrollingText(text, 50, matrix.Color(255, 0, 255));
} else if (command.startsWith("gif:")) {
// Handle GIF command
// Example: gif:frame1,frame2,frame3
// You would need to parse the frames and call playGif()
} else if (command.startsWith("bmp:")) {
// Handle BMP command
// Example: bmp:bitmapData
// You would need to parse the bitmap data and call displayFullScreenBMP()
}
}
}

View File

@@ -6,12 +6,22 @@
// Oled Screen stuff
U8G2_SSD1306_128X64_NONAME_F_HW_I2C u8g2(U8G2_R0, /* reset=*/U8X8_PIN_NONE);
const int MAXPWMVALUE = 1000;
const int MINPWMVALUE = 2000;
const uint8_t broadcastAddress[] = {0x8C, 0xBF, 0xEA, 0xCC, 0x8B, 0x18};
// 8c:bf:ea:cc:8b:18
const int MAXPWMVALUE = 2000;
const int MINPWMVALUE = 1000;
const uint8_t broadcastAddress[] = {0xE4, 0xB3, 0x23, 0xB5, 0x8D, 0xD0};
// e4:b3:23:b5:8d:d0
//=====================================================================================//
// Struct declarations
typedef struct filteredJoystickData
{
int PWMCH1;
int PWMCH2;
int PWMCH3;
int PWMCH4;
int killSwitch = 1; // 1 = throttle cut, 0 = normal operation
} filteredJoystickData;
filteredJoystickData filteredJoystick; // declare the struct as JoystickData
typedef struct struct_message
{
int PWMCH1;
@@ -32,6 +42,16 @@ struct hardJoystickValues
int RXD; // Right joystick X axis down
};
// uncalibrated offsets these are calibrated in setup() function
int offsetPWMCH1 = 0; // Resting value for PWMCH1 (right joystick Y-axis)
int offsetPWMCH2 = 0; // Resting value for PWMCH2 (right joystick X-axis)
int offsetPWMCH3 = 0; // Resting value for PWMCH3 (left joystick X-axis)
int offsetPWMCH4 = 0; // Resting value for PWMCH4 (left joystick Y-axis)
// Define deadzone threshold
const int deadzone = 200;
const int pwmDeadzone = 50; // Much smaller deadzone in PWM space
//=====================================================================================//
// declarations
int normalizePot(int pin, int minValue);
@@ -40,44 +60,58 @@ int analogReadMultiPlexer(int addressA, int addressB, int addressC, int addressD
void espNow();
void readAllMultiPlexer();
void espNowLoop();
void printPWMValues();
void printFilteredPWMValues();
void printUnfilteredPWMValues();
int digitalReadMultiPlexer(int addressA, int addressB, int addressC, int addressD, int pin);
hardJoystickValues GUIParser();
void MUXSetup();
void killSwitch();
void OLEDSetup();
void deadZonedJoysticks(); // Apply deadzone to joystick values
void calibrateJoystickOffsets();
void printOffsets();
void debugPWM1();
void debugAllChannels();
//===========================================================================//
void setup()
{
Serial.begin(9600);
OLEDSetup();
espNow();
MUXSetup(); // Setup the multiplexer
Serial.begin(9600);
calibrateJoystickOffsets();
}
void loop()
{
// Debugging
// readAllMultiPlexer();
// printPWMValues();
// readAllMultiPlexer();
// printFilteredPWMValues();
// printUnfilteredPWMValues();
// printOffsets();
debugAllChannels();
// Set values to send
JoystickData.PWMCH1 = mapPot(analogReadMultiPlexer(0, 0, 0, 0, A0)); // Right joystick Y
JoystickData.PWMCH2 = mapPot(analogReadMultiPlexer(1, 0, 0, 0, A0)); // Right joystick X
JoystickData.PWMCH3 = mapPot(analogReadMultiPlexer(0, 0, 0, 1, A0)); // left joystick Y
JoystickData.PWMCH4 = mapPot(analogReadMultiPlexer(1, 0, 0, 1, A0)); // left joystick X
JoystickData.PWMCH1 = analogReadMultiPlexer(0, 0, 0, 0, A0); // Right joystick Y
JoystickData.PWMCH2 = analogReadMultiPlexer(1, 0, 0, 0, A0); // Right joystick X
JoystickData.PWMCH3 = analogReadMultiPlexer(0, 0, 0, 1, A0); // left joystick Y
JoystickData.PWMCH4 = analogReadMultiPlexer(1, 0, 0, 1, A0); // left joystick X
deadZonedJoysticks(); // Apply deadzone to joystick values
bool buttonRight = abs(analogReadMultiPlexer(0, 0, 1, 0, A0) / 4095); // right button
bool buttonLeft = abs(analogReadMultiPlexer(1, 0, 1, 0, A0) / 4095); // left button
killSwitch();
GUIParser();
espNowLoop();
delay(10); // delay to avoid hammering the radio and to save power/heat
}
int mapPot(int normalizedValue)
{
return map(normalizedValue, 400, 2500, MINPWMVALUE, MAXPWMVALUE); // map the normalized value to the PWM range
return map(normalizedValue, 400, 4095, MINPWMVALUE, MAXPWMVALUE); // map the normalized value to the PWM range
}
// legacy stuff for original potsliders
@@ -139,7 +173,7 @@ void espNow()
void espNowLoop()
{
// Send message via ESP-NOW
esp_err_t result = esp_now_send(broadcastAddress, (uint8_t *)&JoystickData, sizeof(JoystickData));
esp_err_t result = esp_now_send(broadcastAddress, (uint8_t *)&filteredJoystick, sizeof(filteredJoystick));
if (result == ESP_OK)
{
// Serial.println("Sent with success");
@@ -166,15 +200,6 @@ void MUXSetup()
hardJoystickValues GUIParser()
{
// Define joystick offsets (calibrated resting values)
const int offsetPWMCH1 = 1090; // Resting value for PWMCH1 (right joystick Y-axis)
const int offsetPWMCH2 = 1072; // Resting value for PWMCH2 (right joystick X-axis)
const int offsetPWMCH3 = 1043; // Resting value for PWMCH3 (left joystick X-axis)
const int offsetPWMCH4 = 1476; // Resting value for PWMCH4 (left joystick Y-axis)
// Define deadzone threshold
const int deadzone = 120;
// Adjust joystick values by subtracting offsets
int adjustedPWMCH1 = JoystickData.PWMCH1 - offsetPWMCH1;
int adjustedPWMCH2 = JoystickData.PWMCH2 - offsetPWMCH2;
@@ -205,6 +230,108 @@ hardJoystickValues GUIParser()
return {LXU, LXD, 0, 0}; // Return the values as a struct
}
void deadZonedJoysticks()
{
// Convert raw values to PWM first, then check deadzone
int pwmCH1 = mapPot(JoystickData.PWMCH1);
int pwmCH2 = mapPot(JoystickData.PWMCH2);
int pwmCH3 = mapPot(JoystickData.PWMCH3);
int pwmCH4 = mapPot(JoystickData.PWMCH4);
// Convert offsets to PWM too
int pwmOffsetCH1 = mapPot(offsetPWMCH1);
int pwmOffsetCH2 = mapPot(offsetPWMCH2);
int pwmOffsetCH3 = mapPot(offsetPWMCH3);
int pwmOffsetCH4 = mapPot(offsetPWMCH4);
// Calculate adjusted values in PWM space
int adjustedPWMCH1 = pwmCH1 - pwmOffsetCH1;
int adjustedPWMCH2 = pwmCH2 - pwmOffsetCH2;
int adjustedPWMCH3 = pwmCH3 - pwmOffsetCH3;
int adjustedPWMCH4 = pwmCH4 - pwmOffsetCH4;
// // Apply deadzone
// if (abs(adjustedPWMCH1) < deadzone)
// filteredJoystick.PWMCH1 = 1500; // abs to avoid negatives
// else
// filteredJoystick.PWMCH1 = JoystickData.PWMCH1 = mapPot(analogReadMultiPlexer(0, 0, 0, 0, A0)); // Right joystick Y
// if (abs(adjustedPWMCH2) < deadzone)
// filteredJoystick.PWMCH2 = 1500;
// else
// filteredJoystick.PWMCH2 = JoystickData.PWMCH2 = mapPot(analogReadMultiPlexer(1, 0, 0, 0, A0)); // Right joystick X
// if (abs(adjustedPWMCH3) < deadzone)
// filteredJoystick.PWMCH3 = 1500;
// else
// filteredJoystick.PWMCH3 = JoystickData.PWMCH3 = mapPot(analogReadMultiPlexer(0, 0, 0, 1, A0)); // Left joystick Y
// if (abs(adjustedPWMCH4) < deadzone)
// filteredJoystick.PWMCH4 = 1500;
// else
// filteredJoystick.PWMCH4 = JoystickData.PWMCH4 = mapPot(analogReadMultiPlexer(1, 0, 0, 1, A0)); // Left joystick X
// Apply deadzone and set filtered values
// This is the same as above but more compact
filteredJoystick.PWMCH1 = (abs(adjustedPWMCH1) < pwmDeadzone) ? 1500 : pwmCH1;
filteredJoystick.PWMCH2 = (abs(adjustedPWMCH2) < pwmDeadzone) ? 1500 : pwmCH2;
filteredJoystick.PWMCH3 = (abs(adjustedPWMCH3) < pwmDeadzone) ? 1500 : pwmCH3;
filteredJoystick.PWMCH4 = (abs(adjustedPWMCH4) < pwmDeadzone) ? 1500 : pwmCH4;
// Copy kill switch state
filteredJoystick.killSwitch = JoystickData.killSwitch;
}
void calibrateJoystickOffsets()
{
delay(5000); // Wait for everything to stabilize
long sum[4] = {0, 0, 0, 0};
const int samples = 500;
for (int i = 0; i < samples; i++)
{
sum[0] += analogReadMultiPlexer(0, 0, 0, 0, A0);
sum[1] += analogReadMultiPlexer(1, 0, 0, 0, A0);
sum[2] += analogReadMultiPlexer(0, 0, 0, 1, A0);
sum[3] += analogReadMultiPlexer(1, 0, 0, 1, A0);
delay(10); // Longer delay for stability
}
offsetPWMCH1 = sum[0] / samples;
offsetPWMCH2 = sum[1] / samples;
offsetPWMCH3 = sum[2] / samples;
offsetPWMCH4 = sum[3] / samples + 1000; // Hardware quirk of the controller
}
void killSwitch()
{
// Set the kill switch to 1 to stop the motors
if (abs(analogReadMultiPlexer(0, 0, 1, 0, A0) / 4095) == 1) // Right button
{
JoystickData.killSwitch = 1; // Activate kill switch
Serial.println("Kill switch activated, motors stopped.");
u8g2.clearBuffer();
u8g2.drawStr(25, 15, "Kill Switch: ON");
}
else if (abs(analogReadMultiPlexer(1, 0, 1, 0, A0) / 4095) == 1) // Left button
{
JoystickData.killSwitch = 0; // Deactivate kill switch
Serial.println("Kill switch deactivated, motors can run.");
u8g2.clearBuffer();
u8g2.drawStr(25, 15, "Kill Switch: OFF");
}
u8g2.sendBuffer();
}
void OLEDSetup()
{
u8g2.begin();
u8g2.clearBuffer();
u8g2.sendBuffer();
u8g2.setFont(u8g2_font_6x10_tf); // Use a different, simpler font
u8g2.clearBuffer();
u8g2.drawStr(25, 15, "Kill Switch: ON");
}
/////////////////////////////////////////////
// Debugging Functions //
/////////////////////////////////////////////
@@ -246,7 +373,19 @@ void readAllMultiPlexer()
Serial.println(analogReadMultiPlexer(1, 1, 1, 1, A0));
}
void printPWMValues()
void printFilteredPWMValues()
{
Serial.print("PWMCH1: ");
Serial.print(filteredJoystick.PWMCH1);
Serial.print(" PWMCH2: ");
Serial.print(filteredJoystick.PWMCH2);
Serial.print(" PWMCH3: ");
Serial.print(filteredJoystick.PWMCH3);
Serial.print(" PWMCH4: ");
Serial.println(filteredJoystick.PWMCH4);
}
void printUnfilteredPWMValues()
{
Serial.print("PWMCH1: ");
Serial.print(JoystickData.PWMCH1);
@@ -258,31 +397,73 @@ void printPWMValues()
Serial.println(JoystickData.PWMCH4);
}
void killSwitch()
void printOffsets()
{
// Set the kill switch to 1 to stop the motors
if (abs(analogReadMultiPlexer(0, 0, 1, 0, A0) / 4095) == 1) // Right button
{
JoystickData.killSwitch = 1; // Activate kill switch
Serial.println("Kill switch activated, motors stopped.");
u8g2.clearBuffer();
u8g2.drawStr(25, 15, "Kill Switch: ON");
}
else if (abs(analogReadMultiPlexer(1, 0, 1, 0, A0) / 4095) == 1) // Left button
{
JoystickData.killSwitch = 0; // Deactivate kill switch
Serial.println("Kill switch deactivated, motors can run.");
u8g2.clearBuffer();
u8g2.drawStr(25, 15, "Kill Switch: OFF");
}
u8g2.sendBuffer();
Serial.print("offsetPWMCH1: ");
Serial.print(offsetPWMCH1);
Serial.print(" offsetPWMCH2: ");
Serial.print(offsetPWMCH2);
Serial.print(" offsetPWMCH3: ");
Serial.print(offsetPWMCH3);
Serial.print(" offsetPWMCH4: ");
Serial.println(offsetPWMCH4);
}
void OLEDSetup(){
u8g2.begin();
u8g2.clearBuffer();
u8g2.sendBuffer();
u8g2.setFont(u8g2_font_6x10_tf); // Use a different, simpler font
u8g2.clearBuffer();
u8g2.drawStr(25, 15, "Kill Switch: ON");
void debugAllChannels() {
// Raw values
Serial.print("Raw: [");
Serial.print(JoystickData.PWMCH1); Serial.print(",");
Serial.print(JoystickData.PWMCH2); Serial.print(",");
Serial.print(JoystickData.PWMCH3); Serial.print(",");
Serial.print(JoystickData.PWMCH4); Serial.print("] ");
// Offsets
Serial.print("Offsets: [");
Serial.print(offsetPWMCH1); Serial.print(",");
Serial.print(offsetPWMCH2); Serial.print(",");
Serial.print(offsetPWMCH3); Serial.print(",");
Serial.print(offsetPWMCH4); Serial.print("] ");
// PWM converted values
int pwmCH1 = mapPot(JoystickData.PWMCH1);
int pwmCH2 = mapPot(JoystickData.PWMCH2);
int pwmCH3 = mapPot(JoystickData.PWMCH3);
int pwmCH4 = mapPot(JoystickData.PWMCH4);
int pwmOffsetCH1 = mapPot(offsetPWMCH1);
int pwmOffsetCH2 = mapPot(offsetPWMCH2);
int pwmOffsetCH3 = mapPot(offsetPWMCH3);
int pwmOffsetCH4 = mapPot(offsetPWMCH4);
Serial.print("PWM: [");
Serial.print(pwmCH1); Serial.print(",");
Serial.print(pwmCH2); Serial.print(",");
Serial.print(pwmCH3); Serial.print(",");
Serial.print(pwmCH4); Serial.print("] ");
// Adjusted values
int adjustedPWMCH1 = pwmCH1 - pwmOffsetCH1;
int adjustedPWMCH2 = pwmCH2 - pwmOffsetCH2;
int adjustedPWMCH3 = pwmCH3 - pwmOffsetCH3;
int adjustedPWMCH4 = pwmCH4 - pwmOffsetCH4;
Serial.print("Adj: [");
Serial.print(adjustedPWMCH1); Serial.print(",");
Serial.print(adjustedPWMCH2); Serial.print(",");
Serial.print(adjustedPWMCH3); Serial.print(",");
Serial.print(adjustedPWMCH4); Serial.print("] ");
// Deadzone status
Serial.print("InDZ: [");
Serial.print(abs(adjustedPWMCH1) < pwmDeadzone ? "Y" : "N"); Serial.print(",");
Serial.print(abs(adjustedPWMCH2) < pwmDeadzone ? "Y" : "N"); Serial.print(",");
Serial.print(abs(adjustedPWMCH3) < pwmDeadzone ? "Y" : "N"); Serial.print(",");
Serial.print(abs(adjustedPWMCH4) < pwmDeadzone ? "Y" : "N"); Serial.print("] ");
// Final filtered values
Serial.print("Final: [");
Serial.print(filteredJoystick.PWMCH1); Serial.print(",");
Serial.print(filteredJoystick.PWMCH2); Serial.print(",");
Serial.print(filteredJoystick.PWMCH3); Serial.print(",");
Serial.print(filteredJoystick.PWMCH4); Serial.println("]");
}

View File

@@ -19,4 +19,5 @@ lib_deps =
paulstoffregen/PWMServo@^2.1
sparkfun/SparkFun BNO080 Cortex Based IMU@^1.1.12
madhephaestus/ESP32Servo@^3.0.6
build_flags = -DCORE_DEBUG_LEVEL=5
plerup/EspSoftwareSerial@^8.2.0
build_flags = -DCORE_DEBUG_LEVEL=5

View File

@@ -4,6 +4,7 @@
#include <esp_now.h>
#include <WiFi.h>
#include <driver/ledc.h>
#include <softwareSerial.h>
// Arduino/Teensy Flight Controller - dRehmFlight
// Author: Nicholas Rehm
// Project Start: 1/6/2020
@@ -27,7 +28,6 @@ http://www.bolderflight.com
Thank you to:
RcGroups 'jihlein' - IMU implementation overhaul + SBUS implementation.
Everyone that sends me pictures and videos of your flying creations! -Nick
*/
//========================================================================================================================//
@@ -174,9 +174,9 @@ unsigned long channel_5_fs = 2000; // gear, greater than 1500 = throttle cut
unsigned long channel_6_fs = 2000; // aux1
// Filter parameters - Defaults tuned for 2kHz loop rate; Do not touch unless you know what you are doing:
float B_madgwick = 0.04; // Madgwick filter parameter
float B_accel = 0.14; // Accelerometer LP filter paramter, (MPU6050 default: 0.14. MPU9250 default: 0.2)
float B_gyro = 0.1; // Gyro LP filter paramter, (MPU6050 default: 0.1. MPU9250 default: 0.17)
float B_madgwick = 0.00001; // Madgwick filter parameter
float B_accel = 0.00001; // Accelerometer LP filter paramter, (MPU6050 default: 0.14. MPU9250 default: 0.2)
float B_gyro = 0.0001; // Gyro LP filter paramter, (MPU6050 default: 0.1. MPU9250 default: 0.17)
float B_mag = 1.0; // Magnetometer LP filter parameter
// Magnetometer calibration parameters - if using MPU9250, uncomment calibrateMagnetometer() in void setup() to get these values, else just ignore these
@@ -188,33 +188,33 @@ float MagScaleY = 1.0;
float MagScaleZ = 1.0;
// IMU calibration parameters - calibrate IMU using calculate_IMU_error() in the void setup() to get these values, then comment out calculate_IMU_error()
float AccErrorX = 0.0;
float AccErrorY = 0.0;
float AccErrorZ = 0.0;
float GyroErrorX = 0.0;
float GyroErrorY = 0.0;
float GyroErrorZ = 0.0;
float AccErrorX = 0.07;
float AccErrorY = -0.01;
float AccErrorZ = -0.01;
float GyroErrorX = -0.00;
float GyroErrorY = 0.00;
float GyroErrorZ = 0.00;
// Controller parameters (take note of defaults before modifying!):
float i_limit = 25.0; // Integrator saturation level, mostly for safety (default 25.0)
float maxRoll = 30.0; // Max roll angle in degrees for angle mode (maximum ~70 degrees), deg/sec for rate mode
float maxPitch = 30.0; // Max pitch angle in degrees for angle mode (maximum ~70 degrees), deg/sec for rate mode
float maxRoll = 15.0; // Max roll angle in degrees for angle mode (maximum ~70 degrees), deg/sec for rate mode
float maxPitch = 15.0; // Max pitch angle in degrees for angle mode (maximum ~70 degrees), deg/sec for rate mode
float maxYaw = 160.0; // Max yaw rate in deg/sec
float Kp_roll_angle = 0.2; // Roll P-gain - angle mode
float Ki_roll_angle = 0.3; // Roll I-gain - angle mode
float Kd_roll_angle = 0.05; // Roll D-gain - angle mode (has no effect on controlANGLE2)
float Kp_roll_angle = 2.0; // Roll P-gain - angle mode
float Ki_roll_angle = 0.5; // Roll I-gain - angle mode
float Kd_roll_angle = 0.1; // Roll D-gain - angle mode (has no effect on controlANGLE2)
float B_loop_roll = 0.9; // Roll damping term for controlANGLE2(), lower is more damping (must be between 0 to 1)
float Kp_pitch_angle = 0.2; // Pitch P-gain - angle mode
float Ki_pitch_angle = 0.3; // Pitch I-gain - angle mode
float Kd_pitch_angle = 0.05; // Pitch D-gain - angle mode (has no effect on controlANGLE2)
float Kp_pitch_angle = 2.0; // Pitch P-gain - angle mode
float Ki_pitch_angle = 0.5; // Pitch I-gain - angle mode
float Kd_pitch_angle = 0.1; // Pitch D-gain - angle mode (has no effect on controlANGLE2)
float B_loop_pitch = 0.9; // Pitch damping term for controlANGLE2(), lower is more damping (must be between 0 to 1)
float Kp_roll_rate = 0.15; // Roll P-gain - rate mode
float Ki_roll_rate = 0.2; // Roll I-gain - rate mode
float Kp_roll_rate = 0.015; // Roll P-gain - rate mode
float Ki_roll_rate = 0.02; // Roll I-gain - rate mode
float Kd_roll_rate = 0.0002; // Roll D-gain - rate mode (be careful when increasing too high, motors will begin to overheat!)
float Kp_pitch_rate = 0.15; // Pitch P-gain - rate mode
float Ki_pitch_rate = 0.2; // Pitch I-gain - rate mode
float Kp_pitch_rate = 0.015; // Pitch P-gain - rate mode
float Ki_pitch_rate = 0.02; // Pitch I-gain - rate mode
float Kd_pitch_rate = 0.0002; // Pitch D-gain - rate mode (be careful when increasing too high, motors will begin to overheat!)
float Kp_yaw = 0.3; // Yaw P-gain
@@ -231,16 +231,16 @@ float Kd_yaw = 0.00015; // Yaw D-gain (be careful when increasing too high, moto
const int ch1Pin = 15; // throttle
const int ch2Pin = 16; // ail
const int ch3Pin = 17; // ele
const int ch4Pin = 20; // rudd
const int ch5Pin = D7; // gear (throttle cut)
const int ch6Pin = D7; // aux1 (free aux channel)
const int PPM_Pin = D7;
const int ch4Pin = 17; // rudd
const int ch5Pin = 17; // gear (throttle cut)
const int ch6Pin = 17; // aux1 (free aux channel)
const int PPM_Pin = 17;
// OneShot125 ESC pin outputs:
const int m1Pin = D2;
const int m2Pin = D3;
const int m3Pin = D9;
const int m4Pin = D10;
const int m5Pin = D7;
const int m1Pin = D9; // Front Right CW (top right motor)
const int m2Pin = D10; // Front Left CCW (top left motor)
const int m3Pin = D3; // Back Right CCW (bottom right motor)
const int m4Pin = D2; // Back Left CW (bottom left motor)
const int m5Pin = D7; //for some readon D9 doesnt work
const int m6Pin = D8;
@@ -356,6 +356,11 @@ void ESPNowSetup();
void printDebugInfo();
void setupMotorPWM();
int pulseWidthToDutyCycle(int pulseWidth);
void setupMatrixSerial();
void printPitchInfo();
void printAttitudeDebug();
void testIndividualMotors();
void armMotors();
//========================================================================================================================//
// VOID SETUP //
//========================================================================================================================//
@@ -365,14 +370,15 @@ void setup()
Serial.begin(9600); // USB serial
Serial.println("Serial started");
Serial.println("Initiating ESC");
setupMotorPWM();
// Initialize IMU communication
Serial.println("Initiating IMU");
IMUinit();
Serial.println("Initiating ESC");
setupMotorPWM();
Serial.println("Attach servos");
setupMatrixSerial();
// servo7.attach(servo7Pin, 900, 2100);
// Set built in LED to turn on to signal startup
@@ -406,7 +412,7 @@ void setup()
delay(5);
// calibrateESCs(); //PROPS OFF. Uncomment this to calibrate your ESCs by setting throttle stick to max, powering on, and lowering throttle to zero after the beeps
calibrateESCs(); //PROPS OFF. Uncomment this to calibrate your ESCs by setting throttle stick to max, powering on, and lowering throttle to zero after the beeps
// Code will not proceed past here if this function is uncommented!
// Arm OneShot125 motors
@@ -425,6 +431,8 @@ void setup()
// If using MPU9250 IMU, uncomment for one-time magnetometer calibration (may need to repeat for new locations)
// calibrateMagnetometer(); //Generates magentometer error and scale factors to be pasted in user-specified variables section
// armMotors();
// testIndividualMotors(); // Test individual motors by commanding them to 1200us pulse length for 1 second each
}
//========================================================================================================================//
@@ -442,15 +450,17 @@ void loop()
// Print data at 100hz (uncomment one at a time for troubleshooting) - SELECT ONE:
// printRadioData(); //Prints radio pwm values (expected: 1000 to 2000)
printDesiredState(); //Prints desired vehicle state commanded in either degrees or deg/sec (expected: +/- maxAXIS for roll, pitch, yaw; 0 to 1 for throttle)
// printDesiredState(); //Prints desired vehicle state commanded in either degrees or deg/sec (expected: +/- maxAXIS for roll, pitch, yaw; 0 to 1 for throttle)
// printGyroData(); //Prints filtered gyro data direct from IMU (expected: ~ -250 to 250, 0 at rest)
// printAccelData(); // Prints filtered accelerometer data direct from IMU (expected: ~ -2 to 2; x,y 0 when level, z 1 when level)
// printMagData(); //Prints filtered magnetometer data direct from IMU (expected: ~ -300 to 300)
// printRollPitchYaw(); //Prints roll, pitch, and yaw angles in degrees from Madgwick filter (expected: degrees, 0 when level)
// printPIDoutput(); //Prints computed stabilized PID variables from controller and desired setpoint (expected: ~ -1 to 1)
// printMotorCommands(); //Prints the values being written to the motors (expected: 120 to 250)
printMotorCommands(); //Prints the values being written to the motors (expected: 120 to 250)
// printLoopRate(); //Prints the time between loops in microseconds (expected: microseconds between loop iterations)
// printDebugInfo(); //PWM 1 and 5 + Armed condition
// printDebugInfo(); //PWM 1 and 5 + Armed conditio
// printPitchInfo();
// printAttitudeDebug();
// Get arming status
armedStatus(); // Check if the throttle cut is off and throttle is low.
@@ -503,16 +513,16 @@ void controlMixer()
*roll_passthru, pitch_passthru, yaw_passthru - direct unstabilized command passthrough
*channel_6_pwm - free auxillary channel, can be used to toggle things with an 'if' statement
*/
// Quad mixing - EXAMPLE
m1_command_scaled = thro_des - pitch_PID + roll_PID + yaw_PID; // Front Left
m2_command_scaled = thro_des - pitch_PID - roll_PID - yaw_PID; // Front Right
m3_command_scaled = thro_des + pitch_PID - roll_PID + yaw_PID; // Back Right
m4_command_scaled = thro_des + pitch_PID + roll_PID - yaw_PID; // Back Left
// Quad mixer with pitch bias because the sensor isnt flat on the board
m1_command_scaled = thro_des + roll_PID - pitch_PID + yaw_PID; // Front Right CW
m2_command_scaled = thro_des - roll_PID - pitch_PID - yaw_PID; // Back Left CW
m3_command_scaled = thro_des + roll_PID + pitch_PID - yaw_PID; // Back Right CCW
m4_command_scaled = thro_des - roll_PID + pitch_PID + yaw_PID; // Front Left CCW
m5_command_scaled = 0;
m6_command_scaled = 0;
// 0.5 is centered servo, 0.0 is zero throttle if connecting to ESC for conventional PWM, 1.0 is max throttle
s1_command_scaled = 0;
s2_command_scaled = 0;
s3_command_scaled = 0;
@@ -620,7 +630,6 @@ void getIMUdata()
mpu9250.getMotion9(&AcX, &AcY, &AcZ, &GyX, &GyY, &GyZ, &MgX, &MgY, &MgZ);
#elif defined USE_BNO085_I2C
// Keep waiting until data becomes available
// Wait for data with timeout
unsigned long startTime = millis();
while (!myIMU.dataAvailable()) {
delay(1);
@@ -630,18 +639,16 @@ void getIMUdata()
}
}
// Get quaternion directly from BNO085
q0 = myIMU.getQuatReal(); // w component
q1 = myIMU.getQuatI(); // x component
q2 = myIMU.getQuatJ(); // y component
q3 = myIMU.getQuatK(); // z component
// Calculate Euler angles from quaternion
roll_IMU = atan2(2.0f * (q0*q1 + q2*q3), 1.0f - 2.0f * (q1*q1 + q2*q2)) * 57.29577951f;
pitch_IMU = asin(2.0f * (q0*q2 - q3*q1)) * 57.29577951f;
yaw_IMU = atan2(2.0f * (q0*q3 + q1*q2), 1.0f - 2.0f * (q2*q2 + q3*q3)) * 57.29577951f;
// Get quaternion directly from BNO085
q0 = myIMU.getQuatReal(); // w component
q1 = myIMU.getQuatI(); // x component
q2 = myIMU.getQuatJ(); // y component
q3 = myIMU.getQuatK(); // z component
// CORRECTED Euler angle calculation for BNO085
roll_IMU = atan2(2.0f * (q0*q1 + q2*q3), 1.0f - 2.0f * (q1*q1 + q2*q2)) * 57.29577951f;
pitch_IMU = asin(constrain(2.0f * (q0*q2 - q3*q1), -0.999999, 0.999999)) * 57.29577951f;
yaw_IMU = atan2(2.0f * (q0*q3 + q1*q2), 1.0f - 2.0f * (q2*q2 + q3*q3)) * 57.29577951f;
// Get raw sensor data for PID controller
GyroX = myIMU.getGyroX() * 57.29577951f; // Convert rad/s to deg/s
@@ -660,7 +667,7 @@ void getIMUdata()
GyroY_prev = GyroY;
GyroZ_prev = GyroZ;
// Get accelerometer data (still useful for PID control)
// Get accelerometer data (still useful for validation)
AccX = myIMU.getAccelX() / 9.80665f; // Convert m/s² to g
AccY = myIMU.getAccelY() / 9.80665f;
AccZ = myIMU.getAccelZ() / 9.80665f;
@@ -677,7 +684,6 @@ void getIMUdata()
AccY_prev = AccY;
AccZ_prev = AccZ;
// Return to avoid executing code for other IMUs
return;
#endif
@@ -740,45 +746,54 @@ void calculate_IMU_error()
* measurement.
*/
int16_t AcX, AcY, AcZ, GyX, GyY, GyZ, MgX, MgY, MgZ;
AccErrorX = 0.0;
AccErrorY = 0.0;
AccErrorZ = 0.0;
GyroErrorX = 0.0;
GyroErrorY = 0.0;
GyroErrorZ = 0.0;
// DESCRIPTION: Computes IMU accelerometer and gyro error on startup
AccErrorX = 0.0;
AccErrorY = 0.0;
AccErrorZ = 0.0;
GyroErrorX = 0.0;
GyroErrorY = 0.0;
GyroErrorZ = 0.0;
// Read IMU values 12000 times
int c = 0;
while (c < 12000)
{
#if defined USE_MPU6050_I2C
Serial.println("Starting IMU calibration...");
// Read IMU values 2000 times (reduced from 12000 for faster calibration)
int c = 0;
while (c < 2000)
{
#if defined USE_BNO085_I2C
unsigned long startTime = millis();
while (!myIMU.dataAvailable())
{
delay(1);
if (millis() - startTime > 100) // Reduced timeout
{
Serial.print("BNO085 timeout at iteration: ");
Serial.println(c);
return; // Exit if timeout
}
}
// Get raw sensor data - BNO085 already gives calibrated values
float tempGyroX = myIMU.getGyroX() * 57.29577951f; // Convert rad/s to deg/s
float tempGyroY = myIMU.getGyroY() * 57.29577951f;
float tempGyroZ = myIMU.getGyroZ() * 57.29577951f;
float tempAccX = myIMU.getAccelX() / 9.80665f; // Convert m/s² to g
float tempAccY = myIMU.getAccelY() / 9.80665f;
float tempAccZ = myIMU.getAccelZ() / 9.80665f;
// Sum all readings
AccErrorX += tempAccX;
AccErrorY += tempAccY;
AccErrorZ += tempAccZ;
GyroErrorX += tempGyroX;
GyroErrorY += tempGyroY;
GyroErrorZ += tempGyroZ;
#elif defined USE_MPU6050_I2C
mpu6050.getMotion6(&AcX, &AcY, &AcZ, &GyX, &GyY, &GyZ);
#elif defined USE_MPU9250_SPI
mpu9250.getMotion9(&AcX, &AcY, &AcZ, &GyX, &GyY, &GyZ, &MgX, &MgY, &MgZ);
#elif defined USE_BNO085_I2C
while (!myIMU.dataAvailable())
{
delay(1); // Small delay to avoid hammering the I2C bus too hard
}
// bno magnetometer
MgX = myIMU.getMagX();
MgY = myIMU.getMagY();
MgZ = myIMU.getMagZ();
// convert radians to degrees
GyX = myIMU.getGyroX() * 180 / PI;
GyY = myIMU.getGyroY() * 180 / PI;
GyZ = myIMU.getGyroZ() * 180 / PI;
// Acelleration (dont know if I need linear or normal. One way to find out)
AcX = myIMU.getAccelX() / 9.80665; // m/s² to g
AcY = myIMU.getAccelY() / 9.80665; // m/s² to g
AcZ = myIMU.getAccelZ() / 9.80665; // m/s² to g
#endif
AccX = AcX / ACCEL_SCALE_FACTOR;
@@ -1362,7 +1377,7 @@ void getCommands()
#endif
// Low-pass the critical commands and update previous values
float b = 0.7; // Lower=slower, higher=noiser
float b = 0.5; // Lower=slower, higher=noiser
channel_1_pwm = (1.0 - b) * channel_1_pwm_prev + b * channel_1_pwm;
channel_2_pwm = (1.0 - b) * channel_2_pwm_prev + b * channel_2_pwm;
channel_3_pwm = (1.0 - b) * channel_3_pwm_prev + b * channel_3_pwm;
@@ -1448,21 +1463,6 @@ void commandMotors() {
ledcWrite(m6Pin, pulseWidthToDutyCycle(m6_duty));
}
void armMotors()
{
// DESCRIPTION: Sends many command pulses to the motors, to be used to arm motors in the void setup()
/*
* Loops over the commandMotors() function 50 times with a delay in between, simulating how the commandMotors()
* function is used in the main loop. Ensures motors arm within the void setup() where there are some delays
* for other processes that sometimes prevent motors from arming.
*/
for (int i = 0; i <= 50; i++)
{
commandMotors();
delay(2);
}
}
void calibrateESCs()
{
// DESCRIPTION: Used in void setup() to allow standard ESC calibration procedure with the radio to take place.
@@ -1473,9 +1473,7 @@ void calibrateESCs()
*/
while (true)
{
prev_time = current_time;
current_time = micros();
dt = (current_time - prev_time) / 1000000.0;
// digitalWrite(13, HIGH); // LED on to indicate we are not in main loop
@@ -1483,7 +1481,6 @@ void calibrateESCs()
failSafe(); // Prevent failures in event of bad receiver connection, defaults to failsafe values assigned in setup
getDesState(); // Convert raw commands to normalized values based on saturated control limits
getIMUdata(); // Pulls raw gyro, accelerometer, and magnetometer data from IMU and LP filters to remove noise
Madgwick(GyroX, -GyroY, -GyroZ, -AccX, AccY, AccZ, MagY, -MagX, MagZ, dt); // Updates roll_IMU, pitch_IMU, and yaw_IMU (degrees)
getDesState(); // Convert raw commands to normalized values based on saturated control limits
m1_command_scaled = thro_des;
@@ -1888,6 +1885,88 @@ void printDebugInfo() {
}
}
void printPitchInfo() {
if (current_time - print_counter > 10000) {
print_counter = micros();
Serial.print("pitch_IMU:");
Serial.print(pitch_IMU);
Serial.print(" pitch_PID:");
Serial.print(pitch_PID);
Serial.print(" pitch_des:");
Serial.print(pitch_des);
Serial.print(" error_pitch:");
Serial.println(error_pitch);
}
}
void printAttitudeDebug() {
if (current_time - print_counter > 10000) {
print_counter = micros();
Serial.print("q0:");
Serial.print(q0, 4);
Serial.print(" q1:");
Serial.print(q1, 4);
Serial.print(" q2:");
Serial.print(q2, 4);
Serial.print(" q3:");
Serial.print(q3, 4);
Serial.print(" roll:");
Serial.print(roll_IMU);
Serial.print(" pitch:");
Serial.println(pitch_IMU);
}
}
void testIndividualMotors() {
Serial.println("=== MOTOR PIN TEST - PROPS OFF! ===");
// Test each pin individually for 3 seconds
Serial.println("Testing D3 (m1Pin) for 3 seconds...");
ledcWrite(D3, pulseWidthToDutyCycle(1300));
delay(3000);
ledcWrite(D3, pulseWidthToDutyCycle(1000));
delay(2000);
Serial.println("Testing D2 (m2Pin) for 3 seconds...");
ledcWrite(D2, pulseWidthToDutyCycle(1300));
delay(3000);
ledcWrite(D2, pulseWidthToDutyCycle(1000));
delay(2000);
Serial.println("Testing D10 (m3Pin) for 3 seconds...");
ledcWrite(D10, pulseWidthToDutyCycle(1300));
delay(3000);
ledcWrite(D10, pulseWidthToDutyCycle(1000));
delay(2000);
Serial.println("Testing D9 (m4Pin) for 3 seconds...");
ledcWrite(D9, pulseWidthToDutyCycle(1300));
delay(3000);
ledcWrite(D9, pulseWidthToDutyCycle(1000));
delay(2000);
Serial.println("Test complete! Note which physical motor each pin controls.");
while(true) {
;
}
}
void armMotors(){
ledcWrite(m1Pin, pulseWidthToDutyCycle(2000)); // maximum pulse width (2000μs)
ledcWrite(m2Pin, pulseWidthToDutyCycle(2000));
ledcWrite(m3Pin, pulseWidthToDutyCycle(2000));
ledcWrite(m4Pin, pulseWidthToDutyCycle(2000));
delay(9000);
ledcWrite(m1Pin, pulseWidthToDutyCycle(1000)); // Minimum pulse width (1000μs)
ledcWrite(m2Pin, pulseWidthToDutyCycle(1000));
ledcWrite(m3Pin, pulseWidthToDutyCycle(1000));
ledcWrite(m4Pin, pulseWidthToDutyCycle(1000));
}
//=========================================================================================//
// HELPER FUNCTIONS
@@ -1915,6 +1994,8 @@ float invSqrt(float x)
return 1.0 / sqrtf(x); // Teensy is fast enough to just take the compute penalty lol suck it arduino nano
}
/// ESP stuff lol
void ESPNowSetup()
{
WiFi.mode(WIFI_STA);
@@ -1965,4 +2046,11 @@ void OnDataRecv(const uint8_t *mac, const uint8_t *incomingData, int len)
// For debugging - uncomment if needed
// Serial.print("KillSwitch: ");
// Serial.println(ControllerData.killSwitch);
}
void setupMatrixSerial()
{
SoftwareSerial MatrixSerial(D0, D8); //RX is unconnected
MatrixSerial.begin(115200);
MatrixSerial.println("Hi");
}