首页 > 其他分享 >旋转编码器

旋转编码器

时间:2024-02-16 20:45:08浏览次数:21  
标签:编码器 ESP ec11 rotary encoder pcnt 旋转 config

硬件连接图

编码器原理图

程序

添加encoder.h和rotary_encoder.h到platformIO的include目录下,程序如下:

encoder.h

#ifndef __MY_ENCODER_H
#define __MY_ENCODER_H

#include "rotary_encoder.h"
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "freertos/semphr.h"
#include "driver/gpio.h"

typedef enum key_state {
    KEY_UP = 0,                             /* 编码器按键弹起状态 */
    KEY_DOWN,                               /* 编码器按键按下状态 */
}key_state_t;

#define ENCODER_A_PIN       25          /* 编码器A端 */
#define ENCODER_B_PIN       27          /* 编码器B端 */
#define ENCODER_PUSH_PIN    GPIO_NUM_26          /* 编码器KEY端 */   /*需要使用有效的 gpio_num_t 值来替代整数值*/
#define ENCODER_PUSH_GPIO_PIN_SEL   (1ULL << ENCODER_PUSH_PIN)      /* 编码器KEY GPIO bit 掩码 */

void encoder_config(void);              /* 编码器配置 */
void input_task_create(void);         /* 编码器任务创建 */
int32_t encoder_get_diff(void);         /* 获取编码器值 */
bool encoder_get_is_push(void);         /* 获取编码器KEY是否按下值 */

#endif

rotary_encoder.h

// Copyright 2020 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
//     http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#pragma once

#ifdef __cplusplus
extern "C" {
#endif

#include "esp_err.h"

/**
 * @brief Type of Rotary underlying device handle
 *
 */
typedef void *rotary_encoder_dev_t;

/**
 * @brief Type of rotary encoder configuration
 *
 */
typedef struct {
    rotary_encoder_dev_t dev; /*!< Underlying device handle */
    int phase_a_gpio_num;     /*!< Phase A GPIO number */
    int phase_b_gpio_num;     /*!< Phase B GPIO number */
    int flags;                /*!< Extra flags */
} rotary_encoder_config_t;

/**
 * @brief Default rotary encoder configuration
 *
 */
#define ROTARY_ENCODER_DEFAULT_CONFIG(dev_hdl, gpio_a, gpio_b) \
    {                                                          \
        .dev = dev_hdl,                                        \
        .phase_a_gpio_num = gpio_a,                            \
        .phase_b_gpio_num = gpio_b,                            \
        .flags = 0,                                            \
    }

/**
 * @brief Type of rotary encoder handle
 *
 */
typedef struct rotary_encoder_t rotary_encoder_t;

/**
 * @brief Rotary encoder interface
 *
 */
struct rotary_encoder_t {
    /**
     * @brief Filter out glitch from input signals
     *
     * @param encoder Rotary encoder handle
     * @param max_glitch_us Maximum glitch duration, in us
     * @return
     *      - ESP_OK: Set glitch filter successfully
     *      - ESP_FAIL: Set glitch filter failed because of other error
     */
    esp_err_t (*set_glitch_filter)(rotary_encoder_t *encoder, uint32_t max_glitch_us);

    /**
     * @brief Start rotary encoder
     *
     * @param encoder Rotary encoder handle
     * @return
     *      - ESP_OK: Start rotary encoder successfully
     *      - ESP_FAIL: Start rotary encoder failed because of other error
     */
    esp_err_t (*start)(rotary_encoder_t *encoder);

    /**
     * @brief Stop rotary encoder
     *
     * @param encoder Rotary encoder handle
     * @return
     *      - ESP_OK: Stop rotary encoder successfully
     *      - ESP_FAIL: Stop rotary encoder failed because of other error
     */
    esp_err_t (*stop)(rotary_encoder_t *encoder);

    /**
     * @brief Recycle rotary encoder memory
     *
     * @param encoder Rotary encoder handle
     * @return
     *      - ESP_OK: Recycle rotary encoder memory successfully
     *      - ESP_FAIL: rotary encoder memory failed because of other error
     */
    esp_err_t (*del)(rotary_encoder_t *encoder);

    /**
     * @brief Get rotary encoder counter value
     *
     * @param encoder Rotary encoder handle
     * @return Current counter value (the sign indicates the direction of rotation)
     */
    int (*get_counter_value)(rotary_encoder_t *encoder);
};

/**
 * @brief Create rotary encoder instance for EC11
 *
 * @param config Rotary encoder configuration
 * @param ret_encoder Returned rotary encoder handle
 * @return
 *      - ESP_OK: Create rotary encoder instance successfully
 *      - ESP_ERR_INVALID_ARG: Create rotary encoder instance failed because of some invalid argument
 *      - ESP_ERR_NO_MEM: Create rotary encoder instance failed because there's no enough capable memory
 *      - ESP_FAIL: Create rotary encoder instance failed because of other error
 */
esp_err_t rotary_encoder_new_ec11(const rotary_encoder_config_t *config, rotary_encoder_t **ret_encoder);

#ifdef __cplusplus
}
#endif

