stm32两轮平衡小车 -04

中心控制算法:

cs 复制代码
#include "controller.h"
#include "pid.h"
#include "imu.h"
#include "pwm.h"
#include "mpu6050.h"
#include "key.h"
#include "imath.h"
#include "ps2.h"
#include "bluetooth.h"
#include "ultrasonic.h"
#include "Infrared.h"
_OUT_Motor Motor1 = {0};
_OUT_Motor Motor2 = {0};

/* PID参数保存 */
#if 1 /* product motor */

_PID_CONTROL vel = {135.0f, 0.5f, 0.0f};       //{130.0f, 0.65f, 0.0f};
_PID_CONTROL bal = {200.0f, 0.0f , 15.0f};      //{150.0f, 0.0f , 20.0f};
_PID_CONTROL tur = {5.0f,  0.0f,  10.0f};      //{10.0f,  0.0f,  15.5f};
#else  /*self-maker-motor*/

_PID_CONTROL vel = {115.0f, 0.65f, 15.0f};       //{130.0f, 0.65f, 0.0f};
_PID_CONTROL bal = {230.0f, 0.0f , 15.0f};      //{150.0f, 0.0f , 20.0f};
_PID_CONTROL tur = {10.0f,  0.0f,  15.5f};      //{10.0f,  0.0f,  15.5f};
#endif
_PID_CONTROL ReadFlashVel = {0};
_PID_CONTROL ReadFlashBal = {0};
_PID_CONTROL ReadFlashTur = {0};

_PID_CONTROL WriteFlashVel = {0};
_PID_CONTROL WriteFlashBal = {0};
_PID_CONTROL WriteFlashTur = {0};

_OUT_CONTROL ctr = {0};
_REMOTE_Data remote = {0};

/*
 * 函数名:CarSpeedCtrlForwardOrBackward
 * 描述  :遥控时前进或者后退的速度更改
 * 输入  :ChangeStep增加或者减少的阶梯步数(改变前后运行速度的快慢程度)
 * 返回  :处理及限幅之后的前后方向速度更改阶梯步数  
 */
int CarSpeedCtrlForwardOrBackward(int ChangeStep)
{
    static int carUpOrDownOut = 40;                                 //开机上电默认前进后退速度
    if(PS2.KEY==PSB_GREEN)
    {
        carUpOrDownOut += ChangeStep;
    }
    if(PS2.KEY==PSB_BLUE)
    {
        carUpOrDownOut -= ChangeStep;
    }
    
    ForceIntLimit(&carUpOrDownOut,10,70);
    return carUpOrDownOut;                                          //限幅
}

/*
 * 函数名:CarSpeedCtrlLeftOrRight
 * 描述  :更改遥控时左右转向/旋转的速度快慢
 * 输入  :ChangeStep增加或者减少的阶梯步数(改变前后运行速度的快慢程度)
 * 返回  :处理及限幅之后的左右/旋转方向速度更改阶梯步数  
 */
int CarSpeedCtrlLeftOrRight(int ChangeStep)
{
    static int carLeftOrRightOut = 2500;                            //开机上电转向的初始控制量输出
    if(PS2.KEY==PSB_RED)
    {
        carLeftOrRightOut += ChangeStep;
    }
    if(PS2.KEY==PSB_PINK)
    {
        carLeftOrRightOut -= ChangeStep;
    }
    
    ForceIntLimit(&carLeftOrRightOut,1000,4000);
    return carLeftOrRightOut;                                       //限幅
}


/*
 * 函数名:remoteCarForwardOrBackward
 * 描述  :遥控控制前进和后退
 * 输入  :Speed控制前进和后退的速度,RemoteModeSelect遥控模式选择,UltrasonicMode功能模式选择
 * 返回  :当前速度运行 
 */
