ESP32(ESP-IDF)+CNC Shield+A4988控制步进电机

2023-05-16

陈拓 2023/04/15-2023/04/15

1. 简介

在《Arduino Uno开发板+电机驱动扩展版CNC Shield V3.0硬件说明》

https://blog.csdn.net/chentuo2000/article/details/129851439?spm=1001.2014.3001.5502

一文中我们介绍了CNC Shield V3.0的引脚功能以及和Arduino Uno开发板引脚位置的对应关系。

在此基础上,在《D1 R32 – ESP32+Arduino CNC Shield控制步进电机》

https://blog.csdn.net/chentuo2000/article/details/129986246?spm=1001.2014.3001.5502

一文中我们讲述了用ESP32+Arduino CNC Shield通过A4988步进电机驱动模块控制NEMA17步进电机。所给出的例子是Arduino开发环境下的。

本文我们介绍一个ESP-IDF开发环境下的例子。

  • ESP32开发板 + Arduino CNC Shield V3.00 + A4988组合

 

2. 软件开发环境

参考《Ubuntu构建ESP32 ESP-IDF开发环境(简约版)》

https://blog.csdn.net/chentuo2000/article/details/128034585?spm=1001.2014.3001.5502

3. 步进电机控制例程

代码来自[https://github.com/arnosolo/esp32-stepmotor]

4. 构建项目

4.1 项目结构

  • 进入项目目录

cd ~/esp442/cnc_shield_idf

  • 项目结构

 

4.2 配置文件和代码文件

  • 顶层CMakeLists.txt
cmake_minimum_required(VERSION 3.5)

include($ENV{IDF_PATH}/tools/cmake/project.cmake)
project(cnc_shield_idf)
  • main目录下的CMakeLists.txt
idf_component_register(SRCS "main.cpp" "stepper.cpp"
                    INCLUDE_DIRS "include")
  •  stepper.h、stepper.cpp、main.cpp见附录。

4.3 构建项目

  • 刷新esp-idf环境

get_idf

  • 设定目标芯片

idf.py set-target esp32

  • 配置项目

idf.py menuconfig

1) 将闪存设置为4MB

 

保存,退出。

  • 编译项目

idf.py build

  • 烧写项目

查看ESP32开发板连接电脑的串口:

ls -l /dev/ttyUSB*

修改串口权限:

sudo chmod 777 /dev/ttyUSB0

烧写:

idf.py -p /dev/ttyUSB0 -b 115200 flash

5. 测试

插上CNC Shield扩展板,接上USB线用于给ESP32供电,接上12V电源给电机供电。

  • 打开串口监视器

idf.py monitor -p /dev/ttyUSB0

 电机顺时针转动几圈。

附:代码

  • stepper.h
#include <stdio.h>
#include <stdlib.h>
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "freertos/queue.h"
#include "freertos/timers.h"
#include "driver/gpio.h"
#include "esp_intr_alloc.h"
#include "esp_log.h"
#include "driver/mcpwm.h"
// #include "soc/mcpwm_periph.h"
#include "soc/mcpwm_reg.h"
#include "soc/mcpwm_struct.h"
#include "driver/pcnt.h"

#define STEPMOTOR_NUM 6
#define PCNT_H_LIM_VAL 1000

typedef struct
{
    int unit;        // the PCNT unit that originated an interrupt
    uint32_t status; // information on the event type that caused the interrupt
} pcnt_evt_t;

typedef struct
{
  mcpwm_unit_t mcpwm_unit;
  mcpwm_timer_t mcpwm_timer;
  mcpwm_io_signals_t mcpwm_io_signals;
  pcnt_unit_t pcnt_unit;
  // pcnt_channel_t pcnt_channel;
} stepmotor_config_t;

