这次使用的主控芯片是Ti公司的Tiva(TM4C123GX),由于该开发板最近才发布,网上的资料比较少,极易踩坑,在准备电赛的时候,我们根据国内外相关资料,基本完成了针对于小车的大部分用于比赛的常规功能开发。

Tiva这款单片机功能还是非常强大,TM4C123GH6PM,具有最高主频80MHz,100指令速度,256k闪存,8个串口,2个PWM模块,4个PWM发生器,可以产生16路PWM波,6个16/32位通用定时器,和6个32/64位通用定时器。

基于Tiva的综合小车

项目结构

中断

在Drivers路径下的Interrupt文件中

  1. Timer0A:逻辑控制

  2. Timer1A:按键检测

  3. Timer2A:超声波触发

  4. UART0:电脑串口

  5. UART1:蓝牙串口

  6. UART2:循迹的openmv串口

  7. UART5:jy62角度传感器串口

  8. GPIOA:PA7:超声回声;PA4,PA5:减速电机编码器读取

  9. GPIOE:PE2,PE3:减速电机编码器读取

  10. ADCSeq3:驱动板电压读取

硬件连接

TB6612(直流减速电机驱动)

TB6612

TivaC123

E2A

PE2

E2B

PE3

E1A

PA5

E1B

PA4

ADC

PE1

PWMB

PC5

BIN2

PB7

BIN1

PB6

STBY

PA2

AIN1

PD2

AIN2

PD3

PWMA

PC4

HCSR04(超声波)

HCSR04

TivaC123

Trigger

PA6

Echo

PA7

Sg90(舵机)

Sg90

TivaC123

PWM

PD1

JY62(角度传感器)

JY62

TivaC123

RX

PE5

TX

PE4

OLED(SSD1306显示屏)

OLED

TivaC123

SCL

PD0

SDA

PD1

Openmv(循迹)

Openmv

TivaC123

RX

PD7

TX

PD6

D302A(步进电机驱动)

D302A

TivaC123

输出

PC4,PB6

使能

PA2

方向

PD2,PD3

HC05(蓝牙)

HC05

TivaC123

RX

PB1

TX

PB0

蓝牙控制指令

每个指令都以字符x结尾,作为命令结束标识

CMD

Description

Example

r+r/l+xxx

向左或向右旋转xxx度

rr090:向右旋转90度

v+n/p+xxxx

设置速度

vp5000:设置速度正转为5000

start

启动小车

stop

停止小车

程序设计

main.c(主函数)

#include "main.h"

#include "string.h"
#include "stdlib.h"
#include "stdio.h"

/**
 * main.c
 */
int main(void)
{

	MAP_FPUEnable();
	MAP_FPULazyStackingEnable();

	// 16mhz
	// SysCtlClockSet(SYSCTL_SYSDIV_1 | SYSCTL_USE_OSC | SYSCTL_OSC_MAIN |
	// 			   SYSCTL_XTAL_16MHZ);
	// 40mhz
	SysCtlClockSet(SYSCTL_SYSDIV_5 | SYSCTL_USE_PLL | SYSCTL_XTAL_16MHZ | SYSCTL_OSC_MAIN);

	IntMasterEnable();

	// 配置小灯用于测试
	initLights();

	// initOled();
	// clearOled();

	//	 OLED_Init();
	//	 OLED_Clear();
	initSerial();
	initBlueTooth();
	initKeys();
	initMotor();
	// initMotor2();
	// initEncoder();
	initJY62();
	initOpenmvTrack();
	initDelayStructs();
	// initHcsr04();
	initControl();
	// initBattery();
	//initSg90();
	initBeep();
	initE2PRom();

	// triggerHcsr04();

	//rotateSg90(0);
	//   主循环里进行各个事情的轮询
	while (1)
	{
		char text[20];
		sprintf(text, "high_thre:%d\r\n",ee_gray.high_thre);
		sendMsgBySerial(text);
		// setOledCursor(2, 0);
		// showStringOnOled("hello");
		// 处理电脑串口指令
		// ADCProcessorTrigger(ADC0_BASE, 3);
		if (SerialCompleteFlag)
		{
			if (!strcmp(serialDataBuffer, "on"))
			{
				if (GPIOPinRead(GPIO_PORTF_BASE, GPIO_PIN_3))
					turnOffLights(Green);
				else
					turnOnLights(Green);
			}
			// 控制舵机旋转
			if (serialDataBuffer[0] == 'r')
			{
				int a, b, c;
				a = serialDataBuffer[1] - '0';
				b = serialDataBuffer[2] - '0';
				c = serialDataBuffer[3] - '0';
				int angle = 100 * a + 10 * b + c;
				rotateSg90(angle);
			}
			sendMsgBySerial(serialDataBuffer);

			SerialCompleteFlag = false;
			memset(serialDataBuffer, 0, SERIAL_BUFFER_SIZE);
			serialBufferPtr = 0;
		}
		// 处理蓝牙指令
		if (BluetoothCompleteFlag)
		{
			// 业务逻辑
			if (!strcmp(blueToothDataBuffer, "on"))
			{
				if (GPIOPinRead(GPIO_PORTF_BASE, GPIO_PIN_2))
					turnOffLights(Blue);
				else
					turnOnLights(Blue);
			}
			// 控制小车旋转
			if (blueToothDataBuffer[0] == 'r')
			{
				int a, b, c;
				a = blueToothDataBuffer[2] - '0';
				b = blueToothDataBuffer[3] - '0';
				c = blueToothDataBuffer[4] - '0';
				int angle = 100 * a + 10 * b + c;
				if (blueToothDataBuffer[1] == 'l')
					setRotateTarget(angle, LEFT, Yaw);
				else if (blueToothDataBuffer[1] == 'r')
					setRotateTarget(angle, RIGHT, Yaw);
			}
			// 启动小车
			if (!strcmp(blueToothDataBuffer, "start"))
				turnOnMotor();
			// 停止小车
			if (!strcmp(blueToothDataBuffer, "stop"))
				turnOffMotor();

			if (blueToothDataBuffer[0] == 'v')
			{
				int a, b, c, d;
				a = blueToothDataBuffer[2] - '0';
				b = blueToothDataBuffer[3] - '0';
				c = blueToothDataBuffer[4] - '0';
				d = blueToothDataBuffer[5] - '0';
				int speed = 1000 * a + 100 * b + 10 * c + d;
				if (blueToothDataBuffer[1] == 'n')
					speed = -speed;
				Basic_Velocity = speed;
			}

			sendMsgByBT(blueToothDataBuffer);

			BluetoothCompleteFlag = false;
			memset(blueToothDataBuffer, 0, BLUETOOTH_BUFFER_SIZE);
			blueToothBufferPtr = 0;
		}
		// 按键
		{
			// key1单击
			if (Key1SinglePressedFlag)
			{
				ee_gray.high_thre++;
				EEPROMProgram((uint32_t *)&ee_gray,GRAYTHRESHOLDADDR,sizeof(ee_gray));

				// CrossPassDelayFlag.flag = true;
				turnOnMotor();

				Key1SinglePressedFlag = false;
			}
			// key1双击
			if (Key1DoublePressedFlag)
			{
				sendMsgBySerial("k1dp");
				ring(1000);

				Key1DoublePressedFlag = false;
			}
			// key2单击
			if (Key2SinglePressedFlag)
			{
				turnOffMotor();

				Key2SinglePressedFlag = false;
			}
			// key2双击
			if (Key2DoublePressedFlag)
			{
				// setOledCursor(1, 0);
				// showStringOnOled("k2dp");

				Key2DoublePressedFlag = false;
			}
		}
		// 接受到一次jy62数据包
		if (AngleReadOnceFlag)
		{
			char angleText[40];
			sprintf(angleText, "Roll: %d Pitch: %d Yaw: %d\r\n",
					(int)Roll, (int)Pitch, (int)Yaw);
			sendMsgBySerial(angleText);

			AngleReadOnceFlag = false;
		}
		// 接受到一次循迹openmv数据包
		if (OpenmvTrackReadOnceFlag)
		{
			char trackText[40];
			sprintf(trackText, "trackBias: %d", Track_Bias);
			// setOledCursor(0,0);
			// showStringOnOled(trackText);
			sendMsgByBT(trackText);

			OpenmvTrackReadOnceFlag = false;
		}
		// 超声回传了一次
		if (CountDistanceEndFlag)
		{
			char distanceText[40];
			distance = distanceCount * 0.00017 * 2.5;
			sprintf(distanceText, "Distance: %d\r\n", (int)distance);
			sendMsgBySerial(distanceText);
			distanceCount = 0;
			triggerHcsr04();

			CountDistanceEndFlag = false;
		}
	}
}

