ROS2进阶 -- 硬件篇第三章第一节 -- ESP32 DEVKIT_V1捕获MG310霍尔编码电机的脉冲

从第三章开始,我们将分几节,陆续完成ESP32的和各种配件的连接与调试。

参考资料:

零件说明:ROS2进阶 – 硬件篇第一章 – 使用ESP32,树莓派5,ROS2 从零组装一台差速控制的机器人
环境配置:ROS2进阶 – 硬件篇第二章 – 使用 ESP32 DEVKIT_V1 开发板基于 Arduino IDE 的环境搭建教程 windows / ubuntu 双系统安装
第三节:ESP32捕获霍尔编码电机的脉冲

使用本章内容时请提前将代码esp32_ros2_robot下载好

1. 本节需要准备的东西

ESP32,带有霍尔编码器的电机, Arduino IDE
在这里插入图片描述
本节所使用的代码为03-esp32_Hall_encoder_motor

2. 电路图

先将esp32通过USB连接到电脑上,然后将电机和ESP32按照下图连接
在这里插入图片描述

接线说明:
霍尔传感器正极 +(蓝⾊) ESP32_Vin (5.0V)
霍尔传感器负极 - (⿊⾊) ESP32_Gnd (0V)
编码器 Encoder A (黄⾊) ESP32_GPIO4 (Input)
编码器 Encoder B(绿⾊) ESP32_GPIO5 (Input)

实物连接如下:
在这里插入图片描述
在这里插入图片描述
在这里插入图片描述

3. 代码

一共需要两个文件
encoder_driver.h

/*****************************************************************
Motor Encoder Information: 

  Pluse Per Rotation: 11
  Reduction Ratio: 30
  Motor Voltage: 12V
  Hall Encoder Voltage: 5.0V
  Total pluse per Rotation: 
    11(PPR) * 2(Hall) * 2(CHANGE) * 30(Reduction Ratio) =1320 

*****************************************************************/

#define LEFT_ENCODER_A 4  // Pin for Left Encoder A Pin
#define LEFT_ENCODER_B 5  // Pin for Left Encoder B Pin

#define RIGHT_ENCODER_A 18  // Pin for Right Encoder A Pin
#define RIGHT_ENCODER_B 19  // Pin for Right Encoder B Pin

#define LEFT 0
#define RIGHT 1

long leftPosition = 0;   // Global variable for storing the encoder position
long rightPosition = 0;  // Global variable for storing the encoder position

long current_leftPosition = 0;  // Global variable for storing the current encoder position
long current_rightPosition = 0; // Global variable for storing the current encoder position

void Left_encoder_isr_A() {
  // Reading the current state of encoder A and B
  // look for a low-to-high on channel A
  if (digitalRead(LEFT_ENCODER_A) == HIGH) { 
    // check channel B to see which way encoder is turning
    if (digitalRead(LEFT_ENCODER_B) == LOW) {  
      current_leftPosition = current_leftPosition + 1;         // CW
    } 
    else {
      current_leftPosition = current_leftPosition - 1;         // CCW
    }
  }
  else   // must be a high-to-low edge on channel A                                       
  { 
    // check channel B to see which way encoder is turning  
    if (digitalRead(LEFT_ENCODER_B) == HIGH) {   
      current_leftPosition = current_leftPosition + 1;          // CW
    }
    else {
      current_leftPosition = current_leftPosition - 1;          // CCW
    }
  }
}

void Left_encoder_isr_B() {
  // Reading the current state of encoder A and B
  // look for a low-to-high on channel A
if (digitalRead(LEFT_ENCODER_B) == HIGH) {   
   // check channel A to see which way encoder is turning
    if (digitalRead(LEFT_ENCODER_A) == HIGH) {  
      current_leftPosition = current_leftPosition + 1;         // CW
    } 
    else {
      current_leftPosition = current_leftPosition - 1;         // CCW
    }
  }
  // Look for a high-to-low on channel B
  else { 
    // check channel B to see which way encoder is turning  
    if (digitalRead(LEFT_ENCODER_A) == LOW) {   
      current_leftPosition = current_leftPosition + 1;          // CW
    } 
    else {
      current_leftPosition = current_leftPosition - 1;          // CCW
    }
  }
}