float remoteCarForwardOrBackward(float Speed , uint8_t RemoteModeSelect , uint8_t UltrasonicMode)
{
    float TargetVel;
  
    if( UltrasonicMode == ultraFollow)                                  //超声波跟随模式
    {
        if(( getDistance <= 10) && ( getDistance > 0 ))                 //距离小于10CM小车后退
        {
            TargetVel = -20;                                            //后退速度
        }
        else if(( getDistance > 20) && ( getDistance <= 30 ))           //距离大于25且小于30CM小车前进
        {
            TargetVel = 20;                                             //前进速度
        }
        else
        {
            TargetVel = 0;
        }
    }
    else if( UltrasonicMode == ultraAvoid)                              //超声波避障模式
    {
        if(( getDistance <= UltraTurnDist ) && ( getDistance > 0 ))    //距离小于指定距离表示遇到障碍则停止前进
        {
            TargetVel = 0;                                              //停止前进
        }
        else                                                            //无障碍则前进      
        {
            TargetVel = 10;                                             //前进速度默认最低
        }
    }   
    else                                                                //遥控模式
    {
        if( RemoteModeSelect == MODE_PS2 )                                                  
        {
        }
        else if( RemoteModeSelect == MODE_BLUETEETH )
        {
            if(BluetoothParseMsg.Yrocker == 0)                          //前进      
                TargetVel = Speed;                                      //速度期望
            else if(BluetoothParseMsg.Yrocker == 5)                     //后退      
                TargetVel = -Speed;                                     //速度期望
            else
                TargetVel = 0;              
        }
        else if( RemoteModeSelect == MODE_USER )
        {
        }        
    }

    return TargetVel;
}

/*
 * 函数名:shut_down
 * 描述  :关闭电机检测
 * 输入  :angle小车当前角度,Target达到设置的目标角度关闭电机停止
 * 返回  :关闭输出标志位 
 */
uint8_t shut_down(float angle,float Target)
{
    uint8_t shut_flag = 0;
    if(f_abs(angle)>Target)                                             
    {
        shut_flag = 1;                                                  //关闭输出标志置位                 
    }                                                            
    return shut_flag;                                            
}       

static uint8_t theCarStopFlag = 0;
/*
 * 函数名:PickUpTheCar
 * 描述  :小车被拿起
 * 输入  :angle当前角度,leftEncoder左轮编码器值,rightEncoder右轮编码器值
 * 返回  :是否成功拿起
 */
static uint8_t PickUpisOK = 0 ;
uint8_t PickUpTheCar(float carAngle , int leftEncoder , int rightEncoder)
{
    static uint16_t pickUpTime = 0 ;
    /* 小车被拿起后双轮高速转动  */
    if( leftEncoder >=40  || leftEncoder <=-40  ||  rightEncoder >=40  || rightEncoder <=-40  )
    {
        pickUpTime++;
        if(pickUpTime>300)                                   //转动时长:300 * 5ms 
        {
            pickUpTime = 0;
            PickUpisOK = 1;
        }
    }
    
    return PickUpisOK ; 
}
/*
 * 函数名:PutDownTheCar
 * 描述  :小车被放下
 * 输入  :angle当前角度,leftEncoder左轮编码器值,rightEncoder右轮编码器值
 * 返回  :是否成功放下
 */
uint8_t PutDownTheCar(float carAngle , int leftEncoder , int rightEncoder)
{
    static uint16_t isOK = 0 ; 
    static uint16_t PutDownTime = 0;
    
    if(theCarStopFlag==0)                                   //放置误检
        return 0;
    /* 小车两轮静止,并且放置的角度在平衡位置10度附近 */
    if( int_abs(leftEncoder) ==0 &&  int_abs(rightEncoder) == 0 && (f_abs(carAngle) <= 5.0f) )
    {
        PutDownTime++;
        if(PutDownTime>400)                                 //放下持续2S后平衡
        {
            PutDownTime = 0;
            isOK = 1;
        }
    }
    else 
    {
        PutDownTime = 0;
        isOK = 0;
    }
    
    return isOK;
}
/*   
ctr.bais[0]:角度控制器偏差存储 
ctr.bais[1]:速度控制器偏差累计存储 
ctr.bais[2]:转向控制器偏差存储 

ctr.exp[0]:角度控制器期望角度
ctr.exp[1]:速度控制器期望速度
ctr.exp[2]:转向控制器期望角度
*/

/*
 * 函数名:ctr_bal
 * 描述  :角度PD控制器
 * 输入  :angle当前角度,gyro当前角速度
 * 返回  :PID控制器输出
 */
int ctr_bal(float angle,float gyro)
{       
    ctr.exp[0] = 0;                                                     //期望角度    
    ctr.bais[0] = (float)(angle - ctr.exp[0]);                          //角度偏差
    ctr.balance = bal.kp * ctr.bais[0] + gyro * bal.kd;                 //角度平衡控制
    
    return ctr.balance;
}
int CarStepForwardOrBackward;
/*
 * 函数名:ctr_vel
 * 描述  :速度PI控制器
 * 输入  :encoder_left编码器值A,encoder_right编码器值B
 * 返回  :PID控制器输出
 */
