Skip to content

Commit

Permalink
Add possibility to use interrupts on every pulse and set a callback (#52
Browse files Browse the repository at this point in the history
)

* interrupts on every encoder change.

* refine always interrupt

* interrupt callback.

* cleanup.

* whitespace.

* Add example.

* Add enc_isr_cb_data

* Rename example to INO

* Make it Arduino example.

* Complete ctor initialization of members.

* delete old example.
  • Loading branch information
larroy authored Mar 3, 2022
1 parent b8040d1 commit b4bc076
Show file tree
Hide file tree
Showing 3 changed files with 157 additions and 56 deletions.
64 changes: 64 additions & 0 deletions examples/Encoder_interrupt_display/Encoder_interrupt_display.ino
Original file line number Diff line number Diff line change
@@ -0,0 +1,64 @@
#include <Arduino.h>
#include <ESP32Encoder.h>
#include <Adafruit_GFX.h>
#include <Adafruit_SSD1306.h>
#include "esp_task_wdt.h"

static IRAM_ATTR void enc_cb(void* arg) {
ESP32Encoder* enc = (ESP32Encoder*) arg;
//Serial.printf("enc cb: count: %d\n", enc->getCount());
static bool leds = false;
digitalWrite(LED_BUILTIN, (int)leds);
leds = !leds;
}

extern bool loopTaskWDTEnabled;
extern TaskHandle_t loopTaskHandle;

ESP32Encoder encoder(true, enc_cb);
Adafruit_SSD1306 display(128, 32, &Wire);

static const char* LOG_TAG = "main";

void setup(){
loopTaskWDTEnabled = true;
pinMode(LED_BUILTIN, OUTPUT);
Serial.begin(115200);
// Encoder A and B pins connected with 1K series resistor to pins 4 and 5, common pin to ground.
// |- A --- 1K --- pin 4
// >=[enc]|- GND
// |- B --- 1K --- pin 5

ESP32Encoder::useInternalWeakPullResistors=UP;
encoder.attachSingleEdge(4, 5);
encoder.clearCount();
encoder.setFilter(1023);

if (! display.begin(SSD1306_SWITCHCAPVCC, 0x3c))
{
for (;;) {
Serial.println("display init failed");
}
}
display.cp437(true);
display.clearDisplay();
display.setTextSize(2);
display.setTextColor(WHITE);
display.setCursor(0,0);
display.display();
esp_log_level_set("*", ESP_LOG_DEBUG);
esp_log_level_set("main", ESP_LOG_DEBUG);
esp_log_level_set("ESP32Encoder", ESP_LOG_DEBUG);
esp_task_wdt_add(loopTaskHandle);
}

void loop(){

display.clearDisplay();
display.setCursor(0,0);
display.printf("E: %lld\n", encoder.getCount());
display.display();
Serial.printf("Enc count: %d\n", encoder.getCount());
delay(500);

}
99 changes: 60 additions & 39 deletions src/ESP32Encoder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,9 @@

#include <ESP32Encoder.h>
#include <soc/pcnt_struct.h>
#include "esp_log.h"

static const char* TAG = "ESP32Encoder";


//static ESP32Encoder *gpio2enc[48];
Expand All @@ -18,17 +21,24 @@ ESP32Encoder *ESP32Encoder::encoders[MAX_ESP32_ENCODERS] = { NULL, };
bool ESP32Encoder::attachedInterrupt=false;
pcnt_isr_handle_t ESP32Encoder::user_isr_handle = NULL;