control.c(主控函数)

#include "Control.h"

int Track_Bias, Target_Angle;
float Basic_Velocity = 6000;
float Target_Velocity = -10;
float Target_Distance = 25;
int Velocity_PWM;
int Track_Turn_PWM, Rotate_Turn_PWM;
float Velocity_Kp = 8000, Velocity_Ki = 40;
float Track_Turn_Kp = 3000, Rotate_Turn_Kp = 5000;
float Distance_Kp = 3000, Distance_Kd = 3000;
int CrossNum;

void initControl()
{
    SysCtlPeripheralEnable(SYSCTL_PERIPH_TIMER0);
    TimerConfigure(TIMER0_BASE, TIMER_CFG_PERIODIC);
    // 5ms
    TimerLoadSet(TIMER0_BASE, TIMER_A, SysCtlClockGet() / 200);
    TimerIntEnable(TIMER0_BASE, TIMER_TIMA_TIMEOUT);
    IntEnable(INT_TIMER0A);
    TimerEnable(TIMER0_BASE, TIMER_A);
}

void Control()
{
    // if (CrossPassDelayFlag.flag)
    //     passCross();

    // Track_Bias为正,,左轮加速
    // limitDistance(distance);
    Track_Turn_PWM = trackTurn(Track_Bias);
    Velocity_PWM = Basic_Velocity;
    Rotate_Turn_PWM = rotateTurn();

    int Motor_Left = Velocity_PWM + Track_Turn_PWM + Rotate_Turn_PWM;
    int Motor_Right = Velocity_PWM - Track_Turn_PWM - Rotate_Turn_PWM;
    Motor_Left = limitPWM(Motor_Left, 11000, -11000);
    Motor_Right = limitPWM(Motor_Right, 11000, -11000);

    setPWM(Motor_Left, Motor_Right);
}

int velocity(int encoderLeft, int encoderRight)
{
    static float general_bias, last_bias, velocity, integral;

    float bias = Target_Velocity - (encoderLeft + encoderRight) / 2;
    general_bias = 0.16 * bias + 0.84 * last_bias;
    last_bias = general_bias;
    integral += general_bias;
    if (integral > 1000)
        integral = 1000;
    else if (integral < -1000)
        integral = -1000;

    velocity = general_bias * Velocity_Kp / 100 + integral * Velocity_Ki / 100;

    return velocity;
}

int limitPWM(int input, int max, int min)
{
    int output;
    if (input < min)
        output = min;
    else if (input > max)
        output = max;
    else
        output = input;

    return output;
}

void limitDistance(int distance)
{
    static float general_bias, last_bias, pre_bias, derivative;
    general_bias = distance - Target_Distance;
    derivative = general_bias - 2 * last_bias + pre_bias;
    float increment = derivative * Distance_Kd / 2000 + general_bias * Distance_Kp / 2000;
    pre_bias = last_bias;
    last_bias = general_bias;

    if (distance > 40 || distance == 0)
        increment = 0;

    Basic_Velocity += increment;

    Basic_Velocity = limitPWM(Basic_Velocity, 7000, 2000);
}

int trackTurn(float bias)
{
    static float turn, general_bias, last_bias;
    general_bias = 0.16 * bias + 0.84 * last_bias;

    if (bias > 35 || bias < -35)
        general_bias *= 1.7;

    turn = general_bias * Track_Turn_Kp / 10;

    return turn;
}

int rotateTurn()
{
    static float turn, general_bias, last_bias;
    float temp = abs(Yaw - Target_Angle);
    if (temp > 180)
        general_bias = (360 - temp) * 0.16 + 0.84 * last_bias;
    else
        general_bias = temp * 0.16 + 0.84 * last_bias;
    if (RotateRightFlag || RotateLeftFlag)
    {
        if (general_bias < 3)
        {
            RotateRightFlag = RotateLeftFlag = false;
            return 0;
        }
    }
    last_bias = general_bias;
    // 旋转的时候不循迹
    if (RotateLeftFlag)
    {
        turn = -general_bias * Rotate_Turn_Kp / 70;
        Track_Turn_PWM = 0;
    }
    else if (RotateRightFlag)
    {
        turn = general_bias * Rotate_Turn_Kp / 70;
        Track_Turn_PWM = 0;
    }
    else
    {
        turn = 0;
    }
    return turn;
}

void passCross()
{
    countDelay(&CrossPassDelayFlag);
    if (CrossPassDelayFlag.trigger)
    {
        Basic_Velocity = 0;
        setRotateTarget(90, RIGHT, Yaw);
        CrossPassDelayFlag.trigger = false;
    }
}

void setRotateTarget(int angle, bool direction, int current_yaw)
{
    if (direction == LEFT)
    {
        if (current_yaw + angle >= 180)
            Target_Angle = current_yaw + angle - 360;
        else
            Target_Angle = current_yaw + angle;
        RotateLeftFlag = true;
    }
    if (direction == RIGHT)
    {
        if (current_yaw - angle < -180)
            Target_Angle = current_yaw - angle + 360;
        else
            Target_Angle = current_yaw - angle;
        RotateRightFlag = true;
    }
}

BatteryVoltage.c(电池电量读取)

#include "BatteryVoltage.h"

uint32_t pui32ADC0Value[1];
float Voltage;

// PE1
void initBattery()
{
    SysCtlPeripheralEnable(SYSCTL_PERIPH_ADC0);
    SysCtlPeripheralEnable(SYSCTL_PERIPH_GPIOE);
    GPIOPinTypeADC(GPIO_PORTE_BASE, GPIO_PIN_1);
    ADCSequenceConfigure(ADC0_BASE, 3, ADC_TRIGGER_PROCESSOR, 0);
    ADCSequenceStepConfigure(ADC0_BASE, 3, 0,
                             ADC_CTL_CH2 | ADC_CTL_IE | ADC_CTL_END);
    ADCIntEnable(ADC0_BASE, 3);
    IntEnable(INT_ADC0SS3);
    ADCSequenceEnable(ADC0_BASE, 3);
    ADCIntClear(ADC0_BASE, 3);
}
float getBatteryVoltage(void)
{
    ADCSequenceDataGet(ADC0_BASE, 3, pui32ADC0Value);
    float voltage = 1.0*pui32ADC0Value[0] / 4096 * 3.3 *18*100;
    return voltage;
}

Beep.c(蜂鸣器)

#include "Beep.h"

void initBeep(void)
{
    SysCtlPeripheralEnable(SYSCTL_PERIPH_GPIOA);
    GPIOPinTypeGPIOOutput(GPIO_PORTA_BASE, GPIO_PIN_3);
}

void ring(int time)
{
    GPIOPinWrite(GPIO_PORTA_BASE, GPIO_PIN_3, GPIO_PIN_3);
    delayms(time);
    GPIOPinWrite(GPIO_PORTA_BASE, GPIO_PIN_3, 0);
}

BlueTooth.c(蓝牙)

#include "BlueTooth.h"

char blueToothDataBuffer[SERIAL_BUFFER_SIZE];
int blueToothBufferPtr;

