OLED显示部分调试

This commit is contained in:
jxh
2025-03-18 19:34:19 +08:00
commit 17afca8f17
18 changed files with 1809 additions and 0 deletions

6
.gitignore vendored Normal file
View File

@ -0,0 +1,6 @@
/Objects/*
/Listings/*
wireless_charge.uvgui.jxh
wireless_charge.uvopt
wireless_charge.uvproj

123
Driver/iic.c Normal file
View File

@ -0,0 +1,123 @@
#include "iic.h"
// 延时函数2us
void IIC_Delay(void) {
// 软件延时
// _nop_();_nop_();_nop_();_nop_();_nop_();// 30个nop约1us@30MHz
// _nop_();_nop_();_nop_();..............
DelayUs(1);
}
void IIC_Init(void) {
// 配置P2.6和P2.7为开漏模式
P2M1 |= 0xC0; // 1100 0000
P2M0 |= 0xC0; // 开漏模式
SDA = 1;
SCL = 1;
}
void IIC_Start(void) {
SDA = 1;
SCL = 1;
IIC_Delay();
SDA = 0;
IIC_Delay();
SCL = 0;
}
void IIC_Stop(void) {
SDA = 0;
SCL = 1;
IIC_Delay();
SDA = 1;
IIC_Delay();
}
void IIC_SendByte(u8 dat) {
u8 i;
for(i=0; i<8; i++) {
SDA = (dat & 0x80) ? 1 : 0;
dat <<= 1;
IIC_Delay();
SCL = 1;
IIC_Delay();
SCL = 0;
}
}
u8 IIC_RecvByte(void) {
u8 i, dat = 0;
SDA = 1; // 释放数据线
for(i=0; i<8; i++) {
dat <<= 1;
SCL = 1;
IIC_Delay();
if(SDA) dat |= 0x01;
SCL = 0;
IIC_Delay();
}
return dat;
}
bit IIC_WaitAck(void) {
SDA = 1; // 主机释放SDA
IIC_Delay();
SCL = 1;
IIC_Delay();
if(SDA) { // 检测SDA状态
SCL = 0;
return 0; // 无ACK
} else {
SCL = 0;
return 1; // 收到ACK
}
}
void IIC_SendAck(bit ack) {
SDA = ack ? 0 : 1;
IIC_Delay();
SCL = 1;
IIC_Delay();
SCL = 0;
SDA = 1; // 释放SDA
}
/**
* @brief I²C连续写入多个字节数据
* @param devAddr : 从机地址7位地址左对齐
* @param regAddr : 寄存器地址
* @param pData : 待写入数据缓冲区
* @param len : 数据长度
* @retval 写入状态1-成功0-失败
*/
bit IIC_WriteBytes(u8 devAddr, u8 regAddr, u8 *pData, u8 len) {
IIC_Start(); // 启动I²C通信[6](@ref)
// 发送设备地址(写模式)
IIC_SendByte(devAddr & 0xFE); // 7位地址+写位(0)
if (!IIC_WaitAck()) { // 检测从机应答
IIC_Stop();
return 0; // 无应答则终止[2](@ref)
}
// 发送寄存器地址
IIC_SendByte(regAddr);
if (!IIC_WaitAck()) {
IIC_Stop();
return 0; // 寄存器地址无应答
}
// 循环发送数据字节
while (len--) {
IIC_SendByte(*pData++); // 发送当前字节
if (!IIC_WaitAck()) { // 检测数据应答
IIC_Stop();
return 0; // 数据写入失败
}
}
IIC_Stop(); // 结束通信[6](@ref)
return 1; // 写入成功
}

27
Driver/iic.h Normal file
View File

@ -0,0 +1,27 @@
#ifndef __IIC_H__
#define __IIC_H__
#include "stdint.h"
#include <intrins.h>
#include "config.h"
#include "delay.h"
// #define FOSC 30000000UL // 定义系统频率
// sbit SDA = P2^7;
// sbit SCL = P2^6;
void IIC_Init(void);
void IIC_Start(void);
void IIC_Stop(void);
void IIC_SendByte(u8 dat);
u8 IIC_RecvByte(void);
bit IIC_WaitAck(void);
void IIC_SendAck(bit ack);
bit IIC_WriteBytes(u8 devAddr, u8 regAddr, u8 *pData, u8 len);
bit IIC_ReadBytes(u8 devAddr, u8 regAddr, u8 *pData, u8 len);
#endif

45
Driver/timer4.c Normal file
View File

@ -0,0 +1,45 @@
#include "timer4.h"
u8 Timer4_OF = 0; // 定时器4溢出标志
// 定时器4初始化16位自动重载模式
void Timer4_Init(void) {
Timer4_Stop(); // 停止定时器4
T4T3M &= 0x0F; // 清除T4控制位
T4T3M |= 0x20; // 设置T4为1T模式
T4L = 0xD0; // 设置定时初始值
T4H = 0x8A; // 设置定时初始值 1ms@30MHz 1T
IE2 |= 0x40; // 使能定时器4中断
}
// 微秒级延时误差±0.3us
void Timer4_DelayUs(u16 us) {
u32 cycles = us * (FOSC / 1000000); // 计算所需时钟周期数
u16 reload = 65536 - (cycles / 1); // 1T模式下无需分频
T4H = reload >> 8; // 设置重载值高字节
T4L = reload & 0xFF;// 低字节
T4T3M |= 0x80; // 启动定时器4
while ( Timer4_OF != True ); // 等待TF4溢出标志置位
Timer4_OF = False; // 清除溢出标志
}
// 毫秒级延时(基于微秒级扩展)
void Timer4_DelayMs(u16 ms) {
while(ms--) {
Timer4_DelayUs(1000);
}
}
// 停止定时器4
void Timer4_Stop(void) {
T4T3M &= ~0x80; // 停止定时器4
}
// 定时器4中断服务程序
void Timer4_Isr(void) interrupt 20
{
Timer4_OF = True;
Timer4_Stop();
}

14
Driver/timer4.h Normal file
View File

@ -0,0 +1,14 @@
#ifndef __TIMER4_H__
#define __TIMER4_H__
#include "config.h"
#include <STC15.H>
// #define FOSC 30000000UL // 系统时钟30MHz
void Timer4_Init(void);
void Timer4_DelayUs(u16 us);
void Timer4_DelayMs(u16 ms);
void Timer4_Stop(void);
#endif

25
Driver/uart.c Normal file
View File

@ -0,0 +1,25 @@
#include "uart.h"
#include <STC15.H>
void Uart1_Init(void) //115200bps@30.000MHz
{
SCON = 0x50; //8位数据,可变波特率
AUXR |= 0x01; //串口1选择定时器2为波特率发生器
AUXR |= 0x04; //定时器时钟1T模式
T2L = 0xBF; //设置定时初始值
T2H = 0xFF; //设置定时初始值
AUXR |= 0x10; //定时器2开始计时
ES = 1; //使能串口1中断
}
// 重定向putchar函数
char putchar(char c) {
UART_SendByte(c);
return c;
}
void UART_SendByte(unsigned char dat) {
SBUF = dat;
while(!TI); // 等待发送完成
TI = 0; // 清除发送中断标志
}

9
Driver/uart.h Normal file
View File

@ -0,0 +1,9 @@
#ifndef __UART_H__
#define __UART_H__
#include "config.h"
void Uart1_Init(void);
void UART_SendByte(unsigned char dat);
#endif

198
Lib/STARTUP.A51 Normal file
View File

