两轮平衡车


成品照片

写在前面

做这个项目的初衷是想把手头上从学长那里收来的一些电机和电池用上,清一波库存(实际上没用上收来的器件,反而自己又掏钱买了电机和端子╮(╯▽╰)╭)。
于是想到了做一个平衡车,这个算是工科大学自动化类的一个经典项目设计。
虽然咱是EEer,但是秉承要做就做全栈的优良传统,还是想从头到尾完成一个项目。
本文着重于讲解如何从无到有构思并制造出一个完整的系统,并使得它逐渐趋于完美,包括外观设计,接口设计,器件选型,PCB设计,焊接验证,代码编写。
在项目的完成过程中还能顺便学一下PID的思想,体会调参的快乐(痛苦)。

初步构思

  • 首先既然是平衡车,那么一定要有两个轮子,当然还有通过转轴和轮子连接的电机。
  • 而要实现对电机的控制,需要电机控制模块,也就是我们整个系统的控制板。控制板上还要有运动传感器,来检测当前的运动状态。
  • 还需要有电池作为整个系统的电力来源,连接到控制板上。
  • 仅凭一块控制板是难以同时放下电池并固定好电机的,所以我们还需要一层亚力克底板,作为系统的加固和支撑,亚克力材质也方便我们打孔固定。

这是网上的平衡车的3D模型,我们可以依照这个样子,慢慢构想出我们的模型。
平衡车3D模型

选型与设计

这一节我会从系统的每个部件的所要满足的条件出发,环环相扣,完成每一个器件的选型。

电机

可以预见的是,这个平衡小车整个系统的重量并不会太重,可以估算出大概在0.2kg至0.5kg之间,橡胶轮对普通硬质地面的摩擦力系数大概在0.6至0.7左右。
所以让整个系统运动起来所需要提供的力无需太大,也就是不需要选用大力矩电机。
因为大力矩电机的转速往往不高,而我们系统在执行平衡动作的时候需要一个较快的响应,对转速和加速度有一定要求。
这样带来的另一方面的好处就是电机的工作电压无需太大,工作电流也不用太高。减少了变压电路设计的成本。
除此之外,电机还需要带编码器,它能够指示电机转了多少角度,便于我们对系统的速度进行控制。
经过一番挑选,选择了淘宝上的N20减速电机带编码器,6V电压,310转的版本。
电机虽然标称工作电压6V,但是由于电源设计比较常见的是输出5V的LDO,输出6V的比较少见
而这种电机对电压要求没那么严格,标称6V,但是5V下肯定也能使用,只不过力矩和最大转速会稍小一点(粗浅理解,不是机械专业的学生)。所以我们直接供5V电压也是没有问题的
减速电机N20带编码器介绍

DRV8833电机驱动芯片
比较经典的一款电机驱动芯片,2路输出,通过PWM调解转速,最大能输出2A电流。
驱动芯片简化框图

运动传感器
选择经典MPU6050,网上有现成的模块,也有很多的例程和文档。
为了板子的整体美观,我选择使用芯片,QFN封装,会稍稍有点难焊接。
不过我有热风枪,也比较容易搞定,不行的话吹下来重新焊一下就可以了。
MPU6050商品页

MCU
个人平常用的比较多的是单片机是ESP32和STM32,对于这个项目的话两者的性能和外设支持都是完全够用的。
为了方便使用手机控制,我选择使用ESP32,它支持蓝牙和WIFI连接,而且使用Aurdino IDE开发的话有一些现成的库可以使用,也避免了自己移植驱动带来的问题。
我手头上正好有个ESP32-Wroom32,乐鑫官方的封装好的模组,可以直接用,不需要自己设计外围的PCB板载天线,只要注意PCB布局的时候设置Keepout区域就可以了。
淘宝商品页

电源

通过上面的分析,我们需要两个电源域,5V和3.3V,分别供给电机和单片机以及芯片。
而一般的锂电池的供电电压是3.7V,肯定是不能直接供电的。
要么一节电池的3.7V升压到5V,再降压到3.3V。
要么两节电池串联7.4V降压到5V和3.3V。
一节锂电池的优势是轻便,但是带来的劣势是使用时间比较短,而且升压的话是要用到DCDC Boost电路的,对电路设计有一定的要求。
两节锂电池虽然会重一点,占空间会大一些,但是无伤大雅,我们有亚力克底板可以承接。
这样带来的好处是更容易的电路设计,使用两颗LDO就能转换出5V和3.3V的电压。
其实在这里我考虑过电池的充电管理,想的是找一颗适用于2节锂电池串联的充电芯片,SLM6800或者CN3762。
但是转念一想,好像可以直接把电池取出来充电,于是就没有设计这一块。
(然而事实上组装好之后电池仓被挡住了,根本取不出来,但是好在电池比较坚挺,一直坚持到了调参成功)。
电池用的是18650锂电池。一节2600mAH。
电池仓采用的是这种贴片式的,安装的时候让电池朝向一正一反,把一侧的金属触点用线焊到一起,另一侧就是7.4V的电压输出
电池盒商品页