static stepmotor_config_t motor_config[STEPMOTOR_NUM] = {
    {.mcpwm_unit = MCPWM_UNIT_0,
    .mcpwm_timer = MCPWM_TIMER_0,
    .mcpwm_io_signals = MCPWM0A,
    .pcnt_unit = PCNT_UNIT_0
    },
    {.mcpwm_unit = MCPWM_UNIT_0,
    .mcpwm_timer = MCPWM_TIMER_1,
    .mcpwm_io_signals = MCPWM1A,
    .pcnt_unit = PCNT_UNIT_1
    },
    {.mcpwm_unit = MCPWM_UNIT_0,
    .mcpwm_timer = MCPWM_TIMER_2,
    .mcpwm_io_signals = MCPWM2A,
    .pcnt_unit = PCNT_UNIT_2
    },
    {.mcpwm_unit = MCPWM_UNIT_1,
    .mcpwm_timer = MCPWM_TIMER_0,
    .mcpwm_io_signals = MCPWM0A,
    .pcnt_unit = PCNT_UNIT_3
    },
    {.mcpwm_unit = MCPWM_UNIT_1,
    .mcpwm_timer = MCPWM_TIMER_1,
    .mcpwm_io_signals = MCPWM1A,
    .pcnt_unit = PCNT_UNIT_4
    },
    {.mcpwm_unit = MCPWM_UNIT_1,
    .mcpwm_timer = MCPWM_TIMER_2,
    .mcpwm_io_signals = MCPWM2A,
    .pcnt_unit = PCNT_UNIT_5
    },
};

class Stepmotor
{
private:
public:
  int id;
  int dirPin;
  int stepPin;
  int speed;
  int step;
  bool isReady;

  static xQueueHandle pcnt_evt_queue;
  static bool status[6];

  Stepmotor(int idInput, int dirPinInput, int stepPinInput);
  void init();
  void move(int stepInput, int speedInput);
  void stop();

};
  • stepper.cpp
#include <stdio.h>
#include <stdlib.h>
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "freertos/queue.h"
#include "freertos/timers.h"
#include "driver/gpio.h"
#include "esp_intr_alloc.h"
#include "esp_log.h"
#include "driver/mcpwm.h"
// #include "soc/mcpwm_periph.h"
#include "soc/mcpwm_reg.h"
#include "soc/mcpwm_struct.h"
#include "driver/pcnt.h"
#include "stepper.h"

xQueueHandle Stepmotor::pcnt_evt_queue = xQueueCreate(12, sizeof(pcnt_evt_t));
bool Stepmotor::status[6] = {false, false, false, false, false, false};

static void IRAM_ATTR pcnt_example_intr_handler(void *arg)
{
  int pcnt_unit = (int)arg;
  pcnt_evt_t evt;
  evt.unit = pcnt_unit;

  pcnt_get_event_status((pcnt_unit_t)pcnt_unit, &evt.status);
  // xQueueSendFromISR(Stepmotor::pcnt_evt_queue, &evt, NULL); // defult way

  // int id = pcnt_unit;
  Stepmotor::status[pcnt_unit] = true;
  mcpwm_stop(motor_config[pcnt_unit].mcpwm_unit, motor_config[pcnt_unit].mcpwm_timer);
}

