130 long copy_pulse_counter = pulse_counter;
131 long copy_pulse_timestamp = pulse_timestamp;
136 float Ts = (timestamp_us - prev_timestamp_us) * 1e-6f;
138 if(Ts <= 0 || Ts > 0.5f) Ts = 1e-3f;
141 float Th = (timestamp_us - copy_pulse_timestamp) * 1e-6f;
142 long dN = copy_pulse_counter - prev_pulse_counter;
150 float dt = Ts + prev_Th - Th;
151 pulse_per_second = (dN != 0 && dt > Ts/2) ? dN / dt : pulse_per_second;
154 if ( Th > 0.1f) pulse_per_second = 0;
160 prev_timestamp_us = timestamp_us;
163 prev_pulse_counter = copy_pulse_counter;
217 if(doA !=
nullptr) attachInterrupt(digitalPinToInterrupt(
pinA), doA, CHANGE);
218 if(doB !=
nullptr) attachInterrupt(digitalPinToInterrupt(
pinB), doB, CHANGE);
222 if(doA !=
nullptr) attachInterrupt(digitalPinToInterrupt(
pinA), doA, RISING);
223 if(doB !=
nullptr) attachInterrupt(digitalPinToInterrupt(
pinB), doB, RISING);
228 if(hasIndex() && doIndex !=
nullptr) attachInterrupt(digitalPinToInterrupt(
index_pin), doIndex, CHANGE);