From 17da5b4d22a918314f701573ef5302d30cae5505 Mon Sep 17 00:00:00 2001 From: mariosantos-05 Date: Sun, 25 May 2025 14:55:21 -0300 Subject: [PATCH 01/13] Get and set RPM methods --- Test_motor/src/MotorDC.cpp | 26 +++++++++----------------- 1 file changed, 9 insertions(+), 17 deletions(-) diff --git a/Test_motor/src/MotorDC.cpp b/Test_motor/src/MotorDC.cpp index 3ddd764..551e612 100644 --- a/Test_motor/src/MotorDC.cpp +++ b/Test_motor/src/MotorDC.cpp @@ -53,15 +53,8 @@ void MotorDC::ligar_motor(int direcao, int pwmVal){ // Função para ler o encoder do motor void MotorDC::ler_encoder(){ - //fabs(rps*60)<1?posi+=dir:(rps*60)>1?posi++:posi--; - - if(fabs(rps * 60) < 1) - posi += dir; - else if ((rps * 60) > 1) - posi++; - else - posi--; - + posi++; + } // Função para resetar o encoder do motor @@ -72,11 +65,11 @@ void MotorDC::resetar_encoder() voltas = 0; } -void MotorDC::andar_reto(int velocidade_rpm){ +void MotorDC::set_RPM(int velocidade_rpm){ // atualizar_tempo(); - rpm_referencia = velocidade_rpm; // Velocidade de referência + rpm_referencia = fabs(velocidade_rpm); // Velocidade de referência volatile double posi_atual = 0; // posição atual do encoder noInterrupts(); // desabilita interrupções @@ -87,6 +80,7 @@ void MotorDC::andar_reto(int velocidade_rpm){ voltas = posi_atual / encoder_volta; // calcula o número de voltas do motor rps = (voltas - voltas_anterior) / dt; // calcula a velocidade do motor em rps + double rpm = rps*60; double e = rpm_referencia - (rps * 60); // calcula o erro da velocidade em rpm @@ -102,17 +96,14 @@ void MotorDC::andar_reto(int velocidade_rpm){ float pwmVal = fabs(u); // valor do pwm que será enviado ao motor - if (pwmVal > 255) // Limita o valor do pwm para 255 - { - pwmVal = 255; - } + pwmVal = constrain(pwmVal, 0, 255); // Limita o valor do pwm entre 0 e 255 // Define a direção do motor com base no valor de u - if (u > 0) + if (velocidade_rpm > 0) { dir = 1; } - else if (u < 0) + else if (velocidade_rpm < 0) { dir = -1; } @@ -129,4 +120,5 @@ void MotorDC::andar_reto(int velocidade_rpm){ eprev = e; + } \ No newline at end of file From ae2bb9086f628215a5fe35608adedf4e5bc64e72 Mon Sep 17 00:00:00 2001 From: mariosantos-05 Date: Sun, 25 May 2025 14:55:50 -0300 Subject: [PATCH 02/13] Fix: dt variable --- Test_motor/src/Tempo.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Test_motor/src/Tempo.cpp b/Test_motor/src/Tempo.cpp index 5911a4e..dae5c6f 100644 --- a/Test_motor/src/Tempo.cpp +++ b/Test_motor/src/Tempo.cpp @@ -1,8 +1,8 @@ #include "Tempo.h" -extern unsigned long T; -extern unsigned long prevT; -extern double dt; +unsigned long T; +unsigned long prevT; +double dt; void atualizar_tempo() From ba33fee73f843d54619ffc39601c784dc0b0c722 Mon Sep 17 00:00:00 2001 From: mariosantos-05 Date: Sun, 25 May 2025 14:57:29 -0300 Subject: [PATCH 03/13] Refact: MotorDC --- Test_motor/include/MotorDC.h | 12 +++++++----- Test_motor/include/Pins.h | 16 ++++++++-------- 2 files changed, 15 insertions(+), 13 deletions(-) diff --git a/Test_motor/include/MotorDC.h b/Test_motor/include/MotorDC.h index 16387d0..69ad8a9 100644 --- a/Test_motor/include/MotorDC.h +++ b/Test_motor/include/MotorDC.h @@ -15,13 +15,15 @@ class MotorDC{ void ligar_motor(int direcao, int pwmVal); void ler_encoder(); void resetar_encoder(); - void andar_reto(int velocidade_rpm); + void set_RPM(int velocidade_rpm); volatile double posi; // posição do motor em ticks do encoder double rps = 0; // velocidade ATUAL do motor em rotações por segundo - int encoder_volta; // valor de encoder referente a uma volta completa da roda - double comprimento_roda = 2 * M_PI * 6.272; //TODO: medir o raio da roda real + double get_rpm() { return (rps*60); } // função para obter a velocidade do motor em rpm + - private: + private: + int encoder_volta; // valor de encoder referente a uma volta completa da roda + double comprimento_roda = 2 * M_PI * 0.016; int ENCA; // Cabo amarelo int ENCB; // Cabo branco int PWM; @@ -37,7 +39,7 @@ class MotorDC{ float eprev = 0; float eintegral = 0; // erro acumulado pro cálculo do ki int dir = 1; // 1 para frente, -1 para trás (pelo menos essa é a ideia) - + }; #endif \ No newline at end of file diff --git a/Test_motor/include/Pins.h b/Test_motor/include/Pins.h index 8049845..7a89eb7 100644 --- a/Test_motor/include/Pins.h +++ b/Test_motor/include/Pins.h @@ -6,20 +6,20 @@ // Pinos dos motores -#define ENCA1 2 -#define ENCB1 4 -#define IN2 13 -#define IN1 15 +#define ENCA1 15 +#define ENCB1 2 +#define IN2 26 +#define IN1 25 -#define ENCA2 5 +#define ENCA2 4 #define ENCB2 18 #define IN4 14 #define IN3 12 -#define LEDON 33 +//#define LEDON 33 -#define D1 26 -#define D2 25 +#define D1 33 +#define D2 32 #define D3 16 #define D4 17 #define D5 19 From 7790d40c81f93453f9c06c4248a676db8a90069c Mon Sep 17 00:00:00 2001 From: mariosantos-05 Date: Sun, 25 May 2025 14:57:57 -0300 Subject: [PATCH 04/13] Refact: main, test functions PID --- Test_motor/platformio.ini | 8 +-- Test_motor/src/main.cpp | 128 +++++++++++++++++++------------------- 2 files changed, 64 insertions(+), 72 deletions(-) diff --git a/Test_motor/platformio.ini b/Test_motor/platformio.ini index 0aa6fde..680af93 100644 --- a/Test_motor/platformio.ini +++ b/Test_motor/platformio.ini @@ -18,12 +18,6 @@ platform = espressif32 board = esp32dev framework = arduino -monitor_speed = 9600 +monitor_speed = 115200 upload_protocol = esptool - - -;Comando Mario Ubuntu -;sudo modprobe -r usbserial -;sudo modprobe usbserial -;sudo modprobe ch341 \ No newline at end of file diff --git a/Test_motor/src/main.cpp b/Test_motor/src/main.cpp index b3d74df..e0f0355 100644 --- a/Test_motor/src/main.cpp +++ b/Test_motor/src/main.cpp @@ -2,87 +2,85 @@ #include #include "MotorDC.h" #include "Pins.h" +#include "algorithm" // QTRSensors object QTRSensors qtr; // Motor objects -MotorDC MotorD(ENCA1, ENCB1, IN2, IN1); // Left motor -MotorDC MotorE(ENCA2, ENCB2, IN3, IN4); // Right motor +MotorDC MotorD(ENCA1, ENCB1, IN2, IN1); +MotorDC MotorE(ENCA2, ENCB2, IN3, IN4); +int maxRPM = 1100; // Maximum RPM for the motors +int minRPM = 216; // Minimum RPM for the motors TODO: test this with the motor loaded + const uint8_t SensorCount = 8; // Number of sensors uint16_t sensorValues[SensorCount]; // Array to store sensor values void setup() -{ - // Configure the LEDON pin - pinMode(LEDON, OUTPUT); - digitalWrite(LEDON, HIGH); // Turn on the IR LEDs - +{ + Serial.begin(115200); + delay(100); + + qtr.setTypeRC(); + qtr.setSensorPins((const uint8_t[]){D1, D2, D3, D4, D5, D6, D7, D8}, SensorCount); + + + //Hardcoded sensor values + const uint16_t minValues[SensorCount] = {100, 110, 120, 130, 140, 150, 160, 170}; + const uint16_t maxValues[SensorCount] = {900, 890, 880, 870, 860, 850, 840, 830}; + + std::copy(minValues, minValues + 8, qtr.calibrationOn.minimum); + std::copy(maxValues, maxValues + 8, qtr.calibrationOn.maximum); + qtr.calibrationOn.initialized = true; + MotorD.ligar_motor(0,0); MotorE.ligar_motor(0,0); + +} - // Configure the sensors on pins D1 to D8 - qtr.setTypeRC(); - qtr.setSensorPins((const uint8_t[]){D1, D2, D3, D4, D5, D6, D7, D8}, SensorCount); +void MOTORPID_TEST(int desiredSpeed, float kp, float kd, float ki){ + Serial.println("Motor PID test"); + // Modificar apenas KP, KD e KI. + // Não modificar o valor de ticks por volta, pois isso é calculado com base no encoder do motor. + MotorE.configurar(12.0, kp, kd, ki); + MotorD.configurar(12.0, kp, kd, ki); + + MotorD.set_RPM(desiredSpeed); + MotorE.set_RPM(desiredSpeed); + delay(100); + + Serial.print("Desidered RPM: " + desiredSpeed); + Serial.print(" Motor E RPM: " + String(MotorE.get_rpm())); + Serial.print(" Motor D RPM: " + String(MotorD.get_rpm()) + "\n"); - Serial.begin(9600); - //delay(2000); - - // Calibrate the sensors - Serial.println("Calibrating sensors..."); - for (uint16_t i = 0; i < 400; i++) - { - qtr.calibrate(); - delay(10); - } - Serial.println("Calibration complete."); } -// PID control variables -int error = 0; -int lastError = 0; // To store the previous error -float KP = 0.1; // Proportional gain -float KD = 5; // Derivative gain -int baseSpeed = 100; // Base motor speed - -void loop() -{ - // Read the line position (0 to 7000 for 8 sensors) - uint16_t position = qtr.readLineBlack(sensorValues); - - // Calculate the error (center is 3500 for 8 sensors) - error = position - 3500; - - // Calculate motor speed adjustments using proportional and derivative control - int motorSpeed = KP * error + KD * (error - lastError); - - // Update lastError for the next iteration - lastError = error; - - // Set motor speeds - int leftMotorSpeed = baseSpeed - motorSpeed; - int rightMotorSpeed = baseSpeed + motorSpeed; - - // Constrain motor speeds to valid range (0 to 255) - leftMotorSpeed = constrain(leftMotorSpeed, 0, 100); - rightMotorSpeed = constrain(rightMotorSpeed, 0, 100); - - // Drive the motors - MotorE.ligar_motor(-1, leftMotorSpeed); - MotorD.ligar_motor(-1, rightMotorSpeed); - - // Optional: Print debug information - Serial.print("Position: "); - Serial.print(position); - Serial.print(" Error: "); - Serial.print(error); - Serial.print(" Left Speed: "); - Serial.print(leftMotorSpeed); - Serial.print(" Right Speed: "); - Serial.println(rightMotorSpeed); - delay(10); // Small delay for stability - +int16_t prevError = 0; +float integral = 0; +void TEST_SENSOR(int baseRPM, float kp, float kd, float ki){ + uint16_t position = qtr.readLineWhite(sensorValues); + int16_t error = position - (SensorCount - 1) / 2; + + integral += error; + int16_t derivative = error - prevError; + + int correction = kp * error + ki * integral + kd * derivative; + prevError = error; + + int rpmLeft = constrain(baseRPM - correction, minRPM, maxRPM); + int rpmRight = constrain(baseRPM + correction, minRPM, maxRPM); + + MotorD.set_RPM(rpmRight); + MotorE.set_RPM(rpmLeft); + Serial.print("Left RPM: " + String(rpmLeft)); + Serial.print(" Right RPM: " + String(rpmRight)); + Serial.print(" Error: " + String(error)); + Serial.print(" Correction: " + String(correction)); +} +void loop(){ + TEST_SENSOR(500, 0.1, 0.1, 0.1); + delay(100); } \ No newline at end of file From 46f99df4a3e6e0462beb4beb53940cb035272452 Mon Sep 17 00:00:00 2001 From: mariosantos-05 Date: Sun, 25 May 2025 14:58:35 -0300 Subject: [PATCH 05/13] Parcial PD --- Test_motor/src/main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Test_motor/src/main.cpp b/Test_motor/src/main.cpp index e0f0355..4d1b61f 100644 --- a/Test_motor/src/main.cpp +++ b/Test_motor/src/main.cpp @@ -81,6 +81,6 @@ void TEST_SENSOR(int baseRPM, float kp, float kd, float ki){ } void loop(){ - TEST_SENSOR(500, 0.1, 0.1, 0.1); + TEST_SENSOR(500, 0.1, 0.1, 5); delay(100); } \ No newline at end of file From 0bc6a7ea2829e06c7be6c8b0cd3589d90b4c0b60 Mon Sep 17 00:00:00 2001 From: mariosantos-05 Date: Mon, 26 May 2025 15:58:03 -0300 Subject: [PATCH 06/13] Fix of Tempo and DC motor. As well as hardcode values aplication --- Test_motor/include/MotorDC.h | 4 +-- Test_motor/include/Tempo.h | 23 +++++++----- Test_motor/src/MotorDC.cpp | 68 +++++++++++++----------------------- Test_motor/src/Tempo.cpp | 22 +++++++----- Test_motor/src/main.cpp | 30 ++++++++++------ 5 files changed, 72 insertions(+), 75 deletions(-) diff --git a/Test_motor/include/MotorDC.h b/Test_motor/include/MotorDC.h index 69ad8a9..c9c3fe4 100644 --- a/Test_motor/include/MotorDC.h +++ b/Test_motor/include/MotorDC.h @@ -22,8 +22,9 @@ class MotorDC{ private: + Tempo tempo; int encoder_volta; // valor de encoder referente a uma volta completa da roda - double comprimento_roda = 2 * M_PI * 0.016; + double comprimento_roda = 2 * M_PI * 0.000000016; int ENCA; // Cabo amarelo int ENCB; // Cabo branco int PWM; @@ -35,7 +36,6 @@ class MotorDC{ float ki; // constante integral do controle PID float kd; // constante derivativa do controle PID int rpm_referencia; // velocidade desejada do motor, velocidade que ele buscará alcançar - double rpm_max = 87; // velocidade máxima do motor (apenas por curiosidade, usar caso seja necessário) float eprev = 0; float eintegral = 0; // erro acumulado pro cálculo do ki int dir = 1; // 1 para frente, -1 para trás (pelo menos essa é a ideia) diff --git a/Test_motor/include/Tempo.h b/Test_motor/include/Tempo.h index 5665081..f16d89d 100644 --- a/Test_motor/include/Tempo.h +++ b/Test_motor/include/Tempo.h @@ -1,13 +1,18 @@ -#ifndef Tempo_h -#define Tempo_h +// Tempo.h +#ifndef TEMPO_H +#define TEMPO_H -#include "Arduino.h" +#include -//* Este arquivo contém a declaração das variáveis de tempo utilizadas no projeto -extern unsigned long T; -extern unsigned long prevT; -extern double dt; +class Tempo { + private: + unsigned long prevMicros; + double dt; // em segundos -void atualizar_tempo(); + public: + Tempo(); // Construtor + void atualizar(); // Atualiza o tempo atual e calcula o dt + double getDeltaTime(); // Retorna o dt atual +}; -#endif \ No newline at end of file +#endif diff --git a/Test_motor/src/MotorDC.cpp b/Test_motor/src/MotorDC.cpp index 551e612..d7984af 100644 --- a/Test_motor/src/MotorDC.cpp +++ b/Test_motor/src/MotorDC.cpp @@ -16,6 +16,7 @@ MotorDC::MotorDC(const int ENCA, const int ENCB, const int IN1, const int IN2) pinMode(ENCA, INPUT); pinMode(IN1, OUTPUT); pinMode(IN2, OUTPUT); + } @@ -52,7 +53,6 @@ void MotorDC::ligar_motor(int direcao, int pwmVal){ // Função para ler o encoder do motor void MotorDC::ler_encoder(){ - posi++; } @@ -64,61 +64,41 @@ void MotorDC::resetar_encoder() eintegral = 0; voltas = 0; } - void MotorDC::set_RPM(int velocidade_rpm){ - // atualizar_tempo(); + //Serial.print("encoder_volta: "); Serial.println(encoder_volta); - rpm_referencia = fabs(velocidade_rpm); // Velocidade de referência + tempo.atualizar(); + double dt = tempo.getDeltaTime(); - volatile double posi_atual = 0; // posição atual do encoder - noInterrupts(); // desabilita interrupções - posi_atual = posi; // atualiza a posição atual do encoder - interrupts(); // reabilita interrupções + rpm_referencia = fabs(velocidade_rpm); - voltas_anterior = voltas; // atualiza o número de voltas anterior + volatile double posi_atual = 0; + noInterrupts(); + posi_atual = posi; + interrupts(); - voltas = posi_atual / encoder_volta; // calcula o número de voltas do motor - rps = (voltas - voltas_anterior) / dt; // calcula a velocidade do motor em rps - double rpm = rps*60; + voltas_anterior = voltas; + voltas = posi_atual / encoder_volta; + rps = (voltas - voltas_anterior) / dt; + rps = rps/100; - double e = rpm_referencia - (rps * 60); // calcula o erro da velocidade em rpm + double rpm = rps * 60; + double e = rpm_referencia - rpm; float p = kp * e; - eintegral += e; + float i = ki * eintegral * dt; + float d = kd * (e - eprev) / dt; + float u = p + i + d; - float i = ki * eintegral*dt; - - float d = kd * ((e - eprev) / dt); - - float u = p + i + d; //p + (ki * eintegral*dt) + d; + float pwmVal = constrain(fabs(u), 0, 255); - float pwmVal = fabs(u); // valor do pwm que será enviado ao motor - - pwmVal = constrain(pwmVal, 0, 255); // Limita o valor do pwm entre 0 e 255 - - // Define a direção do motor com base no valor de u - if (velocidade_rpm > 0) - { - dir = 1; - } - else if (velocidade_rpm < 0) - { - dir = -1; - } - else - { - dir = 0; - } - - if (velocidade_rpm != 0) { - ligar_motor(dir, pwmVal); - } else { - ligar_motor(0, 0); - } + if (velocidade_rpm > 0) dir = 1; + else if (velocidade_rpm < 0) dir = -1; + else dir = 0; + ligar_motor(dir, pwmVal); eprev = e; - -} \ No newline at end of file +} diff --git a/Test_motor/src/Tempo.cpp b/Test_motor/src/Tempo.cpp index dae5c6f..f5f2c50 100644 --- a/Test_motor/src/Tempo.cpp +++ b/Test_motor/src/Tempo.cpp @@ -1,13 +1,17 @@ +// Tempo.cpp #include "Tempo.h" -unsigned long T; -unsigned long prevT; -double dt; +Tempo::Tempo() { + prevMicros = micros(); + dt = 0.0; +} +void Tempo::atualizar() { + unsigned long currentMicros = micros(); + dt = (currentMicros - prevMicros) / 1.0e6; // converte para segundos + prevMicros = currentMicros; +} -void atualizar_tempo() -{ - T = micros(); - dt = ((float) (T - prevT))/( 1.0e6 ); - prevT = T; -} \ No newline at end of file +double Tempo::getDeltaTime() { + return dt; +} diff --git a/Test_motor/src/main.cpp b/Test_motor/src/main.cpp index 4d1b61f..329a592 100644 --- a/Test_motor/src/main.cpp +++ b/Test_motor/src/main.cpp @@ -8,15 +8,17 @@ QTRSensors qtr; // Motor objects -MotorDC MotorD(ENCA1, ENCB1, IN2, IN1); -MotorDC MotorE(ENCA2, ENCB2, IN3, IN4); +MotorDC MotorE(ENCA1, ENCB1, IN2, IN1); +MotorDC MotorD(ENCA2, ENCB2, IN3, IN4); int maxRPM = 1100; // Maximum RPM for the motors int minRPM = 216; // Minimum RPM for the motors TODO: test this with the motor loaded - const uint8_t SensorCount = 8; // Number of sensors uint16_t sensorValues[SensorCount]; // Array to store sensor values +void encoder_callback() { + MotorD.ler_encoder(); +} void setup() { @@ -26,18 +28,24 @@ void setup() qtr.setTypeRC(); qtr.setSensorPins((const uint8_t[]){D1, D2, D3, D4, D5, D6, D7, D8}, SensorCount); - //Hardcoded sensor values const uint16_t minValues[SensorCount] = {100, 110, 120, 130, 140, 150, 160, 170}; const uint16_t maxValues[SensorCount] = {900, 890, 880, 870, 860, 850, 840, 830}; + qtr.calibrationOn.minimum = new uint16_t[SensorCount]; + qtr.calibrationOn.maximum = new uint16_t[SensorCount]; + + qtr.calibrationOn.initialized = true; std::copy(minValues, minValues + 8, qtr.calibrationOn.minimum); std::copy(maxValues, maxValues + 8, qtr.calibrationOn.maximum); - qtr.calibrationOn.initialized = true; + attachInterrupt(digitalPinToInterrupt(ENCB1), encoder_callback, RISING); + + MotorD.configurar(12.0, 1.0, 0.0, 0.0); // Configure MotorD with ticks per revolution and PID constants + MotorE.configurar(12.0, 1.0, 0.0, 0.0); // Configure MotorE with ticks per revolution and PID constants + MotorD.ligar_motor(0,0); MotorE.ligar_motor(0,0); - } void MOTORPID_TEST(int desiredSpeed, float kp, float kd, float ki){ @@ -53,7 +61,7 @@ void MOTORPID_TEST(int desiredSpeed, float kp, float kd, float ki){ Serial.print("Desidered RPM: " + desiredSpeed); Serial.print(" Motor E RPM: " + String(MotorE.get_rpm())); - Serial.print(" Motor D RPM: " + String(MotorD.get_rpm()) + "\n"); + Serial.println(" Motor D RPM: " + String(MotorD.get_rpm()) + "\n"); } @@ -77,10 +85,10 @@ void TEST_SENSOR(int baseRPM, float kp, float kd, float ki){ Serial.print("Left RPM: " + String(rpmLeft)); Serial.print(" Right RPM: " + String(rpmRight)); Serial.print(" Error: " + String(error)); - Serial.print(" Correction: " + String(correction)); + Serial.println(" Correction: " + String(correction)); } + void loop(){ - TEST_SENSOR(500, 0.1, 0.1, 5); - delay(100); -} \ No newline at end of file + +} From 5819d64bfb0e34514ac1816ef27083b19e56328c Mon Sep 17 00:00:00 2001 From: Quilherpreto <231011391@aluno.unb.br> Date: Thu, 29 May 2025 19:49:21 -0300 Subject: [PATCH 07/13] =?UTF-8?q?teste=20de=20integra=C3=A7=C3=A3o=20entre?= =?UTF-8?q?=20o=20PD=20e=20o=20PID?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Test_motor/include/MotorDC.h | 1 - Test_motor/include/Pins.h | 2 +- Test_motor/src/main.cpp | 127 +++++++++++++++++++++-------------- 3 files changed, 78 insertions(+), 52 deletions(-) diff --git a/Test_motor/include/MotorDC.h b/Test_motor/include/MotorDC.h index c9c3fe4..fdf8c39 100644 --- a/Test_motor/include/MotorDC.h +++ b/Test_motor/include/MotorDC.h @@ -20,7 +20,6 @@ class MotorDC{ double rps = 0; // velocidade ATUAL do motor em rotações por segundo double get_rpm() { return (rps*60); } // função para obter a velocidade do motor em rpm - private: Tempo tempo; int encoder_volta; // valor de encoder referente a uma volta completa da roda diff --git a/Test_motor/include/Pins.h b/Test_motor/include/Pins.h index 7a89eb7..6df788c 100644 --- a/Test_motor/include/Pins.h +++ b/Test_motor/include/Pins.h @@ -16,7 +16,7 @@ #define IN4 14 #define IN3 12 -//#define LEDON 33 +#define LEDON 33 #define D1 33 #define D2 32 diff --git a/Test_motor/src/main.cpp b/Test_motor/src/main.cpp index 329a592..f6886d0 100644 --- a/Test_motor/src/main.cpp +++ b/Test_motor/src/main.cpp @@ -4,91 +4,118 @@ #include "Pins.h" #include "algorithm" -// QTRSensors object +// QTRSensors objeto QTRSensors qtr; -// Motor objects +// OAtivando Objetos do nosso motor MotorDC MotorE(ENCA1, ENCB1, IN2, IN1); MotorDC MotorD(ENCA2, ENCB2, IN3, IN4); -int maxRPM = 1100; // Maximum RPM for the motors -int minRPM = 216; // Minimum RPM for the motors TODO: test this with the motor loaded +int maxRPM = 1000; // RPM máximo para os motores +int minRPM = 216; // RPM mínimo para os motores (isso considerando que o nosso pwm mín fosse 50) + +const int MAX_SPEED_STRAIGHT = 100; //tranformar (255)PWM ==> RPM(1000) +const int MIN_SPEED_CURVE = 35; //tranformar (255)PWM ==> RPM(1000) +const int ERROR_THRESHOLD_MAX_REDUCTION = 50; //tranformar (255)PWM ==> RPM(1000) + +// Variáveis do controle PID DOS SENSORES +int error = 0; +int lastError = 0; +float KPs= 2; // Ganho pra curvas! 5.8 +float KDs = 2.8; // Ganho para suavizar as curvas! +float KIs = 0.0; // Ganho para suavizar as retas! (Não utilizado, efetivamente um PD) +// int baseSpeed = 100; // Esta será substituída pela velocidade dinâmica const uint8_t SensorCount = 8; // Number of sensors uint16_t sensorValues[SensorCount]; // Array to store sensor values +//esta função lê os valores retornados dos encoderes(pode ser útil para definir o ticks por volta) void encoder_callback() { MotorD.ler_encoder(); + MotorE.ler_encoder(); } void setup() { + + pinMode(LEDON, OUTPUT); + digitalWrite(LEDON, HIGH); //não sei ainda o que fazer com isso aqui, antes ia agora nn vai. + Serial.begin(115200); delay(100); qtr.setTypeRC(); qtr.setSensorPins((const uint8_t[]){D1, D2, D3, D4, D5, D6, D7, D8}, SensorCount); - //Hardcoded sensor values - const uint16_t minValues[SensorCount] = {100, 110, 120, 130, 140, 150, 160, 170}; - const uint16_t maxValues[SensorCount] = {900, 890, 880, 870, 860, 850, 840, 830}; - - qtr.calibrationOn.minimum = new uint16_t[SensorCount]; - qtr.calibrationOn.maximum = new uint16_t[SensorCount]; - - qtr.calibrationOn.initialized = true; - std::copy(minValues, minValues + 8, qtr.calibrationOn.minimum); - std::copy(maxValues, maxValues + 8, qtr.calibrationOn.maximum); - + // Calibração dos sensores, se quiser pode trocar por calibração manual. Porém ainda não testei o funcionamento do código PD com isto. + Serial.println("Calibrando sensores..."); + for (uint16_t i = 0; i < 400; i++) + { + qtr.calibrate(); + delay(10); + } + Serial.println("Calibração concluída."); + Serial.println("------------------------------------"); + Serial.println("Iniciando loop principal..."); + + //Ativação das portas de interrupção dos encoderes dos nossos motores. attachInterrupt(digitalPinToInterrupt(ENCB1), encoder_callback, RISING); + attachInterrupt(digitalPinToInterrupt(ENCB2), encoder_callback, RISING); - MotorD.configurar(12.0, 1.0, 0.0, 0.0); // Configure MotorD with ticks per revolution and PID constants - MotorE.configurar(12.0, 1.0, 0.0, 0.0); // Configure MotorE with ticks per revolution and PID constants + MotorD.configurar(12.0, 1.0, 0.0, 0.0); // Constantes PID da VELOCIADE DOS MOTORES (NÃO É DOS SENSORES) PARA O MOTOR DIREITO + MotorE.configurar(12.0, 1.0, 0.0, 0.0); // Constantes PID da VELOCIADE DOS MOTORES (NÃO É DOS SENSORES) PARA O MOTOR ESQUERDO + //isso é opcional, é só para ter certeza de que nossos motores ligaram. MotorD.ligar_motor(0,0); MotorE.ligar_motor(0,0); } -void MOTORPID_TEST(int desiredSpeed, float kp, float kd, float ki){ - Serial.println("Motor PID test"); - // Modificar apenas KP, KD e KI. - // Não modificar o valor de ticks por volta, pois isso é calculado com base no encoder do motor. - MotorE.configurar(12.0, kp, kd, ki); - MotorD.configurar(12.0, kp, kd, ki); +void loop(){ - MotorD.set_RPM(desiredSpeed); - MotorE.set_RPM(desiredSpeed); - delay(100); + // esta parte ativa a função de leitura de linhas pretas do nosso motor e retorna a posição de 0 a 7000 + // onde 0 é a extremidade esquerda e 7000 é a extremidade direita + uint16_t position = qtr.readLineBlack(sensorValues); - Serial.print("Desidered RPM: " + desiredSpeed); - Serial.print(" Motor E RPM: " + String(MotorE.get_rpm())); - Serial.println(" Motor D RPM: " + String(MotorD.get_rpm()) + "\n"); + // ffaz a média da faixa de 0 7000 da nossa variável posicional + error = position - 3500; -} + // esta parte e responsável pela deriavada, então é a variação do erro com o tempo + int derivative = error - lastError; -int16_t prevError = 0; -float integral = 0; -void TEST_SENSOR(int baseRPM, float kp, float kd, float ki){ - uint16_t position = qtr.readLineWhite(sensorValues); - int16_t error = position - (SensorCount - 1) / 2; + // Calcula a velocidade base atual com base no erro + int currentBaseSpeed; + long errorMagnitude = abs(error); - integral += error; - int16_t derivative = error - prevError; - int correction = kp * error + ki * integral + kd * derivative; - prevError = error; + // Mapeia a magnitude do erro para a velocidade base, reduzindo a velocidade máxima conforme o erro aumenta + // A velocidade base diminui linearmente de MAX_SPEED_STRAIGHT a MIN_SPEED_CURVE conforme o erro aumenta + currentBaseSpeed = map(errorMagnitude, 0, ERROR_THRESHOLD_MAX_REDUCTION, MAX_SPEED_STRAIGHT, MIN_SPEED_CURVE); + currentBaseSpeed = constrain(currentBaseSpeed, MIN_SPEED_CURVE, MAX_SPEED_STRAIGHT); - int rpmLeft = constrain(baseRPM - correction, minRPM, maxRPM); - int rpmRight = constrain(baseRPM + correction, minRPM, maxRPM); + //PID dos sensores com base no erro posicional + int correction = KPs * error + KDs * derivative; // + KI * (error + lastError) / 2; - MotorD.set_RPM(rpmRight); - MotorE.set_RPM(rpmLeft); - Serial.print("Left RPM: " + String(rpmLeft)); - Serial.print(" Right RPM: " + String(rpmRight)); - Serial.print(" Error: " + String(error)); - Serial.println(" Correction: " + String(correction)); -} + // Regula a velociada com base no PWM o nosso objetivo e deixar isso numa descala de 0 a 1000 que é em RPM + int leftSpeed = currentBaseSpeed + correction; + int rightSpeed = currentBaseSpeed - correction; + leftSpeed = constrain(leftSpeed, 0, MAX_SPEED_STRAIGHT); + rightSpeed = constrain(rightSpeed, 0, MAX_SPEED_STRAIGHT); -void loop(){ + lastError = error; + + //Antes de soltar este valor na função que seta o nosso PID precisamos passar este valor de PWM ==> RPM, pois a função opera em RPM e responde en PWM. + //Portanto, aqui está feita uma regra de três simples para Left e Right Speed. Ambas operam normalmente em PWM até chegarem aqui e serem passadas para RPM + // isso é um teste. Lembrando que esta relação foi feita considerando 1000 como nosso rpm max possível e 255 como sendo o PWM max possível + + int leftSpeedRPM = (leftSpeed*1000)/255; + int rightSpeedRPM = (rightSpeed*1000)/255; + + //Aplicar o leftSpeed e rightSpeed nos motores (EM RPM, esta função já converte para PWM) + + MotorD.set_RPM(rightSpeedRPM); + MotorE.set_RPM(leftSpeedRPM); + + //o delay ajuda a funcionar, sem ele o motor não faz nada. + delay(50); -} +} \ No newline at end of file From b920eb46bed999f427a19ab797448cb0a50bd67c Mon Sep 17 00:00:00 2001 From: Quilherpreto <231011391@aluno.unb.br> Date: Thu, 29 May 2025 19:50:24 -0300 Subject: [PATCH 08/13] =?UTF-8?q?resto=20da=20integra=C3=A7=C3=A3o?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Test_motor/src/main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Test_motor/src/main.cpp b/Test_motor/src/main.cpp index f6886d0..c8825e0 100644 --- a/Test_motor/src/main.cpp +++ b/Test_motor/src/main.cpp @@ -38,7 +38,7 @@ void setup() { pinMode(LEDON, OUTPUT); - digitalWrite(LEDON, HIGH); //não sei ainda o que fazer com isso aqui, antes ia agora nn vai. + digitalWrite(LEDON, HIGH); Serial.begin(115200); delay(100); From 7fc02e4f655307a54aa9341368ad0637de34d562 Mon Sep 17 00:00:00 2001 From: Quilherpreto <231011391@aluno.unb.br> Date: Sat, 7 Jun 2025 15:06:44 -0300 Subject: [PATCH 09/13] =?UTF-8?q?fazendo=20l=C3=B3gica=20para=20os=20senso?= =?UTF-8?q?res=20perif=C3=A9ricos?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Test_motor/include/Pins.h | 12 ++- Test_motor/src/main.cpp | 194 +++++++++++++++++++++----------------- 2 files changed, 112 insertions(+), 94 deletions(-) diff --git a/Test_motor/include/Pins.h b/Test_motor/include/Pins.h index 6df788c..946e63b 100644 --- a/Test_motor/include/Pins.h +++ b/Test_motor/include/Pins.h @@ -6,13 +6,13 @@ // Pinos dos motores -#define ENCA1 15 -#define ENCB1 2 +#define ENCA_E 15 +#define ENCB_E 2 #define IN2 26 -#define IN1 25 +#define IN1 25 -#define ENCA2 4 -#define ENCB2 18 +#define ENCA_D 4 +#define ENCB_D 18 #define IN4 14 #define IN3 12 @@ -26,6 +26,8 @@ #define D6 21 #define D7 22 #define D8 23 +#define D1_2 34 +#define D2_2 35 #endif \ No newline at end of file diff --git a/Test_motor/src/main.cpp b/Test_motor/src/main.cpp index c8825e0..0d698f6 100644 --- a/Test_motor/src/main.cpp +++ b/Test_motor/src/main.cpp @@ -1,121 +1,137 @@ #include #include -#include "MotorDC.h" -#include "Pins.h" -#include "algorithm" +#include "MotorDC.h" // Certifique-se que esta biblioteca e a MotorDC.cpp estão no seu projeto +#include "Pins.h" // Certifique-se que este arquivo com as definições dos pinos está no seu projeto -// QTRSensors objeto +// Objeto do sensor QTR QTRSensors qtr; +QTRSensors Perifericos; -// OAtivando Objetos do nosso motor -MotorDC MotorE(ENCA1, ENCB1, IN2, IN1); -MotorDC MotorD(ENCA2, ENCB2, IN3, IN4); -int maxRPM = 1000; // RPM máximo para os motores -int minRPM = 216; // RPM mínimo para os motores (isso considerando que o nosso pwm mín fosse 50) +// Objetos dos motores +//MotorDC MotorE(ENCA_E , ENCB_E , IN2, IN1); // Motor esquerdo +//MotorDC MotorD(ENCA_D , ENCB_D , IN3, IN4); // Motor direito -const int MAX_SPEED_STRAIGHT = 100; //tranformar (255)PWM ==> RPM(1000) -const int MIN_SPEED_CURVE = 35; //tranformar (255)PWM ==> RPM(1000) -const int ERROR_THRESHOLD_MAX_REDUCTION = 50; //tranformar (255)PWM ==> RPM(1000) +const uint8_t SensorCount1 = 8; // Número de sensores no array principal +uint16_t sensorValues1[SensorCount1]; // Valores dos sensores no array principal -// Variáveis do controle PID DOS SENSORES +const uint8_t SensorCount2 = 2; // Número de sensores no array periférico +uint16_t sensorValues2[SensorCount2]; // Valores dos sensores no array periférico + +int maxSpeed = 255; // Velocidade máxima em linha reta +int minSpeed = 35; // Velocidade mínima em curvas + +// Variáveis do controle PID int error = 0; int lastError = 0; -float KPs= 2; // Ganho pra curvas! 5.8 -float KDs = 2.8; // Ganho para suavizar as curvas! -float KIs = 0.0; // Ganho para suavizar as retas! (Não utilizado, efetivamente um PD) -// int baseSpeed = 100; // Esta será substituída pela velocidade dinâmica - -const uint8_t SensorCount = 8; // Number of sensors -uint16_t sensorValues[SensorCount]; // Array to store sensor values - -//esta função lê os valores retornados dos encoderes(pode ser útil para definir o ticks por volta) -void encoder_callback() { - MotorD.ler_encoder(); - MotorE.ler_encoder(); -} +float KP = 1.2; // 1.3 e base em 80 +float KD = 3; // Ganho para suavizar as curvas! +float KI = 0; // Ganho para suavizar as retas! (Não utilizado, efetivamente um PD) -void setup() -{ - pinMode(LEDON, OUTPUT); - digitalWrite(LEDON, HIGH); - Serial.begin(115200); - delay(100); - - qtr.setTypeRC(); - qtr.setSensorPins((const uint8_t[]){D1, D2, D3, D4, D5, D6, D7, D8}, SensorCount); - - // Calibração dos sensores, se quiser pode trocar por calibração manual. Porém ainda não testei o funcionamento do código PD com isto. - Serial.println("Calibrando sensores..."); - for (uint16_t i = 0; i < 400; i++) - { - qtr.calibrate(); - delay(10); - } - Serial.println("Calibração concluída."); - Serial.println("------------------------------------"); - Serial.println("Iniciando loop principal..."); +/* - //Ativação das portas de interrupção dos encoderes dos nossos motores. - attachInterrupt(digitalPinToInterrupt(ENCB1), encoder_callback, RISING); - attachInterrupt(digitalPinToInterrupt(ENCB2), encoder_callback, RISING); +Melhores runs: - MotorD.configurar(12.0, 1.0, 0.0, 0.0); // Constantes PID da VELOCIADE DOS MOTORES (NÃO É DOS SENSORES) PARA O MOTOR DIREITO - MotorE.configurar(12.0, 1.0, 0.0, 0.0); // Constantes PID da VELOCIADE DOS MOTORES (NÃO É DOS SENSORES) PARA O MOTOR ESQUERDO - //isso é opcional, é só para ter certeza de que nossos motores ligaram. - MotorD.ligar_motor(0,0); - MotorE.ligar_motor(0,0); -} +kp 1.2 kd 5.0 BS= 80 -void loop(){ - // esta parte ativa a função de leitura de linhas pretas do nosso motor e retorna a posição de 0 a 7000 - // onde 0 é a extremidade esquerda e 7000 é a extremidade direita - uint16_t position = qtr.readLineBlack(sensorValues); +kp 2 kd 10 bs= 100; - // ffaz a média da faixa de 0 7000 da nossa variável posicional - error = position - 3500; - // esta parte e responsável pela deriavada, então é a variação do erro com o tempo - int derivative = error - lastError; - // Calcula a velocidade base atual com base no erro - int currentBaseSpeed; - long errorMagnitude = abs(error); +*/ +int cnt=0; - // Mapeia a magnitude do erro para a velocidade base, reduzindo a velocidade máxima conforme o erro aumenta - // A velocidade base diminui linearmente de MAX_SPEED_STRAIGHT a MIN_SPEED_CURVE conforme o erro aumenta - currentBaseSpeed = map(errorMagnitude, 0, ERROR_THRESHOLD_MAX_REDUCTION, MAX_SPEED_STRAIGHT, MIN_SPEED_CURVE); - currentBaseSpeed = constrain(currentBaseSpeed, MIN_SPEED_CURVE, MAX_SPEED_STRAIGHT); +void setup() +{ + // Liga os LEDs IR dos sensores + pinMode(LEDON, OUTPUT); + digitalWrite(LEDON, HIGH); - //PID dos sensores com base no erro posicional - int correction = KPs * error + KDs * derivative; // + KI * (error + lastError) / 2; + // Define os pinos dos sensores + qtr.setTypeRC(); //Definição dos sensores principais + Perifericos.setTypeRC(); //Definição dos sensores periféricos + qtr.setSensorPins((const uint8_t[]){D1, D2, D3, D4, D5, D6, D7, D8}, SensorCount1); //declaração dos pinos dos sensores principais + Perifericos.setSensorPins((const uint8_t[]){D1_2, D2_2}, SensorCount2); //declaração dos pinos dos sensores periféricos - // Regula a velociada com base no PWM o nosso objetivo e deixar isso numa descala de 0 a 1000 que é em RPM - int leftSpeed = currentBaseSpeed + correction; - int rightSpeed = currentBaseSpeed - correction; + Serial.begin(115200); + delay(2000); // Espera para abrir o Monitor Serial, se necessário - leftSpeed = constrain(leftSpeed, 0, MAX_SPEED_STRAIGHT); - rightSpeed = constrain(rightSpeed, 0, MAX_SPEED_STRAIGHT); + // Calibração dos sensores principais + Serial.println("Calibrando sensores..."); + for (uint16_t i = 0; i < 400; i++) + { + qtr.calibrate(); + delay(10); + } + Serial.println("Calibração concluída."); + Serial.println("------------------------------------"); + Serial.println("Iniciando loop principal..."); +} - lastError = error; - //Antes de soltar este valor na função que seta o nosso PID precisamos passar este valor de PWM ==> RPM, pois a função opera em RPM e responde en PWM. - //Portanto, aqui está feita uma regra de três simples para Left e Right Speed. Ambas operam normalmente em PWM até chegarem aqui e serem passadas para RPM - // isso é um teste. Lembrando que esta relação foi feita considerando 1000 como nosso rpm max possível e 255 como sendo o PWM max possível - int leftSpeedRPM = (leftSpeed*1000)/255; - int rightSpeedRPM = (rightSpeed*1000)/255; + void loop(){ - //Aplicar o leftSpeed e rightSpeed nos motores (EM RPM, esta função já converte para PWM) + uint16_t position = qtr.readLineWhite(sensorValues1); + + // Calcula o erro em relação ao centro (3500) + int error = map(position, 0, 7000, -100, 100); + + + int derivative = error - lastError; + + + int currentBaseSpeed = 80; + int normal = abs(error) / 100; + currentBaseSpeed *= (1-normal); // Base reduzida proporcionalmente ao erro + currentBaseSpeed = constrain(currentBaseSpeed, 40, maxSpeed); + + // Correção com PID (PD) + int correction = KP * error + KD * derivative + KI * ((error + lastError) / 2); + + // Calcula as velocidades dos motores usando a currentBaseSpeed + int leftSpeed = currentBaseSpeed + (correction); + int rightSpeed = currentBaseSpeed - (correction); - MotorD.set_RPM(rightSpeedRPM); - MotorE.set_RPM(leftSpeedRPM); - //o delay ajuda a funcionar, sem ele o motor não faz nada. - delay(50); -} \ No newline at end of file + // Liga os motores com as velocidades ajustadas + //MotorE.ligar_motor(1, rightSpeed); // Assumindo que '1' é para frente + //MotorD.ligar_motor(1, leftSpeed); // Assumindo que '1' é para frente + + // Atualiza o erro anterior + lastError = error; + + // Imprime dados para depuração") + Serial.print(" | BaseSpd: "); // Nova informação para depuração + Serial.print(currentBaseSpeed); + Serial.print(" | VE: "); + Serial.print(leftSpeed); + Serial.print(" | VD: "); + Serial.println(rightSpeed); + Serial.print(" | cnt value: "); + Serial.println(cnt); + + //Faz a leitura dos sensores periféricos, se ele perceber a leitura de um ele somará no contador + + Perifericos.read(sensorValues2, QTRReadMode::On); + + Perifericos.read(sensorValues2); + for (int i = 0; i < SensorCount2; i++) { + if (sensorValues2[i] < 300) { + cnt++; + } + } + + // Se o valor do contador for um valor maior que 1, diminui a velocidade base do robô + + if (cnt >= 1) { + currentBaseSpeed = constrain(currentBaseSpeed - 20, minSpeed, maxSpeed); + } + + delay(10); // Pequeno delay para estabilidade e leitura serial + } \ No newline at end of file From be4c701512aa133bc4be3a106a2e8e837ad5971d Mon Sep 17 00:00:00 2001 From: Quilherpreto <231011391@aluno.unb.br> Date: Mon, 9 Jun 2025 20:08:44 -0300 Subject: [PATCH 10/13] =?UTF-8?q?funcionando=20o=20contador=20at=C3=A9=20p?= =?UTF-8?q?arar=20de=20perceber=20o=20marco=20e=20come=C3=A7o=20do=20mapea?= =?UTF-8?q?mento=20total=20da=20arena?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Test_motor/include/Pins.h | 4 +- Test_motor/src/main.cpp | 81 +++++++++++++++++++++++++++------------ 2 files changed, 58 insertions(+), 27 deletions(-) diff --git a/Test_motor/include/Pins.h b/Test_motor/include/Pins.h index 946e63b..78f1b1e 100644 --- a/Test_motor/include/Pins.h +++ b/Test_motor/include/Pins.h @@ -26,8 +26,8 @@ #define D6 21 #define D7 22 #define D8 23 -#define D1_2 34 -#define D2_2 35 +#define D1_2 13 +#define D2_2 27 #endif \ No newline at end of file diff --git a/Test_motor/src/main.cpp b/Test_motor/src/main.cpp index 0d698f6..c3cfa14 100644 --- a/Test_motor/src/main.cpp +++ b/Test_motor/src/main.cpp @@ -44,9 +44,14 @@ kp 2 kd 10 bs= 100; */ int cnt=0; +int currentBaseSpeed = 80; +bool marcadores[16] = {false,false,false,false,false,false,false,false, + false,false,false,false,false,false,false,false}; +bool brancoDetectado = false; -void setup() -{ + + void setup() + { // Liga os LEDs IR dos sensores pinMode(LEDON, OUTPUT); digitalWrite(LEDON, HIGH); @@ -60,18 +65,18 @@ void setup() Serial.begin(115200); delay(2000); // Espera para abrir o Monitor Serial, se necessário - // Calibração dos sensores principais - Serial.println("Calibrando sensores..."); - for (uint16_t i = 0; i < 400; i++) - { - qtr.calibrate(); - delay(10); - } - Serial.println("Calibração concluída."); - Serial.println("------------------------------------"); - Serial.println("Iniciando loop principal..."); -} + // Calibração dos sensores + Serial.println("Calibrando sensores..."); + for (uint16_t i = 0; i < 400; i++) + { + qtr.calibrate(); + delay(10); + } + Serial.println("Calibração concluída."); + Serial.println("------------------------------------"); + Serial.println("Iniciando loop principal..."); + } void loop(){ @@ -84,8 +89,6 @@ void setup() int derivative = error - lastError; - - int currentBaseSpeed = 80; int normal = abs(error) / 100; currentBaseSpeed *= (1-normal); // Base reduzida proporcionalmente ao erro currentBaseSpeed = constrain(currentBaseSpeed, 40, maxSpeed); @@ -120,18 +123,46 @@ void setup() Perifericos.read(sensorValues2, QTRReadMode::On); - Perifericos.read(sensorValues2); - for (int i = 0; i < SensorCount2; i++) { - if (sensorValues2[i] < 300) { - cnt++; - } + Perifericos.read(sensorValues2, QTRReadMode::On); + + for (int i = 0; i < SensorCount2; i++) { + if (sensorValues2[i] < 300) { + brancoDetectado = true; } - // Se o valor do contador for um valor maior que 1, diminui a velocidade base do robô + else if (brancoDetectado && sensorValues2[i] >= 2500) { + cnt++; + brancoDetectado = false; + } + } + + // Printa os valores dos sensores D1_2 e D2_2 + Serial.print("Leitura D1_2: "); + Serial.println(sensorValues2[0]); // D1_2 está no índice 0 + Serial.print("Leitura D2_2: "); + Serial.println(sensorValues2[1]); // D2_2 está no índice 1 + + + // Quando detectar a primeira marca, reduz a velocidade uma vez + if (!marcador1 && cnt == 1) { + marcador1 = true; + currentBaseSpeed -= 20; + Serial.println(">> Marca 1 detectada: Reduzindo velocidade."); + } + + // Quando detectar a segunda marca, aumenta a velocidade uma vez + if (!marcador2 && cnt == 2) { + marcador2 = true; + currentBaseSpeed += 20; + Serial.println(">> Marca 2 detectada: Aumentando velocidade."); + } + + if(!marcador3 && cnt == 3) { + marcador3 = true; + currentBaseSpeed +=20; + Serial.println(">> Marca 3 detectada: Aumentando velocidade."); + } - if (cnt >= 1) { - currentBaseSpeed = constrain(currentBaseSpeed - 20, minSpeed, maxSpeed); - } - delay(10); // Pequeno delay para estabilidade e leitura serial + delay(500); // Pequeno delay para estabilidade e leitura serial } \ No newline at end of file From 1c0a5ba5d40c9188c90dd1c97ddf787692e595e6 Mon Sep 17 00:00:00 2001 From: Quilherpreto <231011391@aluno.unb.br> Date: Wed, 11 Jun 2025 16:12:23 -0300 Subject: [PATCH 11/13] =?UTF-8?q?finaliza=C3=A7=C3=A3o=20da=20l=C3=B3gica?= =?UTF-8?q?=20da=20arena=20da=20lona=20sem=20otimiza=C3=A7=C3=A3o?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Test_motor/src/main.cpp | 96 +++++++++++++++++++++++++++++++++++++---- 1 file changed, 87 insertions(+), 9 deletions(-) diff --git a/Test_motor/src/main.cpp b/Test_motor/src/main.cpp index c3cfa14..e88d9aa 100644 --- a/Test_motor/src/main.cpp +++ b/Test_motor/src/main.cpp @@ -144,25 +144,103 @@ bool brancoDetectado = false; // Quando detectar a primeira marca, reduz a velocidade uma vez - if (!marcador1 && cnt == 1) { - marcador1 = true; + if (!marcadores[0] && cnt == 1) { + marcador[0]= true; currentBaseSpeed -= 20; Serial.println(">> Marca 1 detectada: Reduzindo velocidade."); } // Quando detectar a segunda marca, aumenta a velocidade uma vez - if (!marcador2 && cnt == 2) { - marcador2 = true; - currentBaseSpeed += 20; + if (!marcadores[1] && cnt == 2) { + marcadores[1] = true; + currentBaseSpeed -= 20; Serial.println(">> Marca 2 detectada: Aumentando velocidade."); } - if(!marcador3 && cnt == 3) { - marcador3 = true; - currentBaseSpeed +=20; + if(!marcadores[2] && cnt == 3) { + marcadores[2]= true; + currentBaseSpeed =currentBaseSpeed; Serial.println(">> Marca 3 detectada: Aumentando velocidade."); } + if(!marcadores[3] && cnt == 4) { + marcadores[3] = true; + currentBaseSpeed +=40; + Serial.println(">> Marca 4 detectada: Aumentando velocidade."); + } + + if(!marcadores[4] && cnt == 5) { + marcadores[4] = true; + currentBaseSpeed -=30; + Serial.println(">> Marca 5 detectada: Aumentando velocidade."); + } + + if(!marcadores[5] && cnt == 6) { + marcadores[5] = true; + currentBaseSpeed +=20; + Serial.println(">> Marca 6 detectada: Aumentando velocidade."); + } + + if(!marcadores[6] && cnt == 7) { + marcadores[6] = true; + currentBaseSpeed =currentBaseSpeed; + Serial.println(">> Marca 7 detectada: Aumentando velocidade."); + } + + if(!marcadores[7] && cnt == 8) { + marcadores[7] = true; + currentBaseSpeed =currentBaseSpeed; + Serial.println(">> Marca 8 detectada: Aumentando velocidade."); + } + + if(!marcadores[8] && cnt == 9) { + marcadores[8] = true; + currentBaseSpeed =currentBaseSpeed; + Serial.println(">> Marca 9 detectada: Aumentando velocidade."); + } + + if(!marcadores[9] && cnt == 10) { + marcadores[9] = true; + currentBaseSpeed -=20; + Serial.println(">> Marca 10 detectada: Aumentando velocidade."); + } + + if(!marcadores[10] && cnt ==11) { + marcadores[10] = true; + currentBaseSpeed =currentBaseSpeed; + Serial.println(">> Marca 11 detectada: Aumentando velocidade."); + } + + if(!marcadores[11] && cnt == 12) { + marcadores[11] = true; + currentBaseSpeed =currentBaseSpeed; + Serial.println(">> Marca 12 detectada: Aumentando velocidade."); + } + + if(!marcadores[12] && cnt == 13) { + marcadores[12] = true; + currentBaseSpeed +=30 + Serial.println(">> Marca 13 detectada: Aumentando velocidade."); + } + + if(!marcadores[13] && cnt == 14) { + marcadores[13] = true; + currentBaseSpeed =currentBaseSpeed; + Serial.println(">> Marca 14 detectada: Aumentando velocidade."); + } + + if(!marcadores[14] && cnt == 15) { + marcadores[14] = true; + currentBaseSpeed -=20; + Serial.println(">> Marca 15 detectada: Aumentando velocidade."); + } + + if(!marcadores[15] && cnt == 16) { + marcadores[15] = true; + currentBaseSpeed +=20; + Serial.println(">> Marca 16 detectada: Aumentando velocidade."); + } + - delay(500); // Pequeno delay para estabilidade e leitura serial + delay(10); // Pequeno delay para estabilidade e leitura serial } \ No newline at end of file From 302fd6e77a5d9aefdf1550ba681264982241a1a8 Mon Sep 17 00:00:00 2001 From: Quilherpreto <231011391@aluno.unb.br> Date: Wed, 11 Jun 2025 16:37:20 -0300 Subject: [PATCH 12/13] =?UTF-8?q?otimiza=C3=A7=C3=A3o=20dos=20estdos=20rep?= =?UTF-8?q?etidos=20na=20pista?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Test_motor/src/main.cpp | 149 ++++++++++++++-------------------------- 1 file changed, 50 insertions(+), 99 deletions(-) diff --git a/Test_motor/src/main.cpp b/Test_motor/src/main.cpp index e88d9aa..fce8683 100644 --- a/Test_motor/src/main.cpp +++ b/Test_motor/src/main.cpp @@ -142,105 +142,56 @@ bool brancoDetectado = false; Serial.print("Leitura D2_2: "); Serial.println(sensorValues2[1]); // D2_2 está no índice 1 - - // Quando detectar a primeira marca, reduz a velocidade uma vez - if (!marcadores[0] && cnt == 1) { - marcador[0]= true; - currentBaseSpeed -= 20; - Serial.println(">> Marca 1 detectada: Reduzindo velocidade."); - } - - // Quando detectar a segunda marca, aumenta a velocidade uma vez - if (!marcadores[1] && cnt == 2) { - marcadores[1] = true; - currentBaseSpeed -= 20; - Serial.println(">> Marca 2 detectada: Aumentando velocidade."); - } - - if(!marcadores[2] && cnt == 3) { - marcadores[2]= true; - currentBaseSpeed =currentBaseSpeed; - Serial.println(">> Marca 3 detectada: Aumentando velocidade."); - } - - if(!marcadores[3] && cnt == 4) { - marcadores[3] = true; - currentBaseSpeed +=40; - Serial.println(">> Marca 4 detectada: Aumentando velocidade."); - } - - if(!marcadores[4] && cnt == 5) { - marcadores[4] = true; - currentBaseSpeed -=30; - Serial.println(">> Marca 5 detectada: Aumentando velocidade."); - } - - if(!marcadores[5] && cnt == 6) { - marcadores[5] = true; - currentBaseSpeed +=20; - Serial.println(">> Marca 6 detectada: Aumentando velocidade."); - } - - if(!marcadores[6] && cnt == 7) { - marcadores[6] = true; - currentBaseSpeed =currentBaseSpeed; - Serial.println(">> Marca 7 detectada: Aumentando velocidade."); - } - - if(!marcadores[7] && cnt == 8) { - marcadores[7] = true; - currentBaseSpeed =currentBaseSpeed; - Serial.println(">> Marca 8 detectada: Aumentando velocidade."); - } - - if(!marcadores[8] && cnt == 9) { - marcadores[8] = true; - currentBaseSpeed =currentBaseSpeed; - Serial.println(">> Marca 9 detectada: Aumentando velocidade."); - } - - if(!marcadores[9] && cnt == 10) { - marcadores[9] = true; - currentBaseSpeed -=20; - Serial.println(">> Marca 10 detectada: Aumentando velocidade."); - } - - if(!marcadores[10] && cnt ==11) { - marcadores[10] = true; - currentBaseSpeed =currentBaseSpeed; - Serial.println(">> Marca 11 detectada: Aumentando velocidade."); - } - - if(!marcadores[11] && cnt == 12) { - marcadores[11] = true; - currentBaseSpeed =currentBaseSpeed; - Serial.println(">> Marca 12 detectada: Aumentando velocidade."); - } - - if(!marcadores[12] && cnt == 13) { - marcadores[12] = true; - currentBaseSpeed +=30 - Serial.println(">> Marca 13 detectada: Aumentando velocidade."); - } - - if(!marcadores[13] && cnt == 14) { - marcadores[13] = true; - currentBaseSpeed =currentBaseSpeed; - Serial.println(">> Marca 14 detectada: Aumentando velocidade."); - } - - if(!marcadores[14] && cnt == 15) { - marcadores[14] = true; - currentBaseSpeed -=20; - Serial.println(">> Marca 15 detectada: Aumentando velocidade."); - } - - if(!marcadores[15] && cnt == 16) { - marcadores[15] = true; - currentBaseSpeed +=20; - Serial.println(">> Marca 16 detectada: Aumentando velocidade."); - } - + // Garante que o código só execute uma vez por marca +if (!marcadores[cnt - 1]) { + marcadores[cnt - 1] = true; + Serial.print(">> Marca "); + Serial.print(cnt); + Serial.print(" detectada: "); + + switch (cnt) { + case 1: + currentBaseSpeed -= 20; + Serial.println("Reduzindo velocidade."); + break; + case 2: + currentBaseSpeed -= 20; // O comentário original dizia "Aumentando", mas o código subtraía + Serial.println("Ajustando velocidade."); + break; + case 4: + currentBaseSpeed += 40; + Serial.println("Aumentando velocidade."); + break; + case 5: + currentBaseSpeed -= 30; + Serial.println("Ajustando velocidade."); + break; + case 6: + currentBaseSpeed += 20; + Serial.println("Aumentando velocidade."); + break; + case 10: + currentBaseSpeed -= 20; + Serial.println("Ajustando velocidade."); + break; + case 13: + currentBaseSpeed += 30; + Serial.println("Aumentando velocidade."); + break; + case 15: + currentBaseSpeed -= 20; + Serial.println("Ajustando velocidade."); + break; + case 16: + currentBaseSpeed += 20; + Serial.println("Aumentando velocidade."); + break; + default: + // Casos 3, 7, 8, 9, 11, 12, 14 não fazem nada + Serial.println("Velocidade mantida."); + break; + } +} delay(10); // Pequeno delay para estabilidade e leitura serial } \ No newline at end of file From 022c3500d414d12f5a8a695fbedd6f20cdafb3a6 Mon Sep 17 00:00:00 2001 From: Quilherpreto <231011391@aluno.unb.br> Date: Wed, 11 Jun 2025 16:39:33 -0300 Subject: [PATCH 13/13] =?UTF-8?q?ajuste=20de=20coment=C3=A1rios?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Test_motor/src/main.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Test_motor/src/main.cpp b/Test_motor/src/main.cpp index fce8683..c72284b 100644 --- a/Test_motor/src/main.cpp +++ b/Test_motor/src/main.cpp @@ -152,10 +152,10 @@ if (!marcadores[cnt - 1]) { switch (cnt) { case 1: currentBaseSpeed -= 20; - Serial.println("Reduzindo velocidade."); + Serial.println("Ajustando velocidade."); break; case 2: - currentBaseSpeed -= 20; // O comentário original dizia "Aumentando", mas o código subtraía + currentBaseSpeed -= 20; Serial.println("Ajustando velocidade."); break; case 4: @@ -193,5 +193,5 @@ if (!marcadores[cnt - 1]) { } } - delay(10); // Pequeno delay para estabilidade e leitura serial + delay(15); // Pequeno delay para estabilidade e leitura serial } \ No newline at end of file