-
Notifications
You must be signed in to change notification settings - Fork 3
/
Encoder.cpp
90 lines (72 loc) · 1.98 KB
/
Encoder.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
#include "Encoder.h"
#include "Definitions.h"
unsigned GlobalId = 0;
Encoder Encoders[2];
unsigned long TempoMedido;
long calculaTempoPassado() {
return millis() - TempoMedido;
}
void resetTempoMedido() {
TempoMedido = millis();
}
void incrementaMotorPulsos1() {
Encoders[0].Pulsos++;
}
void incrementaMotorPulsos2() {
Encoders[1].Pulsos++;
}
void habilitaInterrupcoes() {
attachInterrupt(digitalPinToInterrupt(ENC_1_PIN), incrementaMotorPulsos1, FALLING);
attachInterrupt(digitalPinToInterrupt(ENC_2_PIN), incrementaMotorPulsos2, FALLING);
}
void desabilitaInterrupcoes() {
detachInterrupt(digitalPinToInterrupt(ENC_1_PIN));
detachInterrupt(digitalPinToInterrupt(ENC_2_PIN));
}
void resetEncoders() {
Encoders[0].reset();
Encoders[1].reset();
}
void calculaRpm(unsigned TempoPassado) {
Encoders[0].calculaRpm(TempoPassado);
Encoders[1].calculaRpm(TempoPassado);
}
void imprimeEncoderInfo() {
Serial.println(Encoders[0].toString());
Serial.println(Encoders[1].toString());
}
void setupEncoder() {
pinMode(ENC_1_PIN, INPUT);
pinMode(ENC_2_PIN, INPUT);
habilitaInterrupcoes();
}
void loopEncoder() {
unsigned long TempoPassado = calculaTempoPassado();
if (TempoPassado >= 1000) {
desabilitaInterrupcoes();
calculaRpm(TempoPassado);
imprimeEncoderInfo();
resetEncoders();
resetTempoMedido();
habilitaInterrupcoes();
}
}
// ---------------------------------------------------- Classe Encoder ----------------------------------------------------
Encoder::Encoder() {
Pulsos = 0;
Rpm = 0;
Id = GlobalId++;
}
void Encoder::reset() {
Pulsos = 0;
}
unsigned long Encoder::calculaRpm(unsigned TempoPassado) {
Rpm = (60L * 1000L * Pulsos) / (TempoPassado * PULSOS_POR_VOLTA);
TempoMedido = millis(); //resetTempoMedido(); tem função pra isso, pog
return Rpm;
}
String Encoder::toString() {
String Information;
Information = "{ Id:" + String(Id) + ", Pulsos:" + String(Pulsos) + ", Rpm:" + String(Rpm) + " }";
return Information;
}