int ctr_vel(int encoder_left,int encoder_right)
{  
    static float encoder_cur,encoder_last;

    CarStepForwardOrBackward = CarSpeedCtrlForwardOrBackward(1);        //遥控器控制的前后方向速度    
    remote.ForwardOrBackward = remoteCarForwardOrBackward( (float)CarStepForwardOrBackward , MODE_BLUETEETH , UltraSuccess(BluetoothParseMsg.ModeRocker) ); //遥控器控制前后方向运动
    
    encoder_last = ((encoder_left) + (encoder_right)) - 0;              //速度误差
    encoder_cur = encoder_cur * 0.8 + encoder_last * 0.2;               //对偏差进行低通滤波
    ctr.bais[1] += encoder_cur;                                         //偏差累加和   

    ctr.bais[1] = ctr.bais[1] - remote.ForwardOrBackward;               //遥控控制前后方向
    
    if(ctr.bais[1] > 10000)     ctr.bais[1] = 10000;                    //限幅
    if(ctr.bais[1] <-10000)	    ctr.bais[1] =-10000; 
    ctr.velocity = encoder_cur * vel.kp + ctr.bais[1] * vel.ki;         //速度控制     

    return ctr.velocity;
}

/*
 * 函数名:remoteCarLeftOrRight
 * 描述  :遥控控制左转和右转
 * 输入  :Speed转动速度,RemoteModeSelect遥控模式选择,UltrasonicMode功能模式选择
 * 返回  :经过处理及限幅后的转向速度
 */
int remoteCarLeftOrRight(int16_t Speed,uint8_t RemoteModeSelect , uint8_t UltrasonicMode)
{
    static uint8_t turnFlag = 0;
    static uint8_t turnTime = 0;
    
    if( UltrasonicMode == ultraAvoid )                                              //超声波避障模式
    {
        if((( getDistance <= UltraTurnDist ) && ( getDistance > 0 )) )             //距离小于指定距离时表示遇到障碍,便进行转向标志置位
        {
            turnFlag = 1;
        }
        if( turnFlag == 1 )                                                         //进行转向准备
        {
            tur.kd = 0;                                                             
            remote.LeftOrRight += 15;                                               //固定向左转向
            turnTime++;
            if(turnTime >= 50)                                                      //转向计数达到50时便停止转向
            {
                turnTime = 0;     
                turnFlag = 0;
            }
        }
        else
        {
            remote.LeftOrRight = 0;                                                 //无障碍则不进行转向
        }
    }      
    else if( UltrasonicMode == ultraFollow )                                        //超声波跟随模式
    {
        if(BluetoothParseMsg.Xrocker == 0 || BluetoothParseMsg.Xrocker == 5)        //有转向控制  
        { 
            tur.kd = 0;   
        }
        else                                                                        //无转向控制
        {
            tur.kd = 15.5f;
        }      
        if(BluetoothParseMsg.Xrocker == 0)                                          //左转向                      
            remote.LeftOrRight += 15;                       
        else if(BluetoothParseMsg.Xrocker ==5)                                      //右转向
            remote.LeftOrRight -= 15;
        else 
            remote.LeftOrRight = 0;  
    }
    else                                                                            //遥控模式
    {
        if(RemoteModeSelect==MODE_PS2)                                              
        {
        }
        else if(RemoteModeSelect==MODE_BLUETEETH)                                   //蓝牙遥控模式
        {
            if(BluetoothParseMsg.Xrocker == 0 || BluetoothParseMsg.Xrocker == 5)    //有转向控制  
            { 
                tur.kd = 0;   
            }
            else                                                                    //无转向控制
            {
                tur.kd = 15.5f;
            }      
            if(BluetoothParseMsg.Xrocker == 0)                                      //左转向                                                        
                remote.LeftOrRight += 15;
            else if(BluetoothParseMsg.Xrocker ==5)                                  //右转向
                remote.LeftOrRight -= 15;
            else 
                remote.LeftOrRight = 0;                
        }
        else if(RemoteModeSelect==MODE_USER)
        {
        }          
    }

    remote.LeftOrRightTurOut = (int)(-remote.LeftOrRight * tur.kp);                 //向左向右控制输出
    i_limit(&remote.LeftOrRightTurOut,Speed);                                       //遥控左右转旋转输出速度范围限制,不能太快(最大2500)   
    
    return remote.LeftOrRightTurOut;
}

