Skocz do zawartości

piechnat

Użytkownicy
  • Zawartość

    20
  • Rejestracja

  • Ostatnio

  • Wygrane dni

    1

piechnat wygrał w ostatnim dniu 28 września

piechnat ma najbardziej lubianą zawartość!

Reputacja

13 Dobra

O piechnat

  • Ranga
    2/10

Informacje

  • Płeć
    Mężczyzna

Ostatnio na profilu byli

Blok z ostatnio odwiedzającymi jest wyłączony i nie jest wyświetlany innym użytkownikom.

  1. Faktycznie ostatnie aktualizacje raspbiana w moim przypadku dużo zmieniły. Początkowo myślałem, że to zasługa nowo zakupionych akcesoriów, ale po zrobieniu kilku testów wyszło mi, że kabel HDMI z potrójnym ekranowaniem może poprawia stabilność połączenia, ale trudno stwierdzić, czy zwiększa prędkość. Markowa karta SD (w której prędkość zapisu nie wiele ustępuje prędkości odczytu) wprawdzie przyśpiesza działanie systemu i streamingu filmów po LANie, ale na samą prędkość WiFi średnio wpływa. Nadal podtrzymuję tezę o zmianie HDMI0 na HDMI1. W moim przypadku jest zauważalna różnica około 5 Mbps. Największy wpływ mają jednak ostatnie aktualizację - obecnie prędkość downloadu mam na poziomie 30Mbps.
  2. Chciałem zaprezentować mój pierwszy edukacyjny projekt o nazwie kodowej KLOSZARD, który stanowi połączenie pojazdu sterowanego i autonomicznego. Swoją nazwę zawdzięcza temu, że zbudowałem go z najtańszych części ze sklepów wysyłkowych, a jego głównym zadaniem jest pałętanie się po mieszkaniu bez większego celu Początki Pierwsza wersja powstała na gotowym podwoziu robota 2WD. Posiadała jeden moduł mikrokontrolera (Blue Pro Micro) i czujnik odległości (wpięte na breadboardzie). Była zasilana z czterech baterii AA i uwzględniała sterowanie radiowe (moduł + pilot z czterema przyciskami). Niestety wszystkie te elementy potwornie mnie zawiodły, a przede wszystkim to, że pojazd nie potrafił utrzymać prostego kierunku jazdy. Postanowiłem więc podejść do sprawy bardziej profesjonalnie Konstrukcja Obecne czterokołowe podwozie oparte jest na płytach plexi (dociętych na wymiar z portalu aukcyjnego) połączonych kołkami dystansowymi. Posiada cztery silniki z podwójnym wałem (DC 6V z przekładnią 1:48). Na każdym wale umieściłem tarcze z otworami oraz czujniki szczelinowe stanowiące enkodery optyczne. Moduły czujników FC-03 mają wlutowane kondensatory między pin D0 i GND w celu eliminowania błędnych/fałszywych impulsów (rozwiązanie znalezione w sieci). Pierwsze piętro robota wyposażyłem w pięć czujników odległości, koszyk na akumulatory i przełącznik zasilania. Cała konstrukcja zwieńczona jest gustownym zadaszeniem z plexi Zasilanie Maszynę zasilają dwa ogniwa litowo-jonowe (2S 7.4V). Część logiczna otrzymuje napięcie 5V dzięki miniaturowej przetwornicy step-up/step-down (Pololu S7V8A). Silniki sterowane są przez dwa masywne moduły z radiatorami oparte na dwukanałowym układzie L298N. Moduł jezdny Na parterze konstrukcji umieściłem Arduino Pro Micro, które nieustannie oblicza prędkość obrotową każdego wału oraz reguluje napięcia silników w celu uzyskania prędkości zadanej przez moduł główny. Dzięki temu koła mogą niezależnie poruszać się z jednakową prędkością. Komunikacja z modułem głównym odbywa się po magistrali I2C. Komenda sterująca zawiera trzy liczby: 1. prędkość lewej strony, 2. prędkość prawej strony (koło przednie i tylne otrzymują tę samą wartość w przedziale od -100 do +100 RPM) oraz 3. długość zadania mierzona w impulsach enkodera (0 = zadanie ciągłe, nieskończone). [DriveModule.ino] #include <Wire.h> #include <PID_v1.h> /**************************************************************************************************/ class MotorController { static const int8_t SMPL_COUNT = 4; // speed calculation every 4 sensor events static const double RPM_CONST = (60000000 * (SMPL_COUNT / 40.0)); // 20 holes, 40 events bool lastState; byte encPin, fwdPin, bckPin, pwmPin; int8_t signedRpm = 0; double desiredRpm = 0, pwmVal, currRpm = 0; PID *Pid; public: bool setpointReached; uint32_t counter = 0, lastMeasurement = 0, setpoint = 0; MotorController(byte encPin, byte fwdPin, byte bckPin, byte pwmPin) { pinMode(this->encPin = encPin, INPUT); pinMode(this->fwdPin = fwdPin, OUTPUT); pinMode(this->bckPin = bckPin, OUTPUT); pinMode(this->pwmPin = pwmPin, OUTPUT); lastState = !digitalRead(encPin); Pid = new PID(&currRpm, &pwmVal, &desiredRpm, 0.4, 1.5, 0, DIRECT); Pid->SetSampleTime(50); // PID calculation every 50 milliseconds setRpm(0); } int8_t speedMeasurement() { // ISR bool state = digitalRead(encPin); if (state != lastState) { lastState = state; counter++; setpointReached = (setpoint && (counter >= setpoint)); if ((counter % SMPL_COUNT) == 0) { uint32_t currTime = micros(); currRpm = RPM_CONST / (currTime - lastMeasurement); lastMeasurement = currTime; return 2; // RPM calculated } return 1; // sensor event occurred } return 0; // nothing happened } int8_t voltageAdjustment() { if (setpointReached) return 2; // task completed if (!Pid->Compute()) return 0; // nothing happened, no adjustment or PID turned off noInterrupts(); uint32_t eventDuration = micros() - lastMeasurement; if (eventDuration > 400000) currRpm = 0; // no event for 400ms, engine stopped interrupts(); analogWrite(pwmPin, pwmVal); return (eventDuration < 3000000) ? // no event for 3 seconds means danger of power overload 1 /* voltage adjustment */ : 3 /* power overload */; } void setRpm(int8_t rpm, byte initPwm = 0) { if (((rpm ^ signedRpm) < 0) || (rpm && !signedRpm)) { // if new RPM has opposite sign or ... noInterrupts(); currRpm = 0; interrupts(); pwmVal = initPwm; } signedRpm = rpm; desiredRpm = abs(rpm); digitalWrite(fwdPin, rpm > 0 ? HIGH : LOW); // setting direction depending on sign of RPM digitalWrite(bckPin, rpm < 0 ? HIGH : LOW); Pid->SetMode(rpm ? AUTOMATIC : MANUAL); // PID switch ON-OFF } }; /**************************************************************************************************/ class VehicleController { static const byte MAX_PWM = 255; static const byte MID_PWM = 100; uint32_t lastTime = 0; static int ascComp(const void *a, const void *b) { return (*(uint32_t *)a - *(uint32_t *)b); } public: bool powerOverload = false, isRunning = false; int8_t taskCompleted = 0; static const int8_t M_LEN = 4; MotorController motor[M_LEN] = { {/*ENC1*/ 12, /*FIN1*/ 4, /*FIN2*/ 2, /*FENA*/ 3}, {/*ENC2*/ 11, /*FIN3*/ 8, /*FIN4*/ 7, /*FENB*/ 9}, {/*ENC3*/ 10, /*BIN1*/ A1, /*BIN2*/ A0, /*BENA*/ 6}, {/*ENC4*/ 13, /*BIN3*/ A3, /*BIN4*/ A2, /*BENB*/ 5} }; void interruptRoutine() { // ISR for (byte i = 0; i < M_LEN; i++) motor[i].speedMeasurement(); } void loopRoutine() { for (int8_t i = 0; i < M_LEN; i++) { switch (motor[i].voltageAdjustment()) { case 0: // nothing happened break; case 1: // voltage adjustment break; case 2: // task completed taskCompleted++; noInterrupts(); motor[i].setpointReached = motor[i].setpoint = 0; interrupts(); break; case 3: // power overload powerOverload = true; setSpeed(0, 0); return; } } if (taskCompleted >= M_LEN) setSpeed(0, 0); } void setSpeed(int8_t left, int8_t right, uint32_t taskLen = 0) { uint32_t now = micros(); isRunning = left || right; noInterrupts(); if (isRunning) { powerOverload = taskCompleted = 0; for (byte i = 0; i < M_LEN; i++) { motor[i].lastMeasurement = now; motor[i].setpointReached = motor[i].counter = 0; motor[i].setpoint = taskLen; } } else { for (byte i = 0; i < M_LEN; i++) motor[i].setpointReached = motor[i].setpoint = 0; } interrupts(); motor[0].setRpm(left, MID_PWM); motor[1].setRpm(right, MID_PWM); motor[3].setRpm(left, MID_PWM); motor[2].setRpm(right, MID_PWM); } } vehicle; /**************************************************************************************************/ void setChangeInterrupt(byte pin) { pinMode(pin, INPUT); *digitalPinToPCMSK(pin) |= bit(digitalPinToPCMSKbit(pin)); PCIFR |= bit(digitalPinToPCICRbit(pin)); PCICR |= bit(digitalPinToPCICRbit(pin)); } volatile int8_t gblLeftSpeed = 0, gblRightSpeed = 0; volatile uint8_t gblTaskLen = 0; void setup() { Wire.begin(44); Wire.onReceive(i2cReceiveEvent); Wire.onRequest(i2cRequestEvent); for (byte i = 10; i <= 13; i++) setChangeInterrupt(i); // PCINT0 int8_t tmpLSpeed = 0, tmpRSpeed = 0; uint8_t tmpTaskLen = 0; while (true) { vehicle.loopRoutine(); if (gblLeftSpeed != tmpLSpeed || gblRightSpeed != tmpRSpeed || gblTaskLen != tmpTaskLen) { tmpLSpeed = gblLeftSpeed; tmpRSpeed = gblRightSpeed; tmpTaskLen = gblTaskLen; vehicle.setSpeed(tmpLSpeed, tmpRSpeed, tmpTaskLen); } } } void i2cReceiveEvent(int howMany) { if (howMany >= 3) { gblLeftSpeed = Wire.read(); gblRightSpeed = Wire.read(); gblTaskLen = Wire.read(); howMany =- 3; } while (howMany--) Wire.read(); } void i2cRequestEvent() { // task ended Wire.write(gblTaskLen ? vehicle.taskCompleted >= vehicle.M_LEN : 1); } ISR(PCINT0_vect) { vehicle.interruptRoutine(); } Moduł zbliżeniowy Pięcioma czujnikami odległości (4x HC-SR04 i 1x US-015) steruje samotna Atmega328P na płytce uniwersalnej (wgrany bootloader wykorzystuje wewnętrzny oscylator 8MHz). Każde żądanie danych (wysłane po I2C) do tego modułu jest sygnałem do wykonania kolejnego pomiaru ze wszystkich czujników (po kolei). [ProximityModule.ino] #include <Wire.h> #include <NewPing.h> NewPing sensor[] = { NewPing(12, 12, 200), NewPing(5, 5, 200), NewPing(13, 13, 200), NewPing(4, 4, 200), NewPing(A3, A3, 200) }; const byte ORDER[] = {0, 2, 4, 1, 3}; const byte CNT = sizeof(ORDER); volatile byte distance[CNT] = {}; volatile bool takeNext = false; void setup() { Wire.begin(40); Wire.onRequest(requestEvent); while (true) { if (!takeNext) continue; takeNext = false; for (byte i = 0; i < CNT; i++) { distance[ORDER[i]] = sensor[ORDER[i]].ping_cm(); delay(8); } } } void requestEvent() { for (byte i = 0; i < CNT; i++) Wire.write(distance[i]); takeNext = true; } Sterowanie Pojazd może być sterowany za pomocą smartfonu z Androidem. Aplikacja napisana w Java’ie (Android Studio) przełącza się na WiFi rozgłaszane przez robota i przesyła drogą sieciową (na ustalony adres IP i port) krótkie instrukcje sterujące. Przy tej okazji po raz pierwszy w życiu doceniłem prostotę protokołu UDP – każda komenda znajduje się w osobnym pakiecie danych Nie zamieszczam źródeł aplikacji ponieważ zawierają one mnóstwo nadmiarowego kodu związanego bardziej z interfejsem użytkownika. Moduł główny Przypadkowo wpadłem w posiadanie modułu WiFi NodeMCU v3 z rodziny układów ESP8266. Podczas pierwszych testów w Arduino IDE zauważyłem, że najprostsze szkice wygrywają się do niego potwornie długo. Do tej pory nie znalazłem rozwiązania tej niedogodności, ale w trakcie poszukiwań natrafiłem na firmware obsługujący prosty system plików oraz interpreter języka skryptowego Lua. http://nodemcu.readthedocs.io Koncepcja asynchronicznych callbacków wywoływanych przez zdarzenia i timery (znana mi z JavaScriptu) wydała się genialnym rozwiązaniem symulującym pracę wielozadaniową w środowisku jednowątkowym, dlatego postanowiłem przyjrzeć się temu środowisku. NodeMCU pracuje w standardzie 3.3V. Konwerter poziomów logicznych został ukryty na płytce uniwersalnej bezpośrednio pod modułem Pojazd posiada możliwość autonomicznej jazdy aktywowanej z poziomu aplikacji lub wbudowanego w moduł przycisku FLASH. W tym trybie robot ma za zadanie objechać całe mieszkanie tak, aby po jego prawej stronie w odległości do 40 cm zawsze znajdowała się jakaś przeszkoda. W przypadku braku przeszkody robot obraca się w prawo mniej-więcej o 90 stopni i jedzie prosto. Przeszkoda od strony frontowej uruchamia poszukiwanie otwartej przestrzeni przy jednoczesnym obracaniu w lewo. [main.lua] print("Starting Kloszard") local klrd = require "kloszard" local snsr = require "sensor" local autoDrive = { timer = tmr.create() } function autoDrive:onSetup() self.timer:register(100, tmr.ALARM_AUTO, function() local s = klrd.prxRead() for i = 1, 5 do snsr[i]:add(s:byte(i)) end local act = self:action() if act then self.action = act if act == self.main then -- drive forward klrd.drvSend(45, 45) end end end) self:onStop() end function autoDrive:onStart() self.action = function() return self.main end klrd.prxRead() self.timer:start() snsr.sideCheckLock = true end function autoDrive:onStop() self.timer:stop() klrd.drvSend(0, 0) end function autoDrive:onFinish() self:onStop() self.timer:unregister() end function autoDrive:main() -- obstacle ahead if math.min(snsr[2].val, snsr[3].val, snsr[4].val) < 20 then klrd.drvSend(-45, 45) return function() -- finding escape if snsr[2]:gt(20) and snsr[3]:gt(20, 3) and snsr[4].val > 20 then snsr.sideCheckLock = true return self.main end end end -- open space on right side if snsr:rightSideOpen(40) then klrd.drvSend(45, -45, 30) -- turn right return function() if klrd.drvTaskEnded() then return self.main end end end -- right side collision risk if snsr[5]:lt(10) and snsr[5]:get(5) > snsr[5].val then klrd.drvSend(0, 45) -- course correction return function() if snsr[5]:get(5) < snsr[5].val then return self.main end end end end klrd.setup(autoDrive) [sensor.lua] local Queue = { 100, 100, 100, 100, 100, pos = 1, LEN = 5, val = 100 } Queue.__index = Queue Queue.new = function() return setmetatable({}, Queue) end function Queue:add(value) if value == 0 then value = self.val end self[self.pos], self.val = value, value self.pos = self.pos + 1 if self.pos > self.LEN then self.pos = 1 end end function Queue:get(index) if index > self.LEN then index = self.LEN elseif index < 1 then index = 1 end local shift = self.pos - index if shift < 1 then shift = shift + self.LEN end return self[shift] end function Queue:gt(value, len) -- values greater than if not len then len = self.LEN end for i = 1, len do if self:get(i) <= value then return false end end return true end function Queue:lt(value, len) -- values less than if not len then len = self.LEN end for i = 1, len do if self:get(i) >= value then return false end end return true end local M = { sideCheckLock = true } for i = 1, 5 do M[i] = Queue:new() end function M:rightSideOpen(distance) local cnt = 0 for i = 1, self[5].LEN do if self[5][i] > distance then cnt = cnt + 1 end end if self.sideCheckLock then self.sideCheckLock = cnt > 0 return false else self.sideCheckLock = cnt == self[5].LEN return self.sideCheckLock end end return M [kloszard.lua] local M = {} local AUTOBTN_PIN = 3 local CMD_PING = 121 local DRVM_ADDR = 44 -- DriveModule Address local CMD_DRIVE = 122 local PRXM_ADDR = 40 -- ProximityModule Address local CMD_AUTO = 123 local UDP_PORT = 50000 function M.setup(autoDrive) M.autoDrive = autoDrive wifi.setmode(wifi.SOFTAP) wifi.ap.setip({ ip = "192.168.1.1", netmask = "255.255.255.0", gateway = "192.168.1.1" }) wifi.ap.config({ ssid = "KloszardWiFi", pwd = "abcd1234" }) i2c.setup(0, 5, 6, i2c.SLOW) -- SDA pin 5, SCL pin 6 autoDrive:onSetup() M.udpSock = net.createUDPSocket() M.udpSock:listen(UDP_PORT) M.udpSock:on("receive", function(sock, data, port, ip) if data:byte(1) == CMD_PING then sock:send(port, ip, "PONG") elseif data:byte(1) == CMD_DRIVE then M.drvSend(data:byte(2), data:byte(3), data:byte(4)) elseif data:byte(1) == CMD_AUTO then if data:byte(2) ~= 0 then autoDrive:onStart() else autoDrive:onStop() end end end) gpio.trig(AUTOBTN_PIN, "up", function() if autoDrive.timer:state() then autoDrive:onStop() else autoDrive:onStart() end end) M.drvSend(0, 0) end function M.finish() M.autoDrive:onFinish() M.udpSock:close() wifi.setmode(wifi.NULLMODE) end local lastDrvmLeft, lastDrvmRight, lastTaskLen = 0, 0, 0 function M.drvSend(left, right, taskLen) if not taskLen then taskLen = 0 end if lastDrvmLeft == left and lastDrvmRight == right and lastTaskLen == taskLen -- ignore function call if nothing changed then return end lastDrvmLeft, lastDrvmRight, lastTaskLen = left, right, taskLen left = bit.band(left, 0xFF) right = bit.band(right, 0xFF) i2c.start(0) i2c.address(0, DRVM_ADDR, i2c.TRANSMITTER) i2c.write(0, left, right, taskLen) i2c.stop(0) end function M.drvTaskEnded() i2c.start(0) i2c.address(0, DRVM_ADDR, i2c.RECEIVER) local res = i2c.read(0, 1) i2c.stop(0) return res:byte(1) ~= 0 end function M.prxRead() i2c.start(0) i2c.address(0, PRXM_ADDR, i2c.RECEIVER) local res = i2c.read(0, 5) i2c.stop(0) return res end return M WebEspDitor Konieczność ciągłego podłączania kabla USB w celu modyfikacji najdrobniejszych parametrów kodu zmotywowała mnie do napisania dodatkowego skryptu o nazwie WebEspDitor. Jest to prosty serwer/serwis HTTP, który umożliwia edycję plików znajdujących się w pamięci nodeMCU z poziomu przeglądarki internetowej. Skrypt wyświetla również wyniki funkcji print i ostatni błąd aplikacji, w związku z czym powinien być uruchamiany na wstępie jako init.lua (kod aplikacji należy przenieść do pliku main.lua). [init.lua] gpio.mode(3, gpio.INPUT, gpio.PULLUP) -- FLASH BUTTON if gpio.read(3) == 0 then return end -- boot loop protection print("Starting WebEspDitor...") net.createServer():listen(80, function(socket) local htmlTmpl = { -- 1 -- [===[HTTP/1.0 200 OK Content-Type: text/html; charset=UTF-8 Connection: close <!DOCTYPE html><html><head><title>WebEspDitor</title><meta name="viewport" content="width=device-width"><link rel="icon" href="data:;base64,="><style> a{text-decoration:none;color:navy}a:hover{text-decoration:underline}body{ line-height:1.5em;font-family:monospace}</style></head><body> ]===], -- 2 -- [===[<p><a href="/">WebEspDitor</a> [ <a href="/reset">reset</a> ]</p>]===], -- 3 -- [===[<form action="/save/<!FNAME>" method="post" enctype="text/plain"> <textarea name="s" spellcheck="false" style="position:absolute;width:100%; height:100%;margin:0;border:0;padding:4px;resize:none;white-space:pre; box-sizing:border-box">]===], -- 4 -- [===[</textarea><input style="position:absolute;bottom:0;right:0" type="submit" value="Save"></form><style>body{margin:0;overflow:hidden}</style>]===], -- 5 -- [===[<input id="name" type="text"><input type="button" value="create" onclick="location.href='/edit/'+document.getElementById('name').value">]===], -- 6 -- [===[<script>setTimeout(function(){location.href='/'},2000)</script>]===], -- 7 -- [===[<li><a href="/edit/<!FNAME>"><!FNAME></a> (<!FSIZE>, <a href="/delete/<!FNAME>" onclick="return confirm('Are you sure to delete'+ ' file \'<!FNAME>\'?')">del</a>)</li>]===] } local rqst, rspn = { length = 0, totalLen = 0, fname = nil }, { } local function getLine(str, bgnPos) local line, endPos = "", str:find("\r\n", bgnPos, true) if endPos then line = str:sub(bgnPos, endPos - 1) bgnPos = endPos + 2 end return line, bgnPos end local function sendRspn(sck) -- send response table to client if #rspn > 0 then sck:send(table.remove(rspn, 1), sendRspn) else sck:close() end end local function saveRqst(sck, data) -- save incoming content to file if #data > 0 then rqst[#rqst+1] = data end rqst.length = rqst.length + #data if rqst.length >= rqst.totalLen then -- last network frame data = nil rqst[1] = rqst[1]:sub(3) -- enctype text/plain: rqst[#rqst] = rqst[#rqst]:sub(1, -3) -- s=[data]CRLF local fd = file.open(rqst.fname, "w+") if fd then while #rqst > 0 do fd:write(table.remove(rqst, 1)) end fd:close() end collectgarbage("collect") sendRspn(sck) end end socket:on("receive", function(sck, data) rspn[1] = htmlTmpl[1] local line, dataPos = getLine(data, 1) -- 1 2 3 4 5 local parts = {} -- GET /cmd/prm HTTP/1.1 for elm in line:gmatch("[^/ ]+") do parts[#parts+1] = elm end if #parts == 5 then parts[3] = parts[3]:gsub("[^a-zA-Z0-9_.-]", "") end if parts[1] == "POST" then repeat line, dataPos = getLine(data, dataPos) local len = line:match("Content%-Length: (%d+)") if len then rqst.totalLen = tonumber(len) end until #line == 0 end -- EDIT if parts[2] == "edit" and #parts == 5 then local tmp = htmlTmpl[3]:gsub("<!FNAME>", parts[3], 1) rspn[#rspn+1] = tmp tmp = #rspn + 1 local fd = file.open(parts[3], "r") if fd then while true do local chunk = fd:read(512) if chunk then rspn[#rspn+1] = chunk else break end end fd:close() end for i = tmp, #rspn do rspn[i] = rspn[i]:gsub("&", "&amp;"):gsub("<", "&lt;") end rspn[#rspn+1] = htmlTmpl[4] else rspn[#rspn+1] = htmlTmpl[2] -- SAVE if parts[2] == "save" and #parts == 5 then rqst.fname = parts[3] rspn[#rspn+1] = '<p>File "'..parts[3]..'" has been saved.</p>'..htmlTmpl[6] -- DELETE elseif parts[2] == "delete" and #parts == 5 then file.remove(parts[3]) rspn[#rspn+1] = '<p>File "'..parts[3]..'" has been deleted.</p>'..htmlTmpl[6] -- RESET elseif parts[2] == "reset" then local timer = tmr.create() timer:register(500, tmr.ALARM_SINGLE, function() node.restart() end) timer:start() rspn[#rspn+1] = '<p>Waiting for device...</p>'..htmlTmpl[6] -- INDEX else local res = {'<ul>'} for n, s in pairs(file.list()) do if not n:find("init.", 1, true) then res[#res+1] = htmlTmpl[7]:gsub("<!FNAME>", n):gsub("<!FSIZE>", s) end end res[#res+1] = '</ul>' rspn[#rspn+1] = table.concat(res)..htmlTmpl[5] local res = file.getcontents("init.out") if res then rspn[#rspn+1] = '<p>Lua interpreter output:<pre>'..res..'</pre></p>' end end end rspn[#rspn+1] = '</body></html>' socket, htmlTmpl, line, parts = nil collectgarbage("collect") -- FILE UPLOAD if rqst.fname and rqst.totalLen > 0 then sck:on("receive", saveRqst) saveRqst(sck, data:sub(dataPos)) -- NORMAL REQUEST else sendRspn(sck) end end) end) print("Starting main...") do local res, err file.remove("init.out") node.output(function(s) local fd = file.open("init.out", "a+") if fd then fd:write(s) fd:close() end end, 1) if file.exists("main.lc") then res, err = pcall(function() dofile("main.lc") end) else res, err = pcall(function() dofile("main.lua") end) end if not res then print(err) end end Dalszy rozwój Najsłabszymi elementami obecnej wersji KLOSZARDa są plastikowe przekładnie i wały silniczków, które coraz bardziej uginają się pod ciężarem konstrukcji (1,06 kg). Na horyzoncie rozbudowy pojawiła się jednak nadzieja w postaci identycznych silników z przekładnią metalową. Mam nadzieję, że uda się je bezkarnie podmienić Drugie miejsce niedoskonałości zajmuje sam w sobie NodeMCU, który cierpi z powodu niedostatku pamięci RAM oraz tendencji do resetowania w przypadku wszelkich problemów zarówno softwarowych jak i hardwarowych. W tym przypadku rozwiązaniem wydaje się przejście na Raspberry Pi Zero (WiFi+BT), czego dodatkowym atutem byłoby całkowite uwolnienie projektowania i debugowania od kabla USB Dalsze prace będą ukierunkowane na rozwój oprogramowania (bardziej zaawansowane przetwarzanie danych z modułu zbliżeniowego i jezdnego), a może nawet uda się zaimplementować jakąś skromną formę lokalizowania w przestrzeni.
  3. man amixer [...] -q Quiet mode. Do not show results of changes. ostatni parametr: 0 - automatic 1 - force 3.5 jack 2 - force HDMI0 3 - force HDMI1
  4. Porobiłem kilkanaście testów, z których wynika, że na niską prędkość WiFi składa się kilka rzeczy: 1. W ustawieniach routera miałem na sztywno wybrany kanał 13, tymczasem moje RPi ma najstabilniejszy transfer na kanale 1 mimo tego, że najluźniejszy jest właśnie 13. W ten sposób prędkość uwolniła się z poziomu ułamków do kilku megabitów. 2. Dużym czynnikiem zakłócającym jest stojący obok dekoder TV (WiFi) jeśli był akurat włączony. Po wyłączeniu prędkość doszła do ok. 15 Mbps, ale jest bardzo chwiejna. 3. Poza zmniejszeniem odległości od routera, najlepsze rezultaty przynosi odłączenie kabla HDMI. W takiej sytuacji prędkość wzrasta do 25-35 Mbps. Wydaje mi się, że pewne korzyści, daje również podłączenie telewizora do drugiego portu HDMI. Niestety nie wiem, jak na drugim porcie spowodować, aby działało audio (nie ma również HDMI-CEC)? [edytowane] znalazłem w sieci, może się komuś przyda amixer -q cset numid=3 3 [/edytowane] Zastanawiam się, czy to może mieć jakiś związek z jakością kabla? Zauważyłem przy kablu dedykowanym do RPi adnotację „potrójna warstwa ekranowania w celu izolacji od fal Bluetooth i WiFi”?
  5. Dziękuję za odpowiedź. Trochę męczyłem ten temat i chyba doszedłem do rozwiązania. Mosfet otwiera się pod wpływem napięcie pomiędzy bramką (G) a źródłem (S). W datasheet IRF3205 ma próg otwarcia min 2.0V max 4.0V, natomiast IRF9540N ma VGS min -2.0V max -4.0V, tak więc dla IRF3205 źródło musi być od strony masy, bo wtedy napięcie 3.3V lub 5V (G) jest większe od zera (S) o te minimum 2, natomiast w przypadku IRF9540N źródło (S) musi być od strony zasilania, wtedy zerowa bramka (G) jest niższa o minimum 2, natomiast 3.3V (G) jest niższe nawet od 5V (S) jedynie o 1.7 dlatego ten mosfet jest zamknięty na stanie wysokim, niezależnie od wysokości napięcia zasilania. Wiatraczek mam ze strony botland - 5V, 0.16A: https://botland.com.pl/pl/wentylatory/15170-wentylator-5v-30x30x8mm-do-obudowy-raspberry-pi.html Zdążyłem już wylutować sobie płytkę z mosfetem i sprzętowym przyciskiem do włączania i wyłączania maliny I tutaj mam kolejne pytanie. Wentylator jak się rozkręci to trochę wprawia w drgania całą obudowę i przydało by się zmniejszyć jego obroty. Próbowałem zrobić to używając software GPIO PWM z pythona, ale nie działało tzn. poniżej 38% był wyłączony, a powyżej działał na full. Rozumiem, że mosfety są zero-jedynkowe: otwarty, zamknięty i nic pośredniego?
  6. Mam problem z prędkością WiFi w nowo nabytym Raspberry Pi 4b (sieć domowa z routera TP-Link Archer C7, częstotliwość 2.4Ghz, kanał 6). Strony wczytują się jak krew z nosa, również streaming po LAN nie daje rady. W serwisach testujących prędkość łącza wychodzi download rzędu 0.25 Mbps. Wszystkie inne sprzęty, stojące w tym samym miejscu co malina, osiągają kilkanaście lub kilkadziesiąt megabitów. Co najdziwniejsze, jeśli obok routera położę telefon z włączonym hotspotem (Android), to na tej sieci Raspberry wyciąga bez problemu 8 Mbps (jak przyniosę telefon do pokoju, w którym stoi malina, to już w ogóle mam prawie 40 Mbps). Wynika z tego jakby istniał jakiś konflikt między Raspberry Pi 4b, a tym konkretnym routerem. Czy ktoś spotkał się z takim problemem? Czy można to jakoś rozwiązać? Dziękuję i pozdrawiam.
  7. Chciałbym wentylator dla Raspberry Pi 4b podłączyć do pinu 5V przez mosfet i włączać go osobnym pinem GPIO, aby wentylator uruchamiał się, kiedy temperatura przekroczy np. 75 stopni. W szufladzie mam przypadkiem dwa mosfety typu N: IRF3205 oraz IRF9540N Niestety nie do końca rozumiem ich działanie, szczególnie jeśli chodzi o sprawę kierunku prądu dren-źródło lub źródło-dren oraz umiejscowienie przełącznika w obwodzie tj. przed lub za elementem obciążającym. Czy są w tym względzie jakieś zasady? Metodą brute force znalazłem najlepszą konfigurację dla obu mosfetów: IRF3205 – działa jako domknięcie obwodu (na przewodzie czarnym od strony masy) w kierunku dren-źródło (D -> S). Otwiera się (~4.7V) po dotknięciu jakiegokolwiek napięcia (5V|3.3V) do bramki (G). Po przyłożeniu masy (GND) do bramki (G) na multimetrze odczytuję -0.8V (???). IRF9540N – działa jako włącznik obwodu (na przewodzie czerwonym od strony zasilania) w kierunku źródło-dren (S -> D). Otwiera się (4.25V) po dotknięciu do bramki masy (GND). Po przyłożeniu do bramki (G) jakiegokolwiek napięcia (5V|3.3V) wentylator zatrzymuje się (0.0V). (Wszystkie pozostałe kombinacje były bezużyteczne albo z powodu zbyt małego napięcia [wentylator nie startował] albo permanentnego otwarcia/zamknięcia mosfetu). 1. Czy obie przedstawione kombinacje są prawidłowe i mogę wybrać dowolną do mojego zastosowania (szczególnie intryguje mnie odczyt -0.8V dla IRF3205 przy zamknięciu)? 2. Czy bramkę powinienem podpiąć przez rezystor - jeśli tak to jaki - w pierwszej opcji do masy lub w drugiej do 3.3V żeby wymusić domyślny stan wyłączony? 3. Czy jest jakiś element elektroniczny, który by się do tego celu lepiej nadawał?
  8. Zadanie nie jest skomplikowane, ale czasochłonne. Zasadniczo należałoby wysłać dane z ESP8266 protokołem sieciowym TCP lub UDP do komputera. Jeśli wgrasz do NodeMCU firmware z obsługą języka skryptowego LUA, to całość ograniczy się do kilku linijek kodu. Na komputerze trzeba będzie stworzyć w jakimkolwiek języku skrypt/aplikację, która będzie nasłuchiwać na wybranym porcie i zapisywać dane do pliku. W takiej konfiguracji najlepiej na routerze zarezerwować adres IP dla tej maszyny. Podejrzewam, że najszybciej można byłoby to zrobić w Pythonie, aczkolwiek nie mam w tym języku żadnego doświadczenia.
  9. Hej, dzięki za pomoc, wiem, że to podstawy podstaw – takie już teraz czasy, że do Arduino ciągnie kompletnych amatorów dla 10kOm to będzie 2mW. Już wcześniej chciałem dać na oko opornik 10kOm, ale grzał się jeszcze szybciej, dlatego pomyślałem sobie, że im większy opór „tym większe tarcie”, tym więcej ciepła i napisałem post na forum. Teraz widzę, że się kopnąłem w kolorach pasków i przez przypadek wziąłem 10Om Jeśli dobrze rozumiem dla akumulatora 12V żeby popłynął prąd 1mA powinno się użyć rezystorów o wartościach 5k i 7k Om, co da pracę 5 i 7 mW?
  10. Serdecznie dziękuję za odpowiedzi. Mam jeszcze jedno pytanie niejako związane z tematem. Do zmierzenia napięcia przez ADC chciałem zastosować dzielnik napięcia. Zrobiłem najpierw test: bateria 9V dwa rezystory 220Om no i fajnie napięcie dzieli się na połowę, ale oporniki potwornie się grzeją. Chciałem spytać czy to ma tak być, czy zastosować inne rezystory, czy potrzebny jest radiator? Czy przy pomocy jakichś obliczeń można sprawdzić, czy to się nie spali? Oporniki są zwyczajne, zgodnie z opisem THT przewlekane 0,25W.
  11. Ok. Faktycznie doprowadzenie osobnych przewodów zasilania wyeliminowało kilka dziwnych zachowań, jednak problem z nierównoczesnym ruszaniem kół pozostał. Mam wrażenie, że silniki mają różne progi napięcia, z którego zaczynają się kręcić. PID steruje napięciem płynnie od zera, więc ruszają po kolei, a wspomniana w poprzednim poście kolejność ułożyła się zupełnie przypadkowo. Niestety nie mogę dać większych wartości Kp, Ki, żeby szybciej ruszało, bo wtedy niektóre silniki wpadają w "huśtawkę", zanim osiągną Setpoint. (Zupełnie nie rozumiem działania Kd?) Tutaj mam kolejny dylemat. Być może dojdę do tego za trzy dni, ale może ktoś ma już jakieś doświadczenie. Jak zsynchronizować start kół? Ustalić osobno parametry Kp, Ki dla każdego z silników? Czy nie ruszać tego i jedynie przyjąć indywidualne wartości początkowe PWM (Output), z których rozpocznie działanie algorytm PID?
  12. Na początku mam standardowe przewody z koszyka na baterie, później płytka stykowa i standardowe przewody do płytek stykowych. Dalej dosyć duży rozdzielacz, z którego wychodzi już do silników porządny przewód 0.35mm2. Jeśli ma to jakieś znaczenie, to masy dla silników oraz logiki 5v (Arduino, 2xSterownik, 4xCzujnik szczelinowy) są połączone w rozdzielaczu i wszystko wraca do baterii jednym przewodem do płytek stykowych.
  13. Dziękuję wszystkim za odpowiedzi, udało mi się w końcu zdobyć wszystkie potrzebne elementy do budowy podwozia, skorzystałem z biblioteki PID do Arduino, zrobiłem liczenie prędkości na przerwaniach pinów – wszystko działa względnie dobrze, jednak mam jeszcze jeden problem. Zauważyłem pewne różnice w mocy silników, zwłaszcza podczas ruszania lub kręcenia piruetów, proporcjonalne do kolejności ich podłączenia. Zasilanie z baterii (4 paluszki) prowadzi do pierwszego sterownika silników, a stamtąd kolejny przewód łączy się z drugim sterownikiem i taka też jest kolejność mocy (1A > 1B > 2A > 2B). Jak sobie z tym poradzić? Lepsza wydajność zasilania, większa średnica przewodów?
  14. A jeśli wskazany w pierwszym poście moduł wymienię na poniższy: http://allegro.pl/zabezpieczenie-pcm-balanser-2s-12a-li-ion-7-4v-i7204396830.html To pierwsze dwie odpowiedzi będą twierdzące?
×
×
  • Utwórz nowe...