My long path to configuring the RMT and PCNT to share GPIO

paulhun
Posts: 12
Joined: Wed Jun 06, 2018 11:48 am

Re: My long path to configuring the RMT and PCNT to share GPIO

Postby paulhun » Sat Sep 15, 2018 3:25 pm

Hi,
ESP_Angus many thanks for your reply.

I’ve switched to RMT for input step capture and brought forward some of the various functions.
My issue with the receive ISR handler function timing out after 5 seconds was due to xRingbufferReceive() not blocking correctly, once I changed to xRingbufferReceiveUpTo() then the task blocks and loops as it should without issue.

Depending on the speed required and pulses per mm for the stepper driver a cycle can vary between 200us to 600us.

Using RMT for input stepping capture and PCNT for encoder inputs will give me what I need – I believe. I’m looking to complete as a next stage development to use a second presence for both RMT & PCNT as a check / compare and contrast. I believe this will not cause any performance issues just provide the benefit of a checksum for both inputs, do you agree?

I’m only struggling with one issue now. My process for a step received; when a step is received a step is output to the stepper motor driver and a check is made against the encoder inputs to ensure the physical step has actually happened.
If I do a call to pcnt_get_counter_value() it generally takes 1 to 2us to complete, but it can take 50us to 250us, generally every 6th or 8th function call. Any idea why?

I’ve pinned the receive task to core 1 with all the code on core 0

I'm happy to post the code but it's greater than 700 lines and I don't know how to add a file.....

Many thanks, for the help received Paul
My task loop is as below;
while(rb) {
size_t rx_size = 0;
char *item = (char *) xRingbufferReceiveUpTo(rb, &rx_size, portMAX_DELAY,1);
if(item) {
vRingbufferReturnItem(rb, (void*) item);
// send a STEP, Direction indicator first then pulse to Stepper driver
stepCount++;
char dir = item[0]; // Direction output
if (dir == '1') {
REG_WRITE(GPIO_OUT_W1TS_REG, BIT(18));
};
if (dir == '0') {
REG_WRITE(GPIO_OUT_W1TC_REG, BIT(18));
};
delayMicroseconds(10);
// send STEP, to stepper driver
REG_WRITE(GPIO_OUT_W1TC_REG, BIT(19)); // write pin LOW
delayMicroseconds(10);
REG_WRITE(GPIO_OUT_W1TS_REG, BIT(19)); // write pin HIGH
delayMicroseconds(100); // give time for encoder interrups to be received

portENTER_CRITICAL_ISR(&mux);
pcnt_get_counter_value(PCNT_UNIT_0, &encCount); // get encoder count
if (encCount != last_encCount) { // compare current and last encoder count
stepCount =0;
encEventCount++;
}
portEXIT_CRITICAL_ISR(&mux);

last_encCount = encCount;
}

// validate step / encoder events - a step event should always be followed by an encoder event, ie encoder count should change
if (stepCount > 0) {
StepError++;
}

}

paulhun
Posts: 12
Joined: Wed Jun 06, 2018 11:48 am

Re: My long path to configuring the RMT and PCNT to share GPIO

Postby paulhun » Sun Sep 16, 2018 7:52 am

My code

Code: Select all

#define sVersion   1.01
/**
 * Brief:
 * This test code is used to monitor steps received (destined for a step motor) and checks an encoder for movement.
 *
 * GPIO status:
 * GPIO16: output
 * GPIO17: output
 * GPIO18: output
 * GPIO19: output
 * GPIO4:  input, RMT, steps in
 * GPIO5:  input, PCNT, encoder in
 * GPIO15: input, PCNT, encoder in
 * GPIO21: input, pulled up.

 * Test:
 * GPIO21 is DIR pin in
 * Connect GPIO23 with Vcc (HIGH), this holds off the eStop
 */

#include "esp_log.h"
#include "fonts.h"
#include "ssd1306.hpp"
#include "driver/gpio.h"
#include "driver/adc.h"
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "freertos/queue.h"
#include <stdio.h>
#include <string.h>
#include <stdlib.h>
#include <cstdio>
#include <string>
#include <sstream>
#include <iostream>

