Differences

This shows you the differences between two versions of the page.

Link to this comparison view

pm:prj2025:vradulescu:mihnea.stamatie [2025/05/23 02:08]
mihnea.stamatie [Jurnal]
pm:prj2025:vradulescu:mihnea.stamatie [2025/05/23 17:02] (current)
mihnea.stamatie [Concluzii]
Line 149: Line 149:
 ===== Software Design ===== ===== Software Design =====
  
 +==== 1. Motivarea alegerii bibliotecilor folosite ====
  
-<note tip> +Pentru acest proiect am optat pentru o abordare minimalistă,​ folosind doar **Arduino.h** ca bibliotecă principală. Această alegere a fost motivată de:
-Descrierea codului aplicaţiei (firmware):​ +
-  ​mediu de dezvoltare (if any) (e.g. AVR Studio, CodeVisionAVR) +
-  ​librării şi surse 3rd-party (e.g. Procyon AVRlib) +
-  * algoritmi şi structuri pe care plănuiţi să le implementaţi +
-  * (etapa 3) surse şi funcţii implementate +
-</​note>​+
  
-===== Rezultate Obţinute =====+  * **Simplicitate și performanță**:​ Evitarea dependențelor externe reduce overhead-ul și îmbunătățește timpul de răspuns al sistemului 
 +  * **Control direct asupra hardware-ului**:​ Accesul direct la funcțiile Arduino oferă control precis asupra pin-ilor digitali și PWM 
 +  * **Stabilitate**:​ Cod mai puțin predispus la erori cauzate de conflicte între biblioteci 
 +  * **Optimizare pentru microcontrolere**:​ Codul este optimizat pentru resursele limitate ale Arduino-ului
  
-<note tip> +==== 2Elementul de noutate al proiectului ====
-Care au fost rezultatele obţinute în urma realizării proiectului vostru. +
-</​note>​+
  
-===== Concluzii =====+Principalul element inovator al proiectului constă în **implementarea unui filtru low-pass pe eroarea PID**:
  
-===== Download =====+<​code>​ 
 +error error * 0.4 + input * 0.6; 
 +</​code>​
  
-<note warning>​ +Această abordare oferă: 
-O arhivă (sau mai multe dacă este cazul) cu fişierele obţinute în urma realizării proiectuluisurse, scheme, etc. Un fişier README, un ChangeLog, un script de compilare şi copiere automată pe uC crează întotdeauna o impresie bună ;-).+  * **Reducerea zgomotului**:​ Filtrarea fluctuațiilor bruște ale senzorilor 
 +  * **Stabilitate îmbunătățită**: Mișcări mai line ale robotului 
 +  * **Adaptabilitate**:​ Posibilitatea de fine-tuning prin modificarea coeficienților (0.4/0.6)
  
-Fişierele se încarcă pe wiki folosind facilitatea ​**Add Images or other files**. Namespace-ul în care se încarcă fişierele este de tipul **:​pm:​prj20??:​c?​** sau **:​pm:​prj20??:​c?:​nume_student** (dacă este cazul). **Exemplu:​** Dumitru Alin, 331CC -> **:​pm:​prj2009:​cc:​dumitru_alin**. +Un alt aspect inovator este **sistemul ​de detectare a cazurilor speciale** pentru diferite configurații ale senzorilor, cu tratare separată pentru intersecții și pierderea liniei.
-</​note>​+
  
 +==== 3. Justificarea utilizării funcționalităților din laborator ====
  