void Right_encoder_isr_A() {
  // Reading the current state of encoder A and B
  // look for a low-to-high on channel A
  if (digitalRead(RIGHT_ENCODER_A) == HIGH) { 
    // check channel B to see which way encoder is turning
    if (digitalRead(RIGHT_ENCODER_B) == LOW) {  
      current_rightPosition = current_rightPosition + 1;         // CW
    } 
    else {
      current_rightPosition = current_rightPosition - 1;         // CCW
    }
  }
  else   // must be a high-to-low edge on channel A                                       
  { 
    // check channel B to see which way encoder is turning  
    if (digitalRead(RIGHT_ENCODER_B) == HIGH) {   
      current_rightPosition = current_rightPosition + 1;          // CW
    }
    else {
      current_rightPosition = current_rightPosition - 1;          // CCW
    }
  }
}

void Right_encoder_isr_B() {
  // Reading the current state of encoder A and B
  // look for a low-to-high on channel A
if (digitalRead(RIGHT_ENCODER_B) == HIGH) {   
   // check channel A to see which way encoder is turning
    if (digitalRead(RIGHT_ENCODER_A) == HIGH) {  
      current_rightPosition = current_rightPosition + 1;         // CW
    } 
    else {
      current_rightPosition = current_rightPosition - 1;         // CCW
    }
  }
  // Look for a high-to-low on channel B
  else { 
    // check channel B to see which way encoder is turning  
    if (digitalRead(RIGHT_ENCODER_A) == LOW) {   
      current_rightPosition = current_rightPosition + 1;          // CW
    } 
    else {
      current_rightPosition = current_rightPosition - 1;          // CCW
    }
  }
}

long readEncoder(int i)
{
  if (i==LEFT)
  {
    return (current_leftPosition -leftPosition );
  }
  else
  {
    return (current_rightPosition -rightPosition );
  }
}

void resetEncoder(int i)
{
  if (i==LEFT)
  {
    leftPosition=current_leftPosition;    
  }else
  {
    rightPosition=current_rightPosition;
  }
}

void resetEncoders()
{  
  resetEncoder(LEFT);
  resetEncoder(RIGHT); 
}

void Init_Encoder() 
{
  pinMode(LEFT_ENCODER_A, INPUT);
  pinMode(LEFT_ENCODER_B, INPUT);

  pinMode(RIGHT_ENCODER_A, INPUT);
  pinMode(RIGHT_ENCODER_B, INPUT);

  // Attaching the ISR to encoder Left A B
  attachInterrupt(digitalPinToInterrupt(LEFT_ENCODER_A), Left_encoder_isr_A, CHANGE);
  attachInterrupt(digitalPinToInterrupt(LEFT_ENCODER_B), Left_encoder_isr_B, CHANGE);

  // Attaching the ISR to encoder Rigth A B
  attachInterrupt(digitalPinToInterrupt(RIGHT_ENCODER_A), Right_encoder_isr_A, CHANGE);
  attachInterrupt(digitalPinToInterrupt(RIGHT_ENCODER_B), Right_encoder_isr_B, CHANGE);
}

Encoder_test.ino

#include "encoder_driver.h"

void setup() {
  Serial.begin(115200);  // Initialize serial communication
  Init_Encoder();
}

void loop() {
  Serial.print("Left Encoder: ");
  Serial.println(readEncoder(LEFT));

  // Serial.print("Left Encoder: ");
  // Serial.println(readEncoder(RIGHT));
}

4. 运行代码

首先打开上面下载的代码,
在这里插入图片描述
选择这个.ino文件
在这里插入图片描述
选择开发板和端口号
在这里插入图片描述
点击验证和上传按钮
在这里插入图片描述
在这里插入图片描述

然后点击右上角的串口监视器,然后手动转动轮胎,可以观察到这个值在变化
在这里插入图片描述

5. 视频调试过程如下

编码器测试

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值