void initBlueTooth()
{
    SysCtlPeripheralEnable(SYSCTL_PERIPH_UART1);
    SysCtlPeripheralEnable(SYSCTL_PERIPH_GPIOB);
    GPIOPinConfigure(GPIO_PB0_U1RX);
    GPIOPinConfigure(GPIO_PB1_U1TX);
    GPIOPinTypeUART(GPIO_PORTB_BASE, GPIO_PIN_0 | GPIO_PIN_1);
    UARTConfigSetExpClk(UART1_BASE, SysCtlClockGet(), 9600, (UART_CONFIG_WLEN_8 | UART_CONFIG_STOP_ONE | UART_CONFIG_PAR_NONE));

    UARTFIFODisable(UART1_BASE);
    IntEnable(INT_UART1);
    UARTIntEnable(UART1_BASE, UART_INT_RX);
}

void sendMsgByBT(char *msg)
{
    while(*msg)
    {
        UARTCharPut(UART1_BASE, *msg++);
    }
}

Encoder.c(编码器)

#include "Encoder.h"

int EncoderRight, EncoderLeft;

// PA4,PA5,PE2,PE3
void initEncoder()
{
    SysCtlPeripheralEnable(SYSCTL_PERIPH_GPIOE);
    GPIOPinTypeGPIOInput(GPIO_PORTE_BASE, GPIO_PIN_2 | GPIO_PIN_3);
    IntEnable(INT_GPIOE);
    GPIOIntTypeSet(GPIO_PORTE_BASE, GPIO_PIN_2 | GPIO_PIN_3, GPIO_BOTH_EDGES);
    GPIOIntEnable(GPIO_PORTE_BASE, GPIO_PIN_2 | GPIO_PIN_3);

    SysCtlPeripheralEnable(SYSCTL_PERIPH_GPIOA);
    GPIOPinTypeGPIOInput(GPIO_PORTA_BASE, GPIO_PIN_4 | GPIO_PIN_5);
    IntEnable(INT_GPIOA);
    GPIOIntTypeSet(GPIO_PORTA_BASE, GPIO_PIN_4 | GPIO_PIN_5, GPIO_BOTH_EDGES);
    GPIOIntEnable(GPIO_PORTA_BASE, GPIO_PIN_4 | GPIO_PIN_5);
}

int readEncoder(uint8_t side)
{
    int coder_value = 0;
    if (!side)
    {
        coder_value = EncoderRight;
        EncoderRight = 0;
    }
    else
    {
        coder_value = EncoderLeft;
        EncoderLeft = 0;
    }
    return coder_value;
}

HC-SR04.c(超声波测距)

#include "Hcsr04.h"

int distanceCount;
float distance;

// pa7捕获 pa6触发

void initHcsr04()
{
    SysCtlPeripheralEnable(SYSCTL_PERIPH_GPIOA);
    GPIOPinTypeGPIOOutput(GPIO_PORTA_BASE, GPIO_PIN_6);
    GPIOPinTypeGPIOInput(GPIO_PORTA_BASE, GPIO_PIN_7);
    GPIOPadConfigSet(GPIO_PORTA_BASE, GPIO_PIN_7 | GPIO_PIN_6,
                     GPIO_STRENGTH_4MA, GPIO_PIN_TYPE_STD_WPD);

    IntEnable(INT_GPIOA);
    GPIOIntTypeSet(GPIO_PORTA_BASE, GPIO_PIN_7, GPIO_BOTH_EDGES);
    GPIOIntEnable(GPIO_PORTA_BASE, GPIO_PIN_7);

    SysCtlPeripheralEnable(SYSCTL_PERIPH_TIMER2);
    TimerConfigure(TIMER2_BASE, TIMER_CFG_ONE_SHOT);
    // 4分频-》定时器2 10mhz
    TimerPrescaleSet(TIMER2_BASE, TIMER_A, 2);
    TimerIntEnable(TIMER2_BASE, TIMER_TIMA_TIMEOUT);
    IntEnable(INT_TIMER2A);
}

void triggerHcsr04()
{
    GPIOPinWrite(GPIO_PORTA_BASE, GPIO_PIN_6, GPIO_PIN_6);
    delayus(15);
    GPIOPinWrite(GPIO_PORTA_BASE, GPIO_PIN_6, 0);
}

Interrupt.c(中断)

#include "main.h"
#include "math.h"
#include "DelayStruct.h"

// 控制用的定时器
void Timer0AIntHandler(void)
{
    TimerIntClear(TIMER0_BASE, TIMER_TIMA_TIMEOUT);

    Control();
}

// 按键检测的中断
void Timer1AIntHandler(void)
{
    TimerIntClear(TIMER1_BASE, TIMER_TIMA_TIMEOUT);

    int temp1 = key1Pressed(50);
    int temp2 = key2Pressed(50);
    if (temp1 == 1)
    {
        Key1SinglePressedFlag = true;
    }
    else if (temp1 == 2)
    {
        Key1DoublePressedFlag = true;
    }
    if (temp2 == 1)
    {
        Key2SinglePressedFlag = true;
    }
    else if (temp2 == 2)
    {
        Key2DoublePressedFlag = true;
    }
}

// 超声波长时间未返回直接开始下一次计数
void Timer2AIntHandler(void)
{
    TimerIntClear(TIMER2_BASE, TIMER_TIMA_TIMEOUT);

    triggerHcsr04();
}

// 电脑串口USB
void UART0IntHandler(void)
{
    uint32_t u32IntStatus = UARTIntStatus(UART0_BASE, true);
    UARTIntClear(UART0_BASE, u32IntStatus);
    if (u32IntStatus & UART_INT_RX)
    {
        char dat = UARTCharGet(UART0_BASE);
        if (!(dat == 'x' || serialBufferPtr > SERIAL_BUFFER_SIZE))
        {
            serialDataBuffer[serialBufferPtr++] = (char)dat;
        }
        else
        {
            SerialCompleteFlag = true;
        }
    }
}

// 蓝牙串口
void UART1IntHandler(void)
{
    uint32_t u32IntStatus = UARTIntStatus(UART1_BASE, true);
    UARTIntClear(UART1_BASE, u32IntStatus);
    if (u32IntStatus & UART_INT_RX)
    {
        char dat = UARTCharGet(UART1_BASE);
        if (!(dat == 'x' || blueToothBufferPtr > BLUETOOTH_BUFFER_SIZE))
        {
            blueToothDataBuffer[blueToothBufferPtr++] = (char)dat;
        }
        else
        {
            BluetoothCompleteFlag = true;
        }
    }
}