/* Timer */
#include "driver/ledc.h"
#include "esp_err.h"
#include "time.h"
#include "soc/cpu.h"
#include "soc/rtc.h"

/* Quad Encoder (PCNT) */
#include "driver/pcnt.h"

/* RMT Receiver  (RMT)*/
#include "driver/rmt.h"

using namespace std;

/* Quad Encoder */
#define PCNT_PULSE_GPIO       GPIO_NUM_15      // gpio for PCNT
#define PCNT_CONTROL_GPIO     GPIO_NUM_5
#define PCNT_H_LIM_VAL        10000 // count 16 bit register therefore count is limited to a max of −32,768 - 32,768
#define PCNT_L_LIM_VAL       -10000

typedef enum {
    QUAD_ENC_MODE_1 = 1,
    QUAD_ENC_MODE_2 = 2
} quad_encoder_mode;

int16_t last_encCount;

/* RMT Receiver */
#define RMT_RX_ACTIVE_LEVEL   1             // Data bit is active high
#define RMT_RX_CHANNEL_0      0             // RMT channel for receiver
#define RMT_RX_GPIO_NUM_0     GPIO_NUM_4    // GPIO number for receiver 
#define RMT_RX_CHANNEL_1      1             // RMT channel for receiver
#define RMT_RX_GPIO_NUM_1     GPIO_NUM_0    // GPIO number for receiver 
#define RMT_CLK_DIV           100           // RMT counter clock divider 
#define RMT_TICK_10_US        (80000000/RMT_CLK_DIV/100000)   // RMT counter value for 10 us.(Source clock is APB clock) 
#define RMT_BUFFER_SIZE       5000          // 5000 is max else cpu will crash!!
#define rmt_item32_tIMEOUT_US 50            // RMT receiver timeout value(us) 
                                            // this basically sets the cycle processing speed, 
                                            // may need to be increased when testing / proofing - to 100 or so
TaskHandle_t x_rmt_rx_task = NULL; 

#define RMT_CHANNEL_ERROR_STR "RMT CHANNEL ERR"
#define RMT_ADDR_ERROR_STR    "RMT ADDRESS ERR"
#define RMT_DRIVER_ERROR_STR  "RMT DRIVER ERR"
static const char* RMT_TAG =  "RMT";
static uint8_t s_rmt_driver_channels; // Bitmask (bits 0-7) of installed drivers' channels
static rmt_isr_handle_t x_s_rmt_driver_intr_handle;

#define RMT_CHECK(a, str, ret_val) \
    if (!(a)) { \
        ESP_LOGE(RMT_TAG,"%s(%d): %s", __FUNCTION__, __LINE__, str); \
        return (ret_val); \
    }

// Spinlock for protecting concurrent register-level access only
static portMUX_TYPE rmt_spinlock = portMUX_INITIALIZER_UNLOCKED;
// Mutex lock for protecting concurrent register/unregister of RMT channels' ISR
static _lock_t rmt_driver_isr_lock;

typedef struct {
    int tx_offset;
    int tx_len_rem;
    int tx_sub_len;
    rmt_channel_t channel;
    const rmt_item32_t* tx_data;
    xSemaphoreHandle tx_sem;
    RingbufHandle_t tx_buf;
    QueueHandle_t rx_buf;
    int rx_count =0;
} x_rmt_obj_t;

x_rmt_obj_t* x_p_rmt_obj[RMT_CHANNEL_MAX] = {0};

/* GPIO settings */
#define GPIO_eStop          GPIO_NUM_23  // eStop, to be used to halt all output, pull HIGH to suspend                              
#define GPIO_DUMMY_STEP     GPIO_NUM_16  // To be used to deliver dummy Step interrupt - fired by Timer
#define GPIO_DUMMY_ENCODER  GPIO_NUM_17  // To be used to deliver dummy Encoder interrupt - fired by Timer
#define GPIO_DIR            GPIO_NUM_18  // dirPinOut
#define GPIO_STEP           GPIO_NUM_19  // stepPinOut
// GPIO_NUM_4   // stepPinIn
// GPIO_NUM_5   // encoderPinAIn
// GPIO_NUM_21  // dirPinIn, to be used as dummy dir pin
#define ESP_INTR_FLAG_DEFAULT 0

