DCGM-N20-12V-EN-200RPM
来自Waveshare Wiki
|
| ||||||||||||||||||||
| ||||||||||||||||||||
产品简介
本产品是一款高精度的N20直流编码减速电机,配备了磁性霍尔编码器和全金属齿轮,采用L型引出端子设计便于连接。主要适用于需要精确运动和控制的智能机器人和智能家居设备。
产品特点
- 7线霍尔编码器
- 全金属齿轮高精密减速器
- 空载转速200rpm
- 堵转扭矩可达1.2kg.cm
- 接线端子型号ZH1.5-6PIN
产品参数
| 额定电压 |
DC 12V |
|---|---|
| 空载转速 | 200rpm |
| 空载电流 | 0.1A MAX |
| 空载起动电压 | 3.0V MAX |
| 堵转扭矩 | ≥1.2 kg.cm |
| 堵转电流 | ≤1.1A |
| 霍尔分辨率 | 基础7PPR×150=1050PPR |
| 齿轮减速比 | 1:150 |
工作方式
例程运行
安装Arduino IDE
-
下载Arduino IDE
首先到Arduino官网下载最新版本Arduino IDE 2.1.0的安装包。官方IDE支持不同的操作系统,根据您的操作系统选择进行安装即可。我这里下载的是windows的。(如果已安装,直接跳到第二步)安装过程很简单,一直点击下一步即可。
注意:安装过程中会提示你安装驱动,我们点击安装即可
-
设置Arduino IDE为中文界面
第一次安装完成后,打开Arduino IDE是英文界面的,我们可以点击“File”→“Preferences”。
在“Language”里面选择简体中文,点击OK。
安装ESP32插件
-
打开Arduino IDE,点击“文件”→“首选项”。
-
在附加开发板管理器网址中添加如下链接,点击“确定”保存设置
https://dl.espressif.com/dl/package_esp32_index.json
注意:如果您需要添加多个开发板URL,那无需将ESP32开发板支持的URL删掉,可以直接将其他URL添加至另一行,默认显示是逗号分隔开URL的。例如:如果您需要添加ESP8266开发板的URL,直接添加至另一行,显示出来如下为:https://dl.espressif.com/dl/package_esp32_index.json,http://arduino.esp8266.com/stable/package_esp8266com_index.json
-
下载packages压缩包,在“我的电脑”中输入以下路径:
C:\Users\username\AppData\Local\Arduino15
username根据自己电脑的用户名变换,将解压的packages文件复制到Arduino15文件夹下
安装依赖库
- 点击左边第三个图标是库管理,在搜索栏中输入“INA219_WE”,找到依赖库INA219_WE并点击安装。
- 接着在搜索栏中输入“Adafruit_SSD1306”,找到依赖库Adafruit_SSD1306并点击安装。
- 下载依赖库ESP32Servo,解压依赖库,打开Arduino默认安装的位置C:\Users\username\AppData\Local\Arduino15\libraries,username根据自己电脑的用户名变换,再把图中文件夹复制到Libraries文件夹里。
上传程序
- 下载例程,解压后双击speedLoopCtrl.ino
-
点击“工具”→“端口”,记住自己电脑上已有的COM,不需要点击这个COM(此时我这里显示的COM为COM1,不同电脑显示的COM不一样)。
-
用USB线将多功能驱动板和计算机连接起来(此处插入的是多功能驱动板USB的Type-C接口),点击“工具”→“端口”,再点击新出现的COM(我这里新出现的COM为COM25)。
-
在Arduino IDE中,点击“工具”→“开发板”→“ESP32”→“ESP32 Dev Module”。
- 设置完成后,点击“上传”按钮将程序上传到设备上。
- 上传完成程序后,将 N20 电机和机器人通用驱动板上的电机 PH2.0 2P 接口连接上,将驱动板上 XH2.54 供电接口接上电源后,可以看见电机快速地开始转动。
- 需要注意的是:如果上传期间遇到了问题,需要重新安装或者更换Arduino IDE版本,在这之前,您需要将Arduino IDE卸载干净,卸载软件后需要将C:\Users\username\AppData\Local\Arduino15这个文件夹内的所有内容手动删除(一些隐藏文件需要显示才能看到),接着再重新下载安装。
程序解析
// --- --- --- 编码器部分 --- --- ---
// A路编码器的引脚定义
const uint16_t AENCA = 35; // Encoder A input A_C2(B)
const uint16_t AENCB = 34; // Encoder A input A_C1(A)
// B路编码器的引脚定义
const uint16_t BENCB = 16; // Encoder B input B_C2(B)
const uint16_t BENCA = 27; // Encoder B input B_C1(A)
// 用于计算在“interval”时间(单位ms)内的编码器的某一个霍尔传感器的高低电平变化次数
// 因为后面初始化中断时使用的是RISING,所以具体来说是低电平变高电平的次数
volatile long B_wheel_pulse_count = 0;
volatile long A_wheel_pulse_count = 0;
// 计算速度的周期时间,每隔这么多ms机算一次速度
int interval = 100;
// 当前的时间
long currentMillis = 0;
// 电机的减速比,减速电机的电机转速和输出轴的转速是不一样的
// 例如DCGM3865这款电机,减速比是1:42,意味着电机转动42圈,输出轴转动1圈
// 对应输出轴的一圈,电机需要转的圈数越多,减速比越大,通常扭矩越大
// 一下以DCGM3865电机(减速比1:42)为例
double reduction_ratio = 150;
// 编码器线数,电机转动一圈,编码器的一个霍尔传感器的高低电平变化次数
int ppr_num = 7;
// 输出轴转动一圈,编码器的一个霍尔传感器的高低电平变化次数
double shaft_ppr = reduction_ratio * ppr_num;
// 中断函数的回调函数,参考后面的attachInterrupt()函数
void IRAM_ATTR B_wheel_pulse() {
if(digitalRead(BENCA)){
B_wheel_pulse_count++;
}
else{
B_wheel_pulse_count--;
}
}
void IRAM_ATTR A_wheel_pulse() {
if(digitalRead(AENCA)){
A_wheel_pulse_count++;
}
else{
A_wheel_pulse_count--;
}
}
// --- --- --- --- --- --- --- --- ---
// --- --- --- 电机控制部分 --- --- ---
// 以下定义了用于控制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;
// A路电机控制
void channel_A_Ctrl(float pwmInputA){
// 将pwmInput值取整
int pwmIntA = round(pwmInputA);
// 如果pwmInput是0则停止转动
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, 0));
}
}
// 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, 0, MAX_PWM));
}
else{
digitalWrite(BIN1, HIGH);
digitalWrite(BIN2, LOW);
ledcWrite(channel_B,-constrain(pwmIntB, -MAX_PWM, 0));
}
}
// --- --- --- --- --- --- --- --- ---
// --- --- --- 闭环控制部分 --- --- ---
// PID控制器参数
double Kp = 0.05; // 比例系数
double Ki = 0.05; // 积分系数
double Kd = 0; // 微分系数
// 目标转速和实际转速
double targetSpeed_A = 100.0; // 目标转速(可根据需求调整)
double actualSpeed_A = 0.0; // 实际转速
double targetSpeed_B = 100.0; // 目标转速(可根据需求调整)
double actualSpeed_B = 0.0; // 实际转速
// PID控制器变量
double previousError_A = 0.0;
double integral_A = 0.0;
double previousError_B = 0.0;
double integral_B = 0.0;
// --- --- --- --- --- --- --- --- ---
void setup(){
// 设置编码器相关引脚的工作模式
pinMode(BENCB , INPUT_PULLUP);
pinMode(BENCA , INPUT_PULLUP);
pinMode(AENCB , INPUT_PULLUP);
pinMode(AENCA , INPUT_PULLUP);
// 设置中断和对应的回调函数,当BEBCB由低电平变高电平时(RISING),调用 B_wheel_pulse 函数。
attachInterrupt(digitalPinToInterrupt(BENCB), B_wheel_pulse, RISING);
// 设置中断和对应的回调函数,当AEBCB由低电平变高电平时(RISING),调用 A_wheel_pulse 函数。
attachInterrupt(digitalPinToInterrupt(AENCB), A_wheel_pulse, RISING);
// 初始化串口,波特率115200
Serial.begin(115200);
// 等待串口初始化完成
while(!Serial){}
// 设置用于控制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);
}
void loop(){
// 计算B通道电机输出轴的转速,单位为 转/分钟
actualSpeed_B = (float)((B_wheel_pulse_count / shaft_ppr) * 60 * (1000 / interval));
B_wheel_pulse_count = 0;
// 计算A通道电机输出轴的转速,单位为 转/分钟
actualSpeed_A = (float)((A_wheel_pulse_count / shaft_ppr) * 60 * (1000 / interval));
A_wheel_pulse_count = 0;
// 计算误差和控制量
double error_A = targetSpeed_A - actualSpeed_A;
integral_A += error_A;
double derivative_A = error_A - previousError_A;
double error_B = targetSpeed_B - actualSpeed_B;
integral_B += error_B;
double derivative_B = error_B - previousError_B;
// 计算PID输出
double output_A = Kp * error_A + Ki * integral_A + Kd * derivative_A;
double output_B = Kp * error_B + Ki * integral_B + Kd * derivative_B;
// output_A += Kp * error_A;
// output_B += Kp * error_B;
// 限制输出范围
output_A = constrain(output_A, -MAX_PWM, MAX_PWM);
output_B = constrain(output_B, -MAX_PWM, MAX_PWM);
// 输出PWM信号,控制电机转速
channel_A_Ctrl(-output_A);
channel_B_Ctrl(-output_B);
// 更新上一个误差值
previousError_A = error_A;
previousError_B = error_B;
Serial.print("RPM_A: ");Serial.print(actualSpeed_A);Serial.print(" RPM_B: ");Serial.println(actualSpeed_B);
Serial.println("--- --- ---");
delay(interval);
}

