-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathMA3PWM.cpp
47 lines (33 loc) · 1.06 KB
/
MA3PWM.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
#include "MA3PWM.h"
#if defined(ARDUINO)
#include <Arduino.h>
void MA3PWM::handleInterrupt() {
if (digitalRead(m_pin)) {
m_timeHigh = m_lastFallingEdge - m_lastRisingEdge;
m_lastRisingEdge = micros();
m_timeLow = m_lastRisingEdge - m_lastFallingEdge;
}
else {
m_lastFallingEdge = micros();
}
}
void MA3PWM::begin(void (*isr)(void)) {
pinMode(m_pin, INPUT);
attachInterrupt(digitalPinToInterrupt(m_pin), isr, CHANGE);
}
#endif
uint16_t MA3PWM::readPWM() const {
// See https://www.usdigital.com/products/encoders/absolute/shaft/ma3/ for details
uint16_t ticks = (m_timeHigh * 4098) / (m_timeHigh + m_timeLow);
if (ticks > 4097) ticks = m_lastTicks;
else m_lastTicks = ticks;
return (ticks == 4097)? 4095 : ticks - 1;
}
float MA3PWM::readDegrees() const {
float degrees = ((m_inverted? -1 : 1) * readPWM() * 360.0 / 4096.0) - m_offsetDegrees;
degrees = boundDegrees0_360(degrees);
if (m_allowNegativeDegrees) {
if (degrees > 180) degrees -= 360;
}
return degrees;
}