添加encoder.cpp和rotary_encoder.c到platformIO的src目录下,程序如下:

encoder.cpp

#include "encoder.h"
#include <Arduino.h>

static rotary_encoder_t *encoder = NULL;    /* 编码器 */
static SemaphoreHandle_t mutex = NULL;

static int32_t last_cnt;                    /* 编码器上一次计数值 */
static int32_t encoder_diff = 0;            /* 编码器转动方向,0为静止,1为顺时针旋转,-1为逆时针旋转 */
static bool encoder_diff_disable = false;   /* 获取编码器数值,true为使能,false为失能 */

key_state_t encoder_push_state;

/* 编码器配置 */
void encoder_config(void)
{
    uint32_t pcnt_unit = 0;

    mutex = xSemaphoreCreateMutex();

    /* 1.配置编码器KEY GPIO */
    gpio_config_t io_conf = {               
        .pin_bit_mask = ENCODER_PUSH_GPIO_PIN_SEL,
        .mode = GPIO_MODE_INPUT,
        .pull_up_en = GPIO_PULLUP_DISABLE,
        .pull_down_en = GPIO_PULLDOWN_ENABLE,                              /* 允许下拉 */
        .intr_type = GPIO_INTR_DISABLE,
    };

    gpio_config(&io_conf);

    /* 2.配置编码器A、B */
    rotary_encoder_config_t config = ROTARY_ENCODER_DEFAULT_CONFIG((rotary_encoder_dev_t)pcnt_unit, ENCODER_A_PIN, ENCODER_B_PIN);
    ESP_ERROR_CHECK(rotary_encoder_new_ec11(&config, &encoder));
    ESP_ERROR_CHECK(encoder->set_glitch_filter(encoder, 1));    /* 滤波器 */
    ESP_ERROR_CHECK(encoder->start(encoder));

    last_cnt = encoder->get_counter_value(encoder);             /* 获取编码器初值 */
}

static key_state_t encoder_push_scan(void)
{
    if(gpio_get_level(ENCODER_PUSH_PIN) == 0)
    {
        vTaskDelay(pdMS_TO_TICKS(20));
        if(gpio_get_level(ENCODER_PUSH_PIN) == 0)
        {
            Serial.println("KEY DOWN");  // 编码器按下
            return KEY_DOWN;
        }
    }

    return KEY_UP;
}

static void encoder_task(void *pvParameter)
{
    while(1)
    {
        vTaskDelay(pdMS_TO_TICKS(150));

        if(pdTRUE == xSemaphoreTake(mutex, portMAX_DELAY))
        {
            /* 1.KEY检测 */
            encoder_push_state = encoder_push_scan();
            
            /* 2.方向检测 */
            if(!encoder_diff_disable)
            {
                int32_t dir = 0;
                int32_t cnt = encoder->get_counter_value(encoder);      /* 获取编码器数值 */
                
                /* 方向判断 */
                if(cnt - last_cnt < 0 && cnt - last_cnt <= -3)
                {
                    dir = -1;                   /* 逆时针旋转 */
                    Serial.println("Counterclockwise rotation");
                }
                else if(cnt - last_cnt > 0 && cnt - last_cnt >= 3)
                {
                    dir = 1;                    /* 顺时针旋转 */
                    Serial.println("Clockwise rotation");
                }

                encoder_diff += dir;
                last_cnt = cnt;
            }

            xSemaphoreGive(mutex);
        }
    }
}