@ -0,0 +1,198 @@
$NOMOD51
;------------------------------------------------------------------------------
; This file is part of the C51 Compiler package
; Copyright (c) 1988-2005 Keil Elektronik GmbH and Keil Software, Inc.
; Version 8.01
;
; *** <<< Use Configuration Wizard in Context Menu >>> ***
;------------------------------------------------------------------------------
; STARTUP.A51: This code is executed after processor reset.
;
; To translate this file use A51 with the following invocation:
;
; A51 STARTUP.A51
;
; To link the modified STARTUP.OBJ file to your application use the following
; Lx51 invocation:
;
; Lx51 your object file list, STARTUP.OBJ controls
;
;------------------------------------------------------------------------------
;
; User-defined <h> Power-On Initialization of Memory
;
; With the following EQU statements the initialization of memory
; at processor reset can be defined:
;
; <o> IDATALEN: IDATA memory size <0x0-0x100>
; <i> Note: The absolute start-address of IDATA memory is always 0
; <i> The IDATA space overlaps physically the DATA and BIT areas.
IDATALEN EQU 80H
;
; <o> XDATASTART: XDATA memory start address <0x0-0xFFFF>
; <i> The absolute start address of XDATA memory
XDATASTART EQU 0
;
; <o> XDATALEN: XDATA memory size <0x0-0xFFFF>
; <i> The length of XDATA memory in bytes.
XDATALEN EQU 0
;
; <o> PDATASTART: PDATA memory start address <0x0-0xFFFF>
; <i> The absolute start address of PDATA memory
PDATASTART EQU 0H
;
; <o> PDATALEN: PDATA memory size <0x0-0xFF>
; <i> The length of PDATA memory in bytes.
PDATALEN EQU 0H
;
;</h>
;------------------------------------------------------------------------------
;
;<h> Reentrant Stack Initialization
;
; The following EQU statements define the stack pointer for reentrant
; functions and initialized it:
;
; <h> Stack Space for reentrant functions in the SMALL model.
; <q> IBPSTACK: Enable SMALL model reentrant stack
; <i> Stack space for reentrant functions in the SMALL model.
IBPSTACK EQU 0 ; set to 1 if small reentrant is used.
; <o> IBPSTACKTOP: End address of SMALL model stack <0x0-0xFF>
; <i> Set the top of the stack to the highest location.
IBPSTACKTOP EQU 0xFF +1 ; default 0FFH+1
; </h>
;
; <h> Stack Space for reentrant functions in the LARGE model.
; <q> XBPSTACK: Enable LARGE model reentrant stack
; <i> Stack space for reentrant functions in the LARGE model.
XBPSTACK EQU 0 ; set to 1 if large reentrant is used.
; <o> XBPSTACKTOP: End address of LARGE model stack <0x0-0xFFFF>
; <i> Set the top of the stack to the highest location.
XBPSTACKTOP EQU 0xFFFF +1 ; default 0FFFFH+1
; </h>
;
; <h> Stack Space for reentrant functions in the COMPACT model.
; <q> PBPSTACK: Enable COMPACT model reentrant stack
; <i> Stack space for reentrant functions in the COMPACT model.
PBPSTACK EQU 0 ; set to 1 if compact reentrant is used.
;
; <o> PBPSTACKTOP: End address of COMPACT model stack <0x0-0xFFFF>
; <i> Set the top of the stack to the highest location.
PBPSTACKTOP EQU 0xFF +1 ; default 0FFH+1
; </h>
;</h>
;------------------------------------------------------------------------------
;
; Memory Page for Using the Compact Model with 64 KByte xdata RAM
; <e>Compact Model Page Definition
;
; <i>Define the XDATA page used for PDATA variables.
; <i>PPAGE must conform with the PPAGE set in the linker invocation.
;
; Enable pdata memory page initalization
PPAGEENABLE EQU 0 ; set to 1 if pdata object are used.
;
; <o> PPAGE number <0x0-0xFF>
; <i> uppermost 256-byte address of the page used for PDATA variables.
PPAGE EQU 0
;
; <o> SFR address which supplies uppermost address byte <0x0-0xFF>
; <i> most 8051 variants use P2 as uppermost address byte
PPAGE_SFR DATA 0A0H
;
; </e>
;------------------------------------------------------------------------------
; Standard SFR Symbols
ACC DATA 0E0H
B DATA 0F0H
SP DATA 81H
DPL DATA 82H
DPH DATA 83H
NAME ?C_STARTUP
?C_C51STARTUP SEGMENT CODE
?STACK SEGMENT IDATA
RSEG ?STACK
DS 1
EXTRN CODE (?C_START)
PUBLIC ?C_STARTUP
CSEG AT 0
?C_STARTUP: LJMP STARTUP1
RSEG ?C_C51STARTUP
STARTUP1:
IF IDATALEN <> 0
MOV R0,#IDATALEN - 1
CLR A
IDATALOOP: MOV @R0,A
DJNZ R0,IDATALOOP
ENDIF
IF XDATALEN <> 0
MOV DPTR,#XDATASTART
MOV R7,#LOW (XDATALEN)
IF (LOW (XDATALEN)) <> 0
MOV R6,#(HIGH (XDATALEN)) +1
ELSE
MOV R6,#HIGH (XDATALEN)
ENDIF
CLR A
XDATALOOP: MOVX @DPTR,A
INC DPTR
DJNZ R7,XDATALOOP
DJNZ R6,XDATALOOP
ENDIF
IF PPAGEENABLE <> 0
MOV PPAGE_SFR,#PPAGE
ENDIF
IF PDATALEN <> 0
MOV R0,#LOW (PDATASTART)
MOV R7,#LOW (PDATALEN)
CLR A
PDATALOOP: MOVX @R0,A
INC R0
DJNZ R7,PDATALOOP
ENDIF
IF IBPSTACK <> 0
EXTRN DATA (?C_IBP)
MOV ?C_IBP,#LOW IBPSTACKTOP
ENDIF
IF XBPSTACK <> 0
EXTRN DATA (?C_XBP)
MOV ?C_XBP,#HIGH XBPSTACKTOP
MOV ?C_XBP+1,#LOW XBPSTACKTOP
ENDIF
IF PBPSTACK <> 0
EXTRN DATA (?C_PBP)
MOV ?C_PBP,#LOW PBPSTACKTOP
ENDIF
MOV SP,#?STACK-1
; This code is required if you use L51_BANK.A51 with Banking Mode 4
;<h> Code Banking
; <q> Select Bank 0 for L51_BANK.A51 Mode 4
#if 0
; <i> Initialize bank mechanism to code bank 0 when using L51_BANK.A51 with Banking Mode 4.
EXTRN CODE (?B_SWITCH0)
CALL ?B_SWITCH0 ; init bank mechanism to code bank 0
#endif
;</h>
LJMP ?C_START
END

16
Lib/delay.c Normal file
View File

@ -0,0 +1,16 @@
#include "delay.h"
// timer4初始化
void Delay_Init(void) {
Timer4_Init();
}
// 延时us微秒
void DelayUs(u16 us) {
Timer4_DelayUs(us);
}
// 延时ms毫秒
void DelayMs(u16 ms) {
Timer4_DelayMs(ms);
}

11
Lib/delay.h Normal file
View File

@ -0,0 +1,11 @@
#ifndef __DELAY_H__
#define __DELAY_H__
#include "config.h"
#include "timer4.h"
void Delay_Init(void);
void DelayUs(u16 us);
void DelayMs(u16 ms);
#endif

49
Lib/ina226.c Normal file
View File

@ -0,0 +1,49 @@
#include "ina226.h"
static float CurrentLSB; // 电流分辨率
void INA226_Init(uint16_t r_shunt, float max_current) {
uint16_t cal = 0;
// 1. 计算校准参数
CurrentLSB = max_current / 32768.0f; // 公式来源
cal = (uint16_t)(0.00512f / (CurrentLSB * r_shunt)); // 校准公式
// 2. 配置寄存器设置平均64次转换时间8.244ms
INA226_WriteReg(CONFIG_REG, 0x45FF); // 配置值参考
// 3. 写入校准寄存器
INA226_WriteReg(CAL_REG, cal); // 校准配置方法
}
// 寄存器写入函数
void INA226_WriteReg(uint8_t reg, uint16_t value) {
uint8_t data_t[2];
data_t[0] = (uint8_t)(value >> 8);
data_t[1] = (uint8_t)(value & 0xFF);
I2C_WriteBytes(INA226_ADDR, reg, data_t, 2); // 需适配您的I2C驱动
}
// 寄存器读取函数
uint16_t INA226_ReadReg(uint8_t reg) {
uint8_t data_t[2];
I2C_ReadBytes(INA226_ADDR, reg, data_t, 2); // 需适配您的I2C驱动
return (data_t[0] << 8) | data_t[1];
}
// 电压读取单位V
float INA226_ReadBusVoltage(void) {
int16_t raw = (int16_t)INA226_ReadReg(BUS_V_REG);
return raw * 0.00125f; // LSB=1.25mV
}
// 电流读取单位A
float INA226_ReadCurrent(void) {
int16_t raw = (int16_t)INA226_ReadReg(CURRENT_REG);
return raw * CurrentLSB; // 应用校准参数
}
// 功率读取单位W
float INA226_ReadPower(void) {
int16_t raw = (int16_t)INA226_ReadReg(POWER_REG);
return raw * 25 * CurrentLSB; // P=25×CurrentLSB×raw
}

31
Lib/ina226.h Normal file
View File

@ -0,0 +1,31 @@
#ifndef __INA226_H__
#define __INA226_H__
#include "delay.h"
#include "iic.h"
#include "config.h"
// 寄存器地址定义
#define CONFIG_REG 0x00
#define SHUNT_V_REG 0x01
#define BUS_V_REG 0x02
#define POWER_REG 0x03
#define CURRENT_REG 0x04
#define CAL_REG 0x05
#define ID_REG 0xFF
// I²C地址A0/A1接地
#define INA226_ADDR 0x80
// 函数声明
void INA226_Init(uint16_t r_shunt, float max_current);
void INA226_WriteReg(uint8_t reg, uint16_t value);
uint16_t INA226_ReadReg(uint8_t reg);
float INA226_ReadShuntVoltage(void);
float INA226_ReadBusVoltage(void);
float INA226_ReadCurrent(void);
float INA226_ReadPower(void);
#endif

828
Lib/oled12864_drv.c Normal file
View File

