8.脉冲测量与校准实验
写在前面
- 当前平台文章汇总地址:ROS2机器人从入门到实战
- 获取完整教程及配套资料代码,请关注公众号<鱼香ROS>获取
- 教程配套机器人开发平台:两驱版| 四驱版
- 为方便交流,搭建了机器人技术问答社区:地址 fishros.org.cn
你好,我是小鱼,有了上节的理论,这一节我们编写代码来尝试下是否能够读取到电机上编码器的脉冲数,并通过实验测试出小车的输出轴转速和编码器脉冲的比值。
一、新建工程并导入开源库
新建example25_encoder
添加依赖
[env:featheresp32] ; 这是一个环境配置标签,指定了代码将运行的硬件平台和框架
platform = espressif32 ; 指定了使用的平台为Espressif 32
board = featheresp32 ; 指定使用的硬件板为Feather ESP32
framework = arduino ; 指定使用的框架为Arduino
lib_deps = ; 列出所有依赖库的URL,这些库将被下载和安装
https://github.com/fishros/Esp32PcntEncoder.git ; ESP32 编码器驱动库
这里我们使用的是Esp32PcntEncoder
开源库,这个库调用了ESP32
的脉冲计算外设进行编码器脉冲的计算,使用非常简单。
二、代码实现
编写代码
#include <Arduino.h>
#include <Esp32PcntEncoder.h>
Esp32PcntEncoder encoders[2]; // 创建一个数组用于存储两个编码器
void setup()
{
// 1.初始化串口
Serial.begin(115200); // 初始化串口通信,设置通信速率为115200
// 2.设置编码器
encoders[0].init(0, 32, 33); // 初始化第一个编码器,使用GPIO 32和33连接
encoders[1].init(1, 26, 25); // 初始化第二个编码器,使用GPIO 26和25连接
}
void loop()
{
delay(10); // 等待10毫秒
// 读取并打印两个编码器的计数器数值
Serial.printf("tick1=%d,tick2=%d\n", encoders[0].getTicks(), encoders[1].getTicks());
}
上面这段代码使用了ESP32PcntEncoder
库来读取两个旋转编码器的计数器数值。其中,函数setup()
用于初始化串口和编码器;函数loop()
用于读取并打印两个编码器的计数器数值。以下是代码的详细解释:
- 首先包含了两个头文件
Arduino.h
和Esp32PcntEncoder.h
,用于编写Arduino
程序和使用ESP32PcntEncoder
库。 - 在全局变量中创建了一个长度为2的
Esp32PcntEncoder
数组,用于存储两个编码器。 - 函数setup()用于初始化串口和编码器。在本代码中,首先通过
Serial.begin()
函数初始化串口,设置通信速率为115200
。然后通过encoders[0].init()
和encoders[1].init()
函数分别初始化了两个编码器。其中,函数init()需要传入三个参数,分别是编码器的ID
、引脚A的GPIO
编号和引脚B的GPIO
编号。在本代码中,第一个编码器的ID
为0
,引脚A连接的GPIO
为32
,引脚B连接的GPIO
为33
;第二个编码器的ID
为1
,引脚A连接的GPIO
为26
,引脚B连接的GPIO
为25
。 - 函数loop()用于读取并打印两个编码器的计数器数值。在本代码中,首先通过delay()函数等待10毫秒。然后通过
encoders[0].getTicks()
和encoders[1].getTicks()
函数分别读取了两个编码器的计数器数值。最后通过Serial.printf()
函数将这两个数值打印。
三、下载测试
将代码下载进入开发板,打开串口监视器,查看输出。
四、脉冲/圈计算
为了计算一个脉冲轮子前进的距离,我们可以通过手动将轮子旋转10圈,然后利用前面的公式进行计算。
这里小鱼将轮子转动10圈后得到脉冲数为19419
,也就是说当前电机1941.8个脉冲/圈
根据公式可以算出,一个脉冲轮子前进的距离为
接着我们可以利用公式计算速度。