// 循迹Openmv串口
uint8_t Cx = 0, Cy = 0, Ci = 0;
void UART2IntHandler(void)
{
    uint32_t u32IntStatus = UARTIntStatus(UART2_BASE, true);
    UARTIntClear(UART2_BASE, u32IntStatus);

    uint8_t com_data;
    uint8_t i;
    static uint8_t RxCounter1 = 0;
    static uint16_t RxBuffer1[6] = {0};
    static uint8_t RxState = 0;
    static uint8_t RxFlag1 = 0;

    if (u32IntStatus & UART_INT_RX)
    {
        com_data = UARTCharGet(UART2_BASE);
        if (RxState == 0 && com_data == 0x2C) // 0x2c帧头
        {
            // sendMsgBySerial("openmv");
            RxState = 1;
            RxBuffer1[RxCounter1++] = com_data;
        }

        else if (RxState == 1 && com_data == 0x12) // 0x12帧头
        {
            RxState = 2;
            RxBuffer1[RxCounter1++] = com_data;
        }

        else if (RxState == 2)
        {
            RxBuffer1[RxCounter1++] = com_data;

            if (RxCounter1 >= 6 || com_data == 0x5B) // RxBuffer1接受满了,接收数据结束
            {
                RxState = 3;
                RxFlag1 = 1;

                Cx = RxBuffer1[RxCounter1 - 4];
                Cy = RxBuffer1[RxCounter1 - 3];
                Ci = RxBuffer1[RxCounter1 - 2];
            }
        }
        else if (RxState == 3) // 检测是否接受到结束标志
        {
            if (RxBuffer1[RxCounter1 - 1] == 0x5B)
            {
                // USART_ITConfig(USART2, USART_IT_RXNE, DISABLE); // 关闭DTSABLE中断
                if (RxFlag1)
                {
                    if (Cy)
                        Track_Bias = Cx;
                    else
                        Track_Bias = -Cx;
                    if (abs(Track_Bias) > 200)
                    {
                        Track_Bias = 0;
                    }
                    if (Ci)
                    {
                        if (!CrossPassDelayFlag.flag)
                        {
                            CrossNum++;
                            if (CrossNum == 1)
                                CrossPassDelayFlag.flag = true;
                        }
                    }
                    OpenmvTrackReadOnceFlag = true;
                    sendMsgToOpenmvTrack(RxBuffer1);
                    // Ci检测是否为路口,计数经过了多少个路口
                }
                RxFlag1 = 0;
                RxCounter1 = 0;
                RxState = 0;
                // USART_ITConfig(USART2, USART_IT_RXNE, ENABLE);
            }
            else // 接收错误
            {
                RxState = 0;
                RxCounter1 = 0;
                for (i = 0; i < 6; i++)
                {
                    RxBuffer1[i] = 0x00; // 将存放数据数组清零
                }
            }
        }

        else // 接收异常
        {
            RxState = 0;
            RxCounter1 = 0;
            for (i = 0; i < 6; i++)
            {
                RxBuffer1[i] = 0x00; // 将存放数据数组清零
            }
        }
    }
}

// jy62
uint8_t RollH, RollL, PitchH, PitchL, YawH, YawL, VH, VL, CheckBit, Sum;
void UART5IntHandler(void)
{
    uint8_t com_data;
    uint8_t i;
    static uint8_t RxCounter1 = 0;
    static uint16_t RxBuffer1[11] = {0};
    static uint8_t RxState = 0;
    static uint8_t RxFlag1 = 0;
    uint32_t u32IntStatus = UARTIntStatus(UART5_BASE, true);
    UARTIntClear(UART5_BASE, u32IntStatus);

    if (u32IntStatus & UART_INT_RX)
    {

        com_data = UARTCharGet(UART5_BASE);
        if (RxState == 0 && com_data == 0x55)
        {
            RxState = 1;
            RxBuffer1[RxCounter1++] = com_data;
        }
        else if (RxState == 1 && com_data == 0x53)
        {
            RxState = 2;
            RxBuffer1[RxCounter1++] = com_data;
        }
        else if (RxState == 2)
        {
            RxBuffer1[RxCounter1++] = com_data;
            if (RxCounter1 >= 11)
            {
                RxState = 3;
                RxFlag1 = 1;
                // 取值
                RollL = RxBuffer1[RxCounter1 - 9];
                RollH = RxBuffer1[RxCounter1 - 8];
                PitchL = RxBuffer1[RxCounter1 - 7];
                PitchH = RxBuffer1[RxCounter1 - 6];
                YawL = RxBuffer1[RxCounter1 - 5];
                YawH = RxBuffer1[RxCounter1 - 4];
                VL = RxBuffer1[RxCounter1 - 3];
                VH = RxBuffer1[RxCounter1 - 2];
                CheckBit = RxBuffer1[RxCounter1 - 1];
                Sum = 0x55 + 0x53 + RollH + RollL + PitchH + PitchL + YawL + YawH + VL + VH;
            }
        }
        else if (RxState == 3)
        {
            if (CheckBit == Sum && !AngleReadOnceFlag)
            {

                if (RxFlag1)
                {
                    // 业务逻辑,取值的处理
                    short data1, data2, data3;
                    data1 = (short)(((short)RollH << 8) | RollL);
                    data2 = (short)(((short)PitchH << 8) | PitchL);
                    data3 = (short)(((short)YawH << 8) | YawL);

                    Roll = 1.0 * data1 / 32768 * 180;
                    Pitch = 1.0 * data2 / 32768 * 180;
                    Yaw = 1.0 * data3 / 32768 * 180;

                    AngleReadOnceFlag = true;
                }
                RxFlag1 = 0;
                RxCounter1 = 0;
                RxState = 0;
                //                IntEnable(UART5_BASE);
            }
            else // 接收错误
            {

                RxState = 0;
                RxCounter1 = 0;
                for (i = 0; i < 10; i++)
                {
                    RxBuffer1[i] = 0x00; // 将存放数据数组清零
                }
            }
        }
        else // 接收异常
        {
            RxState = 0;
            RxCounter1 = 0;
            for (i = 0; i < 10; i++)
            {
                RxBuffer1[i] = 0x00; // 将存放数据数组清零
            }
        }
    }
}

// 超声回声+编码器
void GPIOAIntHandler(void)
{
    uint32_t u32IntStatus = GPIOIntStatus(GPIO_PORTA_BASE, 0);
    GPIOIntClear(GPIO_PORTA_BASE, u32IntStatus);
    if (u32IntStatus & GPIO_INT_PIN_7)
    {
        if (GPIOPinRead(GPIO_PORTA_BASE, GPIO_PIN_7) == 0)
        {
            CountDistanceEndFlag = true;
            distanceCount = SysCtlClockGet() / (4 * 100) - TimerValueGet(TIMER2_BASE, TIMER_A);
        }
        else
        {
            TimerLoadSet(TIMER2_BASE, TIMER_A, (SysCtlClockGet() / (4 * 100)));
            TimerEnable(TIMER2_BASE, TIMER_A);
        }
    }

    if (u32IntStatus & GPIO_INT_PIN_4)
    {
        if (GPIOPinRead(GPIO_PORTA_BASE, GPIO_PIN_4) == 0)
        {
            if (GPIOPinRead(GPIO_PORTA_BASE, GPIO_PIN_5) == 0)
                EncoderLeft++;
            else
                EncoderLeft--;
        }
        else
        {
            if (GPIOPinRead(GPIO_PORTA_BASE, GPIO_PIN_5) == GPIO_PIN_5)
                EncoderLeft++;
            else
                EncoderLeft--;
        }
    }
    if (u32IntStatus & GPIO_INT_PIN_5)
    {
        if (GPIOPinRead(GPIO_PORTA_BASE, GPIO_PIN_5) == 0)
        {
            if (GPIOPinRead(GPIO_PORTA_BASE, GPIO_PIN_4) == GPIO_PIN_4)
                EncoderLeft++;
            else
                EncoderLeft--;
        }
        else
        {
            if (GPIOPinRead(GPIO_PORTA_BASE, GPIO_PIN_4) == 0)
                EncoderLeft++;
            else
                EncoderLeft--;
        }
    }
}
// 编码器
void GPIOEIntHandler(void)
{
    uint32_t u32IntStatus = GPIOIntStatus(GPIO_PORTE_BASE, 0);
    GPIOIntClear(GPIO_PORTE_BASE, u32IntStatus);
    if (u32IntStatus & GPIO_INT_PIN_2)
    {
        if (GPIOPinRead(GPIO_PORTE_BASE, GPIO_PIN_2) == 0)
        {
            if (GPIOPinRead(GPIO_PORTE_BASE, GPIO_PIN_3) == 0)
                EncoderRight++;
            else
                EncoderRight--;
        }
        else
        {
            if (GPIOPinRead(GPIO_PORTE_BASE, GPIO_PIN_3) == GPIO_PIN_3)
                EncoderRight++;
            else
                EncoderRight--;
        }
    }
    if (u32IntStatus & GPIO_INT_PIN_3)
    {
        if (GPIOPinRead(GPIO_PORTE_BASE, GPIO_PIN_3) == 0)
        {
            if (GPIOPinRead(GPIO_PORTE_BASE, GPIO_PIN_2) == GPIO_PIN_2)
                EncoderRight++;
            else
                EncoderRight--;
        }
        else
        {
            if (GPIOPinRead(GPIO_PORTE_BASE, GPIO_PIN_2) == 0)
                EncoderRight++;
            else
                EncoderRight--;
        }
    }
}
void ADCSeq3Handler(void)
{
    ADCIntClear(ADC0_BASE, 3);

    Voltage = getBatteryVoltage();
    VoltageSampleCompleteFlag = true;
}