//转向控制器 / 
int CarStepLeftOrRight;
/*
 * 函数名:ctr_turn
 * 描述  :转向控制器
 * 输入  :encoder_left编码器A的值,encoder_right编码器B的值,gyro_z转向的Z轴角速度
 * 返回  :控制器输出
 */
int ctr_turn(int encoder_left,int encoder_right, float gyro_z) 
{
    static int remoteTurOut;
 
    CarStepLeftOrRight = CarSpeedCtrlLeftOrRight(1);                                //转向控制速度加减
    remoteTurOut = remoteCarLeftOrRight( CarStepLeftOrRight , MODE_BLUETEETH , UltraSuccess(BluetoothParseMsg.ModeRocker) );    //左转/右转控制输出
    ctr.turn = remoteTurOut + gyro_z * tur.kd;
    
    return ctr.turn;
}

/*
 * 函数名:_ctr_out
 * 描述  :控制输出
 * 输入  :    
 * 返回  :    
 */
void _ctr_out(void)
{   

    if(PickUpTheCar(att.rol,encoder_val_a,-encoder_val_b) == 1)                //小车被拿起检测
    {
        theCarStopFlag = 1;
    }
    if(PutDownTheCar(att.rol,encoder_val_a,-encoder_val_b))                    //小车被放下检测
    {
        theCarStopFlag = 0;
    }
  
#ifdef USE_BLUETOOTHopenOrclose        
    /* 检测是否倒下和是否人为遥控控制小车停止,倒下或者停止后,积分项清零(不清除会干扰下次平衡),并且电机停转 */
    if( shut_down(att.rol,70.0f) || (BluetoothParseMsg.OpenCloseStatus == 0) || theCarStopFlag == 1)                                                 
    {      
#else
    /* 检测是否倒下小车停止,倒下或者停止后,积分项清零(不清除会干扰下次平衡),并且电机停转 */
    if( shut_down(att.rol,70.0f) || theCarStopFlag == 1)                                                 
    {      
#endif        
        PickUpisOK = 0;
        for(uint8_t i = 0 ; i < 3 ; i++)                                       //清除所有偏差
        {
            ctr.out[i] = 0;
            ctr.bais[i] = 0;
        }
        ctr.motor[0] = 0;
        ctr.motor[1] = 0;
    }                                                                          
    else 
    {
        ctr.motor[0] = ctr.out[0];
        ctr.motor[1] = ctr.out[1];
    }
    if( BluetoothParseMsg.OpenCloseStatus == 1 || theCarStopFlag == 0)          //蓝牙遥控开启小车动力输出或者不使用蓝牙开启关闭
        motor_pwm_out(ctr.motor[0],ctr.motor[1]);                               //正常输出
    else
        motor_pwm_out(0,0);                                                     //关闭电机
}

/*
 * 函数名:dir_config
 * 描述  :电机转向控制
 * 输入  :motor1电机1的pwm值首地址,motor2电机2的pwm值得首地址    
 * 返回  :     
 */
void dir_config(int *motor1,int *motor2)
{
    if(*motor1<0) AIN1_HIGH, AIN2_LOW;
    else          AIN1_LOW, AIN2_HIGH;
    *motor1 = int_abs(*motor1);
    
    if(*motor2<0) BIN1_HIGH, BIN2_LOW;
    else          BIN1_LOW, BIN2_HIGH;
    *motor2 = int_abs(*motor2);	
}
/*
 * 函数名:dirTest
 * 描述  :测试使用
 * 输入  :        
 * 返回  :     
 */
int dirTest(uint8_t AIN1,uint8_t AIN2,uint8_t BIN1,uint8_t BIN2)
{
    if(AIN2==0 && AIN1==1) AIN1_HIGH, AIN2_LOW;
    else if(AIN2==1 && AIN1==0)         AIN1_LOW, AIN2_HIGH;
    else if(BIN2==0 && BIN1==1) BIN1_HIGH, BIN2_LOW;
    else if(BIN2==1 && BIN1==0)         BIN1_LOW, BIN2_HIGH;
    else 
    {
        AIN1_LOW,AIN2_LOW,BIN1_LOW, BIN2_LOW;
    }
    return 0;
}

oled:

cs 复制代码
#include "oled.h"
#include "stdlib.h"
#include "oledfont.h"  	
#include "systick.h"
#include "mpu6050.h"
#include "imu.h"
#include "pwm.h"
#include "adc.h"
#include "controller.h"
#include <string.h>
#include "stdio.h"
#include "imath.h"
#include "ultrasonic.h"
//OLED显存存放格式
//[0]0 1 2 3 ... 127	
//[1]0 1 2 3 ... 127	
//[2]0 1 2 3 ... 127	
//[3]0 1 2 3 ... 127	
//[4]0 1 2 3 ... 127	
//[5]0 1 2 3 ... 127	
//[6]0 1 2 3 ... 127	
//[7]0 1 2 3 ... 127 			   
void IICO_Start()
{
	OLED_SCLK_Set() ;
	OLED_SDIN_Set();
	OLED_SDIN_Clr();
	OLED_SCLK_Clr();    
}
void IICO_Stop()
{
OLED_SCLK_Set() ;
//	OLED_SCLK_Clr();
	OLED_SDIN_Clr();
	OLED_SDIN_Set();	
}
void IICO_Wait_Ack()
{
	//GPIOB->CRH &= 0XFFF0FFFF;	
	//GPIOB->CRH |= 0x00080000;
//	OLED_SDA = 1;
//	delay_us(1);
	//OLED_SCL = 1;
	//delay_us(50000);
/*	while(1)
	{
		if(!OLED_SDA)				
		{
			//GPIOB->CRH &= 0XFFF0FFFF;	
			//GPIOB->CRH |= 0x00030000;
			return;
		}
	}
*/
	OLED_SCLK_Set() ;
	OLED_SCLK_Clr();
}
void Write_IIC_Byte(unsigned char IIC_Byte)
{
	unsigned char i;
	unsigned char m,da;
	da=IIC_Byte;
	OLED_SCLK_Clr();
	for(i=0;i<8;i++)		
	{
        m=da;
		//	OLED_SCLK_Clr();
		m=m&0x80;
		if(m==0x80)
		{
            OLED_SDIN_Set();
        }
        else 
                OLED_SDIN_Clr();
        da=da<<1;
        OLED_SCLK_Set();
        OLED_SCLK_Clr();
    }
}
void Write_IIC_Command(unsigned char IIC_Command)
{
    IICO_Start();
    Write_IIC_Byte(0x78);            //Slave address,SA0=0
    IICO_Wait_Ack();	
    Write_IIC_Byte(0x00);			//write command
    IICO_Wait_Ack();	
    Write_IIC_Byte(IIC_Command); 
    IICO_Wait_Ack();	
    IICO_Stop();
}
void Write_IIC_Data(unsigned char IIC_Data)
{
    IICO_Start();
    Write_IIC_Byte(0x78);			//D/C#=0; R/W#=0
    IICO_Wait_Ack();	
    Write_IIC_Byte(0x40);			//write data
    IICO_Wait_Ack();	
    Write_IIC_Byte(IIC_Data);
    IICO_Wait_Ack();	
    IICO_Stop();
}
void OLED_WR_Byte(unsigned dat,unsigned cmd)
{
	if(cmd)Write_IIC_Data(dat);	
	else Write_IIC_Command(dat);
}
//坐标设置
void OLED_Set_Pos(unsigned char x, unsigned char y) 
{ 
	OLED_WR_Byte(0xb0+y,OLED_CMD);
	OLED_WR_Byte(((x&0xf0)>>4)|0x10,OLED_CMD);
	OLED_WR_Byte((x&0x0f),OLED_CMD); 
}   	  
//开启OLED显示  
void OLED_Display_On(void)
{
	OLED_WR_Byte(0X8D,OLED_CMD);  //SET DCDC命令
	OLED_WR_Byte(0X14,OLED_CMD);  //DCDC ON
	OLED_WR_Byte(0XAF,OLED_CMD);  //DISPLAY ON
}
//关闭OLED显示   
void OLED_Display_Off(void)
{
	OLED_WR_Byte(0X8D,OLED_CMD);  //SET DCDCÃüÁî
	OLED_WR_Byte(0X10,OLED_CMD);  //DCDC OFF
	OLED_WR_Byte(0XAE,OLED_CMD);  //DISPLAY OFF
}		   		
void OLED_Clear(void)  
{  
	u8 i,n;		    
	for(i=0;i<8;i++)  
	{  
		OLED_WR_Byte (0xb0+i,OLED_CMD);    
		OLED_WR_Byte (0x00,OLED_CMD);      
		OLED_WR_Byte (0x10,OLED_CMD);         
		for(n=0;n<128;n++)OLED_WR_Byte(0,OLED_DATA); 
	} 
}
void OLED_On(void)  
{  
	u8 i,n;		    
	for(i=0;i<8;i++)  
	{  
		OLED_WR_Byte (0xb0+i,OLED_CMD);    //设置页地址0-7
		OLED_WR_Byte (0x00,OLED_CMD);      //设置显示位置-列高地址
		OLED_WR_Byte (0x10,OLED_CMD);      //设置显示位置-列低地址
		for(n=0;n<128;n++)OLED_WR_Byte(1,OLED_DATA); 
    }   
}
//在指定位置显示一个字符
//x:0~127  y:0~63
//mode:0,反白显示;1,正常显示	 
//size:选择字体 16/12 
void OLED_ShowChar(u8 x,u8 y,u8 chr,u8 Char_Size)
{      	
    unsigned char c=0,i=0;	
    c=chr-' ';                              //得到偏移后的地址			
    if(x>Max_Column-1)
    {
        x=0;
        y=y+2;
    }
    if(Char_Size ==16)
    {
        OLED_Set_Pos(x,y);	
        for(i=0;i<8;i++)
            OLED_WR_Byte(F8X16[c*16+i],OLED_DATA);
        OLED_Set_Pos(x,y+1);
        for(i=0;i<8;i++)
            OLED_WR_Byte(F8X16[c*16+i+8],OLED_DATA);
    }
    else
    {	
        OLED_Set_Pos(x,y);
        for(i=0;i<6;i++)
            OLED_WR_Byte(F6x8[c][i],OLED_DATA);			
    }
}
u32 oled_pow(u8 m,u8 n)//m^n函数
{
	u32 result=1;	 
	while(n--)result*=m;    
	return result;
}				  
//显示两个数字
//x,y :起点坐标
//len :数字的位数
//size:字体大小
//mode:模式0,填充模式;1,叠加模式
//num:数值(0~4294967295);	 		  
void OLED_ShowNum(u8 x,u8 y,u32 num,u8 len,u8 size2)
{         	
	u8 t,temp;
	u8 enshow=0;						   
	for(t=0;t<len;t++)
	{
		temp=(num/oled_pow(10,len-t-1))%10;
		if(enshow==0&&t<(len-1))
		{
			if(temp==0)
			{
				OLED_ShowChar(x+(size2/2)*t,y,' ',size2);
				continue;
			}
			else enshow=1;  	 
		}
	 	OLED_ShowChar(x+(size2/2)*t,y,temp+'0',size2); 
	}
} 
void OLED_ShowString(u8 x,u8 y,u8 *chr,u8 Char_Size)    //显示一个字符号串
{
	unsigned char j=0;
	while (chr[j]!='\0')
	{
		OLED_ShowChar(x,y,chr[j],Char_Size);
		x+=8;
		if(x>120){x=0;y+=2;}j++;
	}
}
void OLED_ShowCHinese(u8 x,u8 y,u8 no)                  //显示汉字
{      			    
	u8 t,adder=0;
	OLED_Set_Pos(x,y);	
    for(t=0;t<16;t++)
    {
        OLED_WR_Byte(Hzk[2*no][t],OLED_DATA);
        adder+=1;
    }	
    OLED_Set_Pos(x,y+1);	
    for(t=0;t<16;t++)
    {	
        OLED_WR_Byte(Hzk[2*no+1][t],OLED_DATA);
        adder+=1;
    }					
}	    
void OLED_Init(void)                                                //初始化SSD1306		
{ 	 
 	GPIO_InitTypeDef  GPIO_InitStructure;
 	
	RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE);	    
	GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0|GPIO_Pin_1;	 
 	GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP; 		    
	GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;   
 	GPIO_Init(GPIOB, &GPIO_InitStructure);	    
 	GPIO_SetBits(GPIOB,GPIO_Pin_0|GPIO_Pin_1);	

	tdelay_ms(800);
	OLED_WR_Byte(0xAE,OLED_CMD);//--display off
	OLED_WR_Byte(0x00,OLED_CMD);//---set low column address
	OLED_WR_Byte(0x10,OLED_CMD);//---set high column address
	OLED_WR_Byte(0x40,OLED_CMD);//--set start line address  
	OLED_WR_Byte(0xB0,OLED_CMD);//--set page address
	OLED_WR_Byte(0x81,OLED_CMD); // contract control
	OLED_WR_Byte(0xFF,OLED_CMD);//--128   
	OLED_WR_Byte(0xA1,OLED_CMD);//set segment remap 
	OLED_WR_Byte(0xA6,OLED_CMD);//--normal / reverse
	OLED_WR_Byte(0xA8,OLED_CMD);//--set multiplex ratio(1 to 64)
	OLED_WR_Byte(0x3F,OLED_CMD);//--1/32 duty
	OLED_WR_Byte(0xC8,OLED_CMD);//Com scan direction
	OLED_WR_Byte(0xD3,OLED_CMD);//-set display offset
	OLED_WR_Byte(0x00,OLED_CMD);//	
	OLED_WR_Byte(0xD5,OLED_CMD);//set osc division
	OLED_WR_Byte(0x80,OLED_CMD);//	
	OLED_WR_Byte(0xD8,OLED_CMD);//set area color mode off
	OLED_WR_Byte(0x05,OLED_CMD);//	
	OLED_WR_Byte(0xD9,OLED_CMD);//Set Pre-Charge Period
	OLED_WR_Byte(0xF1,OLED_CMD);//	
	OLED_WR_Byte(0xDA,OLED_CMD);//set com pin configuartion
	OLED_WR_Byte(0x12,OLED_CMD);//	
	OLED_WR_Byte(0xDB,OLED_CMD);//set Vcomh
	OLED_WR_Byte(0x30,OLED_CMD);//	
	OLED_WR_Byte(0x8D,OLED_CMD);//set charge pump enable
	OLED_WR_Byte(0x14,OLED_CMD);//	
	OLED_WR_Byte(0xAF,OLED_CMD);//--turn on oled panel
    
    OLED_Clear() ;
}  