/* OLED */
OLED oled = OLED(GPIO_NUM_26, GPIO_NUM_25, SSD1306_128x64);

/* delay functions */
#define NOP() asm volatile ("nop")

/* Variables */
static int  isr_handler_rx_count = 0;
static int  encEventCount  = 0;
static int  StepError      = 0;

static bool eStop          = false;
static bool EventStep      = false;
static bool EventEncoder   = false;
 
portMUX_TYPE mux = portMUX_INITIALIZER_UNLOCKED;


/* ------------------------------------------------------ */
/* ------------Display Task Section---------------------- */
/* ------------------------------------------------------ */
void displayTask(void *pvParameters) {
    /* Running on Core 1 = APP CPU */
	adc1_config_width(ADC_WIDTH_12Bit);
	adc1_config_channel_atten(ADC1_CHANNEL_4, ADC_ATTEN_0db);

	ostringstream os;

    int16_t encCount;
	while (1) {
		oled.clear();
		oled.select_font(1);
		os.str("");
		os << "ISR Step Count: " << x_p_rmt_obj[0]->rx_count;
		oled.draw_string(0, 0, os.str(), WHITE, BLACK);
		oled.draw_hline(0, 11, 128, WHITE);
        os.str("");
		os << "Handler Count:   " << isr_handler_rx_count;
 		oled.draw_string(0, 13, os.str(), WHITE, BLACK);
		oled.draw_hline(0, 24, 128, WHITE);       
        os.str("");
		os << "Step Error:  " << StepError;  
 		oled.draw_string(0, 26, os.str(), WHITE, BLACK);
		oled.draw_hline(0, 37, 128, WHITE);  
        os.str("");

        pcnt_get_counter_value(PCNT_UNIT_0, &encCount);
        os << "Enc  Count:   " << encCount;    
 		oled.draw_string(0, 39, os.str(), WHITE, BLACK);
		oled.draw_hline(0, 50, 128, WHITE);  
        os.str("");      
        if (eStop) {
            os << "eStop:  ACTIVE";
        }
        else {
            os << "eStop:  OK";    
        }
 		oled.draw_string(0, 52, os.str(), WHITE, BLACK);
        os.str("");
		oled.refresh(true);

		vTaskDelay(250 / portTICK_PERIOD_MS);
	}

} // displayTask


/* ------------------------------------------------------ */
/* ------------Micro second delay functions-------------- */
/* ------------------------------------------------------ */
unsigned long IRAM_ATTR micros()
{
    return (unsigned long) esp_timer_get_time();
} // micros
/* ------------------------------------------------------ */


void IRAM_ATTR delayMicroseconds(uint32_t us)
{
    uint32_t m = micros();
    if(us){
        uint32_t e = (m + us);
        if(m > e){ //overflow
            while(micros() > e) {
                NOP();
            }
        }
        while(micros() < e) {
            NOP();
        }
    }
} // delayMicroseconds
/* ------------------------------------------------------ */


esp_err_t x_rmt_get_ringbuf_handle(rmt_channel_t channel, RingbufHandle_t* buf_handle)
{
    RMT_CHECK(channel < RMT_CHANNEL_MAX, RMT_CHANNEL_ERROR_STR, ESP_ERR_INVALID_ARG);
    RMT_CHECK(x_p_rmt_obj[channel] != NULL, RMT_DRIVER_ERROR_STR, ESP_FAIL);
    RMT_CHECK(buf_handle != NULL, RMT_ADDR_ERROR_STR, ESP_ERR_INVALID_ARG);
    *buf_handle = x_p_rmt_obj[channel]->rx_buf;
    return ESP_OK;
}



static void IRAM_ATTR rmt_fill_memory(rmt_channel_t channel, const rmt_item32_t* item, uint16_t item_num, uint16_t mem_offset)
{
    portENTER_CRITICAL(&rmt_spinlock);
    RMT.apb_conf.fifo_mask = RMT_DATA_MODE_MEM;
    portEXIT_CRITICAL(&rmt_spinlock);
    int i;
    for(i = 0; i < item_num; i++) {
        RMTMEM.chan[channel].data32[i + mem_offset].val = item[i].val;
    }
}

