Skip to content

Commit

Permalink
Updated quadrature_encoder.ino to not require library
Browse files Browse the repository at this point in the history
- the library we used was only for AVR microcontrollers,
  so the code could not work on RPi Pico for instance.
- I reimplemented the sketch to have explicit polling
  mode logic that is suitable for noisy mechanical encoders.
- To that I added an interrupt driven mode that works if
  there is one interrupt capable pin available for each encoder.
  This is suitable for optical or hall effect encoders that
  do not need to be debounced.
  • Loading branch information
Ezward committed Feb 4, 2023
1 parent f47a397 commit c743ca3
Show file tree
Hide file tree
Showing 2 changed files with 174 additions and 411 deletions.
222 changes: 174 additions & 48 deletions arduino/quadrature_encoder/quadrature_encoder.ino
Original file line number Diff line number Diff line change
@@ -1,11 +1,7 @@
/*
* quadrature_encoder.ino
*
* Based on teensy Encoder Library Basic Example
* http://www.pjrc.com/teensy/td_libs_Encoder.html,
*
* In Arduino IDE, user the library manager to
* choose Encoder by Paul Stoffregan v1.4.2
* This does not use any libraries.
*
* Note that use of interrupt capable pins will increase
* performance (see `Hardware Requirements` section in
Expand Down Expand Up @@ -42,13 +38,7 @@
*/
#include <Arduino.h>

// This optional setting causes Encoder to use more optimized code,
// It must be defined before Encoder.h is included.
#define ENCODER_OPTIMIZE_INTERRUPTS

// Encoder by Paul Stoffregan v1.4.2
#include <Encoder.h>

#define USE_ENCODER_INTERRUPTS
#define DUAL_ENCODERS

#ifdef DUAL_ENCODERS
Expand All @@ -59,16 +49,16 @@
// Therefore we want the data and clock pins to be hooked up oppositely
// for each encoder. This can be achieved by reversing the connections
// on the right encoder, so that the data pin of the encoder is
// assigned the ENCODER_2_CLK_PIN and the clock pin of the encoder
// is assigned to ENCODER_2_DT_PIN.
// assigned the ENCODER_2_PIN_A and the clock pin of the encoder
// is assigned to ENCODER_2_PIN_B.
//
#define ENCODER_CLK_PIN (2) // clock input pin for first encoder (left wheel)
#define ENCODER_DT_PIN (4) // data input pin for first encoder
#define ENCODER_2_CLK_PIN (3) // input pin for second encoder (right wheel, see above)
#define ENCODER_2_DT_PIN (5) // input pin for second encoder
#define ENCODER_PIN_A (2) // clock input pin for first encoder (left wheel)
#define ENCODER_PIN_B (4) // data input pin for first encoder
#define ENCODER_2_PIN_A (3) // input pin for second encoder (right wheel, see above)
#define ENCODER_2_PIN_B (5) // input pin for second encoder
#else
#define ENCODER_CLK_PIN (2) // clock input pin for first encoder
#define ENCODER_DT_PIN (3) // data input pin for first encoder
#define ENCODER_PIN_A (2) // clock input pin for first encoder
#define ENCODER_PIN_B (3) // data input pin for first encoder
#endif

#define POLL_DELAY_MICROS (100UL) // microseconds between polls
Expand All @@ -77,15 +67,19 @@
// state for an encoder pin
//
struct EncoderState {
Encoder *encoder; // quadrature encoder instance
long ticks; // current tick count
uint8_t pin_clock; // CLOCK pin
uint8_t pin_data; // DATA pin
uint8_t transition; // last two (from and to) quadrature cycle steps as nibble bit field
int8_t transitions; // count of valid quadrature cycle transitions
volatile long ticks; // current tick count (count of full cycles)
};


