教程二 带编码器电机控制例程二
来自Waveshare Wiki
各模块使用教程
- 序章 安装Arduino IDE
- 教程一 带编码器电机控制例程一
- 教程二 带编码器电机控制例程二
- 教程三 带编码器电机控制例程三
- 教程四 无编码器电机控制例程
- 教程五 ST3215总线舵机控制例程
- 教程六 PWM舵机控制例程
- 教程七 IMU数据读取例程
- 教程八 SD卡读取例程
- 教程九 INA219电压电流监测例程
- 教程十 OLED屏幕控制例程
- 教程十一 激光雷达和在ROS2中发布雷达话题
- General Driver for Robots 主页
带编码器电机控制例程二
本教程是用于控制电机的正反转,快速和慢速转,以下提供控制电机转动的例程。
例程
上传程序
下载压缩包打开motorCtrl.ino,用USB线将多功能驱动板和计算机连接起来(此处插入的是多功能驱动板USB的Type-C接口),点击“工具”→“端口”,再点击新出现的COM(我这里新出现的COM为COM26)。
![]()
在Arduino IDE中,点击“工具”→“开发板”→“ESP32”→“ESP32 Dev Module”。开发板以及端口都选择好后上传程序。上传程序后,将无编码器电机和驱动板上的电机接口PH2.0 2P连接上,将XH2.54供电接口接上电源后,可以看见电机开始快速正方向转动3s、慢速反方向转动3s再停转3s的循环。
程序解析
// 以下定义了用于控制TB6612的ESP32引脚
// A路电机
const uint16_t PWMA = 25; // Motor A PWM control Orange
const uint16_t AIN2 = 17; // Motor A input 2 Brown
const uint16_t AIN1 = 21; // Motor A input 1 Green
// B路电机
const uint16_t BIN1 = 22; // Motor B input 1 Yellow
const uint16_t BIN2 = 23; // Motor B input 2 Purple
const uint16_t PWMB = 26; // Motor B PWM control White
// 用于PWM输出的引脚的PWM频率
int freq = 100000;
// 定义PWM通道
int channel_A = 5;
int channel_B = 6;
// 定义PWM的精度,精度为8时,PWM数值在0-255(2^8-1)
const uint16_t ANALOG_WRITE_BITS = 8;
// 最大的PWM数值
const uint16_t MAX_PWM = pow(2, ANALOG_WRITE_BITS)-1;
// 最小的PWM数值,由于直流电机的低速特性一般比较差,过低的PWM达不到电机的转动阈值
const uint16_t MIN_PWM = MAX_PWM/5;
void setup(){
// 设置用于控制TB6612FNG的ESP32引脚的工作模式
pinMode(AIN1, OUTPUT);
pinMode(AIN2, OUTPUT);
pinMode(PWMA, OUTPUT);
pinMode(BIN1, OUTPUT);
pinMode(BIN2, OUTPUT);
pinMode(PWMB, OUTPUT);
// 设置用于PWM输出的ESP32引脚的通道、频率和精度
ledcSetup(channel_A, freq, ANALOG_WRITE_BITS);
ledcAttachPin(PWMA, channel_A);
ledcSetup(channel_B, freq, ANALOG_WRITE_BITS);
ledcAttachPin(PWMB, channel_B);
// 用于控制转动的引脚置于低电平,电机停止转动,避免初始化后立即开始转动
digitalWrite(AIN1, LOW);
digitalWrite(AIN2, LOW);
digitalWrite(BIN1, LOW);
digitalWrite(BIN2, LOW);
}
// A路电机控制
void channel_A_Ctrl(float pwmInputA){
// 将pwmInput值取整
int pwmIntA = round(pwmInputA);
if(pwmIntA == 0){
digitalWrite(AIN1, LOW);
digitalWrite(AIN2, LOW);
return;
}
// 判断pwmInput值的正负来确定旋转方向
if(pwmIntA > 0){
digitalWrite(AIN1, LOW);
digitalWrite(AIN2, HIGH);
// constrain()函数用于将pwmIntA的值限制在MIN_PWM与MAX_PWM之间
ledcWrite(channel_A, constrain(pwmIntA, MIN_PWM, MAX_PWM));
}
else{
digitalWrite(AIN1, HIGH);
digitalWrite(AIN2, LOW);
ledcWrite(channel_A,-constrain(pwmIntA, -MAX_PWM, -MIN_PWM));
}
}
// B路电机控制
void channel_B_Ctrl(float pwmInputB){
int pwmIntB = round(pwmInputB);
if(pwmIntB == 0){
digitalWrite(BIN1, LOW);
digitalWrite(BIN2, LOW);
return;
}
if(pwmIntB > 0){
digitalWrite(BIN1, LOW);
digitalWrite(BIN2, HIGH);
ledcWrite(channel_B, constrain(pwmIntB, MIN_PWM, MAX_PWM));
}
else{
digitalWrite(BIN1, HIGH);
digitalWrite(BIN2, LOW);
ledcWrite(channel_B,-constrain(pwmIntB, -MAX_PWM, -MIN_PWM));
}
}
void loop(){
// 电机停转3秒钟
channel_A_Ctrl(0);
channel_B_Ctrl(0);
delay(3000);
// 电机反方向,以低速转3秒钟
channel_A_Ctrl(-64);
channel_B_Ctrl(-64);
delay(3000);
// 电机正方向,以最高转速转3秒钟
channel_A_Ctrl(255);
channel_B_Ctrl(255);
delay(3000);
}