/* 
函数功能:OLED显示小车的角度
*/
static int OledShowAngle(void)
{
    int err;
    OLED_ShowString(0,0,"angle:",12);      
    if(att.rol>=0)
    {
        OLED_ShowString(82,0,"+",12);
        OLED_ShowNum(90,0,(u32)(att.rol),3,12);
    }
    else          
    {
        OLED_ShowString(82,0,"-",12);
        OLED_ShowNum(90,0,(u32)((-att.rol)),3,12);
    }    
    
    return err;
}
/* 
函数功能:OLED显示小车的角速度
*/
static int OledShowDegs(void)
{
    int err;
    //Mpu.deg_s.y
    OLED_ShowString(0,1,"vel:",12);     
    if(Mpu.deg_s.y>=0)
    {
        OLED_ShowString(82,1,"+",12);
        OLED_ShowNum(90,1,(u32)(Mpu.deg_s.y),3,12);
    }
    else          
    {
        OLED_ShowString(82,1,"-",12);
        OLED_ShowNum(90,1,(u32)(-Mpu.deg_s.y),3,12);
    }    
    return err;
}
/* 
函数功能:OLED显示小车的电源电压
*/
static int OledShowVbat(void)
{
    int err;
    //vbat
    OLED_ShowString(0,2,"vbat:",12);   
    OLED_ShowNum(82,2,(u32)(bat.voltage),1,12);
    OLED_ShowString(89,2,".",12);    
    OLED_ShowNum(95,2,(u32)((u32)(bat.voltage*10)%10),1,12);
    OLED_ShowString(105,2,"v",12);
//    if(bat.voltage>=7.0f)
//        OLED_ShowNum(100,2,(u32)((u32)((bat.voltage/8.4f)*100)),3,12);
//    else 
//        OLED_ShowNum(100,2,(u32)0,3,12);
//    OLED_ShowString(120,2,"%",12); 

    return err;    
}
/* 
函数功能:OLED显示小车的轮子测速编码值
*/
static int OledShowEncoder(void)
{
    int err;
    //encoder
    //L
    OLED_ShowString(0,3,"ValLeft:",12);
    if(encoder_val_a>=0)
    {
        OLED_ShowString(82,3,"+",12);
        OLED_ShowNum(90,3,encoder_val_a,3,12);
    }
    else
    {
        OLED_ShowString(82,3,"-",12);
        OLED_ShowNum(90,3,-(encoder_val_a),3,12);
    }
    //R
    OLED_ShowString(0,4,"ValRight:",12);
    if(encoder_val_b>=0)
    {
        OLED_ShowString(82,4,"+",12);
        OLED_ShowNum(90,4,encoder_val_b,3,12);
    }
    else
    {
        OLED_ShowString(82,4,"-",12);
        OLED_ShowNum(90,4,-(encoder_val_b),3,12);
    }    
    return err;
}
/*
函数功能:OLED显示小车的前后方向增加/减少的速度变量幅度
*/
static int OledShowStepForwardOrBackward(void)
{
    int err;
    //fb
    OLED_ShowString(0,4,"fb:",12);
    if(CarStepForwardOrBackward>=0)
    {
        OLED_ShowString(25,4,"+",12);
        OLED_ShowNum(30,4,CarStepForwardOrBackward,3,12);
    }
    else
    {
        OLED_ShowString(25,4,"-",12);
        OLED_ShowNum(30,4,-(CarStepForwardOrBackward),3,12);
    }  
    //lr
    OLED_ShowString(60,4,"lr:",12);
    if(CarStepLeftOrRight>=0)
    {
        OLED_ShowString(85,4,"+",12);
        OLED_ShowNum(95,4,CarStepLeftOrRight,4,12);
    }
    else
    {
        OLED_ShowString(85,4,"-",12);
        OLED_ShowNum(95,4,-(CarStepLeftOrRight),4,12);
    }  
    return err;
}