// list of encoders
EncoderState encoders[2] = {
{new Encoder(ENCODER_DT_PIN, ENCODER_CLK_PIN), 0L},
#ifdef ENCODER_2_CLK_PIN
{new Encoder(ENCODER_2_DT_PIN, ENCODER_2_CLK_PIN), 0L},
static EncoderState encoders[] = {
{ENCODER_PIN_A, ENCODER_PIN_B, 0x03, 0, 0L},
#ifdef ENCODER_2_PIN_A
{ENCODER_2_PIN_A, ENCODER_2_PIN_B, 0x03, 0, 0L},
#endif
};

Expand All @@ -96,34 +90,122 @@ unsigned long sendAtMs = 0; // next send time in continuous mode
unsigned long delayMs = 0; // time between sends in continuous mode


#ifdef USE_ENCODER_INTERRUPTS
typedef void (*gpio_isr_type)();

//
// count the interrupts.
// When clock is low (we interrupt on high to low transition):
// - if data pin is high, this is aclockwise turn.
// - if data pin is low, this is a counter-clockwise turn.
//
void encode_0() {
if (digitalRead(encoders[0].pin_data)) {
encoders[0].ticks += 1;
} else {
encoders[0].ticks -= 1;
}
}

#ifdef ENCODER_2_PIN_A
void encode_1() {
if (digitalRead(encoders[1].pin_data)) {
encoders[1].ticks += 1;
} else {
encoders[1].ticks -= 1;
}
}
#endif

gpio_isr_type _isr_routines[] = {
encode_0,
#ifdef ENCODER_2_PIN_A
encode_1
#endif
};
#endif


//
// Poll the encoder and increment ticks
// on stable transitions.
//
// The method debounces noisy inputs,
// looking for stable transitions from
// open-to-closed and closed-to-open by polling
// the encoder pin and building a 16 bit value.
// We start by looking for a stable closed-to-open
// transition, which will be a 1 followed by 15 zeroes.
// Then we change to look for the open-to-closed transition,
// which is a zero reading followed by 15 ones.
// looking for valid quadrature transitions
// on the two encoder pins. A full quadrature
// clockwise cycle is:
//
// step 0: clk = 1, data = 1
// step 1: clk = 0, data = 1
// step 2: clk = 0, data = 0
// step 3: clk = 1, data = 0
// step 0: clk = 1, data = 1
//
// Given a polling delay of 100 microseconds, the
// minimum time for a stable reading is
// 100 microseconds * 16 bits = 1.6 milliseconds.
// That then would allow for a maximum read rate of
// 1000 / 1.6 = 625 ticks per second.
// For high resolution encoders, that may be too slow.
// In that case, reduce the POLL_DELAY_MICROS to
// suit your encoder and use case.
// We can count the transition between steps as +1.
// There are 4 transitions between steps, so a
// full quadrature cycle has +4 transitions.
//
// So when we are on step 0 we can check the
// transition count and if it is 4, then
// we have gone clockwise one full cycle (one tick),
// so we add one to the total ticks.
//
// If the transition count is not 4, then there
// has been one or more invalid transitions
// caused by switch bouncing. In this case
// we do not count the tick.
//
// In anycase we clear the transition count
// so we can track the next quadrature cycle.
//
// A counter clockwise cycle would go in reverse,
// and we would count each counter clockwise
// transition as -1. If we get to step 0 and
// the transition count is -4, then we have
// gone one full quadrature cycle counter-clockwise,
// so we subtract one tick form the total.
//
void pollEncoder(EncoderState &encoder) {
encoder.ticks = encoder.encoder->read();
#ifdef USE_ENCODER_INTERRUPTS
if (NOT_AN_INTERRUPT == digitalPinToInterrupt(encoder.pin_clock)) {
Serial.print("Pin ");
Serial.print(encoder.pin_clock);
Serial.println(" must be an interrupt capable pin when compiled with USE_ENCODER_INTERRUPTS");
}
#else
static int8_t TRANSITION_DIRECTION[] = {0,-1,1,0,1,0,0,-1,-1,0,0,1,0,1,-1,0};

uint8_t current_state = (digitalRead(encoder.pin_clock) << 1) | digitalRead(encoder.pin_data);

//
// encoder from(clk | data) and to(clk | data) as a nibble
// and use it to look up the direction of that transition
//
encoder.transition = ((encoder.transition & 0x03) << 2) | current_state;
encoder.transitions += TRANSITION_DIRECTION[encoder.transition];

//
// When clock and data pins are high,
// then we are at the end of one quadrature
// cycle and at the beginning of the next.
// If we had 4 valid transitions, count the tick,
// otherwise there was an invalid transition (a bounce),
// so we do not count the tick.
//
if (0x03 == current_state) {
if (4 == encoder.transitions) {
encoder.ticks += 1; // we went 1 cycle clockwise
} else if (-4 == encoder.transitions) {
encoder.ticks -= 1;
}
encoder.transitions = 0;
}
#endif
}


void pollEncoders() {
for(int i = 0; i < ENCODER_COUNT; i += 1) {
for(uint8_t i = 0; i < ENCODER_COUNT; i += 1) {
pollEncoder(encoders[i]);
}
}
Expand All @@ -132,10 +214,37 @@ void pollEncoders() {
// reset tick counters to zero
//
void resetEncoders() {
for(int i = 0; i < ENCODER_COUNT; i += 1) {
encoders[i].encoder->write(0);
// turn off interrupts so we can
// write mutable shared state atomically
#ifdef USE_ENCODER_INTERRUPTS
noInterrupts();
#endif

for(uint8_t i = 0; i < ENCODER_COUNT; i += 1) {
encoders[i].ticks = 0;
}

// turn back on interrupts
#ifdef USE_ENCODER_INTERRUPTS
interrupts();
#endif
}

void readEncoders(long ticks[ENCODER_COUNT]) {
// turn off interrupts so we can
// read mutable shared state atomically
#ifdef USE_ENCODER_INTERRUPTS
noInterrupts();
#endif

for(uint8_t i = 0; i < ENCODER_COUNT; i += 1) {
ticks[i] = encoders[i].ticks;
}

// turn back on interrupts
#ifdef USE_ENCODER_INTERRUPTS
interrupts();
#endif
}


Expand All @@ -146,12 +255,15 @@ void resetEncoders() {
// "{ticks},{ticksMs}"
//
void writeTicks(unsigned long ticksMs) {
Serial.print(encoders[0].ticks);
long ticks[ENCODER_COUNT];
readEncoders(ticks);

Serial.print(ticks[0]);
Serial.print(',');
Serial.print(ticksMs);
for(int i = 1; i < ENCODER_COUNT; i += 1) {
for(uint8_t i = 1; i < ENCODER_COUNT; i += 1) {
Serial.print(";");
Serial.print(encoders[i].ticks);
Serial.print(ticks[i]);
Serial.print(',');
Serial.print(ticksMs);
}
Expand All @@ -160,6 +272,20 @@ void writeTicks(unsigned long ticksMs) {


void setup() {
// set all encoder pins to inputs
for(uint8_t i = 0; i < ENCODER_COUNT; i += 1) {
pinMode(encoders[i].pin_clock, INPUT);
pinMode(encoders[i].pin_data, INPUT);
#ifdef USE_ENCODER_INTERRUPTS
//
// if the pin is interrupt capable, then use interrupts
//
if (NOT_AN_INTERRUPT != digitalPinToInterrupt(encoders[i].pin_clock)) {
attachInterrupt(digitalPinToInterrupt(encoders[i].pin_clock), _isr_routines[i], FALLING);
}
#endif
}

Serial.begin(115200);
}

Expand Down
Loading

0 comments on commit c743ca3

Please sign in to comment.