Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 7 additions & 6 deletions Test_motor/include/MotorDC.h
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Tempo tempo;
int encoder_volta; // valor de encoder referente a uma volta completa da roda
double comprimento_roda = 2 * M_PI * 0.000000016;
int ENCA; // Cabo amarelo
int ENCB; // Cabo branco
int PWM;
Expand All @@ -33,11 +35,10 @@ 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)

};

#endif
18 changes: 10 additions & 8 deletions Test_motor/include/Pins.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,26 +6,28 @@

// Pinos dos motores

#define ENCA1 2
#define ENCB1 4
#define IN2 13
#define IN1 15
#define ENCA_E 15
#define ENCB_E 2
#define IN2 26
#define IN1 25

#define ENCA2 5
#define ENCB2 18
#define ENCA_D 4
#define ENCB_D 18
#define IN4 14
#define IN3 12

#define LEDON 33

#define D1 26
#define D2 25
#define D1 33
#define D2 32
#define D3 16
#define D4 17
#define D5 19
#define D6 21
#define D7 22
#define D8 23
#define D1_2 13
#define D2_2 27


#endif
23 changes: 14 additions & 9 deletions Test_motor/include/Tempo.h
Original file line number Diff line number Diff line change
@@ -1,13 +1,18 @@
#ifndef Tempo_h
#define Tempo_h
// Tempo.h
#ifndef TEMPO_H
#define TEMPO_H

#include "Arduino.h"
#include <Arduino.h>

//* 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
#endif
8 changes: 1 addition & 7 deletions Test_motor/platformio.ini
Original file line number Diff line number Diff line change
Expand Up @@ -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
84 changes: 28 additions & 56 deletions Test_motor/src/MotorDC.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);


}

Expand Down Expand Up @@ -52,16 +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
Expand All @@ -71,62 +64,41 @@ void MotorDC::resetar_encoder()
eintegral = 0;
voltas = 0;
}
void MotorDC::set_RPM(int velocidade_rpm){

void MotorDC::andar_reto(int velocidade_rpm){
//Serial.print("encoder_volta: "); Serial.println(encoder_volta);

// atualizar_tempo();
tempo.atualizar();
double dt = tempo.getDeltaTime();

rpm_referencia = velocidade_rpm; // Velocidade de referência
rpm_referencia = fabs(velocidade_rpm);

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
volatile double posi_atual = 0;
noInterrupts();
posi_atual = posi;
interrupts();

voltas_anterior = voltas; // atualiza o número de voltas anterior
voltas_anterior = voltas;
voltas = posi_atual / encoder_volta;
rps = (voltas - voltas_anterior) / dt;
rps = rps/100;

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 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 pwmVal = constrain(fabs(u), 0, 255);

float u = p + i + d; //p + (ki * eintegral*dt) + d;

float pwmVal = fabs(u); // valor do pwm que será enviado ao motor

if (pwmVal > 255) // Limita o valor do pwm para 255
{
pwmVal = 255;
}

// Define a direção do motor com base no valor de u
if (u > 0)
{
dir = 1;
}
else if (u < 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;
}

}
22 changes: 13 additions & 9 deletions Test_motor/src/Tempo.cpp
Original file line number Diff line number Diff line change
@@ -1,13 +1,17 @@
// Tempo.cpp
#include "Tempo.h"

extern unsigned long T;
extern unsigned long prevT;
extern 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;
}
double Tempo::getDeltaTime() {
return dt;
}
Loading