@ -0,0 +1,828 @@
#include "oled12864_drv.h"
#include "oled_font.h"
//#define _FONT_LIBRARY // 是否使用外带字库
#ifdef _FONT_LIBRARY
#include "gb2312_font.h"
#endif /* _FONT_LIBRARY */
/*
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
*/
/************************************************
函数名称 OLED_Delay_us
功 能 软件毫秒延时
参 数 Count ---- 次数
返 回 值
*************************************************/
static void OLED_Delay_us( uint32_t Count )
{
DelayUs(Count);
}
/************************************************
函数名称 OLED_Delay_ms
功 能 软件毫秒延时
参 数 Count ---- 次数
返 回 值
*************************************************/
static void OLED_Delay_ms( uint32_t Count )
{
DelayMs(Count);
}
/************************************************
函数名称 OLED_Write_Cmd
功 能 OLED写命令
参 数 Cmd ---- 命令
返 回 值
*************************************************/
void OLED_Write_Cmd( uint8_t Cmd )
{
// IIC_Start();
// IIC_SendByte(0x78); // Slave address,SA0 = 0
// IIC_WaitAck();
// IIC_SendByte(0x00); // write command
// IIC_WaitAck();
// IIC_SendByte(Cmd);
// IIC_WaitAck();
// IIC_Stop();
IIC_WriteBytes(0x78, 0x00, &Cmd, 1);
}
/************************************************
函数名称 OLED_Write_Data
功 能 OLED写数据
参 数 Data ---- 数据
Inverse ---- 反白显示使能
返 回 值
*************************************************/
void OLED_Write_Data( uint8_t Data, uint8_t Inverse )
{
uint8_t temp = 0;
if(!Inverse)
{
temp = Data;
}
else
{
temp = ~Data;
}
// IIC_Start();
// IIC_SendByte(0x78); // Slave address,SA0 = 0
// IIC_WaitAck();
// IIC_SendByte(0x40); // write data
// IIC_WaitAck();
// IIC_SendByte(temp);
// IIC_WaitAck();
// IIC_Stop();
IIC_WriteBytes(0x78, 0x40, &temp, 1);
}
/************************************************
函数名称 OLED_Fill
功 能 OLED亮屏 / 清屏
参 数 Mode ---- 清除/显示(OLED_CLS or OLED_SHOW)
返 回 值
*************************************************/
void OLED_Fill( uint8_t Mode )
{
uint8_t y,x;
for(y = 0;y < 8;y++)
{
OLED_Write_Cmd(0xB0 + y); // 第 n页开始0~7
OLED_Write_Cmd(0x10); // 设置显示位置 - 列高位第一个
OLED_Write_Cmd(0x00); // 设置显示位置 - 列低位第一个
for(x = 0;x < OLED_MAX_COLUMN;x++)
{
OLED_Write_Data(Mode, DISABLE); // Data = 0x00全屏灭Data = 0xff全屏亮
}
}
}
/************************************************
函数名称 OLED_Row_Clear
功 能 OLED单行清除 / 显示
参 数 Row ---- 首行
Amount ---- 行数
Mode ---- 清除/显示(OLED_CLS or OLED_SHOW)
返 回 值
*************************************************/
void OLED_Row_Clear( uint8_t Row, uint8_t Amount ,uint8_t Mode )
{
uint8_t y,x;
if(Row < 8)
{
for(y = 0;y < Amount;y++)
{
OLED_Write_Cmd(0xB0 + Row + y); // 第 n页开始0~7
OLED_Write_Cmd(0x10); // 设置显示位置 - 列高位第一个
OLED_Write_Cmd(0x00); // 设置显示位置 - 列低位第一个
for(x = 0;x < OLED_MAX_COLUMN;x++)
{
OLED_Write_Data(Mode, DISABLE);
}
}
}
}
/************************************************
函数名称 OLED_Coord
功 能 OLED坐标显示
参 数 X ---- X轴
Y ---- Y轴
返 回 值
*************************************************/
void OLED_Coord( uint8_t X, uint8_t Y )
{
// assert(X < X_WIDTH);
// assert(Y < (Y_WIDTH >> 3));
/* B0~B7:此命令仅适用于页面寻址模式 */
OLED_Write_Cmd(0xB0 + Y); // 设置GDDRAM页面开始地址,(Page 0~ Page 7)为页面寻址模式
/* 10~1F:此命令仅适用于页面寻址模式 */
OLED_Write_Cmd(((X & 0xF0) >> 4) | 0x10); // 页面寻址模式下设置列开始地址寄存器的高位
/* 00~0F:此命令仅适用于页面寻址模式 */
OLED_Write_Cmd((X & 0x0F) | 0x00); // 页面寻址模式下设置列开始地址寄存器的低位
}
/************************************************
函数名称 OLED_ShowRoll
功 能 OLED内置滚动显示
参 数 Y ---- 起始行
Line ---- 滚动行数 (0 ---> 取消滚动)
Mode ---- 滚动模式OLED_LEFT_ROLL or OLED_RIGHT_ROLL
返 回 值
*************************************************/
void OLED_ShowRoll( uint8_t Y, uint8_t Line, uint8_t Mode )
{
if(Line > 0)
{
if(Mode == OLED_LEFT_ROLL)
{
OLED_Write_Cmd(OLED_LEFT_ROLL); // 左滚动显示
}
else if(Mode == OLED_RIGHT_ROLL)
{
OLED_Write_Cmd(OLED_RIGHT_ROLL); // 右滚动显示
}
else
{
return ;
}
OLED_Write_Cmd(0x00); // 虚拟字节设置默认为0x00
OLED_Write_Cmd(Y); // 定义开始页面地址
OLED_Write_Cmd(0x07); // 帧频设置
OLED_Write_Cmd(Y + (Line - 1)); // 定义结束页面地址
OLED_Write_Cmd(0x00); // 虚拟字节设置默认为0x00
OLED_Write_Cmd(0xFF); // 虚拟字节设置默认为0xFF
OLED_Write_Cmd(0x2F); // 激活滚动
}
else
{
OLED_Write_Cmd(0x2E); // 失能滚动
}
}
/************************************************
函数名称 OLED_ShowChar
功 能 OLED字符显示
参 数 X ---- X轴
Y ---- Y轴
Char ---- 字符
Size ---- 字体大小
Inverse ---- 反白显示使能
返 回 值
*************************************************/
void OLED_ShowChar( uint8_t X, uint8_t Y, uint8_t Char, uint8_t Size, uint8_t Inverse )
{
uint8_t i;
uint8_t value = 0;
if(X <= OLED_MAX_COLUMN - 8 && (Y < (OLED_MAX_ROW >> 3)))
{
if(X >= 0 && Y >= 0)
{
value = Char - 32; // 得到偏移值(偏移量32)
if(Size == OLED_FONT_SIXTEEN) // 8x16
{
OLED_Coord(X, Y);
for(i = 0;i < 8;i++)
{
OLED_Write_Data(F8x16[value][i], Inverse); // 前八个数据
}
OLED_Coord(X, Y+1);
for(i = 0;i < 8;i++)
{
OLED_Write_Data(F8x16[value][i + 8], Inverse); // 后八个数据
}
}
else if(Size == OLED_FONT_EIGHT) // 6x8
{
OLED_Coord(X, Y);
for(i = 0;i < 6;i++)
{
OLED_Write_Data(F6x8[value][i], Inverse);
}
/* 清除剩下的两个 */
OLED_Write_Data(0x00, Inverse);
OLED_Write_Data(0x00, Inverse);
}
}
}
}
/************************************************
函数名称 OLED_ShowString
功 能 OLED字符串显示
参 数 X ---- X轴
Y ---- Y轴
Len ---- 长度
pChar ---- 数据
Size ---- 字体大小
Inverse ---- 反白(全行)显示使能
返 回 值
*************************************************/
void OLED_ShowString( uint8_t X, uint8_t Y, const uint8_t *pChar, uint16_t Len, uint8_t Size, uint8_t Inverse )
{
uint8_t i,j;
uint8_t temp = 0;
if(Inverse)
{
for(j = 0;j < (Size / 8);j++)
{
OLED_Coord(0, Y + j);
for(i = 0;i < OLED_MAX_COLUMN;i++)
{
OLED_Write_Data(OLED_SHOW, DISABLE); // OLED_CLS = 0x00全屏灭OLED_SHOW = 0xff全屏亮
}
}
}
if(Len <= 16)
{
while(Len--)
{
if(X >= OLED_MAX_COLUMN - 8)
{
break;
}
OLED_ShowChar(X, Y, *pChar, Size, Inverse);
X += 8;
pChar++;
}
}
}
/************************************************
函数名称 OLED_ShowPrintf
功 能 OLED字符串输出自动顶部对齐换行
参 数 X ---- X轴
Y ---- Y轴
pChar ---- 数据
Size ---- 字体大小
Align ---- 对齐显示使能
Inverse ---- 反白(单字体)显示使能
返 回 值
*************************************************/
void OLED_ShowPrintf( uint8_t X, uint8_t Y, const uint8_t *pChar, uint8_t Size, uint8_t Align, uint8_t Inverse )
{
uint8_t addr = 0;
if(Align)
{
addr = X; // 记录顶部对齐位置
}
while(*pChar != '\0')
{
if(X >= OLED_MAX_COLUMN - 8) // 列溢出
{
X = addr; // 对齐列地址
Y += (Size >> 3); // 转到下一行
if(Y >= (OLED_MAX_ROW >> 3))
{
break; // Y轴越界退出
}
}
OLED_ShowChar(X, Y, *pChar, Size, Inverse);
X += 8;
pChar++;
}
}
/************************************************
函数名称 OLED_Power
功 能 OLED幂计算
参 数 M ---- X轴
N ---- Y轴
返 回 值 power ---- 幂
*************************************************/
uint32_t OLED_Power( uint8_t M, uint8_t N )
{
uint32_t power = 1;
while(N--)
{
power *= M;
}
return power;
}
/************************************************
函数名称 OLED_ShowNum
功 能 OLED数字显示限正整数
参 数 X ---- X轴
Y ---- Y轴
Num ---- 数字
Len ---- 位数
Size ---- 字体大小
Prefix ---- 补零显示使能
Inverse ---- 反白显示使能
返 回 值
*************************************************/
void OLED_ShowNum( uint8_t X, uint8_t Y, uint32_t Num, uint8_t Len, uint8_t Size, uint8_t Prefix, uint8_t Inverse )
{
char temp = 0;
uint8_t t;
uint8_t show = 0;
for(t = 0;t < Len;t++)
{
temp = (Num / OLED_Power(10, Len - t - 1)) % 10; // 提取每位数字
if(!show && t < (Len - 1))
{
if(0 == temp)
{
if(Prefix)
OLED_ShowChar(X + 8 *t, Y , '0', Size, Inverse);
else
OLED_ShowChar(X + 8 *t, Y , ' ', Size, Inverse);
continue;
}
else
{
show = 1;
}
}
OLED_ShowChar(X + 8 *t, Y, temp + '0', Size, Inverse);
}
}
/************************************************
函数名称 OLED_ShowHex
功 能 OLED十六进制显示
参 数 X ---- X轴
Y ---- Y轴
Num ---- 数字10进制
Size ---- 字体大小(固定宽度为 8像素
Prefix ---- 补零显示使能
Inverse ---- 反白显示使能
返 回 值
*************************************************/
void OLED_ShowHex( uint8_t X, uint8_t Y, uint32_t Num, uint8_t Size, uint8_t Prefix, uint8_t Inverse )
{
uint8_t t,temp;
uint8_t i = 0;
uint8_t show = 0;
for(t = 0;t < 4;t++)
{
temp = (uint8_t)(Num >> (12 - 4*t)) & 0x000F; // 提取每位数字
if(!show && t < 3)
{
if(0 == temp)
{
if(Prefix)
{
OLED_ShowChar(X + 8 *i, Y , '0', Size, Inverse);
i++;
}
continue;
}
else
{
show = 1;
}
}
switch(temp)
{
case 0: temp = '0'; break;
case 1: temp = '1'; break;
case 2: temp = '2'; break;
case 3: temp = '3'; break;
case 4: temp = '4'; break;
case 5: temp = '5'; break;
case 6: temp = '6'; break;
case 7: temp = '7'; break;
case 8: temp = '8'; break;
case 9: temp = '9'; break;
case 10: temp = 'A'; break;
case 11: temp = 'B'; break;
case 12: temp = 'C'; break;
case 13: temp = 'D'; break;
case 14: temp = 'E'; break;
case 15: temp = 'F'; break;
}
OLED_ShowChar(X + 8 *i, Y, temp, Size, Inverse);
i++;
}
}
/************************************************
函数名称 OLED_ShowFloat
功 能 OLED可变精度小数显示
参 数 X ---- X轴
Y ---- Y轴
Num ---- 数字
Accuracy ---- 精确位数
Size ---- 字体大小
Inverse ---- 反白显示使能
返 回 值
*************************************************/
void OLED_ShowFloat( uint8_t X, uint8_t Y, float Num, uint8_t Accuracy, uint8_t Size, uint8_t Inverse )
{
uint8_t i = 0;
uint8_t j = 0;
uint8_t t = 0;
uint8_t temp = 0;
uint16_t numel = 0;
uint32_t integer = 0;
float decimals = 0;
/* 判断是否为负数 */
if(Num < 0)
{
OLED_ShowChar(X, Y , '-', Size, Inverse);
Num = 0 - Num;
i++;
}
integer = (uint32_t)Num;
decimals = Num - integer;
/* 整数部分 */
if(integer)
{
numel = integer;
while(numel) // 获取整数位数
{
numel /= 10;
j++;
}
i += (j - 1);
for(temp = 0;temp < j;temp++)
{
OLED_ShowChar(X + 8 *(i - temp), Y, integer % 10 + '0', Size, Inverse); // 显示整数部分
integer /= 10;
}
}
else
{
OLED_ShowChar(X + 8 *i, Y, temp + '0', Size, Inverse);
}
i++;
/* 小数部分 */
if(Accuracy)
{
OLED_ShowChar(X + 8 *i, Y , '.', Size, Inverse); // 显示小数点
i++;
for(t = 0;t < Accuracy;t++)
{
decimals *= 10;
temp = (uint8_t)decimals; // 提取每位小数
OLED_ShowChar(X + 8 *(i + t), Y, temp + '0', Size, Inverse);
decimals -= temp;
}
}
}
/************************************************
函数名称 OLED_ShowLanguage
功 能 OLED汉字显示(16x16) 不带字库的
参 数 X ---- X轴
Y ---- Y轴
pArray ---- 数据
Len ---- 字数长度
Inverse ---- 反白显示使能
返 回 值
*************************************************/
/*
mode 0:使用 1级指针来访问二维数组
mode 1:使用指向数组的指针来访问二维数组
*/
#define _OLED_ShowLanguage_MODE 0 // (0 or 1)
#if (0 == _OLED_ShowLanguage_MODE)
void OLED_ShowLanguage( uint8_t X, uint8_t Y, const uint8_t *pArray, uint16_t Len, uint8_t Inverse )
#elif (1 == _OLED_ShowLanguage_MODE)
void OLED_ShowLanguage( uint8_t X, uint8_t Y, const uint8_t (*pArray)[16], uint16_t Len, uint8_t Inverse )
#endif /* _OLED_ShowLanguage_MODE */
{
uint8_t i,j;
uint8_t q = 0;
uint8_t temp = 0;
uint8_t distribute_flag = 0; // 文字平均分布标志
if(Len <= 8)
{
if(!X) // 首位显示,自动平均分布
{
switch(Len)
{
case 1:
temp = 56; // OLED_MAX_COLUMN / 2 - 8 = 56
break;
case 2:
temp = 32; // (OLED_MAX_COLUMN - Len*16) / (Len + 1) = 32 Len = 2
break;
case 3:
temp = 20; // (OLED_MAX_COLUMN / 2 - 8) / 2 - 8 = 20
break;
case 4:
temp = 13; // (OLED_MAX_COLUMN - Len*16) / (Len + 1) = 12 .... 4 Len = 4
break;
case 5:
temp = 8; // ((OLED_MAX_COLUMN / 2 - 8) - ((Len - 1) / 2)*16) / ((Len - 1) / 2 + 1) = 8 Len = 5
break;
case 6:
temp = 5; // (OLED_MAX_COLUMN - Len*16) / (Len + 1) = 4 .... 4 Len = 6
break;
case 7:
temp = 2; // ((OLED_MAX_COLUMN / 2 - 8) / 2 - 8) / 2 - 8 = 2
break;
case 8:
temp = 0;
break;
default:
break;
}
X += temp;
distribute_flag = 1;
}
for(j = 0;j < Len;j++)
{
OLED_Coord(X, Y);
for(i = 0;i < 16;i++)
{
#if (0 == _OLED_ShowLanguage_MODE)
OLED_Write_Data(*(pArray + 2*j*16 + i), Inverse); // 前十六个数据
#elif (1 == _OLED_ShowLanguage_MODE)
OLED_Write_Data(pArray[2*j][i], Inverse); // 前十六个数据
#endif /* _OLED_ShowLanguage_MODE */
}
OLED_Coord(X, Y+1);
for(i = 0;i < 16;i++)
{
#if (0 == _OLED_ShowLanguage_MODE)
OLED_Write_Data(*(pArray + 2*j*16 + 16 + i), Inverse); // 后十六个数据
#elif (1 == _OLED_ShowLanguage_MODE)
OLED_Write_Data(pArray[2*j + 1][i], Inverse); // 后十六个数据
#endif /* _OLED_ShowLanguage_MODE */
}
X += (16 + temp);
if(distribute_flag)
{
q++;
/* 特殊处理 */
if((4 == Len && 2 == q) || (6 == Len && 0 == (q + 1) % 2))
{
X -= 1;
}
}
}
}
}
/************************************************
函数名称 OLED_Display_On
功 能 开启OLED显示
参 数
返 回 值
*************************************************/
void OLED_Display_On(void)
{
OLED_Write_Cmd(0x8D); //SET DCDC命令
OLED_Write_Cmd(0x14); //DCDC ON
OLED_Write_Cmd(0xAF); //DISPLAY ON
}
/************************************************
函数名称 OLED_Display_Off
功 能 关闭OLED显示
参 数
返 回 值
*************************************************/
void OLED_Display_Off(void)
{
OLED_Write_Cmd(0x8D); // SET DCDC命令
OLED_Write_Cmd(0x10); // DCDC OFF
OLED_Write_Cmd(0xAE); // DISPLAY OFF
}
/************************************************
函数名称 OLED_Init
功 能 OLED初始化
参 数
返 回 值
*************************************************/
void OLED_Init(void)
{
/* 从上电到下面开始初始化要有足够的时间,即等待 RC复位完毕 */
OLED_Delay_ms(100);
OLED_Write_Cmd(0xAE); // 关闭OLED -- turn off oled panel
OLED_Write_Cmd(0xD5); // 设置显示时钟分频因子/振荡器频率 -- set display clock divide ratio/oscillator frequency
OLED_Write_Cmd(0x80); // \ set divide ratio, Set Clock as 100 Frames/Sec
OLED_Write_Cmd(0x20); // 设置内存寻址模式 -- Set Memory Addressing Mode (0x00 / 0x01 / 0x02)
OLED_Write_Cmd(0x02); // \ Page Addressing
OLED_Write_Cmd(0xA8); // 设置多路传输比率 -- set multiplex ratio (16 to 63)
OLED_Write_Cmd(0x3F); // \ 1 / 64 duty
OLED_Write_Cmd(0xDA); // 设置列引脚硬件配置 -- set com pins hardware configuration
OLED_Write_Cmd(0x12); // \ Sequential COM pin configurationEnable COM Left/Right remap
/* ----- 方向显示配置 ----- */
OLED_Write_Cmd(0xA1); // 设置段重映射 -- Set SEG / Column Mapping 0xA0左右反置复位值 0xA1正常重映射值
OLED_Write_Cmd(0xC8); // 设置列输出扫描方向 -- Set COM / Row Scan Direction 0xc0上下反置复位值 0xC8正常重映射值
/* ----- END ----- */
OLED_Write_Cmd(0x40); // 设置设置屏幕GDDRAM起始行 -- Set Display Start Line (0x40~0x7F)
OLED_Write_Cmd(0xD3); // 设置显示偏移 -- set display offset (0x00~0x3F)
OLED_Write_Cmd(0x00); // \ not offset
OLED_Write_Cmd(0x81); // 设置对比度 -- set contrast control register (0x00~0x100)
OLED_Write_Cmd(0xCF); // \ Set SEG Output Current Brightness
OLED_Write_Cmd(0xD9); // 设置预充电期间的持续时间 -- set pre-charge period
OLED_Write_Cmd(0xF1); // \ Set Pre-Charge as 15 Clocks & Discharge as 1 Clock
OLED_Write_Cmd(0xDB); // 调整VCOMH调节器的输出 -- set vcomh (0x00 / 0x20 / 0x30)
OLED_Write_Cmd(0x20); // \ Set VCOM Deselect Level
OLED_Write_Cmd(0x8D); // 电荷泵设置 -- set Charge Pump enable / disable (0x14 / 0x10)
OLED_Write_Cmd(0x14); // \ Enable charge pump during display on
OLED_Write_Cmd(0xA4); // 全局显示开启(黑屏/亮屏) -- Entire Display On (0xA4 / 0xA5)
OLED_Write_Cmd(0xA6); // 设置显示方式(正常/反显) -- set normal display (0xA6 / 0xA7)
OLED_Write_Cmd(0xAF); // 打开OLED -- turn on oled panel
OLED_Fill(0x00); // 初始清屏
OLED_Coord(0,0); // 设置原点坐标0, 0
}
/************************* 需要提供字库相关文件 *************************/
#ifdef _FONT_LIBRARY
/************************************************
函数名称 OLED_ShowChinese
功 能 OLED单汉字显示
参 数 X ---- X轴
Y ---- Y轴
pArray ---- 数据
Inverse ---- 反白显示使能
返 回 值
*************************************************/
void OLED_ShowChinese( uint8_t X, uint8_t Y, const uint8_t *pArray, uint8_t Inverse )
{
uint8_t i;
uint8_t buffer[GB2312_1616_BYTE_SIZE] = {0};
if(X <= OLED_MAX_COLUMN - 16 && (Y < (OLED_MAX_ROW >> 3)))
{
Get_GB2312_Code(buffer, pArray);
OLED_Coord(X, Y);
for(i = 0;i < 16;i++)
{
OLED_Write_Data(buffer[i], Inverse); // 前十六个数据
}
OLED_Coord(X, Y+1);
for(i = 0;i < 16;i++)
{
OLED_Write_Data(buffer[i + 16], Inverse); // 后十六个数据
}
}
}
/************************************************
函数名称 OLED_Draw_Font
功 能 OLED中英输出显示支持混合显示
参 数 X ---- X轴
Y ---- Y轴
pArray ---- 数据
Inverse ---- 反白显示使能
返 回 值
*************************************************/
void OLED_Draw_Font( uint8_t X, uint8_t Y, const uint8_t *pArray, uint8_t Inverse )
{
uint8_t i = 0;
uint16_t j = 0;
uint8_t buffer[GB2312_1616_BYTE_SIZE] = {0};
while(*pArray != '\0')
{
if(*pArray < 127) // ASCII码
{
if(X + 8 > OLED_MAX_COLUMN)
{
X = 0;
Y += 2; // 换行
}
if(Y > (OLED_MAX_ROW >> 3))
{
X = 0;
Y = 0; // 跳到原点
}
OLED_ShowChar(X, Y, *pArray, OLED_FONT_SIXTEEN, Inverse);
X += 8;
pArray++; // 一个 ASCII码1个字节
}
else // GB2312码
{
if(X + 16 > OLED_MAX_COLUMN)
{
X = 0;
Y += 2; // 换行
}
if(Y > (OLED_MAX_ROW >> 3))
{
X = 0;
Y = 0; // 跳到原点
}
// Get_GB2312_Code(buffer, pArray);
//
// OLED_Coord(X, Y);
// for(i = 0;i < 16;i++)
// {
// OLED_Write_Data(*(buffer + 2*j*16 + i), Inverse); // 前十六个数据
// }
// OLED_Coord(X, Y+1);
// for(i = 0;i < 16;i++)
// {
// OLED_Write_Data(*(buffer + 2*j*16 + 16 + i), Inverse); // 后十六个数据
// }
// j++;
OLED_ShowChinese(X, Y, pArray, Inverse);
X += 16;
pArray += 2; // 一个 GB2312文字两个字节
}
}
}
#endif /* _FONT_LIBRARY */
/************************* 需要提供字库相关文件 *************************/
/*---------------------------- END OF FILE ----------------------------*/

