31 prev_pulse_counter = 0;
43 bool A = digitalRead(
pinA);
47 if ( A != A_active ) {
48 pulse_counter += (A_active == B_active) ? 1 : -1;
55 if(A && !digitalRead(
pinB)){
64 bool B = digitalRead(
pinB);
68 if ( B != B_active ) {
69 pulse_counter += (A_active != B_active) ? 1 : -1;
76 if(B && !digitalRead(
pinA)){
91 long tmp = pulse_counter;
93 pulse_counter = round((
double)pulse_counter/(
double)
cpr)*
cpr;
95 prev_pulse_counter += pulse_counter - tmp;
105 return _2PI * (pulse_counter) / ((
float)
cpr);
115 float Ts = (timestamp_us - prev_timestamp_us) * 1e-6;
117 if(Ts <= 0 || Ts > 0.5) Ts = 1e-3;
120 float Th = (timestamp_us - pulse_timestamp) * 1e-6;
121 long dN = pulse_counter - prev_pulse_counter;
129 float dt = Ts + prev_Th - Th;
130 pulse_per_second = (dN != 0 && dt > Ts/2) ? dN / dt : pulse_per_second;
133 if ( Th > 0.1) pulse_per_second = 0;
139 prev_timestamp_us = timestamp_us;
142 prev_pulse_counter = pulse_counter;
149 return hasIndex() && !index_found;
153 int Encoder::hasIndex(){
164 pinMode(
pinA, INPUT_PULLUP);
165 pinMode(
pinB, INPUT_PULLUP);
166 if(hasIndex()) pinMode(
index_pin,INPUT_PULLUP);
168 pinMode(
pinA, INPUT);
169 pinMode(
pinB, INPUT);
178 pulse_per_second = 0;
179 prev_pulse_counter = 0;
195 if(doA !=
nullptr) attachInterrupt(digitalPinToInterrupt(
pinA), doA, CHANGE);
196 if(doB !=
nullptr) attachInterrupt(digitalPinToInterrupt(
pinB), doB, CHANGE);
200 if(doA !=
nullptr) attachInterrupt(digitalPinToInterrupt(
pinA), doA, RISING);
201 if(doB !=
nullptr) attachInterrupt(digitalPinToInterrupt(
pinB), doB, RISING);
206 if(hasIndex() && doIndex !=
nullptr) attachInterrupt(digitalPinToInterrupt(
index_pin), doIndex, CHANGE);