亚克力底板

厚度不能太厚也不能太薄,超过6mm会导致螺柱头伸过不来而且不易打孔,太薄容易断裂,3mm是一个比较合适的大小。
亚克力板商品页

控制板PCB

原理图绘制

原理图参考网上的资料,主要是MPU6050以及DRV8833的外围电路,照着Datasheet画就行了,其他的都非常简单。
第一次尝试串口自动下载电路,Arudino IDE的自动下载没问题,但是在下载完成后用sscom打开串口时,要关闭串口软件的打开串口时自动发送RTS,否则会导致芯片进入下载模式。
整体原理图

PCB绘制

注意电源通路,有些一看就是大电流的的线路要加粗,比如电机驱动芯片的输出,ESP32的VCC输入。
去耦电容靠近芯片脚,ESP32的天线区域超过板框悬空即可。
2D预览
3D预览

焊接与组装

这一部分主要会讲实际调试时遇到的问题以及解决办法。

焊接:

  • 抹锡膏的时候均匀涂抹,热风枪先对着要焊接的部分整体预热,后均匀加热。
  • 检查有没有肉眼可见的连锡,用烙铁加助焊剂把ESP32,CH340C等密脚芯片的各个脚拖焊一遍。
  • VCC和GND用万用表连通挡测一下有没有短路。
  • 上电时第一时间观察电源指示灯的情况,发现不对立马断开电源。
  • 板子上是由焊盘通过硅胶线连接到电池正负极,有短路和线材被扯断的风险,在电池正负极焊盘之间附近打上热熔胶。

安装:

  • 把电路板放在亚克力中部,对正,平齐,用记号笔画出定位孔。
  • 用冲击钻将亚克力板钻出孔位,给电路板的四角装上铜柱,安装到亚克力板上。
  • 预估好电机位置,画好定位线,用强力胶水将电机沾到亚克力板的底面侧边,编码器接口朝向地面(这样就无需切割和打孔,直接固定好了电机)。
  • 电机的线从底面的同一侧引出,方便后面接到板子上。
  • 电池仓贴到亚力克板上,用双面胶固定

致命问题:

  1. 接线端子封装画错了

电机的接口封装是ZH1.5接线端子,6线,而我画板子的时候画成了PH2.0,买的也是PH2.0的接线端子。
而且还把直插买成了侧贴(经验教训,嘉立创的封装在种类比较多的时候要确认好是不是自己想要的那种)。
导致到货后和板子一比对发现这是绝对插不上的(╯‵□′)╯︵┻━┻

但是转念一想,既然只是接线端子,而且这个电机也不用频繁拔插,可以把电机的引线直接焊到表贴焊盘上,只要每个脚的定义都对准了就好了。
于是直接开焊,焊接完成后发现效果还不错,锡加的足一点,让线完全包覆在其中就没问题。

  1. MPU6050读不出数据

这个其实是个软件的锅,用MCU一直读不出传感器数据,用示波器看管脚发现SCL和SDA的波形有是有,就是不太对劲。
我一直以为是硬件的问题,因为QFN-24封装确实有那么亿点点难焊接。
拆了又装,买的两片MPU6050轮番上阵,这个不行换那个,折腾了半天。
最后我转念一想,是不是软件的问题,Arudino的库肯定是没有问题的,管脚重映射也是有效的,SCL和SDA脚也确实是有波形的,就是会定时的出现不太对劲的波动。
然后我突然想到,乐鑫的ESP32-Wroom32模组在Arudino IDE中的开发板选择其实是ESP32 Dev Module,而不是下面的ESP32-WROOM-DA Module。
我又查阅了市面上常见的使用乐鑫ESP32-Wroom32模组的开发板,发现它们选的也都是ESP32 Dev Module
开发板选择
然后我一查ESP32-WROOM-DA Module,发现这玩意长这样,虽然它们名字长的很像,但真就不是同一个东西。
DA模块外观
然后在设置里把开发板一改,立马读出数据来了.

  1. 电机只有一个转
    测试电机的时候发现一边转,另一边不转,说明电机驱动芯片功能肯定是好的。问题要么是虚焊,要么是PWM没有输出。
    用联通挡一测,发现没有虚焊。
    用万用表的电压档测,发现不转的那一侧的IO34和IO35的PWM没有输出。
    搜索引擎查阅资料,发现是ESP32的管脚功能问题,ESP32比较多管脚的系列的的IO34-39只能用作输入,不能用作输出。
    不推荐使用的管脚
    于是我直接把IO34和IO35就近飞线到最近的能用的管脚IO12和IO27上,然后在代码中改一下PWM的输出脚,电机就能转动了。