80
Lib/oled12864_drv.h Normal file
View File

@ -0,0 +1,80 @@
#ifndef __OLED12864_DRV_H
#define __OLED12864_DRV_H
#include "delay.h"
#include "iic.h"
#include "config.h"
#ifndef ENABLE
#define ENABLE 1
#endif /* ENABLE */
#ifndef DISABLE
#define DISABLE 0
#endif /* DISABLE */
#ifndef HIGH
#define HIGH 1
#endif /* HIGH */
#ifndef LOW
#define LOW 0
#endif /* LOW */
//
#define OLED_FONT_EIGHT 8
#define OLED_FONT_SIXTEEN 16
#define OLED_GRAM_MAX 30
#define OLED_MAX_COLUMN 128
#define OLED_MAX_ROW 64
#define X_WIDTH 128
#define Y_WIDTH 64
#define OLED_LEFT_ROLL 0x27
#define OLED_RIGHT_ROLL 0x26
#define OLED_CLS 0x00
#define OLED_SHOW 0xFF
// extern uint8_t g_OLED_Gram[OLED_GRAM_MAX][16];
// extern uint8_t g_OLED_Roll_Page;
void OLED_Write_Cmd( uint8_t Cmd );
void OLED_Write_Data( uint8_t Data, uint8_t Inverse );
void OLED_Fill( uint8_t Mode );
void OLED_Row_Clear( uint8_t Row, uint8_t Amount ,uint8_t Mode );
void OLED_Coord( uint8_t X, uint8_t Y );
void OLED_ShowRoll( uint8_t Y, uint8_t Line, uint8_t Mode );
void OLED_ShowChar( uint8_t X, uint8_t Y, uint8_t Char, uint8_t Size, uint8_t Inverse );
void OLED_ShowString( uint8_t X, uint8_t Y, const uint8_t *pChar, uint16_t Len, uint8_t Size, uint8_t Inverse );
void OLED_ShowPrintf( uint8_t X, uint8_t Y, const uint8_t *pChar, uint8_t Size, uint8_t Align, uint8_t Inverse);
uint32_t OLED_Power( uint8_t M, uint8_t N );
void OLED_ShowNum( uint8_t X, uint8_t Y, uint32_t Num, uint8_t Len, uint8_t Size, uint8_t Prefix, uint8_t Inverse );
void OLED_ShowHex( uint8_t X, uint8_t Y, uint32_t Num, uint8_t Size, uint8_t Prefix, uint8_t Inverse );
#if 1
void OLED_ShowLanguage( uint8_t X, uint8_t Y, const uint8_t *pChar, uint16_t Len, uint8_t Inverse );
#else
void OLED_ShowLanguage( uint8_t X, uint8_t Y, const uint8_t (*pArray)[16], uint16_t Len, uint8_t Inverse );
#endif
void OLED_Display_On(void);
void OLED_Display_Off(void);
void OLED_Init(void);
void OLED_ShowChinese( uint8_t X, uint8_t Y, const uint8_t *pArray, uint8_t Inverse );
void OLED_Draw_Font( uint8_t X, uint8_t Y, const uint8_t *pArray, uint8_t Inverse );
#endif /* __OLED12864_DRV_H */
/*---------------------------- END OF FILE ----------------------------*/