void input_task_create(void)
{
    xTaskCreatePinnedToCore(encoder_task, "input task", 1024, NULL, 1, NULL, 1);
}

int32_t encoder_get_diff(void)
{
    int32_t diff = encoder_diff;
    encoder_diff = 0;
    return diff;
}

bool encoder_get_is_push(void)
{
    /* 编码器KEY按下不再读取方向数值 */
    if(encoder_push_state == KEY_DOWN)
    {
        encoder_diff_disable = true;
        return true;
    }
    else
    {
        encoder_diff_disable = false;
        return false;
    }
}

rotary_encoder.c

// Copyright 2020 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
//     http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <stdlib.h>
#include <string.h>
#include <sys/cdefs.h>
#include "esp_compiler.h"
#include "esp_log.h"
#include "driver/pcnt.h"
#include "hal/pcnt_hal.h"
#include "rotary_encoder.h"

static const char *TAG = "rotary_encoder";

#define ROTARY_CHECK(a, msg, tag, ret, ...)                                       \
    do {                                                                          \
        if (unlikely(!(a))) {                                                     \
            ESP_LOGE(TAG, "%s(%d): " msg, __FUNCTION__, __LINE__, ##__VA_ARGS__); \
            ret_code = ret;                                                       \
            goto tag;                                                             \
        }                                                                         \
    } while (0)

#define EC11_PCNT_DEFAULT_HIGH_LIMIT (100)
#define EC11_PCNT_DEFAULT_LOW_LIMIT  (-100)

typedef struct {
    int accumu_count;
    rotary_encoder_t parent;
    pcnt_unit_t pcnt_unit;
} ec11_t;

static esp_err_t ec11_set_glitch_filter(rotary_encoder_t *encoder, uint32_t max_glitch_us)
{
    esp_err_t ret_code = ESP_OK;
    ec11_t *ec11 = __containerof(encoder, ec11_t, parent);

    /* Configure and enable the input filter */
    ROTARY_CHECK(pcnt_set_filter_value(ec11->pcnt_unit, max_glitch_us * 80) == ESP_OK, "set glitch filter failed", err, ESP_FAIL);

    if (max_glitch_us) {
        pcnt_filter_enable(ec11->pcnt_unit);
    } else {
        pcnt_filter_disable(ec11->pcnt_unit);
    }

    return ESP_OK;
err:
    return ret_code;
}

static esp_err_t ec11_start(rotary_encoder_t *encoder)
{
    ec11_t *ec11 = __containerof(encoder, ec11_t, parent);
    pcnt_counter_resume(ec11->pcnt_unit);
    return ESP_OK;
}

static esp_err_t ec11_stop(rotary_encoder_t *encoder)
{
    ec11_t *ec11 = __containerof(encoder, ec11_t, parent);
    pcnt_counter_pause(ec11->pcnt_unit);
    return ESP_OK;
}

static int ec11_get_counter_value(rotary_encoder_t *encoder)
{
    ec11_t *ec11 = __containerof(encoder, ec11_t, parent);
    int16_t val = 0;
    pcnt_get_counter_value(ec11->pcnt_unit, &val);
    return val + ec11->accumu_count;
}

static esp_err_t ec11_del(rotary_encoder_t *encoder)
{
    ec11_t *ec11 = __containerof(encoder, ec11_t, parent);
    free(ec11);
    return ESP_OK;
}

static void ec11_pcnt_overflow_handler(void *arg)
{
    ec11_t *ec11 = (ec11_t *)arg;
    uint32_t status = 0;
    pcnt_get_event_status(ec11->pcnt_unit, &status);

    if (status & PCNT_EVT_H_LIM) {
        ec11->accumu_count += EC11_PCNT_DEFAULT_HIGH_LIMIT;
    } else if (status & PCNT_EVT_L_LIM) {
        ec11->accumu_count += EC11_PCNT_DEFAULT_LOW_LIMIT;
    }
}

esp_err_t rotary_encoder_new_ec11(const rotary_encoder_config_t *config, rotary_encoder_t **ret_encoder)
{
    esp_err_t ret_code = ESP_OK;
    ec11_t *ec11 = NULL;

    ROTARY_CHECK(config, "configuration can't be null", err, ESP_ERR_INVALID_ARG);
    ROTARY_CHECK(ret_encoder, "can't assign context to null", err, ESP_ERR_INVALID_ARG);

    ec11 = calloc(1, sizeof(ec11_t));
    ROTARY_CHECK(ec11, "allocate context memory failed", err, ESP_ERR_NO_MEM);

    ec11->pcnt_unit = (pcnt_unit_t)(config->dev);

    // Configure channel 0
    pcnt_config_t dev_config = {
        .pulse_gpio_num = config->phase_a_gpio_num,
        .ctrl_gpio_num = config->phase_b_gpio_num,
        .channel = PCNT_CHANNEL_0,
        .unit = ec11->pcnt_unit,
        .pos_mode = PCNT_COUNT_DEC,
        .neg_mode = PCNT_COUNT_INC,
        .lctrl_mode = PCNT_MODE_REVERSE,
        .hctrl_mode = PCNT_MODE_KEEP,
        .counter_h_lim = EC11_PCNT_DEFAULT_HIGH_LIMIT,
        .counter_l_lim = EC11_PCNT_DEFAULT_LOW_LIMIT,
    };
    ROTARY_CHECK(pcnt_unit_config(&dev_config) == ESP_OK, "config pcnt channel 0 failed", err, ESP_FAIL);

    // Configure channel 1
    dev_config.pulse_gpio_num = config->phase_b_gpio_num;
    dev_config.ctrl_gpio_num = config->phase_a_gpio_num;
    dev_config.channel = PCNT_CHANNEL_1;
    dev_config.pos_mode = PCNT_COUNT_INC;
    dev_config.neg_mode = PCNT_COUNT_DEC;
    ROTARY_CHECK(pcnt_unit_config(&dev_config) == ESP_OK, "config pcnt channel 1 failed", err, ESP_FAIL);

    // PCNT pause and reset value
    pcnt_counter_pause(ec11->pcnt_unit);
    pcnt_counter_clear(ec11->pcnt_unit);

    // register interrupt handler
    ROTARY_CHECK(pcnt_isr_service_install(0) == ESP_OK, "install isr service failed", err, ESP_FAIL);
    pcnt_isr_handler_add(ec11->pcnt_unit, ec11_pcnt_overflow_handler, ec11);

    pcnt_event_enable(ec11->pcnt_unit, PCNT_EVT_H_LIM);
    pcnt_event_enable(ec11->pcnt_unit, PCNT_EVT_L_LIM);

    ec11->parent.del = ec11_del;
    ec11->parent.start = ec11_start;
    ec11->parent.stop = ec11_stop;
    ec11->parent.set_glitch_filter = ec11_set_glitch_filter;
    ec11->parent.get_counter_value = ec11_get_counter_value;

    *ret_encoder = &(ec11->parent);
    return ESP_OK;
err:
    if (ec11) {
        free(ec11);
    }
    return ret_code;
}

在main.cpp中添加如下代码:

#include <Arduino.h>
#include <encoder.h>

void setup() {
    // put your setup code here, to run once:
    Serial.begin(115200);

    encoder_config();

    input_task_create();
}

void loop() {
    // put your main code here, to run repeatedly:
}

烧录后就可以愉快的玩耍啦()

标签:编码器,ESP,ec11,rotary,encoder,pcnt,旋转,config
From: https://www.cnblogs.com/colinyang/p/18017455

相关文章

  • 逆向实战29——某度-某家号2024旋转验证码识别
    前言本文章中所有内容仅供学习交流,抓包内容、敏感网址、数据接口均已做脱敏处理,严禁用于商业用途和非法用途,否则由此产生的一切后果均与作者无关,若有侵权,请联系我立即删除!目标网站aHR0cHM6Ly9hdXRob3IuYmFpZHUuY29tL2hvbWU/ZnJvbT1iamhfYXJ0aWNsZSZhcHBfaWQ9MTU2NTA5MjE0MjUwO......
  • 10_TIM编码器接口
    TIM编码器接口编码器接口简介正交编码器旋转编码器简介编码器接口基本结构工作模式实例(均不反相)实例(TI1反相)编码器接口测速选择接口和定时器接线图代码Encoder.c#include"stm32f10x.h"//DeviceheadervoidEncoder_Init(void){......
  • Profinet转CANopen主站网关与堡盟编码器通讯案例
    Profinet转CANopen主站网关与堡盟编码器通讯案例Profinet转CANopen主站网关(XD-COPNm20)为CPU与堡盟编码器的通讯提供了CANopen协议向Profinet协议转换互通的桥梁。CANopen是一种基于CAN总线的通讯协议,它被广泛应用于工业自动化领域,而Profinet是一种以太网协议,其优点是高速传输和......
  • Qt按钮字体旋转
    #include"mainwindow.h"#include"ui_mainwindow.h"classRotatedButton:publicQPushButton{public:explicitRotatedButton(constQString&text,QWidget*parent=nullptr):QPushButton(text,parent){}b......
  • 寻找旋转排序数组中的最小值
    153FindMinimuminRotatedSortedArray问题描述:假设按照升序排序的数组在预先未知的某个点上进行了旋转。(例如,数组[0,1,2,4,5,6,7]可能变为[4,5,6,7,0,1,2])。请找出其中最小的元素。示例1:输入:[3,4,5,1,2]输出:1示例2:输入:[4,5,6,7,0,1,2]输出:0/**......
  • 搜索旋转排序数组
    33SearchinRotatedSortedArray问题描述:假设按照升序排序的数组在预先未知的某个点上进行了旋转。(例如,数组[0,1,2,4,5,6,7]可能变为[4,5,6,7,0,1,2])。搜索一个给定的目标值,如果数组中存在这个目标值,则返回它的索引,否则返回-1。你可以假设数组中不存在重复的元素。你......
  • 12.旋转、缩放、倾斜、平移Transform
    RotateTransform旋转RotateTransform表示旋转一个对象的角度。首先我们来看一下它的定义publicsealedclassRotateTransform:Transform{publicstaticreadonlyDependencyPropertyAngleProperty;publicstaticreadonlyDependencyPropertyCenterXPropert......
  • 代码随想录算法训练营第八天| 344.反转字符串 541. 反转字符串II 卡码网:54.替换数字
    反转字符串编写一个函数,其作用是将输入的字符串反转过来。输入字符串以字符数组 s 的形式给出。不要给另外的数组分配额外的空间,你必须原地修改输入数组、使用O(1)的额外空间解决这一问题。题目链接:344.反转字符串-力扣(LeetCode)关于是否用reverse函数解决问题:如果题目......
  • 使用CAShapeLayer,UIBezierPath,CAGradientLayer构建边框颜色会旋转的六边形
    主要思路是:1.使用UIBezierPath绘制一个六边形路径2.创建一个CAShapeLayer图层,将这个六边形path设置到CAShapeLayer属性上。然后设置fillColor为透明,strokeColor为黑色,lineWidth为5.03.创建一个CAGradientLayer渐变色图层,并将它的渐变类型设置成kCAGradientLayerConic以圆心为......
  • [office] Excel旋转图表的两种方法介绍
    Excel的图表本身是不可以旋转放置的,那么怎么可以通过其他方式来实现对图表的旋转呢?下面我向大家介绍二种方法。步骤一:把图表复制为静态图片1、按“shift”键,单击图表区,然后执行“编辑——复制图片”命令,弹出“复制图片”对话框,然后按确定。2、在一个空白的单元格处,点鼠标右键,然后粘......