JY62.c(角度传感器)

#include "JY62.h"

// Z轴角度归零
int command1[3] = {0xff, 0xaa, 0x52};
// 加速度计校准
int command2[3] = {0xff, 0xaa, 0x67};
float Roll,Pitch,Yaw;


void initJY62()
{
    SysCtlPeripheralEnable(SYSCTL_PERIPH_UART5);
    SysCtlPeripheralEnable(SYSCTL_PERIPH_GPIOE);
    GPIOPinConfigure(GPIO_PE4_U5RX);
    GPIOPinConfigure(GPIO_PE5_U5TX);
    GPIOPinTypeUART(GPIO_PORTE_BASE, GPIO_PIN_4 | GPIO_PIN_5);
    UARTConfigSetExpClk(UART5_BASE, SysCtlClockGet(),
                        115200, (UART_CONFIG_WLEN_8 | UART_CONFIG_STOP_ONE | UART_CONFIG_PAR_NONE));

    UARTFIFODisable(UART5_BASE);
    IntEnable(INT_UART5);
    UARTIntEnable(UART5_BASE, UART_INT_RX);

    //初始化校准
    sendJY62Command(command1);
    sendJY62Command(command2);

}

void sendJY62Command(int *command)
{
    while (*command)
    {
        UARTCharPut(UART5_BASE,*command++);
    }
}

Key.c(按键)

#include "Key.h"

#define KEY1 GPIOPinRead(GPIO_PORTF_BASE, GPIO_PIN_4)
#define KEY2 GPIOPinRead(GPIO_PORTF_BASE, GPIO_PIN_0)

void initKeys()
{
    SysCtlPeripheralEnable(SYSCTL_PERIPH_GPIOF);
    // 解锁PF0
    HWREG(GPIO_PORTF_BASE + GPIO_O_LOCK) = GPIO_LOCK_KEY;
    HWREG(GPIO_PORTF_BASE + GPIO_O_CR) = 0xFF;
    GPIOPinTypeGPIOInput(GPIO_PORTF_BASE, GPIO_PIN_0 | GPIO_PIN_4);
    GPIOPadConfigSet(GPIO_PORTF_BASE, GPIO_PIN_0 | GPIO_PIN_4,
                     GPIO_STRENGTH_2MA, GPIO_PIN_TYPE_STD_WPU);
    // 定时器timer1中断
    SysCtlPeripheralEnable(SYSCTL_PERIPH_TIMER1);
    TimerConfigure(TIMER1_BASE, TIMER_CFG_PERIODIC);
    // 5ms
    TimerLoadSet(TIMER1_BASE, TIMER_A, SysCtlClockGet() / 200);
    TimerIntEnable(TIMER1_BASE, TIMER_TIMA_TIMEOUT);
    IntEnable(INT_TIMER1A);
    TimerEnable(TIMER1_BASE, TIMER_A);
}

int key1Pressed(int time)
{
    static uint16_t flag_key = 0, count_key = 0, double_key = 0;
    static uint16_t count_single = 0, Forever_count = 0;
    // 长按标志位未置1
    if (KEY1 == 0)
        Forever_count++;
    else
        Forever_count = 0;
    // 按键按下,且按键按下标志为0
    if (KEY1 == 0 && flag_key == 0)
        flag_key = 1;
    // 第一次为0
    if (count_key == 0)
    {
        // 按键按下一次,double_key加一次,count=1
        if (flag_key == 1)
        {
            double_key++;
            count_key = 1;
        }
        // 双击执行的指令
        if (double_key == 2)
        {
            double_key = 0;
            count_single = 0;
            return 2;
        }
    }
    // 按键未按下
    if (KEY1)
        flag_key = 0, count_key = 0;
    // 按键已经按下一次
    if (double_key == 1)
    {
        // 超过等待时间
        count_single++;
        // 单击执行的指令
        if (count_single > time && Forever_count < time)
        {
            double_key = 0;
            count_single = 0;
            return 1;
        }
        if (Forever_count > time)
        {
            double_key = 0;
            count_single = 0;
        }
    }
    return 0;
}

int key2Pressed(int time)
{
    static uint16_t flag_key = 0, count_key = 0, double_key = 0;
    static uint16_t count_single = 0, Forever_count = 0;
    // 长按标志位未置1
    if (KEY2 == 0)
        Forever_count++;
    else
        Forever_count = 0;
    // 按键按下,且按键按下标志为0
    if (KEY2 == 0 && flag_key == 0)
        flag_key = 1;
    // 第一次为0
    if (count_key == 0)
    {
        // 按键按下一次,double_key加一次,count=1
        if (flag_key == 1)
        {
            double_key++;
            count_key = 1;
        }
        // 双击执行的指令
        if (double_key == 2)
        {
            double_key = 0;
            count_single = 0;
            return 2;
        }
    }
    // 按键未按下
    if (KEY2)
        flag_key = 0, count_key = 0;
    // 按键已经按下一次
    if (double_key == 1)
    {
        // 超过等待时间
        count_single++;
        // 单击执行的指令
        if (count_single > time && Forever_count < time)
        {
            double_key = 0;
            count_single = 0;
            return 1;
        }
        if (Forever_count > time)
        {
            double_key = 0;
            count_single = 0;
        }
    }
    return 0;
}

Motor.c(电机)

#include "Motor.h"

// pc4 pb6输出 pa2使能 pd2(左) pd3(右)方向,低电平正转,高电平反转
void initMotor(void)
{
    // pwm
    SysCtlPWMClockSet(SYSCTL_PWMDIV_32);
    SysCtlPeripheralEnable(SYSCTL_PERIPH_GPIOC);
    SysCtlPeripheralEnable(SYSCTL_PERIPH_GPIOB);
    SysCtlPeripheralEnable(SYSCTL_PERIPH_PWM0);
    GPIOPinTypePWM(GPIO_PORTC_BASE, GPIO_PIN_4);
    GPIOPinTypePWM(GPIO_PORTB_BASE, GPIO_PIN_6);
    GPIOPinConfigure(GPIO_PC4_M0PWM6);
    GPIOPinConfigure(GPIO_PB6_M0PWM0);
    // 设置PWM0模块的第三个发生器为向下计数与不同步计数
    PWMGenConfigure(PWM0_BASE, PWM_GEN_3,
                    PWM_GEN_MODE_DOWN | PWM_GEN_MODE_NO_SYNC);
    PWMGenConfigure(PWM0_BASE, PWM_GEN_0,
                    PWM_GEN_MODE_DOWN | PWM_GEN_MODE_NO_SYNC);

    // 方向
    SysCtlPeripheralEnable(SYSCTL_PERIPH_GPIOD);
    GPIODirModeSet(GPIO_PORTD_BASE, GPIO_PIN_2 | GPIO_PIN_3, GPIO_DIR_MODE_OUT);
    GPIOPadConfigSet(GPIO_PORTD_BASE,
                     GPIO_PIN_2 | GPIO_PIN_3, GPIO_STRENGTH_2MA, GPIO_PIN_TYPE_STD); // 推挽输出

    // 使能
    SysCtlPeripheralEnable(SYSCTL_PERIPH_GPIOA);
    GPIODirModeSet(GPIO_PORTA_BASE, GPIO_PIN_2, GPIO_DIR_MODE_OUT);
    GPIOPadConfigSet(GPIO_PORTA_BASE,
                     GPIO_PIN_2, GPIO_STRENGTH_2MA, GPIO_PIN_TYPE_STD); // 推挽输出
    GPIOPinWrite(GPIO_PORTA_BASE, GPIO_PIN_2, 0);                       // PA2输出低电平
}