218
Lib/oled_font.h Normal file
View File

@ -0,0 +1,218 @@
#ifndef __OLED_FONT_H
#define __OLED_FONT_H
/************************************************
函数名称 F6x8
功 能 6*8的 ASCII点阵(偏移量32)
参 数
返 回 值
*************************************************/
const unsigned char F6x8[][6] =
{
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // sp
0x00, 0x00, 0x00, 0x2f, 0x00, 0x00, // !
0x00, 0x00, 0x07, 0x00, 0x07, 0x00, // "
0x00, 0x14, 0x7f, 0x14, 0x7f, 0x14, // #
0x00, 0x24, 0x2a, 0x7f, 0x2a, 0x12, // $
0x00, 0x62, 0x64, 0x08, 0x13, 0x23, // %
0x00, 0x36, 0x49, 0x55, 0x22, 0x50, // &
0x00, 0x00, 0x05, 0x03, 0x00, 0x00, // '
0x00, 0x00, 0x1c, 0x22, 0x41, 0x00, // (
0x00, 0x00, 0x41, 0x22, 0x1c, 0x00, // )
0x00, 0x14, 0x08, 0x3E, 0x08, 0x14, // *
0x00, 0x08, 0x08, 0x3E, 0x08, 0x08, // +
0x00, 0x00, 0x00, 0xA0, 0x60, 0x00, // ,
0x00, 0x08, 0x08, 0x08, 0x08, 0x08, // -
0x00, 0x00, 0x60, 0x60, 0x00, 0x00, // .
0x00, 0x20, 0x10, 0x08, 0x04, 0x02, // /
0x00, 0x3E, 0x51, 0x49, 0x45, 0x3E, // 0
0x00, 0x00, 0x42, 0x7F, 0x40, 0x00, // 1
0x00, 0x42, 0x61, 0x51, 0x49, 0x46, // 2
0x00, 0x21, 0x41, 0x45, 0x4B, 0x31, // 3
0x00, 0x18, 0x14, 0x12, 0x7F, 0x10, // 4
0x00, 0x27, 0x45, 0x45, 0x45, 0x39, // 5
0x00, 0x3C, 0x4A, 0x49, 0x49, 0x30, // 6
0x00, 0x01, 0x71, 0x09, 0x05, 0x03, // 7
0x00, 0x36, 0x49, 0x49, 0x49, 0x36, // 8
0x00, 0x06, 0x49, 0x49, 0x29, 0x1E, // 9
0x00, 0x00, 0x36, 0x36, 0x00, 0x00, // :
0x00, 0x00, 0x56, 0x36, 0x00, 0x00, // ;
0x00, 0x08, 0x14, 0x22, 0x41, 0x00, // <
0x00, 0x14, 0x14, 0x14, 0x14, 0x14, // =
0x00, 0x00, 0x41, 0x22, 0x14, 0x08, // >
0x00, 0x02, 0x01, 0x51, 0x09, 0x06, // ?
0x00, 0x32, 0x49, 0x59, 0x51, 0x3E, // @
0x00, 0x7C, 0x12, 0x11, 0x12, 0x7C, // A
0x00, 0x7F, 0x49, 0x49, 0x49, 0x36, // B
0x00, 0x3E, 0x41, 0x41, 0x41, 0x22, // C
0x00, 0x7F, 0x41, 0x41, 0x22, 0x1C, // D
0x00, 0x7F, 0x49, 0x49, 0x49, 0x41, // E
0x00, 0x7F, 0x09, 0x09, 0x09, 0x01, // F
0x00, 0x3E, 0x41, 0x49, 0x49, 0x7A, // G
0x00, 0x7F, 0x08, 0x08, 0x08, 0x7F, // H
0x00, 0x00, 0x41, 0x7F, 0x41, 0x00, // I
0x00, 0x20, 0x40, 0x41, 0x3F, 0x01, // J
0x00, 0x7F, 0x08, 0x14, 0x22, 0x41, // K
0x00, 0x7F, 0x40, 0x40, 0x40, 0x40, // L
0x00, 0x7F, 0x02, 0x0C, 0x02, 0x7F, // M
0x00, 0x7F, 0x04, 0x08, 0x10, 0x7F, // N
0x00, 0x3E, 0x41, 0x41, 0x41, 0x3E, // O
0x00, 0x7F, 0x09, 0x09, 0x09, 0x06, // P
0x00, 0x3E, 0x41, 0x51, 0x21, 0x5E, // Q
0x00, 0x7F, 0x09, 0x19, 0x29, 0x46, // R
0x00, 0x46, 0x49, 0x49, 0x49, 0x31, // S
0x00, 0x01, 0x01, 0x7F, 0x01, 0x01, // T
0x00, 0x3F, 0x40, 0x40, 0x40, 0x3F, // U
0x00, 0x1F, 0x20, 0x40, 0x20, 0x1F, // V
0x00, 0x3F, 0x40, 0x38, 0x40, 0x3F, // W
0x00, 0x63, 0x14, 0x08, 0x14, 0x63, // X
0x00, 0x07, 0x08, 0x70, 0x08, 0x07, // Y
0x00, 0x61, 0x51, 0x49, 0x45, 0x43, // Z
0x00, 0x00, 0x7F, 0x41, 0x41, 0x00, // [
0x00, 0x55, 0x2A, 0x55, 0x2A, 0x55, // 55
0x00, 0x00, 0x41, 0x41, 0x7F, 0x00, // ]
0x00, 0x04, 0x02, 0x01, 0x02, 0x04, // ^
0x00, 0x40, 0x40, 0x40, 0x40, 0x40, // _
0x00, 0x00, 0x01, 0x02, 0x04, 0x00, // '
0x00, 0x20, 0x54, 0x54, 0x54, 0x78, // a
0x00, 0x7F, 0x48, 0x44, 0x44, 0x38, // b
0x00, 0x38, 0x44, 0x44, 0x44, 0x20, // c
0x00, 0x38, 0x44, 0x44, 0x48, 0x7F, // d
0x00, 0x38, 0x54, 0x54, 0x54, 0x18, // e
0x00, 0x08, 0x7E, 0x09, 0x01, 0x02, // f
0x00, 0x18, 0xA4, 0xA4, 0xA4, 0x7C, // g
0x00, 0x7F, 0x08, 0x04, 0x04, 0x78, // h
0x00, 0x00, 0x44, 0x7D, 0x40, 0x00, // i
0x00, 0x40, 0x80, 0x84, 0x7D, 0x00, // j
0x00, 0x7F, 0x10, 0x28, 0x44, 0x00, // k
0x00, 0x00, 0x41, 0x7F, 0x40, 0x00, // l
0x00, 0x7C, 0x04, 0x18, 0x04, 0x78, // m
0x00, 0x7C, 0x08, 0x04, 0x04, 0x78, // n
0x00, 0x38, 0x44, 0x44, 0x44, 0x38, // o
0x00, 0xFC, 0x24, 0x24, 0x24, 0x18, // p
0x00, 0x18, 0x24, 0x24, 0x18, 0xFC, // q
0x00, 0x7C, 0x08, 0x04, 0x04, 0x08, // r
0x00, 0x48, 0x54, 0x54, 0x54, 0x20, // s
0x00, 0x04, 0x3F, 0x44, 0x40, 0x20, // t
0x00, 0x3C, 0x40, 0x40, 0x20, 0x7C, // u
0x00, 0x1C, 0x20, 0x40, 0x20, 0x1C, // v
0x00, 0x3C, 0x40, 0x30, 0x40, 0x3C, // w
0x00, 0x44, 0x28, 0x10, 0x28, 0x44, // x
0x00, 0x1C, 0xA0, 0xA0, 0xA0, 0x7C, // y
0x00, 0x44, 0x64, 0x54, 0x4C, 0x44, // z
0x14, 0x14, 0x14, 0x14, 0x14, 0x14, // horiz lines
};
/************************************************
函数名称 F8x16
功 能 8*16的 ASCII点阵(偏移量32)
参 数
返 回 值
*************************************************/
const unsigned char F8x16[][16]=
{
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, // 0
0x00,0x00,0x00,0xF8,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x33,0x30,0x00,0x00,0x00, // ! 1
0x00,0x10,0x0C,0x06,0x10,0x0C,0x06,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, // " 2
0x40,0xC0,0x78,0x40,0xC0,0x78,0x40,0x00,0x04,0x3F,0x04,0x04,0x3F,0x04,0x04,0x00, // # 3
0x00,0x70,0x88,0xFC,0x08,0x30,0x00,0x00,0x00,0x18,0x20,0xFF,0x21,0x1E,0x00,0x00, // $ 4
0xF0,0x08,0xF0,0x00,0xE0,0x18,0x00,0x00,0x00,0x21,0x1C,0x03,0x1E,0x21,0x1E,0x00, // % 5
0x00,0xF0,0x08,0x88,0x70,0x00,0x00,0x00,0x1E,0x21,0x23,0x24,0x19,0x27,0x21,0x10, // & 6
0x10,0x16,0x0E,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, // ' 7
0x00,0x00,0x00,0xE0,0x18,0x04,0x02,0x00,0x00,0x00,0x00,0x07,0x18,0x20,0x40,0x00, // ( 8
0x00,0x02,0x04,0x18,0xE0,0x00,0x00,0x00,0x00,0x40,0x20,0x18,0x07,0x00,0x00,0x00, // ) 9
0x40,0x40,0x80,0xF0,0x80,0x40,0x40,0x00,0x02,0x02,0x01,0x0F,0x01,0x02,0x02,0x00, // * 10
0x00,0x00,0x00,0xF0,0x00,0x00,0x00,0x00,0x01,0x01,0x01,0x1F,0x01,0x01,0x01,0x00, // + 11
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x80,0xB0,0x70,0x00,0x00,0x00,0x00,0x00, // , 12
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x01,0x01,0x01,0x01,0x01,0x01,0x01, // - 13
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x30,0x30,0x00,0x00,0x00,0x00,0x00, // . 14
0x00,0x00,0x00,0x00,0x80,0x60,0x18,0x04,0x00,0x60,0x18,0x06,0x01,0x00,0x00,0x00, // / 15
0x00,0xE0,0x10,0x08,0x08,0x10,0xE0,0x00,0x00,0x0F,0x10,0x20,0x20,0x10,0x0F,0x00, // 0 16
0x00,0x10,0x10,0xF8,0x00,0x00,0x00,0x00,0x00,0x20,0x20,0x3F,0x20,0x20,0x00,0x00, // 1 17
0x00,0x70,0x08,0x08,0x08,0x88,0x70,0x00,0x00,0x30,0x28,0x24,0x22,0x21,0x30,0x00, // 2 18
0x00,0x30,0x08,0x88,0x88,0x48,0x30,0x00,0x00,0x18,0x20,0x20,0x20,0x11,0x0E,0x00, // 3 19
0x00,0x00,0xC0,0x20,0x10,0xF8,0x00,0x00,0x00,0x07,0x04,0x24,0x24,0x3F,0x24,0x00, // 4 20
0x00,0xF8,0x08,0x88,0x88,0x08,0x08,0x00,0x00,0x19,0x21,0x20,0x20,0x11,0x0E,0x00, // 5 21
0x00,0xE0,0x10,0x88,0x88,0x18,0x00,0x00,0x00,0x0F,0x11,0x20,0x20,0x11,0x0E,0x00, // 6 22
0x00,0x38,0x08,0x08,0xC8,0x38,0x08,0x00,0x00,0x00,0x00,0x3F,0x00,0x00,0x00,0x00, // 7 23
0x00,0x70,0x88,0x08,0x08,0x88,0x70,0x00,0x00,0x1C,0x22,0x21,0x21,0x22,0x1C,0x00, // 8 24
0x00,0xE0,0x10,0x08,0x08,0x10,0xE0,0x00,0x00,0x00,0x31,0x22,0x22,0x11,0x0F,0x00, // 9 25
0x00,0x00,0x00,0xC0,0xC0,0x00,0x00,0x00,0x00,0x00,0x00,0x30,0x30,0x00,0x00,0x00, // : 26
0x00,0x00,0x00,0x80,0x00,0x00,0x00,0x00,0x00,0x00,0x80,0x60,0x00,0x00,0x00,0x00, // ; 27
0x00,0x00,0x80,0x40,0x20,0x10,0x08,0x00,0x00,0x01,0x02,0x04,0x08,0x10,0x20,0x00, // < 28
0x40,0x40,0x40,0x40,0x40,0x40,0x40,0x00,0x04,0x04,0x04,0x04,0x04,0x04,0x04,0x00, // = 29
0x00,0x08,0x10,0x20,0x40,0x80,0x00,0x00,0x00,0x20,0x10,0x08,0x04,0x02,0x01,0x00, // > 30
0x00,0x70,0x48,0x08,0x08,0x08,0xF0,0x00,0x00,0x00,0x00,0x30,0x36,0x01,0x00,0x00, // ? 31
0xC0,0x30,0xC8,0x28,0xE8,0x10,0xE0,0x00,0x07,0x18,0x27,0x24,0x23,0x14,0x0B,0x00, // @ 32
0x00,0x00,0xC0,0x38,0xE0,0x00,0x00,0x00,0x20,0x3C,0x23,0x02,0x02,0x27,0x38,0x20, // A 33
0x08,0xF8,0x88,0x88,0x88,0x70,0x00,0x00,0x20,0x3F,0x20,0x20,0x20,0x11,0x0E,0x00, // B 34
0xC0,0x30,0x08,0x08,0x08,0x08,0x38,0x00,0x07,0x18,0x20,0x20,0x20,0x10,0x08,0x00, // C 35
0x08,0xF8,0x08,0x08,0x08,0x10,0xE0,0x00,0x20,0x3F,0x20,0x20,0x20,0x10,0x0F,0x00, // D 36
0x08,0xF8,0x88,0x88,0xE8,0x08,0x10,0x00,0x20,0x3F,0x20,0x20,0x23,0x20,0x18,0x00, // E 37
0x08,0xF8,0x88,0x88,0xE8,0x08,0x10,0x00,0x20,0x3F,0x20,0x00,0x03,0x00,0x00,0x00, // F 38
0xC0,0x30,0x08,0x08,0x08,0x38,0x00,0x00,0x07,0x18,0x20,0x20,0x22,0x1E,0x02,0x00, // G 39
0x08,0xF8,0x08,0x00,0x00,0x08,0xF8,0x08,0x20,0x3F,0x21,0x01,0x01,0x21,0x3F,0x20, // H 40
0x00,0x08,0x08,0xF8,0x08,0x08,0x00,0x00,0x00,0x20,0x20,0x3F,0x20,0x20,0x00,0x00, // I 41
0x00,0x00,0x08,0x08,0xF8,0x08,0x08,0x00,0xC0,0x80,0x80,0x80,0x7F,0x00,0x00,0x00, // J 42
0x08,0xF8,0x88,0xC0,0x28,0x18,0x08,0x00,0x20,0x3F,0x20,0x01,0x26,0x38,0x20,0x00, // K 43
0x08,0xF8,0x08,0x00,0x00,0x00,0x00,0x00,0x20,0x3F,0x20,0x20,0x20,0x20,0x30,0x00, // L 44
0x08,0xF8,0xF8,0x00,0xF8,0xF8,0x08,0x00,0x20,0x3F,0x00,0x3F,0x00,0x3F,0x20,0x00, // M 45
0x08,0xF8,0x30,0xC0,0x00,0x08,0xF8,0x08,0x20,0x3F,0x20,0x00,0x07,0x18,0x3F,0x00, // N 46
0xE0,0x10,0x08,0x08,0x08,0x10,0xE0,0x00,0x0F,0x10,0x20,0x20,0x20,0x10,0x0F,0x00, // O 47
0x08,0xF8,0x08,0x08,0x08,0x08,0xF0,0x00,0x20,0x3F,0x21,0x01,0x01,0x01,0x00,0x00, // P 48
0xE0,0x10,0x08,0x08,0x08,0x10,0xE0,0x00,0x0F,0x18,0x24,0x24,0x38,0x50,0x4F,0x00, // Q 49
0x08,0xF8,0x88,0x88,0x88,0x88,0x70,0x00,0x20,0x3F,0x20,0x00,0x03,0x0C,0x30,0x20, // R 50
0x00,0x70,0x88,0x08,0x08,0x08,0x38,0x00,0x00,0x38,0x20,0x21,0x21,0x22,0x1C,0x00, // S 51
0x18,0x08,0x08,0xF8,0x08,0x08,0x18,0x00,0x00,0x00,0x20,0x3F,0x20,0x00,0x00,0x00, // T 52
0x08,0xF8,0x08,0x00,0x00,0x08,0xF8,0x08,0x00,0x1F,0x20,0x20,0x20,0x20,0x1F,0x00, // U 53
0x08,0x78,0x88,0x00,0x00,0xC8,0x38,0x08,0x00,0x00,0x07,0x38,0x0E,0x01,0x00,0x00, // V 54
0xF8,0x08,0x00,0xF8,0x00,0x08,0xF8,0x00,0x03,0x3C,0x07,0x00,0x07,0x3C,0x03,0x00, // W 55
0x08,0x18,0x68,0x80,0x80,0x68,0x18,0x08,0x20,0x30,0x2C,0x03,0x03,0x2C,0x30,0x20, // X 56
0x08,0x38,0xC8,0x00,0xC8,0x38,0x08,0x00,0x00,0x00,0x20,0x3F,0x20,0x00,0x00,0x00, // Y 57
0x10,0x08,0x08,0x08,0xC8,0x38,0x08,0x00,0x20,0x38,0x26,0x21,0x20,0x20,0x18,0x00, // Z 58
0x00,0x00,0x00,0xFE,0x02,0x02,0x02,0x00,0x00,0x00,0x00,0x7F,0x40,0x40,0x40,0x00, // [ 59
0x00,0x0C,0x30,0xC0,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x01,0x06,0x38,0xC0,0x00, // \ 60
0x00,0x02,0x02,0x02,0xFE,0x00,0x00,0x00,0x00,0x40,0x40,0x40,0x7F,0x00,0x00,0x00, // ] 61
0x00,0x00,0x04,0x02,0x02,0x02,0x04,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, // ^ 62
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80, // _ 63
0x00,0x02,0x02,0x04,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, // ` 64
0x00,0x00,0x80,0x80,0x80,0x80,0x00,0x00,0x00,0x19,0x24,0x22,0x22,0x22,0x3F,0x20, // a 65
0x08,0xF8,0x00,0x80,0x80,0x00,0x00,0x00,0x00,0x3F,0x11,0x20,0x20,0x11,0x0E,0x00, // b 66
0x00,0x00,0x00,0x80,0x80,0x80,0x00,0x00,0x00,0x0E,0x11,0x20,0x20,0x20,0x11,0x00, // c 67
0x00,0x00,0x00,0x80,0x80,0x88,0xF8,0x00,0x00,0x0E,0x11,0x20,0x20,0x10,0x3F,0x20, // d 68
0x00,0x00,0x80,0x80,0x80,0x80,0x00,0x00,0x00,0x1F,0x22,0x22,0x22,0x22,0x13,0x00, // e 69
0x00,0x80,0x80,0xF0,0x88,0x88,0x88,0x18,0x00,0x20,0x20,0x3F,0x20,0x20,0x00,0x00, // f 70
0x00,0x00,0x80,0x80,0x80,0x80,0x80,0x00,0x00,0x6B,0x94,0x94,0x94,0x93,0x60,0x00, // g 71
0x08,0xF8,0x00,0x80,0x80,0x80,0x00,0x00,0x20,0x3F,0x21,0x00,0x00,0x20,0x3F,0x20, // h 72
0x00,0x80,0x98,0x98,0x00,0x00,0x00,0x00,0x00,0x20,0x20,0x3F,0x20,0x20,0x00,0x00, // i 73
0x00,0x00,0x00,0x80,0x98,0x98,0x00,0x00,0x00,0xC0,0x80,0x80,0x80,0x7F,0x00,0x00, // j 74
0x08,0xF8,0x00,0x00,0x80,0x80,0x80,0x00,0x20,0x3F,0x24,0x02,0x2D,0x30,0x20,0x00, // k 75
0x00,0x08,0x08,0xF8,0x00,0x00,0x00,0x00,0x00,0x20,0x20,0x3F,0x20,0x20,0x00,0x00, // l 76
0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x00,0x20,0x3F,0x20,0x00,0x3F,0x20,0x00,0x3F, // m 77
0x80,0x80,0x00,0x80,0x80,0x80,0x00,0x00,0x20,0x3F,0x21,0x00,0x00,0x20,0x3F,0x20, // n 78
0x00,0x00,0x80,0x80,0x80,0x80,0x00,0x00,0x00,0x1F,0x20,0x20,0x20,0x20,0x1F,0x00, // o 79
0x80,0x80,0x00,0x80,0x80,0x00,0x00,0x00,0x80,0xFF,0xA1,0x20,0x20,0x11,0x0E,0x00, // p 80
0x00,0x00,0x00,0x80,0x80,0x80,0x80,0x00,0x00,0x0E,0x11,0x20,0x20,0xA0,0xFF,0x80, // q 81
0x80,0x80,0x80,0x00,0x80,0x80,0x80,0x00,0x20,0x20,0x3F,0x21,0x20,0x00,0x01,0x00, // r 82
0x00,0x00,0x80,0x80,0x80,0x80,0x80,0x00,0x00,0x33,0x24,0x24,0x24,0x24,0x19,0x00, // s 83
0x00,0x80,0x80,0xE0,0x80,0x80,0x00,0x00,0x00,0x00,0x00,0x1F,0x20,0x20,0x00,0x00, // t 84
0x80,0x80,0x00,0x00,0x00,0x80,0x80,0x00,0x00,0x1F,0x20,0x20,0x20,0x10,0x3F,0x20, // u 85
0x80,0x80,0x80,0x00,0x00,0x80,0x80,0x80,0x00,0x01,0x0E,0x30,0x08,0x06,0x01,0x00, // v 86
0x80,0x80,0x00,0x80,0x00,0x80,0x80,0x80,0x0F,0x30,0x0C,0x03,0x0C,0x30,0x0F,0x00, // w 87
0x00,0x80,0x80,0x00,0x80,0x80,0x80,0x00,0x00,0x20,0x31,0x2E,0x0E,0x31,0x20,0x00, // x 88
0x80,0x80,0x80,0x00,0x00,0x80,0x80,0x80,0x80,0x81,0x8E,0x70,0x18,0x06,0x01,0x00, // y 89
0x00,0x80,0x80,0x80,0x80,0x80,0x80,0x00,0x00,0x21,0x30,0x2C,0x22,0x21,0x30,0x00, // z 90
0x00,0x00,0x00,0x00,0x80,0x7C,0x02,0x02,0x00,0x00,0x00,0x00,0x00,0x3F,0x40,0x40, // { 91
0x00,0x00,0x00,0x00,0xFF,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0xFF,0x00,0x00,0x00, // | 92
0x00,0x02,0x02,0x7C,0x80,0x00,0x00,0x00,0x00,0x40,0x40,0x3F,0x00,0x00,0x00,0x00, // } 93
0x00,0x06,0x01,0x01,0x02,0x02,0x04,0x04,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00, // ~ 94
};
#endif /* __OLED_FONT_H */
/*---------------------------- END OF FILE ----------------------------*/