static int OledShowDistance(void)
{
    int err;
    unsigned char buff[32]={0};

    snprintf((char*)buff, 21,"distance: %.1fcm", getDistance);
    OLED_ShowString(0,5,buff,12);
    
    return err;
} 

void OledShowDatas(void)
{	
    OledShowAngle();
    OledShowDegs();
    OledShowVbat();
    OledShowEncoder();
    OledShowEncoder();
//    OledShowStepForwardOrBackward();
    OledShowDistance(); 
    OLED_ShowString(0,7," ----working----",12); 
}
//填充函数
void fill_picture(unsigned char fill_Data)      
{
	unsigned char m,n;
	for(m=0;m<8;m++)
	{
		OLED_WR_Byte(0xb0+m,0);	    //´0-7页
		OLED_WR_Byte(0x00,0);		//low column start address
		OLED_WR_Byte(0x10,0);		//high column start address
		for(n=0;n<128;n++)OLED_WR_Byte(fill_Data,1);	
	}
}

adc:

cs 复制代码
void adc_init(void)
{
    adc_gpio_init();
    adc_config();
    dma_config();
}
/*
 * 函数名:voltage_detection
 * 描述  :电源电压采集
 * 输入  :    
 * 返回  :     
 */
void voltage_detection(void)
{
    bat.adc = adc_value[0];
    bat.voltage = (float)(bat.adc)/4096.0f*3.3f*11.0f;      //实际电路采用电阻10:1比例进行分压
    
    if(bat.voltage<=7.0f)
    {
        bat.danger_flag = 1;
    }
    else
    {
        bat.danger_flag = 0;
    }
}    
相关推荐
silno3 小时前
图解 STM32 USB CDC虚拟串口 的实现
stm32·单片机·stm32f103c8t6·cdc虚拟串口
皓月盈江6 小时前
STC12、STC15、STM32系列单片机控制16*64LED点阵屏显示,修改显示内容
单片机·嵌入式硬件·keil·stm32f103c8t6·stc12c5a60s2·stc15w4k32s4·led点阵屏程序源码
qq_448011166 小时前
USB概述
嵌入式硬件
一枝小雨7 小时前
7 App代码转AES加密文件生成步骤
stm32·单片机·嵌入式·aes·ota·bootloader·加密升级
li星野7 小时前
打工人日报#20251202
单片机·嵌入式硬件
云山工作室8 小时前
基于ZigBee的温室智能控制系统设计(论文+源码)
stm32·单片机·嵌入式硬件·物联网·课程设计
IT_阿水8 小时前
基于STM32的智慧物联网系统板
stm32·物联网·perl
小李做物联网8 小时前
为什么你的老是焊接后通信不成功,物联网焊接注意点
单片机·嵌入式硬件·物联网·课程设计
sam-zy8 小时前
PY32F406K1CU6 FLASH模拟EEPROM
单片机·嵌入式硬件·fpga开发