/*
 *关闭电机
 */
void turnOffMotor(void)
{
    GPIOPinWrite(GPIO_PORTA_BASE, GPIO_PIN_2, 0); // PA2输出低电平
}

/*
 * 打开电机
 */
void turnOnMotor(void)
{
    GPIOPinWrite(GPIO_PORTA_BASE, GPIO_PIN_2, GPIO_PIN_2); // PA2输出高电平
}

void setPWM(int left, int right)
{
    // 正负决定方向
    if (left > 0)
        GPIOPinWrite(GPIO_PORTD_BASE, GPIO_PIN_2, 0);
    else
        GPIOPinWrite(GPIO_PORTD_BASE, GPIO_PIN_2, GPIO_PIN_2);
    if (right > 0)
        GPIOPinWrite(GPIO_PORTD_BASE, GPIO_PIN_3, 0);
    else
        GPIOPinWrite(GPIO_PORTD_BASE, GPIO_PIN_3, GPIO_PIN_3);

    int pwm_left = 1250000 / abs(left);
    int pwm_right = 1250000 / abs(right);
    // 设置PWM0模块的第三个发生器每个计数周期为2000个数,而PWM时钟为10MHz,
    // 那么PWM输出频率就是10^7/2000为5KHz,但是这个数为16位寄存器,不能超过65535
    if (pwm_right != 0)
        PWMGenPeriodSet(PWM0_BASE, PWM_GEN_3,  pwm_right);
    else
        PWMGenPeriodSet(PWM0_BASE, PWM_GEN_3, 0);
    if (pwm_left != 0)
        PWMGenPeriodSet(PWM0_BASE, PWM_GEN_0,  pwm_left);
    else
        PWMGenPeriodSet(PWM0_BASE, PWM_GEN_0, 0);

    // 设置PWM0模块的第六个通道的占空比为10%,这个函数的第三个参数为周期内的高电平数,
    // 所以可以通过PWMGenPeriodGet得出一个周期内的计数总数再乘0.1然后减1就行
    PWMPulseWidthSet(PWM0_BASE, PWM_OUT_6, PWMGenPeriodGet(PWM0_BASE, PWM_GEN_3) * 0.1 - 1);
    // 同理,只不过是设置第七个通道

    PWMPulseWidthSet(PWM0_BASE, PWM_OUT_0, PWMGenPeriodGet(PWM0_BASE, PWM_GEN_0) * 0.1 - 1);
    // 使能第六个通道
    PWMOutputState(PWM0_BASE, PWM_OUT_6_BIT, true);

    PWMOutputState(PWM0_BASE, PWM_OUT_0_BIT, true);
    // 使能第三个发生器
    PWMGenEnable(PWM0_BASE, PWM_GEN_3);
    PWMGenEnable(PWM0_BASE, PWM_GEN_0);
}

Motor2.c(电机驱动)

#include "Motor2.h"
// pc4 pc5输出 pd2 pd3B的方向 pb6 pb7A的方向
void initMotor2()
{
    SysCtlPeripheralEnable(SYSCTL_PERIPH_PWM0);
    SysCtlPWMClockSet(SYSCTL_PWMDIV_4);
    SysCtlPeripheralEnable(SYSCTL_PERIPH_GPIOC);
    SysCtlPeripheralEnable(SYSCTL_PERIPH_GPIOD);
    GPIOPinTypePWM(GPIO_PORTC_BASE, GPIO_PIN_4);
    GPIOPinTypePWM(GPIO_PORTC_BASE, GPIO_PIN_5);
    GPIOPinConfigure(GPIO_PC4_M0PWM6);
    GPIOPinConfigure(GPIO_PC5_M0PWM7);
    PWMGenConfigure(PWM0_BASE, PWM_GEN_3,
                    PWM_GEN_MODE_DOWN | PWM_GEN_MODE_NO_SYNC);
    PWMGenPeriodSet(PWM0_BASE, PWM_GEN_3, 1000);
    PWMOutputState(PWM0_BASE, PWM_OUT_6_BIT, true);
    PWMOutputState(PWM0_BASE, PWM_OUT_7_BIT, true);
    PWMGenEnable(PWM0_BASE, PWM_GEN_3);

    GPIOPinTypeGPIOOutput(GPIO_PORTD_BASE,GPIO_PIN_2|GPIO_PIN_3);
    GPIOPinTypeGPIOOutput(GPIO_PORTB_BASE,GPIO_PIN_6|GPIO_PIN_7);
                                                                                                               //    GPIODirModeSet(GPIO_PORTD_BASE,
                                                                                                               //                   GPIO_PIN_6 | GPIO_PIN_7, GPIO_DIR_MODE_OUT);

    GPIOPinTypeGPIOOutput(GPIO_PORTA_BASE, GPIO_PIN_2);
    GPIOPinWrite(GPIO_PORTA_BASE, GPIO_PIN_2, 0);
}

void turnOffMotor2(void)
{
    GPIOPinWrite(GPIO_PORTA_BASE, GPIO_PIN_2, 0); // PA2输出低电平
}

void turnOnMotor2(void)
{
    GPIOPinWrite(GPIO_PORTA_BASE, GPIO_PIN_2, GPIO_PIN_2); // PA2输出高电平
}

void setPWM2(int left, int right)
{
    if (left > 0)
    {
        GPIOPinWrite(GPIO_PORTD_BASE, GPIO_PIN_2, GPIO_PIN_2);
        GPIOPinWrite(GPIO_PORTD_BASE, GPIO_PIN_3, 0);
    }
    else
    {
        GPIOPinWrite(GPIO_PORTD_BASE, GPIO_PIN_2, 0);
        GPIOPinWrite(GPIO_PORTD_BASE, GPIO_PIN_3, GPIO_PIN_3);
    }

    if (right > 0)
    {
        GPIOPinWrite(GPIO_PORTB_BASE, GPIO_PIN_6, GPIO_PIN_6);
        GPIOPinWrite(GPIO_PORTB_BASE, GPIO_PIN_7, 0);
    }
    else
    {
        GPIOPinWrite(GPIO_PORTB_BASE, GPIO_PIN_6, 0);
        GPIOPinWrite(GPIO_PORTB_BASE, GPIO_PIN_7, GPIO_PIN_7);
    }
    int pwm_left = abs(left);
    int pwm_right = abs(right);

    PWMPulseWidthSet(PWM0_BASE, PWM_OUT_6, pwm_left);
    PWMPulseWidthSet(PWM0_BASE, PWM_OUT_7, pwm_right);
}

OLED.c(显示屏)

#include "Oled.h"