static void IRAM_ATTR x_rmt_driver_isr_default(void* arg)
{
    uint32_t intr_st = RMT.int_st.val;
    uint32_t i = 0;
    uint8_t channel;
    portBASE_TYPE HPTaskAwoken = 0;
    for(i = 0; i < 32; i++) {
        if(i < 24) {
            if(intr_st & BIT(i)) {
                channel = i / 3;
                x_rmt_obj_t* p_rmt = x_p_rmt_obj[channel];
                switch(i % 3) {
                    //TX END
                    case 0: {
                        ESP_EARLY_LOGD(RMT_TAG, "RMT INTR : TX END");
                        xSemaphoreGiveFromISR(p_rmt->tx_sem, &HPTaskAwoken);
                        if(HPTaskAwoken == pdTRUE) {
                            portYIELD_FROM_ISR();
                        }
                        p_rmt->tx_data = NULL;
                        p_rmt->tx_len_rem = 0;
                        p_rmt->tx_offset = 0;
                        p_rmt->tx_sub_len = 0;
                        break;
                        //RX_END
                    }
                    case 1: {
                        ESP_EARLY_LOGD(RMT_TAG, "RMT INTR : RX END");
                        // Retrieve a bit-mask of the values of the first 32 GPIOs (0-31). Reading direct from reg is the quickest way to get data
                        uint32_t regval = REG_READ(GPIO_IN_REG) & BIT(21);        
                        char tx_item[1];
                        sprintf(tx_item,"%u", (regval & 1<< GPIO_NUM_21 ) >> GPIO_NUM_21);
                        RMT.conf_ch[channel].conf1.rx_en = 0;
                        RMT.conf_ch[channel].conf1.mem_owner = RMT_MEM_OWNER_TX;
                        p_rmt->rx_count++;
                        if(p_rmt->rx_buf) {
                            BaseType_t res = xRingbufferSendFromISR(p_rmt->rx_buf, (void*) tx_item, sizeof(tx_item), &HPTaskAwoken);                           
                            if(res == pdFALSE) {
                                ESP_EARLY_LOGE(RMT_TAG, "RMT RX BUFFER FULL");
                            } else {
                                //
                            }
                            if(HPTaskAwoken == pdTRUE) {
                                portYIELD_FROM_ISR();
                            }
                        } else {
                            ESP_EARLY_LOGE(RMT_TAG, "RMT RX BUFFER ERROR\n");
                        }
                        RMT.conf_ch[channel].conf1.mem_wr_rst = 1;
                        RMT.conf_ch[channel].conf1.mem_owner = RMT_MEM_OWNER_RX;
                        RMT.conf_ch[channel].conf1.rx_en = 1;
                        break;
                        //ERR
                    }
                    case 2: {
                        ESP_EARLY_LOGE(RMT_TAG, "RMT[%d] ERR", channel);
                        ESP_EARLY_LOGE(RMT_TAG, "status: 0x%08x", RMT.status_ch[channel]);
                        RMT.int_ena.val &= (~(BIT(i)));
                        break;
                    }
                    default:
                        break;
                }
                RMT.int_clr.val = BIT(i);
            }
        } else {
            if(intr_st & (BIT(i))) {
                channel = i - 24;
                x_rmt_obj_t* p_rmt = x_p_rmt_obj[channel];
                RMT.int_clr.val = BIT(i);
                ESP_EARLY_LOGD(RMT_TAG, "RMT CH[%d]: EVT INTR", channel);
                if(p_rmt->tx_data == NULL) {
                    //skip
                } else {
                    const rmt_item32_t* pdata = p_rmt->tx_data;
                    int len_rem = p_rmt->tx_len_rem;
                    if(len_rem >= p_rmt->tx_sub_len) {
                        rmt_fill_memory((rmt_channel_t)channel, pdata, p_rmt->tx_sub_len, p_rmt->tx_offset);
                        p_rmt->tx_data += p_rmt->tx_sub_len;
                        p_rmt->tx_len_rem -= p_rmt->tx_sub_len;
                    } else if(len_rem == 0) {
                        RMTMEM.chan[channel].data32[p_rmt->tx_offset].val = 0;
                    } else {
                        rmt_fill_memory((rmt_channel_t)channel, pdata, len_rem, p_rmt->tx_offset);
                        RMTMEM.chan[channel].data32[p_rmt->tx_offset + len_rem].val = 0;
                        p_rmt->tx_data += len_rem;
                        p_rmt->tx_len_rem -= len_rem;
                    }
                    if(p_rmt->tx_offset == 0) {
                        p_rmt->tx_offset = p_rmt->tx_sub_len;
                    } else {
                        p_rmt->tx_offset = 0;
                    }
                }
            }
        }
    }
}