25
Lib/stdint.h Normal file
View File

@ -0,0 +1,25 @@
/* stdint.h - 用于 51 单片机的自定义标准整数类型定义 */
#ifndef __STDINT_H__
#define __STDINT_H__
/* 精确宽度整数类型 */
typedef unsigned char uint8_t; // 无符号 8-bit
typedef signed char int8_t; // 有符号 8-bit
typedef unsigned int uint16_t; // 无符号 16-bit (Keil C51中int是16位)
typedef signed int int16_t; // 有符号 16-bit
typedef unsigned long uint32_t; // 无符号 32-bit
typedef signed long int32_t; // 有符号 32-bit
/* 快速最小宽度类型(按编译器最优选择)*/
typedef unsigned char uint_fast8_t;
typedef unsigned int uint_fast16_t;
typedef unsigned long uint_fast32_t;
/* 指针类型51 单片机为 8/16 位地址)*/
typedef unsigned char uintptr_t; // 数据指针8位
typedef unsigned int uintptr16_t;// 代码指针16位
#endif /* __STDINT_H__ */

28
Src/config.h Normal file
View File

@ -0,0 +1,28 @@
#ifndef __CONFIG_H__
#define __CONFIG_H__
#include "stdint.h"
//#define NDEBUG //取消断言
#include <assert.h> // 断言库
#include <intrins.h>
#include <STC15.H>
#define FOSC 30000000UL // 定义系统频率
typedef uint32_t u32;
typedef uint16_t u16;
typedef uint8_t u8;
#define True 1
#define False 0
sbit SDA = P2^7;
sbit SCL = P2^6;
#endif