const uint8_t OledFont[][8] =
    {
        {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00},
        {0x00, 0x00, 0x5F, 0x00, 0x00, 0x00, 0x00, 0x00},
        {0x00, 0x00, 0x07, 0x00, 0x07, 0x00, 0x00, 0x00},
        {0x00, 0x14, 0x7F, 0x14, 0x7F, 0x14, 0x00, 0x00},
        {0x00, 0x24, 0x2A, 0x7F, 0x2A, 0x12, 0x00, 0x00},
        {0x00, 0x23, 0x13, 0x08, 0x64, 0x62, 0x00, 0x00},
        {0x00, 0x36, 0x49, 0x55, 0x22, 0x50, 0x00, 0x00},
        {0x00, 0x00, 0x05, 0x03, 0x00, 0x00, 0x00, 0x00},
        {0x00, 0x1C, 0x22, 0x41, 0x00, 0x00, 0x00, 0x00},
        {0x00, 0x41, 0x22, 0x1C, 0x00, 0x00, 0x00, 0x00},
        {0x00, 0x08, 0x2A, 0x1C, 0x2A, 0x08, 0x00, 0x00},
        {0x00, 0x08, 0x08, 0x3E, 0x08, 0x08, 0x00, 0x00},
        {0x00, 0xA0, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00},
        {0x00, 0x08, 0x08, 0x08, 0x08, 0x08, 0x00, 0x00},
        {0x00, 0x60, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00},
        {0x00, 0x20, 0x10, 0x08, 0x04, 0x02, 0x00, 0x00},
        {0x00, 0x3E, 0x51, 0x49, 0x45, 0x3E, 0x00, 0x00},
        {0x00, 0x00, 0x42, 0x7F, 0x40, 0x00, 0x00, 0x00},
        {0x00, 0x62, 0x51, 0x49, 0x49, 0x46, 0x00, 0x00},
        {0x00, 0x22, 0x41, 0x49, 0x49, 0x36, 0x00, 0x00},
        {0x00, 0x18, 0x14, 0x12, 0x7F, 0x10, 0x00, 0x00},
        {0x00, 0x27, 0x45, 0x45, 0x45, 0x39, 0x00, 0x00},
        {0x00, 0x3C, 0x4A, 0x49, 0x49, 0x30, 0x00, 0x00},
        {0x00, 0x01, 0x71, 0x09, 0x05, 0x03, 0x00, 0x00},
        {0x00, 0x36, 0x49, 0x49, 0x49, 0x36, 0x00, 0x00},
        {0x00, 0x06, 0x49, 0x49, 0x29, 0x1E, 0x00, 0x00},
        {0x00, 0x00, 0x36, 0x36, 0x00, 0x00, 0x00, 0x00},
        {0x00, 0x00, 0xAC, 0x6C, 0x00, 0x00, 0x00, 0x00},
        {0x00, 0x08, 0x14, 0x22, 0x41, 0x00, 0x00, 0x00},
        {0x00, 0x14, 0x14, 0x14, 0x14, 0x14, 0x00, 0x00},
        {0x00, 0x41, 0x22, 0x14, 0x08, 0x00, 0x00, 0x00},
        {0x00, 0x02, 0x01, 0x51, 0x09, 0x06, 0x00, 0x00},
        {0x00, 0x32, 0x49, 0x79, 0x41, 0x3E, 0x00, 0x00},
        {0x00, 0x7E, 0x09, 0x09, 0x09, 0x7E, 0x00, 0x00},
        {0x00, 0x7F, 0x49, 0x49, 0x49, 0x36, 0x00, 0x00},
        {0x00, 0x3E, 0x41, 0x41, 0x41, 0x22, 0x00, 0x00},
        {0x00, 0x7F, 0x41, 0x41, 0x22, 0x1C, 0x00, 0x00},
        {0x00, 0x7F, 0x49, 0x49, 0x49, 0x41, 0x00, 0x00},
        {0x00, 0x7F, 0x09, 0x09, 0x09, 0x01, 0x00, 0x00},
        {0x00, 0x3E, 0x41, 0x41, 0x51, 0x72, 0x00, 0x00},
        {0x00, 0x7F, 0x08, 0x08, 0x08, 0x7F, 0x00, 0x00},
        {0x00, 0x41, 0x7F, 0x41, 0x00, 0x00, 0x00, 0x00},
        {0x00, 0x20, 0x40, 0x41, 0x3F, 0x01, 0x00, 0x00},
        {0x00, 0x7F, 0x08, 0x14, 0x22, 0x41, 0x00, 0x00},
        {0x00, 0x7F, 0x40, 0x40, 0x40, 0x40, 0x00, 0x00},
        {0x00, 0x7F, 0x02, 0x0C, 0x02, 0x7F, 0x00, 0x00},
        {0x00, 0x7F, 0x04, 0x08, 0x10, 0x7F, 0x00, 0x00},
        {0x00, 0x3E, 0x41, 0x41, 0x41, 0x3E, 0x00, 0x00},
        {0x00, 0x7F, 0x09, 0x09, 0x09, 0x06, 0x00, 0x00},
        {0x00, 0x3E, 0x41, 0x51, 0x21, 0x5E, 0x00, 0x00},
        {0x00, 0x7F, 0x09, 0x19, 0x29, 0x46, 0x00, 0x00},
        {0x00, 0x26, 0x49, 0x49, 0x49, 0x32, 0x00, 0x00},
        {0x00, 0x01, 0x01, 0x7F, 0x01, 0x01, 0x00, 0x00},
        {0x00, 0x3F, 0x40, 0x40, 0x40, 0x3F, 0x00, 0x00},
        {0x00, 0x1F, 0x20, 0x40, 0x20, 0x1F, 0x00, 0x00},
        {0x00, 0x3F, 0x40, 0x38, 0x40, 0x3F, 0x00, 0x00},
        {0x00, 0x63, 0x14, 0x08, 0x14, 0x63, 0x00, 0x00},
        {0x00, 0x03, 0x04, 0x78, 0x04, 0x03, 0x00, 0x00},
        {0x00, 0x61, 0x51, 0x49, 0x45, 0x43, 0x00, 0x00},
        {0x00, 0x7F, 0x41, 0x41, 0x00, 0x00, 0x00, 0x00},
        {0x00, 0x02, 0x04, 0x08, 0x10, 0x20, 0x00, 0x00},
        {0x00, 0x41, 0x41, 0x7F, 0x00, 0x00, 0x00, 0x00},
        {0x00, 0x04, 0x02, 0x01, 0x02, 0x04, 0x00, 0x00},
        {0x00, 0x80, 0x80, 0x80, 0x80, 0x80, 0x00, 0x00},
        {0x00, 0x01, 0x02, 0x04, 0x00, 0x00, 0x00, 0x00},
        {0x00, 0x20, 0x54, 0x54, 0x54, 0x78, 0x00, 0x00},
        {0x00, 0x7F, 0x48, 0x44, 0x44, 0x38, 0x00, 0x00},
        {0x00, 0x38, 0x44, 0x44, 0x28, 0x00, 0x00, 0x00},
        {0x00, 0x38, 0x44, 0x44, 0x48, 0x7F, 0x00, 0x00},
        {0x00, 0x38, 0x54, 0x54, 0x54, 0x18, 0x00, 0x00},
        {0x00, 0x08, 0x7E, 0x09, 0x02, 0x00, 0x00, 0x00},
        {0x00, 0x18, 0xA4, 0xA4, 0xA4, 0x7C, 0x00, 0x00},
        {0x00, 0x7F, 0x08, 0x04, 0x04, 0x78, 0x00, 0x00},
        {0x00, 0x00, 0x7D, 0x00, 0x00, 0x00, 0x00, 0x00},
        {0x00, 0x80, 0x84, 0x7D, 0x00, 0x00, 0x00, 0x00},
        {0x00, 0x7F, 0x10, 0x28, 0x44, 0x00, 0x00, 0x00},
        {0x00, 0x41, 0x7F, 0x40, 0x00, 0x00, 0x00, 0x00},
        {0x00, 0x7C, 0x04, 0x18, 0x04, 0x78, 0x00, 0x00},
        {0x00, 0x7C, 0x08, 0x04, 0x7C, 0x00, 0x00, 0x00},
        {0x00, 0x38, 0x44, 0x44, 0x38, 0x00, 0x00, 0x00},
        {0x00, 0xFC, 0x24, 0x24, 0x18, 0x00, 0x00, 0x00},
        {0x00, 0x18, 0x24, 0x24, 0xFC, 0x00, 0x00, 0x00},
        {0x00, 0x00, 0x7C, 0x08, 0x04, 0x00, 0x00, 0x00},
        {0x00, 0x48, 0x54, 0x54, 0x24, 0x00, 0x00, 0x00},
        {0x00, 0x04, 0x7F, 0x44, 0x00, 0x00, 0x00, 0x00},
        {0x00, 0x3C, 0x40, 0x40, 0x7C, 0x00, 0x00, 0x00},
        {0x00, 0x1C, 0x20, 0x40, 0x20, 0x1C, 0x00, 0x00},
        {0x00, 0x3C, 0x40, 0x30, 0x40, 0x3C, 0x00, 0x00},
        {0x00, 0x44, 0x28, 0x10, 0x28, 0x44, 0x00, 0x00},
        {0x00, 0x1C, 0xA0, 0xA0, 0x7C, 0x00, 0x00, 0x00},
        {0x00, 0x44, 0x64, 0x54, 0x4C, 0x44, 0x00, 0x00},
        {0x00, 0x08, 0x36, 0x41, 0x00, 0x00, 0x00, 0x00},
        {0x00, 0x00, 0x7F, 0x00, 0x00, 0x00, 0x00, 0x00},
        {0x00, 0x41, 0x36, 0x08, 0x00, 0x00, 0x00, 0x00},
        {0x00, 0x02, 0x01, 0x01, 0x02, 0x01, 0x00, 0x00},
        {0x00, 0x02, 0x05, 0x05, 0x02, 0x00, 0x00, 0x00},
};