esp_err_t x_rmt_driver_install(rmt_channel_t channel, size_t rx_buf_size, int intr_alloc_flags)
{
    RMT_CHECK(channel < RMT_CHANNEL_MAX, RMT_CHANNEL_ERROR_STR, ESP_ERR_INVALID_ARG);
    RMT_CHECK((s_rmt_driver_channels & BIT(channel)) == 0, "RMT driver already installed for channel", ESP_ERR_INVALID_STATE);

    esp_err_t err = ESP_OK;

    if(x_p_rmt_obj[channel] != NULL) {
        ESP_LOGD(RMT_TAG, "RMT driver already installed");
        return ESP_ERR_INVALID_STATE;
    }

    x_p_rmt_obj[channel] = (x_rmt_obj_t*) malloc(sizeof(x_rmt_obj_t));

    if(x_p_rmt_obj[channel] == NULL) {
        ESP_LOGE(RMT_TAG, "RMT driver malloc error");
        return ESP_ERR_NO_MEM;
    }
    memset(x_p_rmt_obj[channel], 0, sizeof(x_rmt_obj_t));

    x_p_rmt_obj[channel]->tx_len_rem = 0;
    x_p_rmt_obj[channel]->tx_data = NULL;
    x_p_rmt_obj[channel]->channel = channel;
    x_p_rmt_obj[channel]->tx_offset = 0;
    x_p_rmt_obj[channel]->tx_sub_len = 0;

    if(x_p_rmt_obj[channel]->tx_sem == NULL) {
        x_p_rmt_obj[channel]->tx_sem = xSemaphoreCreateBinary();
        xSemaphoreGive(x_p_rmt_obj[channel]->tx_sem);
    }
    if(x_p_rmt_obj[channel]->rx_buf == NULL && rx_buf_size > 0) {
        x_p_rmt_obj[channel]->rx_buf = xRingbufferCreate(rx_buf_size, RINGBUF_TYPE_BYTEBUF);
        rmt_set_rx_intr_en(channel, 1);
        rmt_set_err_intr_en(channel, 1);
    }

    _lock_acquire_recursive(&rmt_driver_isr_lock);

    if(s_rmt_driver_channels == 0) { // first RMT channel using driver
        err = rmt_isr_register(x_rmt_driver_isr_default, NULL, intr_alloc_flags, &x_s_rmt_driver_intr_handle);
    }
    if (err == ESP_OK) {
        s_rmt_driver_channels |= BIT(channel);
        rmt_set_tx_intr_en(channel, 1);
    }

    _lock_release_recursive(&rmt_driver_isr_lock);

    return err;
}



static void gpio_isr_eStop_handler(void* arg) { 
    eStop = true;
} // gpio_isr_eStop_handler
/*--------------------------------------------------------*/