76
Src/main.c Normal file
View File

@ -0,0 +1,76 @@
//System
#include <stdio.h>
#include <stdint.h>
#include <STC15.H>
// Driver
#include "uart.h"
#include "iic.h"
// Config
#include "config.h"
// Lib
#include "delay.h"
#include "oled12864_drv.h"
void SystemClock_Init(void) {
// 烧录时选择30M主频
CLK_DIV = 0x00; // 时钟不分频30MHz直接输出
}
void main() {
u8 addr;
SystemClock_Init(); // 时钟配置
EA = 1; // 开总中断
Delay_Init();
Uart1_Init();
printf("IIC_Init()\r\n");
IIC_Init();
printf("OLED_Init()\r\n");
OLED_Init();
DelayMs(100); // 初始化延时
printf("OLED_ShowPrintf()\r\n");
OLED_ShowPrintf(0, 0, "Hello, oWorld!", OLED_FONT_SIXTEEN, OLED_LEFT_ROLL, OLED_SHOW);
OLED_ShowPrintf(0, 2, "Hello, 2World!", OLED_FONT_SIXTEEN, OLED_LEFT_ROLL, OLED_CLS);
OLED_ShowPrintf(0, 1, "Hello, 1Worl2d!", OLED_FONT_SIXTEEN, OLED_LEFT_ROLL, OLED_CLS);
OLED_ShowPrintf(0, 4, "Hello, 4Wo4rld!", OLED_FONT_SIXTEEN, OLED_LEFT_ROLL, OLED_CLS);
OLED_ShowNum(4, 6, 123456789, 10, OLED_FONT_SIXTEEN, OLED_LEFT_ROLL, OLED_SHOW);
while(1) {
printf("Scanning I2C bus...\r\n");
for(addr = 0x08; addr <= 0x78; addr++) { // 有效地址范围
IIC_Start();
IIC_SendByte(addr << 1); // 发送写命令
if(IIC_WaitAck()) {
printf("Device found at: 0x%02X\n", addr);
}
IIC_Stop();
DelayMs(1);
}
printf("Scan complete.\n");
DelayMs(1000);
}
}
void Uart1_Isr(void) interrupt 4
{
if (TI) //检测串口1发送中断
{
TI = 0; //清除串口1发送中断请求位
}
if (RI) //检测串口1接收中断
{
RI = 0; //清除串口1接收中断请求位
}
}