void initOled(void)
{
    // enable i2c0 module
    SysCtlPeripheralEnable(SYSCTL_PERIPH_I2C3);

    // reset module
    // SysCtlPeripheralReset(SYSCTL_PERIPH_I2C3);

    // enable GPIO that contains I2C0
    SysCtlPeripheralEnable(SYSCTL_PERIPH_GPIOD);

    // Configure the pin muxing for I2C0 functions on port B2 and B3.
    GPIOPinConfigure(GPIO_PD0_I2C3SCL);
    GPIOPinConfigure(GPIO_PD1_I2C3SDA);

    // Select the I2C function for these pins.
    GPIOPinTypeI2CSCL(GPIO_PORTD_BASE, GPIO_PIN_0);
    GPIOPinTypeI2C(GPIO_PORTD_BASE, GPIO_PIN_1);

    I2CMasterInitExpClk(I2C3_BASE, SysCtlClockGet(), false);

    // clear I2C FIFOs
    HWREG(I2C3_BASE + I2C_O_FIFOCTL) = 80008000;

    sendOledCommand(OLED_DISPLAYOFF);         // 0xAE
    sendOledCommand(OLED_SETDISPLAYCLOCKDIV); // 0xD5
    sendOledCommand(0x80);                    // the suggested ratio 0x80
    sendOledCommand(OLED_SETMULTIPLEX);       // 0xA8
    sendOledCommand(0x1F);
    sendOledCommand(OLED_SETDISPLAYOFFSET);   // 0xD3
    sendOledCommand(0x0);                     // no offset
    sendOledCommand(OLED_SETSTARTLINE | 0x0); // line #0
    sendOledCommand(OLED_CHARGEPUMP);         // 0x8D
    sendOledCommand(0xAF);
    sendOledCommand(OLED_MEMORYMODE); // 0x20
    sendOledCommand(0x00);            // 0x0 act like ks0108
    sendOledCommand(OLED_SEGREMAP | 0x1);
    sendOledCommand(OLED_COMSCANDEC);
    sendOledCommand(OLED_SETCOMPINS); // 0xDA
    sendOledCommand(0x02);
    sendOledCommand(OLED_SETCONTRAST); // 0x81
    sendOledCommand(0x8F);
    sendOledCommand(OLED_SETPRECHARGE); // 0xd9
    sendOledCommand(0xF1);
    sendOledCommand(OLED_SETVCOMDETECT); // 0xDB
    sendOledCommand(0x40);
    sendOledCommand(OLED_DISPLAYALLON_RESUME); // 0xA4
    sendOledCommand(OLED_NORMALDISPLAY);       // 0xA6
    sendOledCommand(OLED_DISPLAYON);           //--turn on oled panel
}

void sendOledCommand(uint8_t cmd)
{
    uint8_t control = 0x00;
    char arr[2] = {control, cmd};
    sendI2CMultipleBytes(slaveAddress, 2, arr);
}

void sendI2CMultipleBytes(uint8_t slave_addr, uint8_t numOfBytes, char by[])
{
    uint8_t i;
    // Tell the master module what address it will place on the bus when
    // communicating with the slave.
    I2CMasterSlaveAddrSet(I2C3_BASE, slave_addr, false);

    // put the data to be sent in the FIFO
    I2CMasterDataPut(I2C3_BASE, by[0]);

    // Initialize sending data from the MCU
    I2CMasterControl(I2C3_BASE, I2C_MASTER_CMD_BURST_SEND_START);

    // wait while MCU is done transferring
    while (I2CMasterBusy(I2C3_BASE))
        ;
    for (i = 1; i < numOfBytes - 1; i++)
    {
        // put next piece of data into I2C FIFO
        I2CMasterDataPut(I2C3_BASE, by[i]);
        // send next data that was just placed into FIFO
        I2CMasterControl(I2C3_BASE, I2C_MASTER_CMD_BURST_SEND_CONT);

        // Wait until MCU is done transferring.
        while (I2CMasterBusy(I2C3_BASE))
            ;
    }
    // put last byte of data
    I2CMasterDataPut(I2C3_BASE, by[numOfBytes - 1]);
    // send next data that was just placed into FIFO
    I2CMasterControl(I2C3_BASE, I2C_MASTER_CMD_BURST_SEND_FINISH);
    // Wait until MCU is done transferring.
    while (I2CMasterBusy(I2C3_BASE))
        ;
}

void setOledCursor(unsigned char Row, unsigned char Column)
{
    sendOledCommand(0xB0 + Row);
    sendOledCommand(0x00 + (8 * Column & 0x0F));
    sendOledCommand(0x10 + ((8 * Column >> 4) & 0x0F));
}

void putCharOnOled(char ch)
{
    if ((ch < 32) || (ch > 127))
    {
        ch = ' ';
    }

    const uint8_t *base = &OledFont[ch - 32][0];

    uint8_t bytes[9];
    bytes[0] = 0x40;
    memmove(bytes + 1, base, 8);

    sendI2CMultipleBytes(slaveAddress, 9, bytes);
}

void clearOled()
{
    uint16_t row, col;
    for (row = 0; row < 4; row++)
    {
        for (col = 0; col < 16; col++)
        {
            setOledCursor(row, col);
            putCharOnOled(' ');
        }
    }
}

void showStringOnOled(char *s)
{
    while (*s)
        putCharOnOled(*s++);
}

Sg90.c(舵机)

#include "Sg90.h"

int UnitValue;

void initSg90(void)
{
    SysCtlPWMClockSet(SYSCTL_PWMDIV_32);
    SysCtlPeripheralEnable(SYSCTL_PERIPH_PWM1);
    SysCtlPeripheralEnable(SYSCTL_PERIPH_GPIOD);
    GPIOPinTypePWM(GPIO_PORTD_BASE, GPIO_PIN_0);
    GPIOPinConfigure(GPIO_PD0_M1PWM0);
    PWMGenConfigure(PWM1_BASE, PWM_GEN_0,
                    PWM_GEN_MODE_DOWN | PWM_GEN_MODE_NO_SYNC);
    PWMGenPeriodSet(PWM1_BASE, PWM_GEN_0, 25000);
    PWMOutputState(PWM1_BASE, PWM_OUT_0_BIT, true);
    PWMGenEnable(PWM1_BASE, PWM_GEN_0);

    UnitValue = 25;
}

void rotateSg90(int angle)
{
    int value = 5 * angle / 9 + 25;
    PWMPulseWidthSet(PWM1_BASE, PWM_OUT_0, value * UnitValue);
    PWMGenEnable(PWM1_BASE, PWM_GEN_0);
}