-===== Bibliografie/Resurse ​=====+Funcționalitățile implementate sunt direct derivate din conceptele de laborator:​ 
 + 
 +=== Control PID ==
 +  * **Proporțional (KP=17.00)**:​ Corecție bazată pe eroarea curentă 
 +  * **Derivativ (KD=600.00)**:​ Anticiparea schimbărilor pentru stabilitate 
 +  * **Integral (KI=0.00)**:​ Dezactivat pentru evitarea oscilațiilor în acest caz specific 
 + 
 +=== Controlul motoarelor === 
 +  * **PWM pentru viteza**: Utilizarea analogWrite pentru control precis 
 +  * **Control direcțional**:​ Utilizarea pin-ilor digitali pentru forward/backward 
 +  * **Maparea valorilor**:​ Conversie din procentaj (-100 la 100) în valori PWM (0-255) 
 + 
 +=== Senzoristica digitală === 
 +  * **Array de 5 senzori**: Configurație standard pentru detectarea precisă a liniei 
 +  * **Logică inversată**:​ ''​!digitalRead()''​ pentru adaptarea la tipul de senzor utilizat 
 + 
 +==== 4. Scheletul proiectului și interacțiunea dintre funcționalități ==== 
 + 
 +=== Arhitectura sistemului: === 
 + 
 +  ┌─────────────────┐ ​   ┌──────────────┐ ​   ┌─────────────────┐ 
 +  │  Senzori Linie  │───▶│ Algoritm PID │───▶│ ​  ​Motoare DC    │ 
 +  │   (5 senzori) ​  ​│ ​   │              │    │ (Stânga/​Dreapta)│ 
 +  └─────────────────┘ ​   └──────────────┘ ​   └─────────────────┘ 
 + 
 +=== Fluxul de execuție: === 
 + 
 +  - **Inițializare (setup())**:​ 
 +    * Configurarea pin-ilor pentru motoare și senzori 
 +    * Setarea orientării motoarelor 
 +    * Inițializarea comunicației seriale 
 + 
 +  - **Bucla principală (loop())**:​ 
 +    * Citirea valorilor de la senzori 
 +    * Calculul erorii de poziție 
 +    * Aplicarea algoritmului PID 
 +    * Ajustarea vitezei motoarelor 
 + 
 +=== Validarea funcționalităților:​ === 
 + 
 +  * **Testarea senzorilor**:​ Funcția ''​SerialLineAnalyzer()''​ permite monitorizarea în timp real 
 +  * **Calibrarea PID**: Constante ajustabile pentru fine-tuning 
 +  * **Debugging**:​ Output serial pentru verificarea valorilor 
 + 
 +==== 5. Mediul de dezvoltare utilizat ==== 
 + 
 +Pentru acest proiect am utilizat **CLion IDE** în combinație cu **PlatformIO**,​ o alegere motivată de următoarele avantaje: 
 + 
 +=== CLion IDE: === 
 +  * **IntelliSense avansat**: Autocompletare inteligentă și detecția erorilor în timp real 
 +  * **Debugging integrat**: Posibilitatea de debug pas cu pas pentru identificarea problemelor 
 +  * **Refactoring tools**: Restructurarea facilă a codului pentru optimizare 
 +  * **Git integration**:​ Control versiuni integrat pentru managementul modificărilor 
 + 
 +=== PlatformIO: === 
 +  * **Managementul dependențelor**:​ Gestionarea automată a bibliotecilor și framework-urilor 
 +  * **Suport multi-platformă**:​ Compatibilitate cu diverse tipuri de microcontrolere 
 +  * **Build system optimizat**:​ Compilare rapidă și eficientă 
 +  * **Library manager**: Acces facil la biblioteca vastă de componente Arduino 
 + 
 +=== Configurarea proiectului:​ === 
 +<code ini> 
 +; platformio.ini 
 +[env:uno] 
 +platform = atmelavr 
 +board = uno 
 +framework = arduino 
 +monitor_speed = 9600 
 +</​code>​ 
 + 
 +Această combinație oferă: 
 +  * **Productivitate crescută**:​ Mediu profesional de dezvoltare 
 +  * **Debugging eficient**: Identificarea rapidă a problemelor 
 +  * **Managementul dependencies**:​ Evitarea conflictelor de versiuni 
 +  * **Scalabilitate**:​ Posibilitatea de extindere pentru proiecte mai complexe 
 + 
 +==== 6. Calibrarea elementelor de senzoristica ==== 
 + 
 + 
 +=== Strategia de calibrare implementată:​ === 
 + 
 +  - **Maparea pozițiilor**:​ Fiecare combinație de senzori este mapată la o valoare specifică:​ 
 +    * Centru (00100): valoare 0 
 +    * Stânga extremă (10000): valoare -6 
 +    * Dreapta extremă (00001): valoare +6 
 + 
 +  - **Modificatorul nearLineModifier (0.50)**: 
 +    * Reduce sensibilitatea pentru pozițiile apropiate de centru 
 +    * Evită corecțiile bruște pentru deviații mici 
 + 
 +  - **Tratarea cazurilor speciale**:​ 
 +    * **Intersecții** (11111, 01110): Păstrarea ultimei valori valide 
 +    * **Curbe strânse** (11100, 00111): Valori extreme pentru rotire rapidă 
 + 
 +=== Procesul de calibrare: === 
 +<code cpp> 
 +// Testare individuală a senzorilor 
 +lineSensorModule.SerialLineAnalyzer("​every sensor"​);​ 
 + 
 +// Monitorizare completă 
 +lineSensorModule.SerialLineAnalyzer("​all"​);​ 
 +</​code>​ 
 + 
 +==== 7. Optimizări implementate ==== 
 + 
 +=== 7.1 Filtrul Low-Pass pe eroare === 
 +  * **Unde**: În funcția ''​PID()''​ 
 +  * **De ce**: Reducerea zgomotului de la senzori 
 +  * **Cum**: ''​error = error * 0.4 + input * 0.6;''​ 
 + 
 +=== 7.2 Limitarea integratorului === 
 +  * **Unde**: ''​errorInt = constrain(error + errorInt, -20, 20);''​ 
 +  * **De ce**: Prevenirea wind-up-ului integratorului 
 +  * **Cum**: Limitarea valorii cumulate între -20 și 20 
 + 
 +=== 7.3 Optimizarea structurilor === 
 +  * **Unde**: Structurile ''​motor''​ și ''​lineSensor''​ 
 +  * **De ce**: Organizarea logică a codului și reutilizarea 
 +  * **Cum**: Encapsularea funcționalităților în metode specifice 
 + 
 +=== 7.4 Maparea eficientă a puterii === 
 +  * **Unde**: Metoda ''​setPower()''​ din structura motor 
 +  * **De ce**: Conversie directă din procente în valori PWM 
 +  * **Cum**: Utilizarea funcției ''​map()''​ și ''​constrain()''​ 
 + 
 +=== 7.5 Detecția inteligentă a lipsei liniei === 
 +  * **Unde**: Metoda ''​noDetection()''​ 
 +  * **De ce**: Păstrarea comportamentului predictibil când linia se pierde 
 +  * **Cum**: Returnarea ultimei valori valide în loc de 0 
 + 
 +==== Concluzii ==== 
 + 
 +Proiectul implementează un sistem robust de urmărire a liniei cu: 
 +  * **Control PID optimizat** cu filtru low-pass 
 +  * **Senzoristica redundantă** cu 5 senzori 
 +  * **Gestionarea cazurilor speciale** pentru intersecții și curbe 
 +  * **Arhitectură modulară** pentru ușurința în dezvoltare și debug 
 + 
 +Rezultatul este un robot stabil și predictibil,​ capabil să urmărească trasee complexe cu precizie ridicată. 
 + 
 +<code cpp> 
 +#include <​Arduino.h>​ 
 +double error; 
 +double lastError;​ 
 +double errorDiff;​ 
 +double errorInt; 
 + 
 +#define KP 17.00 
 +#define KD 600.00 
 +#define KI 0.00 
 +#define baseSpeed 40.00 
 +#define nearLineModifier 0.50 
 + 
 +struct motor { 
 +    int motorControllerForwardPIN{};​ 
 +    int motorControllerBackwardPIN{};​ 
 +    int motorControllerSpeedPIN{};​ 
 +    int internalPower{};​ 
 +    int mappedPower{};​ 
 +    bool internalOrientation = false; 
 + 
 +    void setOrientation(const bool orientation) { 
 +        internalOrientation = orientation;​ 
 +    } 
 + 
 +    void setPins(const int forwardPIN, const int backwardPIN,​ const int speedPWMPIN) { 
 +        motorControllerForwardPIN = forwardPIN;​ 
 +        motorControllerBackwardPIN = backwardPIN;​ 
 +        motorControllerSpeedPIN = speedPWMPIN;​ 
 +        pinMode(motorControllerForwardPIN,​ OUTPUT); 
 +        pinMode(motorControllerBackwardPIN,​ OUTPUT); 
 +        pinMode(motorControllerSpeedPIN,​ OUTPUT); 
 +    } 
 + 
 +    void setPower(int power) { 
 +        power = constrain(power,​ -100, 100); 
 +        mappedPower = power; 
 +        if (internalOrientation) 
 +            power *= -1; 
 +        internalPower = static_cast<​int>​(map(abs(power),​ 0, 100, 0, 255)); 
 +        if (power < 0) { 
 +            digitalWrite(motorControllerForwardPIN,​ LOW); 
 +            digitalWrite(motorControllerBackwardPIN,​ HIGH); 
 +        } else { 
 +            digitalWrite(motorControllerBackwardPIN,​ LOW); 
 +            digitalWrite(motorControllerForwardPIN,​ HIGH); 
 +        } 
 +        analogWrite(motorControllerSpeedPIN,​ internalPower);​ 
 +    } 
 +}; 
 + 
 +motor Right; 
 +motor Left; 
 + 
 +struct lineSensor { 
 +    bool leftValue = false; 
 +    bool leftCenterValue = false; 
 +    bool centerValue = false; 
 +    bool rightCenterValue = false; 
 +    bool rightValue = false; 
 + 
 +    double globalLineValue = 0; 
 +    String lineOutput;​ 
 +    int lastGlobalLineValue = 0; 
 +    int leftSensorPIN = 0; 
 +    int leftCenterSensorPIN = 0; 
 +    int centerSensorPIN = 0; 
 +    int rightCenterSensorPIN = 0; 
 +    int rightSensorPIN = 0; 
 + 
 +    void setPins(const int left, const int leftCenter, const int center, const int rightCenter,​ const int right) { 
 +        leftSensorPIN = left; 
 +        leftCenterSensorPIN = leftCenter;​ 
 +        centerSensorPIN = center; 
 +        rightCenterSensorPIN = rightCenter;​ 
 +        rightSensorPIN = right; 
 +        pinMode(leftSensorPIN,​ INPUT); 
 +        pinMode(leftCenterSensorPIN,​ INPUT); 
 +        pinMode(centerSensorPIN,​ INPUT); 
 +        pinMode(rightCenterSensorPIN,​ INPUT); 
 +        pinMode(rightSensorPIN,​ INPUT); 
 +    } 
 + 
 +    void LineValueAnalyzer() { 
 +        if (!noDetection()) 
 +            lastGlobalLineValue = static_cast<​int>​(globalLineValue);​ 
 +        leftValue = !digitalRead(leftSensorPIN);​ 
 +        leftCenterValue = !digitalRead(leftCenterSensorPIN);​ 
 +        centerValue = !digitalRead(centerSensorPIN);​ 
 +        rightCenterValue = !digitalRead(rightCenterSensorPIN);​ 
 +        rightValue = !digitalRead(rightSensorPIN);​ 
 +        lineOutput = leftValue + static_cast<​String>​(leftCenterValue) + static_cast<​String>​(centerValue) + static_cast<​ 
 +                         ​String>​(rightCenterValue) + static_cast<​String>​(rightValue);​ 
 + 
 +        if (lineOutput == "​10000"​) { 
 +            globalLineValue = -6; // -5 
 +        } else if (lineOutput == "​11000"​) { 
 +            globalLineValue = -5; // -3 
 +        } else if (lineOutput == "​01000"​) { 
 +            globalLineValue = -2 * nearLineModifier;​ 
 +        } else if (lineOutput == "​01100"​) { 
 +            globalLineValue = -1 * nearLineModifier;​ 
 +        } else if (lineOutput == "​00100"​) { 
 +            globalLineValue = 0; 
 +        } else if (lineOutput == "​00110"​) { 
 +            globalLineValue = 1 * nearLineModifier;​ 
 +        } else if (lineOutput == "​00010"​) { 
 +            globalLineValue = 2 * nearLineModifier;​ 
 +        } else if (lineOutput == "​00011"​) { 
 +            globalLineValue = 5; // 3 
 +        } else if (lineOutput == "​00001"​) { 
 +            globalLineValue = 6; // 5 
 +        } else if (lineOutput == "​11100"​ || lineOutput == "​11110"​ || lineOutput == "​10100"​ || lineOutput == "​10010"​) { 
 +            globalLineValue = -6; 
 +        } else if (lineOutput == "​00111"​ || lineOutput == "​01111"​ || lineOutput == "​00101"​ || lineOutput == "​01001"​) { 
 +            globalLineValue = 6; 
 +        } else if (lineOutput == "​11111"​ || lineOutput == "​01110"​ || lineOutput == "​01010"​) { 
 +            globalLineValue = lastGlobalLineValue;​ 
 +        } 
 +    } 
 + 
 +    bool noDetection() { 
 +        leftValue = digitalRead(leftSensorPIN);​ 
 +        leftCenterValue = digitalRead(leftCenterSensorPIN);​ 
 +        centerValue = digitalRead(centerSensorPIN);​ 
 +        rightCenterValue = digitalRead(rightCenterSensorPIN);​ 
 +        rightValue = digitalRead(rightSensorPIN);​ 
 + 
 +        if (leftValue == 1 && leftCenterValue == 1 && centerValue == 1 && rightCenterValue == 1 && rightValue == 1) 
 +            return true; 
 + 
 +        return false; 
 +    } 
 + 
 +    int returnLineValue() { 
 +        if (noDetection()) { 
 +            Serial.println(lastGlobalLineValue);​ 
 +            return lastGlobalLineValue;​ 
 +        } 
 + 
 +        Serial.println(globalLineValue);​ 
 +        return static_cast<​int>​(globalLineValue);​ 
 +    } 
 + 
 +    void SerialLineAnalyzer(const String &​command) { 
 +        LineValueAnalyzer();​ 
 + 
 +        if (command == "every sensor"​) { 
 +            Serial.print(leftValue);​ 
 +            Serial.print("​ "); 
 +            Serial.print(leftCenterValue);​ 
 +            Serial.print("​ "); 
 +            Serial.print(centerValue);​ 
 +            Serial.print("​ "); 
 +            Serial.print(rightCenterValue);​ 
 +            Serial.print("​ "); 
 +            Serial.print(rightValue);​ 
 +            Serial.print("​\n"​);​ 
 +        } 
 + 
 +        if (command == "​all"​) { 
 +            Serial.print(leftValue);​ 
 +            Serial.print("​ "); 
 +            Serial.print(leftCenterValue);​ 
 +            Serial.print("​ "); 
 +            Serial.print(centerValue);​ 
 +            Serial.print("​ "); 
 +            Serial.print(rightCenterValue);​ 
 +            Serial.print("​ "); 
 +            Serial.print(rightValue);​ 
 +            Serial.print(" ​      "​);​ 
 +            Serial.print(globalLineValue);​ 
 +            Serial.print("​ "); 
 +        } 
 +        if (command == "​value"​) { 
 +            Serial.print(globalLineValue);​ 
 +            Serial.print("​\n"​);​ 
 +        } 
 +    } 
 +}; 
 + 
 +lineSensor lineSensorModule;​ 
 + 
 +void setup() { 
 +    Serial.begin(9600);​ 
 +    Right.setOrientation(false);​ 
 +    Left.setOrientation(true);​ 
 +    Right.setPins(4,​ 5, 3); 
 +    Left.setPins(7,​ 8, 6); 
 +    lineSensorModule.setPins(9,​ 10, 11, 12, 13); 
 +
 + 
 +double output; 
 + 
 +double PID(int input) { 
 +    error = error * 0.4 + input * 0.6; 
 +    errorDiff = error - lastError;​ 
 +    errorInt = constrain(error + errorInt, -20, 20); 
 +    output = KP * error + KD * errorDiff + KI * errorInt; 
 +    lastError = error; 
 + 
 +    return output; 
 +
 + 
 +void loop() { 
 +    lineSensorModule.LineValueAnalyzer();​ 
 + 
 +    Left.setPower(baseSpeed - PID(lineSensorModule.returnLineValue()));​ 
 +    Right.setPower(baseSpeed + PID(lineSensorModule.returnLineValue()));​ 
 +
 + 
 +</​code>​ 
 +===== Download ===== 
 + 
 +{{:​pm:​prj2025:​vradulescu:​linefollower.zip|}} 
 + 
 +===== Rezultate Obţinute ​=====
  
-<​note>​ +{{:​pm:​prj2025:​vradulescu:​linefollower.gif?800|}}
-Listă cu documente, datasheet-uri,​ resurse Internet folosite, eventual grupate pe **Resurse Software** şi **Resurse Hardware**. +
-</​note>​+
  
-<​html><​class="​media mediafile mf_pdf"​ href="?​do=export_pdf">​Export to PDF</​a></​html>​+  * Robotul urmărește linia neagră pe fundal alb 
 +  * La intersecții,​ utilizează ultima valoare validă pentru ​continua 
 +  * Viteza de bază este 40% din capacitatea maximă pentru stabilitate 
 +  * Corecțiile PID sunt vizibile prin mișcările de ajustare ale robotului
  
pm/prj2025/vradulescu/mihnea.stamatie.1747955293.txt.gz · Last modified: 2025/05/23 02:08 by mihnea.stamatie
CC Attribution-Share Alike 3.0 Unported
www.chimeric.de Valid CSS Driven by DokuWiki do yourself a favour and use a real browser - get firefox!! Recent changes RSS feed Valid XHTML 1.0