/* ------------------------------------------------------ */
/* ------------GPIO Setup-------------------------------- */
/* ------------------------------------------------------ */
void gpio_init() {
    gpio_pad_select_gpio(GPIO_DIR);
    gpio_pad_select_gpio(GPIO_STEP);
    gpio_pad_select_gpio(GPIO_eStop);
    gpio_pad_select_gpio(GPIO_DUMMY_STEP);
    gpio_pad_select_gpio(GPIO_DUMMY_ENCODER);
    gpio_set_direction(GPIO_DIR,GPIO_MODE_OUTPUT);
    gpio_set_direction(GPIO_STEP,GPIO_MODE_OUTPUT);
    gpio_set_direction(GPIO_eStop,GPIO_MODE_INPUT);
    gpio_set_direction(GPIO_DUMMY_STEP,GPIO_MODE_OUTPUT);
    gpio_set_direction(GPIO_DUMMY_ENCODER,GPIO_MODE_OUTPUT);
    gpio_install_isr_service(ESP_INTR_FLAG_DEFAULT);
    gpio_isr_handler_add(GPIO_eStop, gpio_isr_eStop_handler,   (void*) GPIO_eStop); // pin23 // eStop
}// gpio_init
/*-----------------------------------------------------------*/


/* --------------------------------------------------------- */
/* ------------Quad Encoder Initialise     ----------------- */
/* --------------------------------------------------------- */
static void quadrature_encoder_counter_init(quad_encoder_mode enc_mode) {
    pcnt_config_t pcnt_config = {      
        .pulse_gpio_num = PCNT_PULSE_GPIO,
        .ctrl_gpio_num = PCNT_CONTROL_GPIO,
        .lctrl_mode = PCNT_MODE_KEEP,          // Reverse counting direction if low
        .hctrl_mode = PCNT_MODE_REVERSE,       // Keep the primary counter mode if high             
        .pos_mode = PCNT_COUNT_INC,            // Count up on the positive edge
        .neg_mode = PCNT_COUNT_DIS,            // Keep the counter value on the negative edge            
        .counter_h_lim = (int16_t)PCNT_H_LIM_VAL,
        .counter_l_lim = (int16_t)PCNT_L_LIM_VAL,
        .unit = PCNT_UNIT_0,
        .channel = PCNT_CHANNEL_0,
    };

    switch (enc_mode) {
    case QUAD_ENC_MODE_1:
        break;
    case QUAD_ENC_MODE_2:
        pcnt_config.neg_mode = PCNT_COUNT_DEC;
        break;     
    }

    pcnt_unit_config(&pcnt_config);
    pcnt_set_filter_value(PCNT_UNIT_0, 100);
    pcnt_filter_enable(PCNT_UNIT_0);

    pcnt_event_enable(PCNT_UNIT_0, PCNT_EVT_ZERO);
    pcnt_event_enable(PCNT_UNIT_0, PCNT_EVT_H_LIM);
    pcnt_event_enable(PCNT_UNIT_0, PCNT_EVT_L_LIM);

    /* Initialize PCNT's counter */
    pcnt_counter_pause(PCNT_UNIT_0);
    pcnt_counter_clear(PCNT_UNIT_0);

    pcnt_counter_resume(PCNT_UNIT_0);

} // quadrature_encoder_counter_init
/*-----------------------------------------------------------*/


/* --------------------------------------------------------- */
/* ---Remote Receiver Initialise, for input Step control---- */
/* --------------------------------------------------------- */
static void rmt_rx_init() { 
rmt_config_t rmt_rx;
    rmt_rx.channel = (rmt_channel_t)RMT_RX_CHANNEL_0;
    rmt_rx.gpio_num = RMT_RX_GPIO_NUM_0;
    rmt_rx.clk_div = RMT_CLK_DIV;
    rmt_rx.mem_block_num = 1;
    rmt_rx.rmt_mode = RMT_MODE_RX;
    rmt_rx.rx_config.filter_en = true;
    rmt_rx.rx_config.filter_ticks_thresh = 50;  // Pulses shorter than this setting will be filtered out.
    rmt_rx.rx_config.idle_threshold = rmt_item32_tIMEOUT_US / 10 * (RMT_TICK_10_US);
    rmt_config(&rmt_rx);
    x_rmt_driver_install(rmt_rx.channel, 1000, ESP_INTR_FLAG_IRAM);  // channel, ringbuffer size, interrup allocation flag 

} // RMT_rx_init
/* ------------------------------------------------------ */
  

