RSeries astromech firmware
RotaryEncoder.h
Go to the documentation of this file.
1 #ifndef RotaryEncoder_h
2 #define RotaryEncoder_h
3 
4 #include "ReelTwo.h"
5 #include "core/SetupEvent.h"
6 #include "core/AnimatedEvent.h"
8 
20 {
21 public:
22  enum class Direction
23  {
24  kNoRotation = 0,
25  kClockwise = 1,
27  };
28 
29  enum class LatchMode
30  {
31  kFour3 = 1, // 4 steps, Latch at position 3 only (compatible to older versions)
32  kFour0 = 2, // 4 steps, Latch at position 0 (reverse wirings)
33  kTwo03 = 3 // 2 steps, Latch at position 0 and 3
34  };
35 
36  RotaryEncoder(byte pin1, byte pin2, LatchMode mode = LatchMode::kFour0, bool useInterrupt = true) :
37  fPin1(pin1),
38  fPin2(pin2),
39  fMode(mode),
40  fUseInterrupt(useInterrupt ? 2 : 0)
41  {
42  pinMode(fPin1, INPUT_PULLUP);
43  pinMode(fPin2, INPUT_PULLUP);
44 
45  // when not started in motion, the current
46  // state of the encoder should be 3
47  int sig1 = digitalRead(fPin1);
48  int sig2 = digitalRead(fPin2);
49  fOldState = sig1 | (sig2 << 1);
50 
51  // start with position 0;
52  fPosition = 0;
53  fPositionExt = 0;
54  fPositionExtPrev = 0;
55  }
56 
57  virtual void setup() override
58  {
59  begin();
60  }
61 
62  virtual void animate() override
63  {
64  int32_t val = getValue();
65  int32_t curval = fValue;
66  if (!fUseInterrupt)
67  interrupt();
68  if (val != curval)
69  {
70  // if (fChangeNotify != NULL)
71  // fChangeNotify(val);
72  fValue = val;
73  }
74  }
75 
76  void begin()
77  {
78  if (fUseInterrupt == 2)
79  fUseInterrupt = (attachInterrupt(fPin1) && attachInterrupt(fPin2));
80  }
81 
82  void end()
83  {
84  if (fUseInterrupt == 1)
85  {
86  detachInterrupt(fPin1);
87  detachInterrupt(fPin2);
88  }
89  }
90 
94  inline bool hasChanged()
95  {
96  return (getValue() != fValue);
97  }
98 
102  long getValue()
103  {
104  return fPositionExt;
105  }
106 
110  bool isActive()
111  {
112  return getValue() != 0 && getMillisBetweenRotations() < 250;
113  }
114 
119  {
121 
122  if (fPositionExtPrev > fPositionExt)
123  {
125  fPositionExtPrev = fPositionExt;
126  }
127  else if (fPositionExtPrev < fPositionExt)
128  {
129  ret = Direction::kClockwise;
130  fPositionExtPrev = fPositionExt;
131  }
132  else
133  {
135  fPositionExtPrev = fPositionExt;
136  }
137  return ret;
138  }
139 
143  void setValue(long newValue)
144  {
145  switch (fMode)
146  {
147  case LatchMode::kFour3:
148  case LatchMode::kFour0:
149  // only adjust the external part of the position.
150  fPosition = ((newValue << 2) | (fPosition & 0x03L));
151  fPositionExt = newValue;
152  fPositionExtPrev = newValue;
153  break;
154 
155  case LatchMode::kTwo03:
156  // only adjust the external part of the position.
157  fPosition = ((newValue << 1) | (fPosition & 0x01L));
158  fPositionExt = newValue;
159  fPositionExtPrev = newValue;
160  break;
161  }
162  }
163 
167  uint32_t getMillisBetweenRotations() const
168  {
169  return (fPositionExtTime - fPositionExtTimePrev);
170  }
171 
175  uint32_t getRPM()
176  {
177  // calculate max of difference in time between last position changes or last change and now.
178  uint32_t timeBetweenLastPositions = fPositionExtTime - fPositionExtTimePrev;
179  uint32_t timeToLastPosition = millis() - fPositionExtTime;
180  uint32_t t = max(timeBetweenLastPositions, timeToLastPosition);
181  return 60000.0 / ((float)(t * 20));
182  }
183 
184 protected:
185  virtual void interrupt() override
186  {
187  enum {
188  kLatch0 = 0, // input state at position 0
189  kLatch3 = 3 // input state at position 3
190  };
191  static const int8_t KNOBDIR[] = {
192  0, -1, 1, 0,
193  1, 0, 0, -1,
194  -1, 0, 0, 1,
195  0, 1, -1, 0
196  };
197  int sig1 = digitalRead(fPin1);
198  int sig2 = digitalRead(fPin2);
199  int8_t thisState = sig1 | (sig2 << 1);
200  if (fOldState != thisState)
201  {
202  fPosition += KNOBDIR[thisState | (fOldState << 2)];
203  fOldState = thisState;
204 
205  switch (fMode)
206  {
207  case LatchMode::kFour3:
208  if (thisState == kLatch3)
209  {
210  // The hardware has 4 steps with a latch on the input state 3
211  fPositionExt = fPosition >> 2;
212  fPositionExtTimePrev = fPositionExtTime;
213  fPositionExtTime = millis();
214  }
215  break;
216 
217  case LatchMode::kFour0:
218  if (thisState == kLatch0)
219  {
220  // The hardware has 4 steps with a latch on the input state 0
221  fPositionExt = fPosition >> 2;
222  fPositionExtTimePrev = fPositionExtTime;
223  fPositionExtTime = millis();
224  }
225  break;
226 
227  case LatchMode::kTwo03:
228  if ((thisState == kLatch0) || (thisState == kLatch3))
229  {
230  // The hardware has 2 steps with a latch on the input state 0 and 3
231  fPositionExt = fPosition >> 1;
232  fPositionExtTimePrev = fPositionExtTime;
233  fPositionExtTime = millis();
234  }
235  break;
236  }
237  }
238  }
239 
240 private:
241  byte fPin1;
242  byte fPin2; // Arduino pins used for the encoder.
243  LatchMode fMode; // Latch mode from initialization
244  uint8_t fUseInterrupt;
245 
246  volatile int8_t fOldState;
247 
248  long fValue = 0;
249  volatile long fPosition = 0; // Internal position (4 times fPositionExt)
250  volatile long fPositionExt = 0; // External position
251  volatile long fPositionExtPrev = 0; // External position (used only for direction checking)
252 
253  uint32_t fPositionExtTime = 0; // The time the last position change was detected.
254  uint32_t fPositionExtTimePrev = 0; // The time the previous position change was detected.
255 };
256 #endif
RotaryEncoder::LatchMode
LatchMode
Definition: RotaryEncoder.h:29
RotaryEncoder::setValue
void setValue(long newValue)
Sets the current value.
Definition: RotaryEncoder.h:143
ReelTwo.h
SetupEvent.h
PinInterruptHandler::detachInterrupt
void detachInterrupt(unsigned pin)
Definition: PinInterruptHandler.h:9
AnimatedEvent
Base class for all animated devices. AnimatedEvent::animate() is called for each device once through ...
Definition: AnimatedEvent.h:18
SetupEvent
Base class for all devices that require setup that cannot happen in the constructor....
Definition: SetupEvent.h:15
AnimatedEvent.h
RotaryEncoder::Direction::kClockwise
@ kClockwise
RotaryEncoder::getDirection
Direction getDirection()
Return the direction the knob was rotated last time.
Definition: RotaryEncoder.h:118
RotaryEncoder::Direction
Direction
Definition: RotaryEncoder.h:22
PinInterruptHandler::attachInterrupt
bool attachInterrupt(unsigned pin)
Definition: PinInterruptHandler.h:16
RotaryEncoder::getValue
long getValue()
Returns current value.
Definition: RotaryEncoder.h:102
RotaryEncoder::interrupt
virtual void interrupt() override
Definition: RotaryEncoder.h:185
RotaryEncoder::RotaryEncoder
RotaryEncoder(byte pin1, byte pin2, LatchMode mode=LatchMode::kFour0, bool useInterrupt=true)
Definition: RotaryEncoder.h:36
RotaryEncoder::animate
virtual void animate() override
Subclasses must implement this function to run through a single frame of animation/activity.
Definition: RotaryEncoder.h:62
PinInterruptHandler.h
RotaryEncoder::Direction::kNoRotation
@ kNoRotation
PinInterruptHandler
Definition: PinInterruptHandler.h:6
RotaryEncoder::getMillisBetweenRotations
uint32_t getMillisBetweenRotations() const
Returns time in milliseconds between the current observed.
Definition: RotaryEncoder.h:167
RotaryEncoder::LatchMode::kFour3
@ kFour3
RotaryEncoder::begin
void begin()
Definition: RotaryEncoder.h:76
RotaryEncoder::isActive
bool isActive()
Returns true if recently used (<250ms)
Definition: RotaryEncoder.h:110
RotaryEncoder::LatchMode::kFour0
@ kFour0
RotaryEncoder::hasChanged
bool hasChanged()
Returns true if value has changed since last animated event.
Definition: RotaryEncoder.h:94
RotaryEncoder::end
void end()
Definition: RotaryEncoder.h:82
RotaryEncoder::Direction::kCounterClockwise
@ kCounterClockwise
RotaryEncoder::getRPM
uint32_t getRPM()
Returns the RPM.
Definition: RotaryEncoder.h:175
RotaryEncoder::setup
virtual void setup() override
Subclasses must implement this function to perform any necessary setup that cannot happen in the cons...
Definition: RotaryEncoder.h:57
RotaryEncoder
Decodes the signals from a rotary encoder (quadrature pulses) and translates them into a counter posi...
Definition: RotaryEncoder.h:19
RotaryEncoder::LatchMode::kTwo03
@ kTwo03