Stepmotor::Stepmotor(int idInput, int dirPinInput, int stepPinInput)
{
  id = idInput;
  dirPin = dirPinInput;
  stepPin = stepPinInput;

  // 1.初始化转动方向引脚
  gpio_config_t io_conf = {};
  io_conf.pin_bit_mask = 1ULL << dirPin;
  io_conf.mode = GPIO_MODE_OUTPUT;
  gpio_config(&io_conf);
  gpio_set_level((gpio_num_t)dirPin, 1);

  // 2.初始化脉冲计数器
  pcnt_unit_t unit = motor_config[id].pcnt_unit;
  pcnt_config_t pcnt_config;
  // Set PCNT input signal and control GPIOs
  pcnt_config.pulse_gpio_num = stepPin,
  pcnt_config.ctrl_gpio_num = PCNT_PIN_NOT_USED,
  pcnt_config.channel = PCNT_CHANNEL_0,
  pcnt_config.unit = unit,
  // What to do on the positive / negative edge of pulse input?
  pcnt_config.pos_mode = PCNT_COUNT_INC, // Count up on the positive edge
  pcnt_config.neg_mode = PCNT_COUNT_DIS, // Keep the counter value on the negative edge
  // What to do when control input is low or high?
  pcnt_config.lctrl_mode = PCNT_MODE_KEEP,
  pcnt_config.hctrl_mode = PCNT_MODE_KEEP, // Keep the primary counter mode if high
  // Set the maximum and minimum limit values to watch
  pcnt_config.counter_h_lim = PCNT_H_LIM_VAL,
  // .counter_l_lim = PCNT_L_LIM_VAL,
  pcnt_unit_config(&pcnt_config);

  /* Configure and enable the input filter */
  pcnt_set_filter_value(unit, 100);
  pcnt_filter_enable(unit);

  pcnt_event_enable(unit, PCNT_EVT_H_LIM);

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

  /* Install interrupt service and add isr callback handler */
  pcnt_isr_service_install(0);
  pcnt_isr_handler_add(unit, pcnt_example_intr_handler, (void *)unit);

  /* Everything is set up, now go to counting */
  pcnt_counter_resume(unit);

  // 3.生成电机控制脉冲
  // 细分为16,所以一圈需要3200步. 每秒800个脉冲,则电机大概4s转一圈
  ESP_ERROR_CHECK(mcpwm_gpio_init(motor_config[id].mcpwm_unit, motor_config[id].mcpwm_io_signals, stepPin));

  mcpwm_config_t pwm_config;
  pwm_config.frequency = 1000; //frequency = 50Hz
  pwm_config.cmpr_a = 50;      //duty cycle of PWMxA = 50.0%
  pwm_config.counter_mode = MCPWM_UP_COUNTER;
  pwm_config.duty_mode = MCPWM_DUTY_MODE_0;
  ESP_ERROR_CHECK(mcpwm_init(motor_config[id].mcpwm_unit, motor_config[id].mcpwm_timer, &pwm_config));


  // 这么搞一下同一个引脚就既能输出pwm,又能读取脉冲数了...
  gpio_iomux_in(stepPin, PCNT_SIG_CH0_IN0_IDX);

  isReady = true;
  Stepmotor::status[id] = isReady;
  const char *TAG = "motor class";
  ESP_LOGI(TAG, "init complete");
};

/**
 * @brief Ask step motor to move
 *
 * @param stepInput step number, should >= 0. Negative values ​​are converted to positive values
 * @param speedInput speed, step/s
 */
void Stepmotor::move(int stepInput, int speedInput)
{
  isReady = false;
  Stepmotor::status[id] = isReady;
  speed = speedInput;

  if(stepInput < 0) {
    step = -stepInput;
  } else {
    step = stepInput;
  }

  if (speed == 0)
  {
    stop();
  }
  else
  {
    if (speed < 0)
    {
      gpio_set_level((gpio_num_t)dirPin, 0);
      speed = -speedInput;
    }
    else
    {
      gpio_set_level((gpio_num_t)dirPin, 1);
    }

    pcnt_unit_t unit = motor_config[id].pcnt_unit;
    pcnt_set_event_value(unit, PCNT_EVT_H_LIM, (int16_t)step);
    pcnt_event_enable(unit, PCNT_EVT_H_LIM);
    pcnt_counter_pause(unit);
    pcnt_counter_clear(unit);
    pcnt_counter_resume(unit);

    mcpwm_set_frequency(motor_config[id].mcpwm_unit, motor_config[id].mcpwm_timer, speed);
    mcpwm_start(motor_config[id].mcpwm_unit, motor_config[id].mcpwm_timer);
  }
};

void Stepmotor::stop()
{
  // isReady = true;
  // Stepmotor::status[id] = isReady;
  mcpwm_stop(motor_config[id].mcpwm_unit, motor_config[id].mcpwm_timer);
};
  • main.cpp
#include <stdio.h>
#include <stdlib.h>
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "freertos/queue.h"
#include "freertos/timers.h"
#include "driver/gpio.h"
#include "esp_intr_alloc.h"
#include "esp_log.h"
#include "stepper.h"

const char *TAG = "Motor Control";