代码编写

  • MPU6050和电机驱动没啥好讲的,都是现成的库,下载来直接用就可以。
  • PWM使用的是ledc函数,调节占空比。
  • 可以用串口命令发送PID参数,避免了改一下就要重新烧录的问题

调PID

原本有想过好好写一下,但是发现前辈们已经把这些东西讲的很透彻了,再重复也没什么意义。
有需要学习的同学可以参考以下文章。
平衡小车的PID环体会心得_ReCclay的博客-CSDN博客_stm32平衡小车
PID深度解析(基于STM32平衡小车)Carbon6的博客-CSDN博客平衡车控制算法
平衡小车PID,就该这么调!!! - 知乎 (zhihu.com)

打包好的工程文件

Balance_Bike.zip

一些照片

侧视
正视

源代码

#include "MPU6050_tockn.h"
#include "Wire.h"

MPU6050 mpu6050(Wire);

long timer = 0;

#define PWM1 32
#define PWM2 33
#define PWM3 27
#define PWM4 12

int Rcode1 = 0, Lcode1 = 0;


void Rcode1callBack(void)
{
  if (digitalRead(22) == 1 )
    Rcode1++;
  else
    Rcode1--;
}

void Lcode1callBack(void)
{
  if (digitalRead(4) == 1 )
    Lcode1--;
  else
    Lcode1++;
}

void Motor_Left_Setspeed(int Motorspeed)
{
  if (Motorspeed > 0)
  {
    int PWM = Motorspeed ;  // 正转
    if (PWM > 1000)
      PWM = 1000;
    ledcWrite(0, 0);                     // 设置占空比
    ledcWrite(1, PWM);
  }
  else
  {
    int PWM = (-Motorspeed) ;  // 反转
    if (PWM > 1000)
      PWM = 1000;
    ledcWrite(0, PWM);                     // 设置占空比
    ledcWrite(1, 0);
  }
}

void Motor_Right_Setspeed(int Motorspeed)
{
  if (Motorspeed > 0)
  {
    int PWM = Motorspeed ;  // 正转
    if (PWM > 1000)
      PWM = 1000;
    ledcWrite(2, PWM);    // 设置占空比
    ledcWrite(3, 0);
  }
  else
  {
    int PWM = (-Motorspeed) ;  // 反转
    if (PWM > 1000)
      PWM = 1000;
    ledcWrite(2, 0);     // 设置占空比
    ledcWrite(3, PWM);
  }
}



int Mechanical_balance = -3;
int balance_UP_KP = 100;
int balance_UP_KD = 8;
/*******************************************************************
  函数功能:直立PD控制
  入口参数:角度、角速度
  返回  值:直立控制PWM
******************************************************************/
int balance_UP(float Angle, float Gyro)
{
  float Bias;    //  角度误差
  int balance;   //  直立环计算出来的电机转速PWM值
  Bias = Angle - Mechanical_balance;
  // 求出平衡的角度中值和机械相关
  balance = balance_UP_KP * Bias + balance_UP_KD * Gyro;
  //===计算平衡控制的电机PWM  PD控制   KP是P系数 KD是D系数
  return balance;
}

/**************************************
  函数功能:速度PI控制
  入口参数:电机编码器的值
  返回值:速度控制PWM
**************************************/
int velocity_KP = 2;
float velocity_KI = 0.01;
int delaytime = 5;
int velocity(int encoder_left, int encoder_right)
{
  static float Velocity, Encoder_Least, Encoder, Movement;
  static float Encoder_Integral;
  //=============速度PI控制器=======================//
  Encoder_Least = (encoder_left + encoder_right) - 0;    //===获取最新速度偏差    测量速度(左右编码器之和)-目标速度(此处为零)

  Encoder *= 0.7;
  Encoder += Encoder_Least * 0.3; //  低通滤波

  Encoder_Integral += Encoder;  //   积分出位移 积分时间:delaytime

  if (Encoder_Integral > 10000)    Encoder_Integral = 10000;   // 积分限幅
  if (Encoder_Integral < -10000)    Encoder_Integral = -10000; // 积分限幅

  Velocity = Encoder * velocity_KP + Encoder_Integral * velocity_KI; // 速度控制

  //  if (pitch < -40 || pitch > 40)   Encoder_Integral = 0;  //===电机关闭后清除积分

  return Velocity;
}