ESP32Encoder::ESP32Encoder() {
attached = false;
aPinNumber = (gpio_num_t) 0;
bPinNumber = (gpio_num_t) 0;
working = false;
direction = false;
unit = (pcnt_unit_t) -1;
ESP32Encoder::ESP32Encoder(bool always_interrupt_, enc_isr_cb_t enc_isr_cb, void* enc_isr_cb_data):
always_interrupt{always_interrupt_},
aPinNumber{(gpio_num_t) 0},
bPinNumber{(gpio_num_t) 0},
unit{(pcnt_unit_t) -1},
fullQuad{false},
countsMode{2},
count{0},
r_enc_config{},
_enc_isr_cb(enc_isr_cb),
_enc_isr_cb_data(enc_isr_cb_data),
attached{false},
direction{false},
working{false}
{
}

ESP32Encoder::~ESP32Encoder() {
}
ESP32Encoder::~ESP32Encoder() {}

/* Decode what PCNT's unit originated an interrupt
* and pass this information together with the event type
Expand All @@ -41,39 +51,46 @@ ESP32Encoder::~ESP32Encoder() {
#define COUNTER_H_LIM h_lim_lat
#define COUNTER_L_LIM l_lim_lat
#endif
static void IRAM_ATTR pcnt_example_intr_handler(void *arg) {
ESP32Encoder * ptr;

static void IRAM_ATTR esp32encoder_pcnt_intr_handler(void *arg) {
ESP32Encoder * esp32enc = {};
uint32_t intr_status = PCNT.int_st.val;
int i;

for (i = 0; i < PCNT_UNIT_MAX; i++) {
for (uint8_t i = 0; i < PCNT_UNIT_MAX; i++) {
if (intr_status & (BIT(i))) {
ptr = ESP32Encoder::encoders[i];
/* Save the PCNT event type that caused an interrupt
to pass it to the main program */

int64_t status=0;
pcnt_unit_t unit = static_cast<pcnt_unit_t>(i);
esp32enc = ESP32Encoder::encoders[i];
if(PCNT.status_unit[i].COUNTER_H_LIM){
status=ptr->r_enc_config.counter_h_lim;
esp32enc->count += esp32enc->r_enc_config.counter_h_lim;
pcnt_counter_clear(unit);
} else if(PCNT.status_unit[i].COUNTER_L_LIM){
esp32enc->count += esp32enc->r_enc_config.counter_l_lim;
pcnt_counter_clear(unit);
} else if(esp32enc->always_interrupt && (PCNT.status_unit[i].thres0_lat || PCNT.status_unit[i].thres1_lat)) {
int16_t c;
pcnt_get_counter_value(unit, &c);
esp32enc->count += c;
pcnt_set_event_value(unit, PCNT_EVT_THRES_0, -1);
pcnt_set_event_value(unit, PCNT_EVT_THRES_1, 1);
pcnt_event_enable(unit, PCNT_EVT_THRES_0);
pcnt_event_enable(unit, PCNT_EVT_THRES_1);
pcnt_counter_clear(unit);
if (esp32enc->_enc_isr_cb) {
esp32enc->_enc_isr_cb(esp32enc->_enc_isr_cb_data);
}
}
if(PCNT.status_unit[i].COUNTER_L_LIM){
status=ptr->r_enc_config.counter_l_lim;
}
//pcnt_counter_clear(ptr->unit);
PCNT.int_clr.val = BIT(i); // clear the interrupt
ptr->count = status + ptr->count;
}
}
}

void ESP32Encoder::detatch(){
pcnt_counter_pause(unit);
ESP32Encoder::encoders[unit]=NULL;

}
void ESP32Encoder::attach(int a, int b, enum encType et) {
if (attached) {
Serial.println("Already attached, FAIL!");
ESP_LOGE(TAG, "attach: already attached");
return;
}
int index = 0;
Expand All @@ -84,7 +101,7 @@ void ESP32Encoder::attach(int a, int b, enum encType et) {
}
}
if (index == MAX_ESP32_ENCODERS) {
Serial.println("Too many encoders, FAIL!");
ESP_LOGE(TAG, "Too many encoders, FAIL!");
return;
}

Expand Down Expand Up @@ -159,28 +176,32 @@ void ESP32Encoder::attach(int a, int b, enum encType et) {
r_enc_config .counter_h_lim = _INT16_MAX;
r_enc_config .counter_l_lim = _INT16_MIN ;

pcnt_unit_config(&r_enc_config);
pcnt_unit_config(&r_enc_config);
}


// Filter out bounces and noise
setFilter(250); // Filter Runt Pulses

/* Enable events on maximum and minimum limit values */
pcnt_event_enable(unit, PCNT_EVT_H_LIM);
pcnt_event_enable(unit, PCNT_EVT_L_LIM);

