JMotor
Loading...
Searching...
No Matches
JEncoderQuadraturePinChange.h
Go to the documentation of this file.
1#ifndef J_ENCODER_QUADRATURE_PIN_CHANGE_H
2#define J_ENCODER_QUADRATURE_PIN_CHANGE_H
3#include "EnableInterrupt.h" //https://github.com/GreyGnome/EnableInterrupt
5#include <Arduino.h>
14public:
23 JEncoderQuadraturePinChange(byte _encoderAPin, byte _encoderBPin, float _distPerCountFactor = 1.0, bool _reverse = false, unsigned long _slowestIntervalMicros = 100000UL)
24 : JEncoderQuadrature(_encoderAPin, _encoderBPin, _distPerCountFactor, _reverse, _slowestIntervalMicros)
25 {
26 }
27
28 void setUpInterrupts(void (*_isrAPointer)(void), void (*_isrBPointer)(void))
29 {
30
31 pinMode(encoderAPin, INPUT);
32 pinMode(encoderBPin, INPUT);
33
34 enableInterrupt(encoderAPin, _isrAPointer, CHANGE);
35 enableInterrupt(encoderBPin, _isrBPointer, CHANGE);
36 }
38 {
39 disableInterrupt(encoderAPin);
40 disableInterrupt(encoderBPin);
41 }
42};
43#endif
reads a quadrature (incremental) encoder
Definition JEncoderQuadrature.h:13
byte encoderBPin
Definition JEncoderQuadrature.h:17
byte encoderAPin
Definition JEncoderQuadrature.h:16
uses a pin change interrupt library to support more pins than attachInterrupt().
Definition JEncoderQuadraturePinChange.h:13
void turnOffInterrupts()
disable interrupts and stop monitoring encoder
Definition JEncoderQuadraturePinChange.h:37
JEncoderQuadraturePinChange(byte _encoderAPin, byte _encoderBPin, float _distPerCountFactor=1.0, bool _reverse=false, unsigned long _slowestIntervalMicros=100000UL)
constructor, sets pins and settings
Definition JEncoderQuadraturePinChange.h:23
void setUpInterrupts(void(*_isrAPointer)(void), void(*_isrBPointer)(void))
set up pins and interrupts
Definition JEncoderQuadraturePinChange.h:28