/*********** Tasks ***********/
void clock(void *arg)
{
    const char *TAG = "Clock";
    int cnt = 0;
    while (1)
    {
        ESP_LOGI(TAG, "%d s", cnt);
        cnt++;
        vTaskDelay(1000 / portTICK_RATE_MS);
    }
}

/*********** Main ***********/
extern "C" void app_main(void)
{
    // 1.Create a motor instance
    Stepmotor motorX(0, 16, 26); // id(0~6), dirPin, stepPin

    xTaskCreate(clock, "clock", 2048, NULL, 5, NULL);

    int cnt = 1;
    while (1)
    {
        // 2.Update motor status
        motorX.isReady = Stepmotor::status[motorX.id];

        // 3.Ask the motor move a little
        if (motorX.isReady)
        {
            ESP_LOGI(TAG, "motorX start moving, %d steps at %d step/s", cnt * 500, 500);
            motorX.move(cnt * 500, 500); // stepNum, speed(step/s)
            cnt++;
        }

        if (cnt == 4)
        {
            ESP_LOGI(TAG, "motorX stop");
            motorX.stop();
            cnt++;
        }

        vTaskDelay(10 / portTICK_RATE_MS);
    }
}
本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)

ESP32(ESP-IDF)+CNC Shield+A4988控制步进电机 的相关文章

  • esp32添加头文件

    环境 linux idf vsode 前言 在按照官方教程安装完成后 虽然可以编译成功 但是有些函数找不到定义 而且强迫症看到波浪号也非常难受 方法 点击小灯泡 点击第一个选项 如下图所示 拉到底点击advanced settings 让v
  • ESP32 上快捷部署 Tensorflow lite 机器学习(TinyML)

    在这篇文章中 我将向您展示使用 Arduino IDE 将 TensorFlow Lite 模型部署到 ESP32 的最简单方法 无需任何编译内容 Arduino 库 这个 Arduino 库是为了简化使用 Arduino IDE 将用于微
  • ESP32上实现LVGL的界面显示

    提示 文章写完后 目录可以自动生成 如何生成可参考右边的帮助文档 文章目录 前言 一 元器件 二 导入库 三 调试TFT eSPI 四 调试LVGL 总结 前言 基于Vscode中的 PlatformIO平台arduino框架 使用1 8
  • 展会速递丨启明云端亮相AWE2021 :看应用,新技术引领家电智能化升级--启明云端WIFI\蓝牙\智慧屏一站式解决方案赢关注 ; 看产品--4寸旋钮屏惊艳AWE2021

    3月23日 25日 由中国家用电器协会主办的2021年中国家电及消费电子博览会 AWE 在上海虹桥国家会展中心 NECC 举行 本届展览会展出了近两年来的创新智慧产品和技术解决方案 启明云端也携多款无线连接及智慧屏方案在内的 无线传输 显示
  • 【ESP32】VSCode添加驱动文件

    1 创建文件夹并添加驱动文件 2 修改main文件夹下的 CMakeLists txt
  • 【STM32 x ESP8266】连接 MQTT 服务器(报文,附部分源码解析)

    MQTT 协议作为物联网非常重要的传输协议 如何使用它十分重要 如果有不理解的同学可以点击这里学习 这里只是简单介绍一下 同时这里附上MQTT 3 1 1协议中文版 pdf 的链接 对协议底层感兴趣的同学可以下载学习一下 同时下面的实现函数
  • esp32-S3专题二:内存2之RTC内存、FLASH使用

    承接上文 讲一下esp32上剩下的几个存储空间的用途 目录 一 RTC存储器 一 RTC 快速存储器 二 RTC 慢速存储器 二 Flash 一 NVS 表 二 程序和OTA分区 三 SPIFFS 文件系统 三 总结 一 RTC存储器 es
  • 个人对智能家居平台选择的思考

    本人之前开发过不少MicroPython程序 其中涉及到自动化以及局域网控制思路 也可以作为智能家居的实现方式 而NodeMCU ESPHome的方案具有方便添加硬件 容易更新程序和容量占用小的优势 本人也查看过相关教程后感觉部署ESPHo
  • ESP32开发板手动更换外置的flash

    ESP32开发板手动更换外置的flash 实物板 风险提示 操作有风险 需谨慎 新手请勿模仿 第一步拿下屏蔽罩 用热风枪 360 吹下来的 第二步 更换flash芯片 ESP32 D0WDQ6芯片下方那个就是flash芯片了型号 25VQ3
  • ESP32/ESP8266使用MicroPython控制DHT11/DHT22

    本教程介绍了如何使用MicroPython固件将DHT11或DHT22温度和湿度传感器与ESP32和ESP8266开发板一起使用 DHT模块 刷新MicroPython固件 要遵循本教程 您需要在ESP32或ESP8266板上安装Micro
  • ESP32基础应用之LVGL基础

    文章目录 1 实验目的 1 1 参考文章 2 实验工具 3 准备工作 3 1 搭建ESP32开发环境 3 2 克隆lv port esp32工程 4 配置lv port esp32工程 5 实验验证 6 使用过程遇到的问题 6 1 触摸功能
  • ESP32-S2应用开发——USB通信(CDC类)

    ESP32S2应用开发 USB通信 CDC类 目录 ESP32S2应用开发 USB通信 CDC类 前言 1 硬件介绍 1 1 硬件连接 2 软件开发 2 1 安装开发板 2 2 安装库 2 3 运行示例代码 2 4 USB传输速度测试 结束
  • esp32 CMT130-V1.0 PS 240*240屏幕使用方法实验

    1 安装好Arduino 1 8 13 注意尽量不要大于1 8的版本 2 安装esp32驱动代码并且配置 3 esp32选择波特率 921600 4 选择频率 80MHZ 5 具体连线总结 6 需要在Arduino库管理中心下载TFT eS
  • esp32开发板学习

    1 esp32简介 esp32说到底就是一个小型的linux 可以执行我们的代码 尺寸只有一个苹果watch se的大小 可以集成各个物理组件 好像是通过开发板上的引脚来操作的 2 开发板部署python环境 2 1 在pdd花10块钱买了
  • ESP32(Micro Python) LVGL 传感器数值显示

    本程序用于显示SR04超声波传感器和BMP280气压温度传感器的读数 由于高度数值类型不符合要求 BMP280改为显示气压和温度值 气压值分两部分显示 分别为千帕值 100 避免超出表盘显示范围 和千帕值的两位小数 由于标签不能显示动态数值
  • 在 esp32 上运行 lvgl + freetype

    前言 最近有个需求 如何在 esp32 上运行 lvgl freetype 这个想法的难点是 freetype 的环境搭建 我想将其做得非常简单 最好的办法是做成组件来使用 所以我将 freetype 的相关依赖做成了 esp idf 组件
  • ESP32-cam 初体验 从esp32-cam的购买到局域网监控的实现

    ESP32 cam小项目 helloworld项目 前言 手头有一块esp32 cam闲置很久了 因为比赛和找工作的事情导致许欸小延期了很久 还是因为懒 最近从小仓库把板子捞出来了 上手玩一玩 本次学习参考了B站up 小铭同学 的教程 教程
  • 还是 “月饼” 后续,玩转炫彩 “月饼” 之 问题说明

    画一个 月饼 陪我过中秋 开发板后续问题跟进说明 目录 前言 一 出现问题 二 寻求办法 三 若有所思 四 问题测试 结语 悬赏送开发板 前言 本文有纯理论玩家是永远不会经历的实际问题 嵌入式工程师不动手永远出不了作品 本文最后有送开发板的
  • Micropython驱动ST7735显示中文(中文字体库)

    大家是不是遇到显示中文就头大了 又是取模又是怎么的 但麻烦 太繁琐了 对确定的字符显示来说还可以 但不确定的内容时就麻烦了 所以 今天还是来讲讲干货了 来使用一个方便的方式来显示中文 不用取模 直接显示你想要的中英文字体 开始之前要说一下的
  • linux espidf vscode

    安装 根据 https docs espressif com projects esp idf zh CN latest esp32s2 get started linux macos setup html 里的要求安装一些东西 点插件的首

随机推荐