pcnt_counter_pause(unit); // Initial PCNT init
pcnt_counter_clear(unit);
/* Register ISR handler and enable interrupts for PCNT unit */
if(attachedInterrupt==false){
attachedInterrupt=true;
esp_err_t er = pcnt_isr_register(pcnt_example_intr_handler,(void *) NULL, (int)0,
if(! attachedInterrupt){
if (always_interrupt) {
pcnt_set_event_value(unit, PCNT_EVT_THRES_0, -1);
pcnt_set_event_value(unit, PCNT_EVT_THRES_1, 1);
pcnt_event_enable(unit, PCNT_EVT_THRES_0);
pcnt_event_enable(unit, PCNT_EVT_THRES_1);
}
esp_err_t er = pcnt_isr_register(esp32encoder_pcnt_intr_handler,(void *) NULL, (int)0,
(pcnt_isr_handle_t *)&ESP32Encoder::user_isr_handle);
if (er != ESP_OK){
Serial.println("Encoder wrap interrupt failed");
ESP_LOGE(TAG, "Encoder wrap interrupt failed");
}
attachedInterrupt=true;
}
pcnt_counter_clear(unit);
pcnt_intr_enable(unit);
pcnt_counter_resume(unit);

Expand All @@ -206,7 +227,7 @@ int64_t ESP32Encoder::getCountRaw() {
return c;
}
int64_t ESP32Encoder::getCount() {
return getCountRaw() + count;
return count + getCountRaw();
}

int64_t ESP32Encoder::clearCount() {
Expand All @@ -225,10 +246,10 @@ int64_t ESP32Encoder::resumeCount() {
void ESP32Encoder::setFilter(uint16_t value) {
if(value>1023)value=1023;
if(value==0) {
pcnt_filter_disable(unit);
pcnt_filter_disable(unit);
} else {
pcnt_set_filter_value(unit, value);
pcnt_filter_enable(unit);
pcnt_filter_enable(unit);
}

}
50 changes: 33 additions & 17 deletions src/ESP32Encoder.h
Original file line number Diff line number Diff line change
Expand Up @@ -6,30 +6,34 @@
#define _INT16_MAX 32766
#define _INT16_MIN -32766


enum encType {
single,
half,
full
single,
half,
full
};

enum puType {
UP,
DOWN,
NONE
UP,
DOWN,
NONE
};
class ESP32Encoder {
private:
void attach(int aPintNumber, int bPinNumber, enum encType et);
boolean attached=false;

class ESP32Encoder;

static pcnt_isr_handle_t user_isr_handle; //user's ISR service handle
bool direction;
bool working;
typedef void (*enc_isr_cb_t)(void*);

static bool attachedInterrupt;
int64_t getCountRaw();
class ESP32Encoder {
public:
ESP32Encoder();
/**
* @brief Construct a new ESP32Encoder object
*
* @param always_interrupt set to true to enable interrupt on every encoder pulse, otherwise false
* @param enc_isr_cb callback executed on every encoder ISR, gets a pointer to
* the ESP32Encoder instance as an argument, no effect if always_interrupt is
* false
*/
ESP32Encoder(bool always_interrupt=false, enc_isr_cb_t enc_isr_cb=nullptr, void* enc_isr_cb_data=nullptr);
~ESP32Encoder();
void attachHalfQuad(int aPintNumber, int bPinNumber);
void attachFullQuad(int aPintNumber, int bPinNumber);
Expand All @@ -43,6 +47,7 @@ class ESP32Encoder {
void setCount(int64_t value);
void setFilter(uint16_t value);
static ESP32Encoder *encoders[MAX_ESP32_ENCODERS];
bool always_interrupt;
gpio_num_t aPinNumber;
gpio_num_t bPinNumber;
pcnt_unit_t unit;
Expand All @@ -51,8 +56,19 @@ class ESP32Encoder {
volatile int64_t count=0;
pcnt_config_t r_enc_config;
static enum puType useInternalWeakPullResistors;
enc_isr_cb_t _enc_isr_cb;
void* _enc_isr_cb_data;

private:
static pcnt_isr_handle_t user_isr_handle;
static bool attachedInterrupt;
void attach(int aPintNumber, int bPinNumber, enum encType et);
int64_t getCountRaw();
bool attached;
bool direction;
bool working;
};

//Added by Sloeber
//Added by Sloeber
#pragma once

0 comments on commit b4bc076

Please sign in to comment.