int Straight_KS = 20;
/**************************************
  函数功能:两侧电机同速控制
  入口参数:电机编码器的值
  返回值:电机同转速控制PWM
**************************************/
int Straight_compensation(int encoder_left, int encoder_right)
{
  int diff = encoder_left - encoder_right;
  int compensation = Straight_KS * diff;
  return compensation;
}


void setup()
{
  Serial.begin(115200);
  ledcSetup(0, 10000, 10);  //设置LEDC通道0频率为10K,分辨率为10位,即占空比可选0~1023
  ledcSetup(1, 10000, 10);
  ledcSetup(2, 10000, 10);
  ledcSetup(3, 10000, 10);

  ledcAttachPin(PWM1, 0);     //设置LEDC通道0在IO1上输出
  ledcAttachPin(PWM2, 1);
  ledcAttachPin(PWM3, 2);
  ledcAttachPin(PWM4, 3);

  ledcWrite(0, 0);        // 设置占空比
  ledcWrite(1, 0);
  ledcWrite(2, 0);
  ledcWrite(3, 0);

  pinMode(23 , INPUT_PULLDOWN); // Rcode1
  pinMode(22 , INPUT_PULLDOWN); // Rcode2
  pinMode(21 , INPUT_PULLDOWN); // Lcode1
  pinMode(4 ,  INPUT_PULLDOWN);  // Lcode2

  attachInterrupt(23, Rcode1callBack, RISING);  //当电平上升沿时,触发中断
  attachInterrupt(21, Lcode1callBack, RISING);


  Wire.begin(26, 25);
  mpu6050.begin();
  mpu6050.calcGyroOffsets(true);

}

int n = 0;
void loop()
{
  delay(delaytime);
  mpu6050.update();

  int balance_PWM = balance_UP(mpu6050.getAngleY(), mpu6050.getGyroY());
  int velocity_PWM = velocity(Lcode1, Rcode1);
  int Final_PWM = balance_PWM - velocity_PWM;
  int compensation_PWM = Straight_compensation(Lcode1, Rcode1);
  Motor_Left_Setspeed(Final_PWM);
  Motor_Right_Setspeed(Final_PWM + compensation_PWM);

  n++;
  if (n == 50)
  {
    Serial.println("===================");
    Serial.print("tgyroY : "); Serial.print(mpu6050.getGyroY());      // 打印角度
    Serial.print("\t angleY : "); Serial.println(mpu6050.getAngleY());
    Serial.print("Lcode1 = ");  Serial.print(Lcode1);                 // 打印编码器计数
    Serial.print("Rcode1 = ");  Serial.println(Rcode1);
    Serial.print("balancePWM = ");  Serial.println(balance_PWM);      // 打印直立环PWM值
    Serial.print("velocityPWM = ");  Serial.println(velocity_PWM);    // 打印速度环PWM值
    Serial.print("compensationPWM = ");  Serial.println(compensation_PWM);    // 打印同速环PWM值
    Serial.println("==================\n");
    n = 0;
  }

  Rcode1 = 0, Lcode1 = 0; // 清空计数

  if (Serial.available() > 0)//判读是否串口有数据
  {
    String comdata = "";//缓存清零
    while (Serial.available() > 0)//循环串口是否有数据
    {
      comdata += char(Serial.read()); //叠加数据到comdata
      delay(2);//延时等待
    }
    if (comdata.indexOf('p') != -1)
    {
      String substr = comdata.substring(2); // 从第三位开始截取
      balance_UP_KP = substr.toInt(); // 转成整数
    }
    else if (comdata.indexOf('d') != -1)
    {
      String substr = comdata.substring(2);  // 从第三位开始截取
      balance_UP_KD = substr.toInt(); // 转成整数
    }
    else if (comdata.indexOf('v') != -1)
    {
      String substr = comdata.substring(2);  // 从第三位开始截取
      velocity_KP = substr.toInt(); // 转成整数
    }
    else if (comdata.indexOf('i') != -1)
    {
      String substr = comdata.substring(2); // 从第三位开始截取
      velocity_KI = substr.toFloat(); // 转成整数
    }
    else if (comdata.indexOf('s') != -1)
    {
      String substr = comdata.substring(2); // 从第三位开始截取
      Straight_KS = substr.toFloat(); // 转成整数
    }
    else if (comdata.indexOf('m') != -1)
    {
      String substr = comdata.substring(2);  // 从第三位开始截取
      Mechanical_balance = substr.toInt(); // 转成整数
    }
    else if (comdata.indexOf('t') != -1)
    {
      String substr = comdata.substring(2);  // 从第三位开始截取
      delaytime = substr.toInt(); // 转成整数
    }
  }

}

文章作者: Allen Hong
版权声明: 本博客所有文章除特別声明外,均采用 CC BY 4.0 许可协议。转载请注明来源 Allen Hong !
  目录