聚丰项目 > 基于AB32VG1的自平衡自行车

基于AB32VG1的自平衡自行车

基于AB32VG1开发板设计的自平衡自行车机器人,具有一定的观赏性。车体姿态通过串口陀螺仪WT931获取,由S3010舵机控制前轮转向,使用RS-385电机和绝对值编码器实现后轮速度闭环控制,使用直流减速电机驱动动量轮。硬件部分测试稳定,利用STM32裸机平台完成了整机控制。现阶段软件控制部分利用RTT Studio完成了串口陀螺仪角度数据获取,单极性电机驱动控制。对于RTT了解还不够深入,有待后续积累经验。

zhuyshuang zhuyshuang

分享
1 喜欢这个项目
团队介绍

zhuyshuang zhuyshuang

团队成员

zhuyshuang 学生

分享
项目简介
基于AB32VG1开发板设计的自平衡自行车机器人,具有一定的观赏性。车体姿态通过串口陀螺仪WT931获取,由S3010舵机控制前轮转向,使用RS-385电机和绝对值编码器实现后轮速度闭环控制,使用直流减速电机驱动动量轮。硬件部分测试稳定,利用STM32裸机平台完成了整机控制。现阶段软件控制部分利用RTT Studio完成了串口陀螺仪角度数据获取,单极性电机驱动控制。对于RTT了解还不够深入,有待后续积累经验。
硬件说明
  1. 电源模块

    1. 电池:电池采用3300mah 2s航模电池,该类型电池具有高效的利用率和稳定的性能,一直被作为各种航模、电动车等的供电设备

    2. 稳6V电源模块:使用TI公司开关电源TPS5430降压到6V供舵机使用。电路原理图如图所示。

    3. 稳5V电源模块:TPS7350是TI公司生产的高性能线性稳压芯片,其使用方便,电路的设计原理如图所示。

    2.电机驱动模块:本设计的驱动电路由4片mos管构成H桥。通过控制4个MOS管的导通和关断来实现正反转,并通过控制输入的PWM波的占空比来调节电机两端的平均电压,达到控制电机的转速的目的,具体电路图如图所示

    3.陀螺仪:陀螺仪使用维特智能的WT931串口陀螺仪模块,模块集成高精度的陀螺仪、加速度计、地磁场传感器,采用高性能的微处理器和先进 的动力学解算与卡尔曼动态滤波算法,能够快速求解出模块当前的实时运动姿态。



软件说明
  1. QQ截图20211215212648.png

  2. 车模速度控制:车模速度采用PID控制,P为比例参数,I为积分参数,D为微分参数,P项使输出随误差大小变化,I项消除由于摩擦力等因素导致的速度的稳态误差,使得实际速度始终跟随目标速度,提高车模运行速度的稳定性,D项提高速度的动态响应能力及降低超调,使速度响应及时且平顺。

  3. 车模姿态获取:

    参考WT931的操作手册写串口定长数据接收处理即可,以下为与上位机通信代码,用于实际调试。

  4. void SCI_Send_Datas()
    {
        static unsigned short int send_data[3][4] = { { 0 }, { 0 }, { 0 } };
        short int checksum=0;
        unsigned char xorsum=0,high,low;

        send_data[0][0] = (unsigned short int)(Roll);
        send_data[0][1] = (unsigned short int)(90);
        send_data[0][2] = (unsigned short int)(0);
        send_data[0][3] = (unsigned short int)(0);

        send_data[1][0] = (unsigned short int)(output);
        send_data[1][1] = (unsigned short int)(0);
        send_data[1][2] = (unsigned short int)(0);
        send_data[1][3] = (unsigned short int)(0);

        send_data[2][0] = (unsigned short int)(0);
        send_data[2][1] = (unsigned short int)(0);
        send_data[2][2] = (unsigned short int)(0);
        send_data[2][3] = (unsigned short int)(0);

        rt_sprintf(tx_buf0, "%c",0x53);
        rt_device_write(serial, 0, tx_buf0, (sizeof(tx_buf0)) );
        rt_sprintf(tx_buf0, "%c",0x54);
        rt_device_write(serial, 0, tx_buf0, (sizeof(tx_buf0)) );

        for (int i = 0; i < 3; i++)
        for (int j = 0; j < 4; j++)
        {
          low=(unsigned char)(send_data[i][j] & 0x00ff);
          high=(unsigned char)(send_data[i][j] >> 8u);

          rt_sprintf(tx_buf0, "%c",low);
          rt_device_write(serial, 0, tx_buf0, (sizeof(tx_buf0)) );
          rt_sprintf(tx_buf0, "%c",high);
          rt_device_write(serial, 0, tx_buf0, (sizeof(tx_buf0)) );

          checksum+=low; checksum+=high;
          xorsum^=low; xorsum^= high;
        }

        rt_sprintf(tx_buf0, "%c",(unsigned char)(checksum & 0x00ff));
        rt_device_write(serial, 0, tx_buf0, (sizeof(tx_buf0)) );
        rt_sprintf(tx_buf0, "%c",xorsum);
        rt_device_write(serial, 0, tx_buf0, (sizeof(tx_buf0)) );
    }

  5. 车模平衡控制:简单的考虑是,不考虑舵机转向和后轮电机速度对于单车平衡的影响,类比于两轮平衡小车直立环、速度环和方向环的三环控制,单车采用角速度环和角度环串级作为直立环,直立环以动量轮为执行器,由舵机控制转向,后轮电机提供动力。

    如果不考虑动量轮的作用,单车的运动控制此时是一个欠驱动系统。按照单车的运动模型,后轮电机速度对单车的直立环也会产生影响,速度越快,则向心力越大,所以不同速度下单车倾角所对应的前轮舵机打角也不同。假设在匀速状态下的参数正好适合,我们想到可以配合加减速来辅助直立环,在单车过弯道时减速,过弯后及时加速使单车回正,这样的策略可以让单车在过弯时起到压弯的效果。

    实际情况是舵机与两个电机相互耦合作用,值得深入研究研究。

    通过动量轮实现单车平衡控制算法:

        

        void balance_pid(float turn)
        {
             float idata  servo_bias,gyro_bias;
             static float idata last_output=0,last_g_output=0;
             static float  servo_bias_last,gyro_bias_last;
             static float  servo_integration;
             static float gyro_integration;
             float actual;
             //角度环
             servo_bias = Roll- pid.balance_init0-turn;
             servo_integration+=servo_bias;

             if(servo_integration>600)//外环积分限幅
               servo_integration=600;
             else if(servo_integration<-600)
               servo_integration=-600;

             pid.output= pid.balance_P * servo_bias + pid.balance_I * servo_integration  + pid.balance_D * ((float)gyro[0]/16.4);//+center.result;

             //角速度环
              gyro_bias = pid.output -  ((float)gyro[0]/16.4);

    
             gyro_integration+=gyro_bias;
             if(gyro_integration>1000)//内环积分限幅
                  gyro_integration=1000;
             else if(gyro_integration<-1000)
                  gyro_integration=-1000;
             key.servo_pwm =pid.outside_P * gyro_bias +pid.outside_I*gyro_integration+ pid.outside_D * (gyro_bias - gyro_bias_last);
             gyro_bias_last = gyro_bias;
             servo_duty((unsigned short)((short)key.servo_pwm+970));//输出到动量轮电机

}



演示效果

车模姿态的获取

附件

(11.06 MB)下载

评论区(0 )