/* ------------------------------------------------------ */
/* ------------Step Control Task   ---------------------- */
/* ------------------------------------------------------ */
static void rmt_rx_task(void *pvParameters)
{
    int channel = RMT_RX_CHANNEL_0;
    int stepCount = 0;
    int tollerance = 9; // for +- comparison tollerance when comparing steps to encoder value
    int16_t encCount;
    rmt_rx_init();
    RingbufHandle_t rb = NULL;
    //get RMT RX ringbuffer handle
    x_rmt_get_ringbuf_handle((rmt_channel_t)channel, &rb);
    rmt_rx_start((rmt_channel_t)channel, 1);
    while(rb) {
        //get condition of eStop input pin, if HIGH suspend task
        eStop = gpio_get_level(GPIO_eStop); 
        if (eStop) {
            vTaskSuspend(NULL);          
        }
        size_t rx_size = 0;
        char *item = (char *) xRingbufferReceiveUpTo(rb, &rx_size, portMAX_DELAY,1);
        if(item) {
            //after reading the data, return spaces to ringbuffer.
            vRingbufferReturnItem(rb, (void*) item);
            stepCount++;

            char dir = item[0];
            if (dir == '1') {
                // write pin HIGH
                REG_WRITE(GPIO_OUT_W1TS_REG, BIT(18)); // GPIO_OUTPUT_IO_2
                isr_handler_rx_count--;
            };
            if (dir == '0') {
                // write pin LOW
                REG_WRITE(GPIO_OUT_W1TC_REG, BIT(18));
                isr_handler_rx_count++;
            };       
            delayMicroseconds(10);                 // give a minimum 5us delay after a DIR pulse    
            // send STEP                           // output needs to be high to low for falling edge
            // write pin LOW                       // write direct to register as faster than using 'gpio_set_level'
            REG_WRITE(GPIO_OUT_W1TC_REG, BIT(19)); // GPIO_STEP // the step output gets converted / flipped
            delayMicroseconds(10);                 // so sent as low to high
            // write pin HIGH
            REG_WRITE(GPIO_OUT_W1TS_REG, BIT(19)); // GPIO_STEP
            
            delayMicroseconds(100);  // gives time for encoder interrups to be received
           
            portENTER_CRITICAL_ISR(&mux);
            pcnt_get_counter_value(PCNT_UNIT_0, &encCount);           
            if ( (( abs(encCount / 3) + tollerance) > abs(isr_handler_rx_count)) && ((abs(encCount / 3) - tollerance) < abs(isr_handler_rx_count)) ) {              
                    stepCount =0;
        	        encEventCount++;                // tollerance added as count will catch up!!
            }
            portEXIT_CRITICAL_ISR(&mux);  
        }
        // validate step / encoder events  - a step event should always be followed by an encoder event
        if (stepCount > 0) {
            StepError++;
        }
        EventStep = false;
        EventEncoder = false;       
    }
    vTaskDelete(NULL);
} // rmt_rx_task
/* ------------------------------------------------------ */


/*-----------------------------------------------------------*/
/* --------------Startup Config Section--------------------- */
/* --------------------------------------------------------- */

#ifdef __cplusplus
extern "C" {
#endif
void app_main() {
    //gpio setup
    gpio_init();
    //quad encoder setup
    quadrature_encoder_counter_init(QUAD_ENC_MODE_2);  // options: QUAD_ENC_MODE_1 or QUAD_ENC_MODE_2
    //receiver setup
    xTaskCreatePinnedToCore(rmt_rx_task, "rmt_rx_task", 2048, NULL, 10, NULL,1);
    //set display 
	oled = OLED(GPIO_NUM_26, GPIO_NUM_25, SSD1306_128x64);
    //display opening screen
	if (oled.init()) {
		ESP_LOGI("OLED", "oled initiated");
		oled.draw_rectangle(10, 30, 20, 20, WHITE);
		oled.fill_rectangle(12,32,16,16, WHITE);
		oled.select_font(0);
		oled.draw_string(0, 0, "Hello Mate", WHITE, BLACK);
		oled.select_font(1);
		oled.draw_string(0, 12, "Step Control is here to stay, oh yeah!", WHITE, BLACK);
		oled.draw_string(35, 35, "Hello  E S P 3 2  !", WHITE, BLACK);
		oled.refresh(true);
		vTaskDelay(3000 / portTICK_PERIOD_MS);
		xTaskCreatePinnedToCore(&displayTask, "displaytask", 2048, NULL, 2, NULL, 0);
	} else {
		ESP_LOGE("OLED", "oled initiation failed");
	}
}
#ifdef __cplusplus
}
#endif



