Jakiś czas temu (już ponad 8 miesięcy) zastanawiałem się co mógłbym zbudować. Chciałem stworzyć robota/urządzenie które było by dla mnie wyzwaniem i dzięki któremu nauczył bym się nowych rzeczy. Było wiele różnych pomysłów ale większość z nich była już przez innych zrobiona, lub zdecydowanie poza moimi możliwościami (głównie finansowymi). I wtedy przyszło mi do głowy, żeby zrobić drona kompletnie od zera włączając w to własny kontroler lotu, pilot, program oraz własną ramę (z tym ostatnim trochę nie wyszło). Nigdy w życiu nic tak długo nie budowałem jak tego drona, ponad 8 miesięcy. Ale uważam że było warto i to bardzo, wiedza którą zdobyłem podczas budowy oraz udowodnienie sobie że dałem radę jest super.
Zanim przejdziemy do opisu budowy drona zapraszam was na mój fanpage na Facebooku będę tam publikował moje najnowsze budowle i nie tylko.
Dla ciekawych jak ludwik działa podaję filmik:
Wersja przeszła:
Wersja teraźniejsza:
Prezentacja opowiadająca historię Ludwika:
https://docs.google.com/presentation/d/1UwQ2nXc_tWmhPJeOyTAkAelXADP4sjPqJ53q9BsgJlI/edit#slide=id.g2148d6ea44_0_75
Na początku wielu z Was może się zapytać po co robić to wszystko samemu skoro można kupić gotowe elementy i połączyć lub wgrać multiwii na arduino. A no głównie dla tego, że mogę i lubię. Dodatkowym powodem jest wiedza, której naprawdę dużo wyniosłem z tej budowy. Moim zdaniem nie ma lepszego sposobu nauki niż sprawdzanie jak działają dane rzeczy od podstaw, ważne również jest popełnianie błędów których nie zabrakło w trakcie tej budowy, ale to dobrze bo błędy bardzo skutecznie uczą. Ostatnim argumentem są oczywiście pieniądze, wydałem znacznie mniej dzięki zrobieniu większości rzeczy przez siebie. Najlepiej widać to na przykładzie pilota, aby go kupić trzeba wydać co najmniej 200zł a często nawet znacznie więcej ja swój zbudowałem za 60 zł.
Największe problemy wystąpiły w kodzie dla kontrolera lotu, nie był on specjalnie skomplikowany ale regulacja algorytmów PID aby lot ludwika był stabilny to był dramat. Nigdy wcześniej nie bawiłem się w regulację tych algorytmów a samą zasadę ich działania poznałem dopiero w trakcie budowy. Znalezienie prawidłowych wartości (aczkolwiek nie idealnych) zajęło mnóstwo czasu, i pochłonęło wiele filamentu :). Było też kilka ciekawych bugów, np. wymyśliłem pewnego dnia że zrobię system dzięki któremu po utracie połączenia z pilotem dron zacznie zmniejszać (dekrementować) wartość mocy silników (throttle), zadowolony włączyłem go żeby przetestować. Silniki zaczęły powoli zmniejszać swoje obroty aż się zatrzymały, hura! Nie do końca, po kilku minutach nagle dron poderwał się do góry wraz z drewnianą ramą którą wykorzystywałem do testów w domu uderzył w moje drzwi i ścianę, przynajmniej nie we mnie. Dlaczego? Bo wartość dekremetowała się tak długo, że w końcu z wartości minimalnej przeszła na maksymalną odpalając silniki z pełną mocą.
Początkowo plan był taki aby cała rama i wszystko co się tylko da było wydrukowane na drukarce 3D. I to się po części udało, latającą wersję drona z wydrukowaną ramą można zobaczyć na tym filmie:
Jak widać działała ona całkiem nieźle, był jeden mały problem a w sumie to siedem bo tyle też razy ją połamałem. Ostatecznie zdecydowałem się kupić gotową ramę i skupić się na dopracowaniu elektroniki oraz programu. Gdyby została ona inaczej zaprojektowana z pewnością dała by radę, niestety wtedy nie miałem tej wiedzy którą mam teraz a ciągłe drukowanie nowych części spowodowało, że odpuściłem sobie drukowanie ramy na jakiś czas. To zdjęcie przedstawia wszystkie połamane części:
Z stworzeniem PCB, schematów i programu dla pilota nie było żadnych problemów.
Lista potrzebnych części:
Do zabudowania całości jest potrzebne trochę części za całość zapłaciłem ponad 650 zł (nie licząc rzeczy które zepsułem). Daję linki do polskiego sklepu abc-rc.pl który bardzo polecam ponieważ ceny tam są naprawdę świetne i szybko realizują zamówienia oraz do chińskiego sklepu gearbest, tutaj niektóre rzeczy mogą być jeszcze tańsze.
- Silniki – ja użyłem możliwie tanich silników bezszczotkowych 1000KV potrzebujemy 4 takie silniki, powinny mieć w komplecie piastę aby zamontować śmigło. abc-rc.pl | GearBest
- ESC – jeśli wybrałeś inny silnik prawdopodobnie (ale nie zawsze) będziesz musiał dobrać do niego inne ESC. Maksymalny prąd jaki może zostać obsłużony przez ESC nie może być mniejszy od maksymalnego prądu pobieranego przez silnik. Ważne aby miały układ BEC ponieważ to on zasila nasz kontroler lotu. abc-rc.pl | GearBest
- Bateria – 3S czyli 11.1V Li-Po ja użyłem baterii o pojemności 3300 mAh ale nic nie szkodzi na przeszkodzie aby użyć większej (lub mniejszej). Czas lotu na mojej baterii to około 15 minut. Musisz się upewnić że maksymalny prąd rozładowania jest wystarczający aby zasilić drona. abc-rc.pl | GearBest
- Rama – bardzo popularna F450. abc-rc.pl | GearBest
- Ładowarka do baterii – do ładowania baterii LiPo wymagana jest specjalna ładowarka z balancerem. abc-rc.pl | GearBest
- Śmigła – mogą być inne ale te w połączeniu z silnikami powyżej współpracują najlepiej. Warto kupić więcej na wypadek złamania. Muszą mieć otwór a nie gwint. abc-rc.pl | GearBest
- Monitor baterii – nigdy nie korzystaj z baterii bez podłączonego monitora, możesz ja za bardzo rozładować i uszkodzić. Monitor taki informuje bardzo głośnym piszczeniem gdy poziom baterii jest zbyt niski. abc-rc.pl | GearBest
Lista części do budowy kontrolera lotu:
Nie będę tutaj podawał linków, większość tych części kupisz w lokalnym sklepie elektronicznym.
- Atmega328
- NRF24L01 – z zewnętrzną anteną (najlepiej wersja z anteną na kablu) dla większego zasięgu
- MPU6050 – żyroskop i akcelerometr w jednym module
- Kilka mniejszych części:
- kondensator 22pF (x2)
- kondensator 10uF
- rezystor 4,7kOhm
- stabilizator napięcia o napięciu wyjściowy 3,3V (LV33CV3)
- trochę goldpinów (męskich i żeńskich)
I ostatnia lista części do pilota:
- Atmega328
- NRF24L01 – z zewnętrzną anteną (najlepiej wersja z anteną na kablu) dla większego zasięgu
- Joysticki – takie jak w playstation (x2)
- Some smaller parts:
- kondensator 22pF (x2)
- kondensator 10uF
- rezystor 4,7kOhm
- stabilizator napięcia o napięciu wyjściowy 3,3V (LV33CV3)
- dioda LED
Teraz kiedy już wiemy czego potrzebujemy możemy zaczynać budowę.
Myślę że złożenia ramy opisywać nie trzeba macie tam kilka śrubek do przykręcenia. Następne co trzeba przykręcić to silniki, ważne aby śruby których użyjecie nie były zbyt długie bo mogą haczyć o zwoje cewek silnika i go uszkodzić. Przewody silnika lutujemy do ESC. Aby zapobiec kręceniu się drona wokół własnej osi silniki lewy przedni i prawy tylny kręcą się zgodnie z wskazówkami zegara a prawy przedni i lewy tylny przeciwnie do nich. Dlatego też śmigła zamontowane na silnikach muszą być odpowiednie (powinny być podpisane CW – zgodnie z wskazówkami CCW – przeciwnie). Należy również zamienić ze sobą dwie dowolne fazy na 2 silnikach aby kręciły się w przeciwną stronę. Czerwony przewód z ESC lutujemy do rozdzielacza napięcia w naszej ramie a czarny do minusa robimy to oczywiście cztery razy. Jeśli nie masz w ramie rozdzielacza możesz skorzystać z zaprojektowanego przeze mnie, poniżej znajdziesz pdf do zrobienia PCB. Następnie lutujemy przewody wraz z złączem dla naszej baterii do płytki rozdzielającej. Wszystkie luty i połączenia muszą być oczywiście ładnie zaizolowane czarną taśmą lub koszulkami termokurczliwymi.
Teraz czas na zrobienie PCB kontrolera lotu i pilota wstawiam schematy, pliki .brd oraz .sch i layouty PCB znajdziecie poniżej w zipie bo nie ma opcji wstawienia ich tutaj (chyba że jest a ja nie ogarniam :)). Jeśli masz jakieś dodatkowe pytania pisz w komentarzach lub na maila. Pilot zasilany jest trzema bateriami AAA.
Do zamocowania kontrolera lotu na ramie wydrukowałem specjalny uchwyt (plik .stl znajdziecie poniżej). Pod ten uchwyt dodałem kawałek miękkiej gąbki która zabezpieczała jakąś paczkę z Chin służy ona do tłumienia drgań dzięki czemu żyroskop wraz z akcelerometrem dają dokładniejsze odczyty. Uchwyt na kontroler lotu został specjalnie tak zaprojektowany aby można było swobodnie regulować jego i ustawić go jak najbardziej równolegle w stosunku do ramy. Należy również wywiercić dodatkowy otwór na uchwyt do anteny (byle nie w ścieżkach płytki), ewentualnie jeśli użyjesz dłuższej śruby na mocowaniu to możesz tam przyczepić uchwyt anteny (uchwyt również został wydrukowany plik na dole). Tak to wygląda od dołu:
Ostatnie co zostało nam do zrobienia to wgranie programu. Poniżej dodaję cały program dla kontrolera lotu oraz pilota, na dole znajdziecie .zip z wszystkimi potrzebnymi bibliotekami. Jest on dość długi, a ja najlepszy w tłumaczeniu kodu nie jestem :) dodałem kilka komentarzy (dosłownie kilka). Wbrew pozorom nie jest on wcale aż tak skomplikowany i jak go przeanalizujesz zobaczysz, że nie ma w tym nic aż tak bardzo trudnego (poza kalibracją PIDów oczywiście :D). Aby go wgrać do atmegi potrzebujesz programator np USBasp lub arduino które możesz wykorzystać jako programator. Nie dodawałem złącza dla programatora na obu płytkach więc musisz zaprogramować atmegę na płytce stykowej lub też pokombinować i wpiąć kable do złącz.
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 |
#include "I2Cdev.h" #include <Servo.h> #include <SPI.h> #include "RF24.h" #include "MPU6050_6Axis_MotionApps20.h" #if I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE #include "Wire.h" #endif //we need this to see nrf24l01 configuration in serial #include "printf.h" //end of libraries ############################################### MPU6050 mpu; float x_rotation, y_rotation, z_rotation; Servo motor1; Servo motor2; Servo motor3; Servo motor4; bool first_loop = true; //radio RF24 radio(9,10); uint8_t data[6]; const uint64_t pipe = 0xE8E8F0F0E1LL; long last_received; int controll_number = 159; //values = 5.2, 0.02, 1500 //variables for movement and positions ########################################### //for my quadcopter this are the best settings for pid float x_kp = 5, x_ki = 0.02, x_kd = 1100; //values for PID X axis int max_pid = 300; float x_p_out, x_i_out, x_d_out, x_output; //outputs for PID float x_now, x_lasttime = 0, x_timechange; float x_input, x_lastinput = 0, x_setpoint = 0; float x_error, x_errorsum = 0, x_d_error, x_lasterror; //values = 5.2, 0.02, 1500 float y_kp = 5, y_ki = 0.02, y_kd = 1100; //values for PID Y axis float y_p_out, y_i_out, y_d_out, y_output; //outputs for PID float y_now, y_lasttime = 0, y_timechange; float y_input, y_lastinput = 0, y_setpoint = 0; float y_error, y_errorsum = 0, y_d_error, y_lasterror; float z_kp = 2, z_ki = 0, z_kd = 0; //values for PID Z axis float z_p_out, z_i_out, z_d_out, z_output; //outputs for PID float z_now, z_lasttime = 0, z_timechange; float z_input, z_lastinput = 0, z_setpoint = 0; float z_error, z_errorsum = 0, z_d_error, z_lasterror; //set it to 0 and see on serial port what is the value for x and y rotation, use only if your flightcontroller board is not perfevtly leveled. If your board is perfectly leveled set it to 0 float x_level_error = 0; float y_level_error = 0; /* * * * JUNE 2016 - APRIL 2017 * C by Nikodem Bartnik * nikodem.bartnik@gmail.com * nikodembartnik.pl * * * */ #define INTERRUPT_PIN 2 // use pin 2 on Arduino Uno & most boards int motor1_power; int motor2_power; int motor3_power; int motor4_power; float allmotors_power = 600; // MPU control/status vars bool dmpReady = false; // set true if DMP init was successful uint8_t mpuIntStatus; // holds actual interrupt status byte from MPU uint8_t devStatus; // return status after each device operation (0 = success, !0 = error) uint16_t packetSize; // expected DMP packet size (default is 42 bytes) uint16_t fifoCount; // count of all bytes currently in FIFO uint8_t fifoBuffer[64]; // FIFO storage buffer // orientation/motion vars Quaternion q; // [w, x, y, z] quaternion container VectorFloat gravity; // [x, y, z] gravity vector float rotation[3]; // [yaw, pitch, roll] yaw/pitch/roll container and gravity vector int safe_lock = 1; volatile bool mpuInterrupt = false; // indicates whether MPU interrupt pin has gone high void dmpDataReady() { mpuInterrupt = true; } void setup() { // join I2C bus (I2Cdev library doesn't do this automatically) #if I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE Wire.begin(); Wire.setClock(400000); // 400kHz I2C clock. Comment this line if having compilation difficulties #elif I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_FASTWIRE Fastwire::setup(400, true); #endif printf_begin(); Serial.begin(115200); Serial.println("Initializing I2C devices..."); mpu.initialize(); pinMode(INTERRUPT_PIN, INPUT); // verify connection Serial.println("Testing device connections..."); Serial.println(mpu.testConnection() ? "MPU6050 connection successful" : "MPU6050 connection failed"); // bmp.begin(); radio.begin(); delay(1000); radio.setDataRate(RF24_250KBPS); radio.setPALevel(RF24_PA_MAX); radio.openReadingPipe(1,pipe); radio.startListening(); // load and configure the DMP Serial.println("Initializing DMP..."); devStatus = mpu.dmpInitialize(); // gyro offsets here mpu.setXGyroOffset(87); mpu.setYGyroOffset(77); mpu.setZGyroOffset(110); mpu.setZAccelOffset(2287); mpu.setYAccelOffset(-1283); mpu.setXAccelOffset(-3083); // make sure it worked (returns 0 if so) if (devStatus == 0) { Serial.println("Enabling DMP..."); mpu.setDMPEnabled(true); attachInterrupt(digitalPinToInterrupt(INTERRUPT_PIN), dmpDataReady, RISING); mpuIntStatus = mpu.getIntStatus(); dmpReady = true; packetSize = mpu.dmpGetFIFOPacketSize(); } else { // ERROR! // 1 = initial memory load failed // 2 = DMP configuration updates failed // (if it's going to break, usually the code will be 1) Serial.print("DMP Initialization failed (code "); Serial.print(devStatus); Serial.println(")"); } motor1.attach(5); motor2.attach(8); motor3.attach(7); motor4.attach(4); pinMode(A0, INPUT); pinMode(A1, INPUT); digitalWrite(A0, LOW); motor1.write(0); motor2.write(0); motor3.write(0); motor4.write(0); radio.printDetails(); } void loop() { if (radio.available()) { bool done = false; while (!done){ done = radio.read(data, sizeof(data)); // Serial.print("Controll number: "); //Serial.println(data[0]); if((millis()-last_received) < 3000){ if(data[0] == controll_number){ Serial.print("DATA1: "); Serial.println(data[1]); allmotors_power = map(data[1], 0, 255, 800, 1500); if(allmotors_power < 0){ allmotors_power = 0; } //allmotors_power = map(data[1], 0, 255, 800, 1600); x_setpoint = data[3] - 20; y_setpoint = data[2] - 20; Serial.print("PID OUT X: "); Serial.print(x_rotation); Serial.print(" PID OUT Y: "); Serial.print(y_rotation); Serial.print("Z NOW: "); Serial.println(z_rotation); Serial.print(" TIME: "); Serial.println(millis()); Serial.print("MOTORS POWER: "); Serial.println(allmotors_power); } } // Serial.println(data[1]); if(done == true){ last_received = millis(); } } } if((millis()-last_received) > 3000 && allmotors_power > 0){ safe_lock = 0; } // if programming failed, don't try to do anything // if (!dmpReady) return; while (!mpuInterrupt && fifoCount < packetSize) { } // reset interrupt flag and get INT_STATUS byte mpuInterrupt = false; mpuIntStatus = mpu.getIntStatus(); // get current FIFO count fifoCount = mpu.getFIFOCount(); // check for overflow (this should never happen unless our code is too inefficient) if ((mpuIntStatus & 0x10) || fifoCount == 1024) { // otherwise, check for DMP data ready interrupt (this should happen frequently) } else if (mpuIntStatus & 0x02) { // wait for correct available data length, should be a VERY short wait while (fifoCount < packetSize) fifoCount = mpu.getFIFOCount(); // read a packet from FIFO mpu.getFIFOBytes(fifoBuffer, packetSize); // track FIFO count here in case there is > 1 packet available // (this lets us immediately read more without waiting for an interrupt) fifoCount -= packetSize; if(safe_lock == 1){ mpu.dmpGetQuaternion(&q, fifoBuffer); mpu.dmpGetGravity(&gravity, &q); mpu.dmpGetYawPitchRoll(rotation, &q, &gravity); x_rotation = rotation[1] * 180/M_PI - x_level_error; y_rotation = rotation[2] * 180/M_PI - y_level_error; z_rotation = rotation[0] * 180/M_PI; /* if(pressure_loop_number == 10){ // Serial.print("Preasure: "); //Serial.println(bmp.readAltitude()); pressure_loop_number = 0; allmotors_power = 1000; } pressure_loop_number++; */ if(first_loop == true){ z_setpoint = z_rotation; // current_altitude = bmp.readAltitude(); //set_altitude = current_altitude; first_loop = false; } motor1_power = allmotors_power; motor2_power = allmotors_power; motor3_power = allmotors_power; motor4_power = allmotors_power; if(allmotors_power > 1500){ allmotors_power = 1500; } x_output = calculatePID(0, x_rotation); y_output = calculatePID(1, y_rotation); z_output = calculatePID(2, z_rotation); motor1_power += x_output/2; motor1_power += z_output; motor4_power -= x_output/2; motor4_power += z_output; motor2_power -= y_output/2; motor2_power -= z_output; motor3_power += y_output/2; motor3_power -= z_output; motor1.writeMicroseconds(motor1_power); motor4.writeMicroseconds(motor4_power); motor2.writeMicroseconds(motor2_power); motor3.writeMicroseconds(motor3_power); mpu.resetFIFO(); }else{ motor1.write(0); motor2.write(0); motor3.write(0); motor4.write(0); } } } float calculatePID(int _axis, float _angel){ // X AXIS if(_axis == 0){ x_now = millis(); x_timechange = x_now - x_lasttime; x_error = x_setpoint - _angel; x_p_out = (x_kp * x_error); x_errorsum = (x_errorsum + x_error); if(x_errorsum > 1023){ x_errorsum = 1023; } if(x_errorsum < -1023){ x_errorsum = -1023; } x_i_out = x_ki * x_errorsum; x_d_error = (x_error - x_lasterror) / x_timechange; x_d_out = x_kd * x_d_error; x_lasterror = x_error; x_output = x_p_out + x_i_out + x_d_out; if(x_output > max_pid){ x_output = max_pid; }else if(x_output < -(max_pid)){ x_output = -(max_pid); } x_lasttime = millis(); return x_output; } // Y AXIS else if(_axis == 1){ y_now = millis(); y_timechange = y_now - y_lasttime; y_error = y_setpoint - _angel; y_p_out = (y_kp * y_error); y_errorsum = (y_errorsum + y_error) * y_timechange; if(y_errorsum > 1023){ y_errorsum = 1023; } if(y_errorsum < -1023){ y_errorsum = -1023; } y_i_out = y_ki * y_errorsum; y_d_error = (y_error - y_lasterror) / y_timechange; y_d_out = y_kd * y_d_error; y_lasterror = y_error; y_output = y_p_out + y_i_out + y_d_out; if(y_output > max_pid){ y_output = max_pid; }else if(y_output < -(max_pid)){ y_output = -(max_pid); } y_lasttime = millis(); return y_output; // ALTITUDE // } else if(_axis == 2){ // return (set_altitude - current_altitude) * 20; }else if(_axis == 2){ z_now = millis(); z_timechange = z_now - z_lasttime; z_error = z_setpoint - _angel; z_p_out = (z_kp * z_error); z_errorsum = (z_errorsum + z_error) * z_timechange; if(z_errorsum > 1023){ z_errorsum = 1023; } if(z_errorsum < -1023){ z_errorsum = -1023; } z_i_out = z_ki * z_errorsum; z_d_error = (z_error - z_lasterror) / z_timechange; z_d_out = z_kd * y_d_error; z_lasterror = y_error; z_output = z_p_out + z_i_out + z_d_out; if(z_output > max_pid){ z_output = max_pid; }else if(z_output < -(max_pid)){ z_output = -(max_pid); } z_lasttime = millis(); return z_output; // ALTITUDE // } else if(_axis == 2){ // return (set_altitude - current_altitude) * 20; }else{ return 0; } } |
Kod pilota
Jest bardzo prosty, tylko sczytuje wartości analogowe z joysticków i wysyła do drona. Dodatkowo przewidziałem 2 przełączniki gdybym kiedyś chciał dodać jakieś lampki albo coś innego do drona aktualnie nie są one zaimplementowane w kodzie. Pilot wysyła również liczbę kontrolną tak na wszelki wypadek jakiś zakłóceń lub gdyby tak drugi nadajnik znalazł się w pobliżu żeby żadnych problemów nie było możesz ją zmienić ale pamiętaj żeby zrobić to również w kodzie z kontrolera lotu. MAX_TILIT określa maksymalne dopuszczalne wychylenie, jest ustawiony na 20 to oczywiście bardzo mało ale dla bezpieczeństwa proponuję tak to zostawić na początek, jak już wszystko będzie ok to wtedy zmienić na więcej.
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 |
#include <SPI.h> #include "RF24.h" #define MAX_TILT 20 RF24 radio(9,10); int a = 0; uint8_t data[6]; int controll_number = 159; int safe_lock = 0; int x_offset, y_offset; const uint64_t pipe = 0xE8E8F0F0E1LL; void setup(void){ Serial.begin(57600); pinMode(4, OUTPUT); pinMode(3, INPUT); pinMode(A0, INPUT); pinMode(A1, INPUT); pinMode(A2, INPUT); pinMode(A3, INPUT); digitalWrite(3, HIGH); digitalWrite(4, HIGH); radio.begin(); radio.setDataRate(RF24_250KBPS); radio.setPALevel(RF24_PA_MAX); radio.openWritingPipe(pipe); radio.printDetails(); } void loop(void) { if(!digitalRead(3)){ Serial.print("LOW 1"); delay(1000); if(!digitalRead(3)){ Serial.print("LOW 2"); delay(1000); if(!digitalRead(3)){ Serial.print("LOW 3"); if(safe_lock == 0){ safe_lock = 1; }else{ safe_lock = 0; } } } } int power = map(analogRead(A2), 0, 1023, 0, 255); int x = map(analogRead(A1), 0, 1023, 0, 255); int y = map(analogRead(A0), 0, 1023, 0, 255); int rotation = map(analogRead(A3), 0, 1023, 0, 255); if(x > 150){ x = map(x, 150, 255, 0, MAX_TILT); }else if(x < 105){ x = map(x, 105, 0, 0, -MAX_TILT); }else{ x = 0; } if(y > 150){ y = map(y, 150, 255, 0, MAX_TILT); }else if(y < 105){ y = map(y, 105, 0, 0, -MAX_TILT); }else{ y = 0; } if(rotation > 150){ rotation = map(rotation, 150, 255, 0, MAX_TILT); }else if(rotation < 105){ rotation = map(rotation, 105, 0, 0, -MAX_TILT); }else{ rotation = 0; } data[0] = controll_number; data[1] = power; // + 10 because you can't send negative number data[2] = x + MAX_TILT; data[3] = y + MAX_TILT; data[4] = rotation + MAX_TILT; data[5] = safe_lock; radio.write( data, sizeof(data) ); delay(8); } |
O druku 3D w tym projekcie
Miała być wydrukowana w 3D rama i była przez trochę (jakieś 5 miesięcy), została wiele razy połamana aż w końcu zamieniłem ją na kupioną. Gdyby była inaczej zaprojektowana była by mocniejsza i wytrzymała znacznie więcej. Głównym błędem była zbyt cienka główna płytka trzymająca ramiona, a konkretnie “listki” do których ramiona były mocowane, sam nie wiem dlaczego zrobiłem je taki cienkie. Nie miałem wtedy jeszcze tak dużo doświadczenia z projektowaniem 3D i drukiem więc też nie do końca wiedziałem jak to zrobić dobrze. Teraz po 8 miesiącach i po wielu innych projektach wiem już znacznie więcej i tym razem zaprojektował bym ją znacznie inaczej. Na dole dodaję modele ramy ale nie zalecam jej wam drukować bo tak jak napisałem nie jest zbyt udana, potraktujcie to jako przykład jak nie projektować ramy do drona :)
Za to za udały się uchwyt anteny oraz kontrolera lotu, cudowne i bardzo skomplikowane elementy :D
Wszystko było projektowane w fusion360 łącznie z projektem ramy do testów.
Zaprojektowałem również specjalne uchwyty montowane na dole ramy pod silnikami aby możliwe było testowanie go w drewnianej ramie. Trochę bałem się o wytrzymałość tego elementu ale na 100% wypełnieniu dało radę i nie pękło ani jedno.
Jak latać:
Aby rozpocząć lot musisz włączyć pilot, ustawić lewy joystick (przepustnicę) maksymalnie na dole. Następnie możesz podłączyć baterię do drona, powinna ona być mocno przymocowana aby nie wypadła podczas lotu. Silniki (wszystkie 4) powinny wydać 3 dźwięki, kiedy tak się stanie możesz powoli dodawać gazu aż dron się podniesie. Podczas pierwszych prób zalecam latać nisko i blisko w razie czego natychmiast lądować. W momencie gdy nasz dron zgubi zasięg na ponad 3 sekundy automatycznie się wyłącza, dzieje się tak samo gdy wyłączymy pilot więc w sytuacji awaryjnej wystarczy wyłączyć pilot.
Ludwik zwycięzca!
W Ryniku dnia 01.04.2017r. odbył się międzynarodowy turniej robotów w którym to decyzją jury Ludwik zajął 1 miejsce w kategorii freestyle! Bardzo dziękuję :)
Mam nadzieję, że spodobał Wam się mój Ludwik dron :) Jeśli macie jakieś pytania zapraszam do komentarzy. Zachęcam do polubienia mojego fanpage’a na facebooku oraz do subskrypcji kanału na youtubie.
Projekt ten został również opisany po angielsku na instructables i bierze udział w konkursie jeśli byś chciał to proszę cię o oddanie głosu na niego:
https://www.instructables.com/id/Arduino-Drone-Quadcopter-3D-Printed/
Bardzo dziękuję za przeczytanie!
Nikodem Bartnik
Pliki załączone do artykułu:
- remote_0.1.pdf
- antenna_holder.stl
- arm3.stl
- pcb-holder-v1.stl
- plate4.stl
- ludwikdron-nikodembartnik.pl_.zip
- side-holder2.stl
- quadcopter_final_2.pdf
Powiem krótko – WOW!!!
Dzięki!
Chyle czoło !
Dziękuję :)
Chyba wiem co będę robił ;-) Bardzo fajny projekt
Dzięki i powodzenia!
Gratuluję wytrzymałości
Dzięki! :)
Zasłużone 5! Jak z zasięgiem tych modułów ? Producent zakłada 1000m na otwartym terenie, ile jest w rzeczywistości ?
Przy testach na szybko udało mi się w mieście osiągnąć około 400-500m ale myślę że na otwartym terenie dało by radę jeszcze więcej. Dzięki!
Ciekawy projekt. Jednak tylko jako poznanie i nauczenie się czegoś nowego. Na rynku jest cała masa całkiem sprawnych kontrolerów lotu. Do tego tanich a jednocześnie o dużych możliwościach. Dlatego budowanie takiego kontrolera uważam za ciekawostkę dla kogoś kto to lubi. Zwykły kowalski pójdzie do sklepu i kupi phantoma. Majsterkowicz zbuduje z dobranych przez siebie elementów. A hadkorowiec sam wszystko zlutuje.
niemniej szacunek
Jasne ale to jest moim głównym celem, mam 17 lat lubię się uczyć :) chciałbym pracować w jakimś fajnym miejscu a najlepiej mieć własną firmę i produkować coś ciekawego. Dlatego też zrobiłem to i inne podobne rzeczy. Kupienie wszystkiego w sklepie było by niewątpliwie łatwiejsze i działało by lepiej ale jaka była by z tego frajda i nauka? Do tego cena stworzenia czegoś takiego była by niewątpliwie wyższa.
I to się chwali.
17 lat? Fajnie mieć kogoś w swoim wieku kto robi coś takiego ;-)
Oczywiście piątka z plusem, bez dwóch zdań!
Zastanawia mnie jedno – Arduino naprawdę dało radę? Moc obliczeniowa Atmegi wystarczyła na ogarnięcie komunikacji, sterowania silnikami i obróbkę matematyczną sygnałów? Byłem przekonany, że do tego bez STM-a ani rusz!
Nie jestem za bardzo w temacie procesorów, ale stm jest używany przy bardziej zaawansowanych maszynach. Gdzie np jeszcze steruje gimbalem, ledami, czujnikami kolizji, wspomaga się barometrem, kompasem czy gps. A to prostego utrzymania poziomu spokojnie wystarczy. Nie znam też szczegółów technicznych, ale jest dostępny na rynku kontroler lotu ardupilot. Ma w nazwie ardu i też jest oparty na jakiejś atmedze, albo i dwóch. I on na płytce ma barometr, a można podłączyć gps, kompas, czujniki sonaru i inne.
Dzięki! Jasne że tak 16MHz to wcale nie tak mało. Jedna pętla zajmuje tutaj około 10ms co daje 100Hz ale jest to spowodowane modułem MPU6050 (konkretnie modułu DMP) przy większym odświeżaniu jakość odczytów bardzo spada. Gdyby nie to dało by się stabilizować jeszcze częściej. CO do GPS, też by dało radę bez problemu. Wykrywanie przeszkód za pomocą stereo vision to już zupełnie co innego do tego trzeba potężnej mocy obliczeniowej.
Pytanie odnośnie druku. Na jakiej drukarce drukowales i czy to jest prywatna czy że szkoły itp. Jak prywatna to gdzie i za ile kupiłeś i jak się sprawdza, ponieważ zastanawiam się nad taką inwestycja.
Sorki za polski znaki, mój telefon jest dziwny :P
Drukarka prywatna, z GearBest’a, dość tania i sprawdza się całkiem dobrze. Przyszła do mnie bez instrukcji a więc żeby ją złożyć trzeba mieć trochę pojęcia jak to działa i co gdzie jest. Tutaj możesz poczytać więcej:
https://www.instructables.com/id/How-to-Assemble-Very-Cheap-3D-Printer/
ale po angielsku. Znajdziesz tam również link do niej.
Dzięki, widziałeś https://blog.arduino.cc/2017/04/21/teenage-maker-builds-his-own-arduino-drone/ ?
Tak, widziałem :)
super projekt :) od razu ma sie ochote niesmialo zdjac folie z opakowania od lutownicy kupionej w lidlu pewnie z rok temu, moze byc dluzej :) i otworzyc niedomykajace sie pudlo po butach z elektronika dla odmiany z aliexpress :)
naprawde cudo , gratuluje pomyslu, cierpliwosci i samego wykonania :)
Mega
Hej, jaką miałeś drukarke 3d? Ile kosztowała?