edigi32
Posts: 8
Joined: Fri Oct 05, 2018 6:49 am

Re: My long path to configuring the RMT and PCNT to share GPIO

Postby edigi32 » Tue Oct 16, 2018 12:56 pm

Sorry for hijacking this thread with a question that somewhat still relates to it.
So I'd like to control from ISR when PCNT counting is started/stopped (without any control pin assigned to this).

That is i'd like to connect the input signal of 41 (pcnt_ctrl_ch0_in0; PCNT unit 0, channel 0) to GPIO_NUM_48 (const 0) or GPIO_NUM_56 (const 1) or something similar.

What would be the correct way to do this (some example code please) with minimal delay (GPIO_SIG41_IN_SEL+GPIO_FUNC41_IN_SEL?)?

Maybe?

Code: Select all

REG_WRITE(GPIO_FUNC41_IN_SEL_CFG_REG, 0x80+0x38); // set 1
REG_WRITE(GPIO_FUNC41_IN_SEL_CFG_REG, 0x80+0x30); // set 0
Update: I've tested the above code and it works, however pcnt_config.ctrl_gpio_num has to be set to a real GPIO for pcnt_unit_config even though in practice it's not used later on.

edigi32
Posts: 8
Joined: Fri Oct 05, 2018 6:49 am

Re: My long path to configuring the RMT and PCNT to share GPIO

Postby edigi32 » Fri Oct 26, 2018 7:22 am

It is possible to use the PCNT without any control pin if -1 is assigned to control GPIO at initialization time. Thus:

Code: Select all

  pcnt_config.ctrl_gpio_num = -1;


Via this and my earlier sample it is possible that counting is started/stopped entirely from SW (in my case from interrupt code, connecting the control GPIO to the always 1/0 GPIO) without any control pin used (thus only counting pin is needed).

It's not RMT based like started in this thread, but it's another alternative for saving some pins connected to PCNT use that can be useful in some cases.

ataboo
Posts: 1
Joined: Mon Jan 04, 2021 12:09 am

Re: My long path to configuring the RMT and PCNT to share GPIO

Postby ataboo » Mon Jan 04, 2021 12:30 am

I really appreciate the way this was laid out. It made journeying into lower level IDF much more manageable as I'm still figuring things out.

For anyone looking to get MCPWM and PCNT using the same pin, I have an example here:
https://github.com/ataboo/esp-mcpwm-pcn ... ain/main.c

The key fix for getting input and output on the same pulse and direction pins:

Code: Select all

// Enable both pins as output.
REG_SET_BIT(GPIO_ENABLE_REG, (1ULL<<TICK_PIN|1ULL<<DIR_PIN));
// Enable input on direction pin mux.
PIN_INPUT_ENABLE(GPIO_PIN_MUX_REG[DIR_PIN]);
// Connect MCPWM pulse signal to TICK output in-case MCPWM is setup before TICK is registered as an input.
gpio_matrix_out(TICK_PIN, pulse_signal, 0, 0);
// Enable TICK as input in GPIO mux.
PIN_INPUT_ENABLE(GPIO_PIN_MUX_REG[TICK_PIN]);
I'm sure there's more elegant approaches but hopefully this can help anyone else trying to understand what the fix is doing.

One part that was a little confusing in the above example was this line:

Code: Select all

REG_SET_BIT(IO_MUX_GPIO4_REG, 512);
If I understand it correctly, this is enabling FUN_IE (1ULL<<9) as seen in the technical reference manual under IO_MUX_X_REG:

https://www.espressif.com/sites/default ... ual_en.pdf

I found the the PIN_INPUT_ENABLE macro is just setting the same thing so used that instead.

Who is online

Users browsing this forum: No registered users and 118 guests