从dunnan_anlogic分支迁移代码;调整部分文件目录;增加UI独立进程,负责液晶显示、按键输入、关键日志(滚轴张数)记录及休眠处理

This commit is contained in:
gb 2024-01-09 14:26:46 +08:00
parent 8f294f8bf6
commit e3a746c49f
33 changed files with 2733 additions and 243 deletions

View File

@ -6,7 +6,7 @@
#include <thread> #include <thread>
#include "../uart/uartregsaccess.h" #include "../uart/uartregsaccess.h"
#include <iostream> #include <iostream>
#include "../uart/Gpio.h" #include <uart/Gpio.h>
#include <base/utils.h> #include <base/utils.h>
#define Reg(x) (fpgaParams.x) #define Reg(x) (fpgaParams.x)

File diff suppressed because one or more lines are too long

View File

@ -27,11 +27,12 @@ class MotorBoard;
class scanner_hw : public sane_opt_provider class scanner_hw : public sane_opt_provider
{ {
std::function<IMAGE_HANDLER_PROTO> img_handler_ = std::function<IMAGE_HANDLER_PROTO>(); std::function<IMAGE_HANDLER_PROTO> img_handler_ = std::function<IMAGE_HANDLER_PROTO>();
bool scanning_ = false; volatile bool scanning_ = false;
int time_to_exit_auto_scan_ = 60; // seconds int time_to_exit_auto_scan_ = 60; // seconds
std::unique_ptr<FpgaComm> img_controller_; std::unique_ptr<FpgaComm> img_controller_;
std::unique_ptr<GVideoISP1> camera_; std::unique_ptr<GVideoISP1> camera_;
std::unique_ptr<MotorBoard> motor_; std::unique_ptr<MotorBoard> motor_;
std::unique_ptr<std::thread> scan_thread_;
enum enum
{ {
@ -50,6 +51,7 @@ class scanner_hw : public sane_opt_provider
std::string family_ = "G200"; std::string family_ = "G200";
volatile bool auto_scan_ = false; volatile bool auto_scan_ = false;
int scan_count_ = -1; int scan_count_ = -1;
int cis_length_ = 1632;
int dpi_ = 300; int dpi_ = 300;
int baud_ = 921600; int baud_ = 921600;
int delay_ = 1000; int delay_ = 1000;
@ -559,6 +561,21 @@ public:
// }, // },
// "depend": "is-check-askew==true" // "depend": "is-check-askew==true"
// }, // },
// "cis-len": {
// "cat": "base",
// "group": "关于",
// "title": "镜头长",
// "desc": "图像采集镜头的长度单位为毫米mm",
// "type": "int",
// "ui-pos": 30,
// "auth": 0,
// "unit": "mm",
// "readonly": true,
// "size": 4,
// "auto": false,
// "cur": 1632,
// "default": 1632
// },
// "motor-ver": { // "motor-ver": {
// "cat": "none", // "cat": "none",
// "group": "关于", // "group": "关于",
@ -589,3 +606,4 @@ public:
// "default": "" // "default": ""
// } // }
// } // }

View File

@ -4,45 +4,59 @@
#include "../uart/PinMonitor.h" #include "../uart/PinMonitor.h"
#include "../uart/uartregsaccess.h" #include "../uart/uartregsaccess.h"
#include <iomanip> #include <iomanip>
// #include "StateControl.h"
// #include "MotorConfig.h"
#include <bitset>
// #include "SensorConfig.h"
#include <base/utils.h> #include <base/utils.h>
#include <base/ui.h>
#define MOTOR_UART "/dev/ttyS4" #define MOTOR_UART "/dev/ttyS4"
static const std::string loggername = "MotorBoard"; static const std::string loggername = "MotorBoard";
MotorBoard::MotorBoard(std::function<void(int, unsigned int)> cbev) MotorBoard::MotorBoard(std::function<void(int, unsigned int)> evcb)
: devPort(MOTOR_UART) : devPort(MOTOR_UART), event_cb_(evcb)
, cb_event_(cbev) , autopaperkeystop(nullptr)
{ {
auto cb_null = [&](int type, unsigned int val) -> void auto empty_cb = [&](int t, unsigned int v) -> void
{ {
utils::to_log(LOG_LEVEL_DEBUG, "motorboard event %d value: 0x%08x\n", type, val); utils::to_log(LOG_LEVEL_DEBUG, "motorboard event(%d, 0x%08x)\n", t, v);
}; };
if(!event_cb_)
event_cb_ = empty_cb;
if(!cb_event_) // LOG_INIT();
cb_event_ = cb_null; //m_uartEnable.reset(new GpioOut(149));
m_uartEnable.reset(new GpioOut(152));
m_uartEnable->setDirection(Gpio::out);
// m_uartEnable->setEdge(Gpio::rising);
//m_uartEnable->setValue(Gpio::Low); //m_uartEnable->setValue(Gpio::Low);
std::this_thread::sleep_for(std::chrono::milliseconds(10)); std::this_thread::sleep_for(std::chrono::milliseconds(10));
m_regsAccess.reset(new UartRegsAccess(devPort, bauds, 0x07, 0x87)); m_regsAccess.reset(new UartRegsAccess(devPort, bauds, 0x07, 0x87));
m_intPinMonitor.reset(new PinMonitor(intport, std::bind(&MotorBoard::pin_call, this, std::placeholders::_1))); m_intPinMonitor.reset(new PinMonitor(intport, std::bind(&MotorBoard::pin_call, this, std::placeholders::_1)));
//m_scansensorMonitor.reset(new PinMonitor(149, std::bind(&MotorBoard::scansensor_call, this, std::placeholders::_1)));
//m_uartEnable->setValue(Gpio::High); //m_uartEnable->setValue(Gpio::High);
std::this_thread::sleep_for(std::chrono::milliseconds(10)); std::this_thread::sleep_for(std::chrono::milliseconds(10));
m_os_mode = os_mode(); m_os_mode = os_mode();
// m_statecontrol.reset(new StateControl(m_regsAccess,wake));
init_sensor_duty();
} }
static int paperinnum = 0; static int paperinnum = 0;
void MotorBoard::start() void MotorBoard::start(void)
{ {
keep_last_paper=false; keep_last_paper=false;
paperinnum = 0 ; paperinnum = 0;
m_paperout_count = 0;
clear_error();
set_time_error(120);
// set_double_inpect(m_config.g200params.double_feed_enbale);
// set_staple_inpect(m_config.g200params.stable_enbale);
// set_paper_inspect(0);
// set_auto_paper(m_config.g200params.is_autopaper,m_config.g200params.en_anlogic_key);
// set_screw_inpect(m_config.g200params.screw_detect_enable);
// set_screw_level(m_config.g200params.screw_detect_level);
// set_long_paper(true);
// set_double_out_en(m_config.g200params.double_out_en);
unsigned int val; unsigned int val;
SMBCONFIG *smbc = (SMBCONFIG *)(&val); SMBCONFIG *smbc = (SMBCONFIG *)(&val);
read(0, val); read(0, val);
@ -50,29 +64,80 @@ void MotorBoard::start()
write(0, val); write(0, val);
smbc->enable = 1; smbc->enable = 1;
write(0, val); write(0, val);
en_lifter();
} }
void MotorBoard::stop() void MotorBoard::stop()
{ {
printf("MotorBoard Stop \n");
unsigned int val; unsigned int val;
SMBCONFIG *smbc = (SMBCONFIG *)(&val); SMBCONFIG *smbc = (SMBCONFIG *)(&val);
read(0, val); read(0, val);
smbc->enable = 0; smbc->enable = 0;
write(0, val); write(0, val);
} }
bool MotorBoard::en_lifter()
void MotorBoard::pick_paper(void)
{ {
unsigned int val; unsigned int val;
SMBCONFIG *smbc = (SMBCONFIG *)(&val); SMBCONFIG *smbc = (SMBCONFIG *)(&val);
read(PORT_CONFIG, val); read(0x00, val);
smbc->lifter_en = 1;
write(0x00, val);
smbc->lifter_en = 0;
return write(0x00, val);
}
void MotorBoard::pick_paper(void)
{
unsigned int val,pick_en;
SMBCONFIG *smbc = (SMBCONFIG *)(&val);
read(0x00, val);
smbc->pick_paper = 0; smbc->pick_paper = 0;
write(PORT_CONFIG, val); write(0x00, val);
std::this_thread::sleep_for(std::chrono::microseconds(400));
smbc->pick_paper = 1; smbc->pick_paper = 1;
write(PORT_CONFIG, val); write(0x00, val);
std::string v_str = std::to_string(m_version);
if(v_str.size()<8)
return;
uint32_t date = atoi(v_str.substr(2,6).c_str());
#ifdef G100
if(date < 231115)
return;
#else
if(date < 231122)
return;
#endif
std::this_thread::sleep_for(std::chrono::milliseconds(5));
read(0x09,pick_en);
if(!(pick_en&0xffff))
{
smbc->pick_paper = 0;
write(0x00, val);
std::this_thread::sleep_for(std::chrono::microseconds(400));
smbc->pick_paper = 1;
write(0x00, val);
}
// smbc->pick_paper = 0; // smbc->pick_paper = 0;
// write(PORT_CONFIG, val); // write(0x00, val);
}
void MotorBoard::clean_paper_road(){
unsigned int val;
SMB_FUNC *smbc = (SMB_FUNC *)(&val);
read(6, val);
if(smbc->param.work_mode == 0)
{
smbc->param.func_clean_passthro = 1;
write(6, val);
smbc->param.func_clean_passthro = 0;
write(6, val);
}
else{
printf("\n 非空闲模式不允许清理纸道!!!!");
}
} }
void MotorBoard::clear_error() void MotorBoard::clear_error()
@ -86,21 +151,38 @@ void MotorBoard::clear_error()
write(0, val); write(0, val);
} }
bool MotorBoard::wait_arrival_top(int timeout_ms)
{
return cv_arrival_top.wait(timeout_ms);
}
bool MotorBoard::wait_paper_in(int timeout_ms) bool MotorBoard::wait_paper_in(int timeout_ms)
{ {
return cv_paper_in.wait(timeout_ms); return cv_paper_in.wait(timeout_ms);
} }
bool MotorBoard::wait_paper_out(int timeout_ms)
{
return cv_paper_out.wait(timeout_ms);
}
bool MotorBoard::wait_error(int timeout_ms) bool MotorBoard::wait_error(int timeout_ms)
{ {
return cv_error.wait(timeout_ms); return cv_error.wait(timeout_ms);
} }
bool MotorBoard::wait_paper_out(int timeout_ms)
{
// StopWatch sw;
// LOG_TRACE("wait_paper_out ");
// while(sw.elapsed_ms()<timeout_ms)
// {
// if(m_paperout_count > 0)
// {
// m_paperout_count--;
// return true;
// }
// std::this_thread::sleep_for(std::chrono::milliseconds(1));
// }
// return false;
return cv_paper_out.wait(timeout_ms);
}
bool MotorBoard::wait_done(int timeout_ms) bool MotorBoard::wait_done(int timeout_ms)
{ {
return cv_scan_done.wait(timeout_ms); return cv_scan_done.wait(timeout_ms);
@ -108,16 +190,20 @@ bool MotorBoard::wait_done(int timeout_ms)
int MotorBoard::os_mode() int MotorBoard::os_mode()
{ {
// unsigned int val;
// read(0x02, val);
// SMB_MODE *smb_mode = (SMB_MODE *)&val;
// return smb_mode->scan_mode;
unsigned int val; unsigned int val;
read(PORT_MODE, val); read(0x06,val);
SMB_MODE *smb_mode = (SMB_MODE *)&val; SMB_FUNC smb_func = *(SMB_FUNC*)&val;
return smb_mode->scan_mode; return smb_func.param.work_mode == 1;
} }
bool MotorBoard::paper_ready() bool MotorBoard::paper_ready()
{ {
unsigned int val; unsigned int val;
read(PORT_MODE, val); read(0x02, val);
SMB_MODE *smb_mode = (SMB_MODE *)&val; SMB_MODE *smb_mode = (SMB_MODE *)&val;
return smb_mode->feeding_paper_ready; return smb_mode->feeding_paper_ready;
} }
@ -125,7 +211,7 @@ bool MotorBoard::paper_ready()
bool MotorBoard::is_scanning() bool MotorBoard::is_scanning()
{ {
unsigned int val; unsigned int val;
read(PORT_MODE, val); read(0x02, val);
SMB_MODE *smb_mode = (SMB_MODE *)&val; SMB_MODE *smb_mode = (SMB_MODE *)&val;
return smb_mode->work_status; return smb_mode->work_status;
} }
@ -133,7 +219,7 @@ bool MotorBoard::is_scanning()
int MotorBoard::paper_counter() int MotorBoard::paper_counter()
{ {
unsigned int val; unsigned int val;
read(PORT_MODE, val); read(0x02, val);
SMBMODE *smb_mode = (SMBMODE *)&val; SMBMODE *smb_mode = (SMBMODE *)&val;
return smb_mode->scan_num; return smb_mode->scan_num;
} }
@ -141,11 +227,11 @@ int MotorBoard::paper_counter()
bool MotorBoard::set_paper_inspect_param(unsigned int value /* = 1000 */) bool MotorBoard::set_paper_inspect_param(unsigned int value /* = 1000 */)
{ {
unsigned int val; unsigned int val;
if (!read(PORT_CONFIG_EX, val)) if (!read(0x04, val))
return false; return false;
SMBCONFIGEXT *smb_config_ext = (SMBCONFIGEXT *)&val; SMBCONFIGEXT *smb_config_ext = (SMBCONFIGEXT *)&val;
smb_config_ext->error_range_set = value; smb_config_ext->error_range_set = value;
return write(PORT_CONFIG_EX, val); return write(0x04, val);
} }
bool MotorBoard::get_keeplastpaper(){ bool MotorBoard::get_keeplastpaper(){
@ -155,214 +241,290 @@ bool MotorBoard::get_keeplastpaper(){
bool MotorBoard::set_paper_inpect_info(unsigned int value) bool MotorBoard::set_paper_inpect_info(unsigned int value)
{ {
unsigned int val; unsigned int val;
if (!read(PORT_CONFIG_EX, val)) if (!read(0x04, val))
return false; return false;
SMBCONFIGEXT *smb_config_ext = (SMBCONFIGEXT *)&val; SMBCONFIGEXT *smb_config_ext = (SMBCONFIGEXT *)&val;
smb_config_ext->paper_infor = value; smb_config_ext->paper_infor = value;
return write(PORT_CONFIG_EX, val); return write(0x04, val);
} }
bool MotorBoard::set_paper_inspect(bool enable /* = true */) bool MotorBoard::set_paper_inspect(bool enable /* = true */)
{ {
unsigned int val; unsigned int val;
if (!read(PORT_CONFIG_EX, val)) if (!read(0x04, val))
return false; return false;
SMBCONFIGEXT *smb_config_ext = (SMBCONFIGEXT *)&val; SMBCONFIGEXT *smb_config_ext = (SMBCONFIGEXT *)&val;
smb_config_ext->paper_size_check_en = enable; smb_config_ext->paper_size_check_en = enable;
return write(PORT_CONFIG_EX, val); return write(0x04, val);
} }
bool MotorBoard::set_double_inpect(bool enable) bool MotorBoard::set_double_inpect(bool enable)
{ {
unsigned int val; unsigned int val;
if (!read(PORT_CONFIG, val)) if (!read(0x00, val))
return false; return false;
// enable?m_statecontrol->lcdcontrol(4):m_statecontrol->lcdcontrol(5);
SMBCONFIG *smb_config = (SMBCONFIG *)&val; SMBCONFIG *smb_config = (SMBCONFIG *)&val;
smb_config->double_paper = enable; smb_config->double_paper = enable;
return write(PORT_CONFIG, val); return write(0x00, val);
} }
bool MotorBoard::get_doublle_inpect() bool MotorBoard::get_doublle_inpect()
{ {
return 0;
} }
bool MotorBoard::set_double_out_en(bool enable)
bool MotorBoard::set_auto_paper(bool enable){ {
unsigned int val; unsigned int val;
if (!read(PORT_CONFIG, val)) if (!read(0x00, val))
return false; return false;
SMBCONFIG *smb_config = (SMBCONFIG *)&val; SMBCONFIG *smb_config = (SMBCONFIG *)&val;
smb_config->paper_auto_module = enable; smb_config->double_out_en = enable;
return write(PORT_CONFIG, val); return write(0x00, val);
}
bool MotorBoard::get_double_out_en()
{
unsigned int val;
if (!read(0x00, val))
return false;
SMBCONFIG *smb_config = (SMBCONFIG *)&val;
return smb_config->double_out_en;
} }
bool MotorBoard::set_staple_inpect(bool enable) bool MotorBoard::set_staple_inpect(bool enable)
{ {
unsigned int val; unsigned int val;
if (!read(PORT_CONFIG, val)) if (!read(0x00, val))
return false; return false;
SMBCONFIG *smb_config = (SMBCONFIG *)&val; SMBCONFIG *smb_config = (SMBCONFIG *)&val;
smb_config->staple_enable = enable; smb_config->staple_enable = enable;
return write(PORT_CONFIG, val); return write(0x00, val);
} }
bool MotorBoard::get_staple_inpect() bool MotorBoard::get_staple_inpect()
{ {
return 0;
} }
bool MotorBoard::set_cuospeed(int value)
{
unsigned int val;
if (!read(0x4, val))
return false;
SMBCONFIGEXT *smb_config = (SMBCONFIGEXT *)&val;
smb_config->cuo_speed = value;
return write(0x04, val);
}
// bool MotorBoard::set_en600DPI(bool en)
// {
// unsigned int val;
// if (!read(0x00, val))
// return false;
// SMBCONFIG *smb_config = (SMBCONFIG *)&val;
// smb_config->dpi600 = en?1:0;
// return write(0x00, val);
// }
bool MotorBoard::set_color_mode(int mode) bool MotorBoard::set_color_mode(int mode)
{ {
unsigned int val; unsigned int val;
if (!read(PORT_CONFIG, val)) if (!read(0x00, val))
return false; return false;
SMBCONFIG *smb_config = (SMBCONFIG *)&val; SMBCONFIG *smb_config = (SMBCONFIG *)&val;
smb_config->color_mode = mode; smb_config->color_mode = mode;
return write(PORT_CONFIG, val); return write(0x00, val);
} }
bool MotorBoard::set_slowmoire(bool en){
unsigned int val;
if (!read(0x00, val))
return false;
SMBCONFIG *smb_config = (SMBCONFIG *)&val;
smb_config->slow_moire = en;
return write(0x00, val);
}
int MotorBoard::get_color_mode() int MotorBoard::get_color_mode()
{ {
return 0;
} }
bool MotorBoard::set_speed_mode(int mode) bool MotorBoard::set_speed_mode(int mode)
{ {
unsigned int val; unsigned int val;
if (!read(PORT_CONFIG, val)) if (!read(0x00, val))
return false; return false;
SMBCONFIG *smb_config = (SMBCONFIG *)&val; SMBCONFIG *smb_config = (SMBCONFIG *)&val;
smb_config->speed_set_enable = 1; smb_config->speed_set_enable = 1;
smb_config->v_setting = mode; smb_config->v_setting = mode;
write(PORT_CONFIG, val); write(0x00, val);
smb_config->speed_set_enable = 0; smb_config->speed_set_enable = 0;
return write(PORT_CONFIG, val); return write(0x00, val);
}
bool MotorBoard::set_speed_mode_v_temp(int mode)
{
unsigned int val;
if (!read(0x00, val))
return false;
printf(" set v_tmp = %d \n",mode);
SMBCONFIG *smb_config = (SMBCONFIG *)&val;
smb_config->speed_set_enable = 1;
smb_config->v_temp = mode;
write(0x00, val);
smb_config->speed_set_enable = 0;
return write(0x00, val);
} }
int MotorBoard::get_speed_mode() int MotorBoard::get_speed_mode()
{ {
unsigned int val; unsigned int val;
if (!read(PORT_CONFIG, val)) if (!read(0x00, val))
return -1; return -1;
SMBCONFIG *smb_config = (SMBCONFIG *)&val; SMBCONFIG *smb_config = (SMBCONFIG *)&val;
return smb_config->v_setting; return smb_config->v_setting;
} }
bool MotorBoard::set_cuospeed(unsigned int speed)
{
unsigned int val;
if (!read(PORT_CONFIG_EX, val))
return -1;
SMB_CONFIG_EXT *smb_config = (SMB_CONFIG_EXT *)&val;
smb_config->cuo_speed = speed;
return write(PORT_CONFIG_EX,val);
}
std::shared_ptr<IRegsAccess> MotorBoard::regs() std::shared_ptr<IRegsAccess> MotorBoard::regs()
{ {
return m_regsAccess; return m_regsAccess;
} }
static int countindex =0;
static int pinindex=0;
void MotorBoard::pin_call(unsigned int pinNum) void MotorBoard::pin_call(unsigned int pinNum)
{ {
int os_m = os_mode(); static int index = 0;
if (m_os_mode != os_m) // int os_m = os_mode(); //安路屏蔽计数 扫描过程中无法操作按键
{ // if (m_os_mode != os_m)
m_os_mode = os_m; // {
cv_os_mode.notify_all(); // m_os_mode = os_m;
cb_event_(MOTOR_BORD_EVENT_MODE, m_os_mode); // cv_os_mode.notify_all();
} // if (m_glue.m_os_mode_call)
// m_glue.m_os_mode_call(m_os_mode);
// }
if (m_os_mode) // if (m_os_mode) //安路屏蔽计数返回 以刷新计数状态
{ // {
// utils::to_log(LOG_LEVEL_DEBUG, "not scan mode"); // LOG_TRACE("not scan mode");
return; // return;
} // }
unsigned int val; unsigned int val;
SMBSTATUS *smb_status = (SMBSTATUS *)&val; SMBSTATUS *s = (SMBSTATUS *)&val;
if (!read(PORT_STATUS, val)) if (!read(MB_PORT_STATUS, val))
{ utils::to_log(LOG_LEVEL_FATAL, "read motorboard status failed.\n");
utils::to_log(LOG_LEVEL_DEBUG, "read motorboard status failed\n"); else
return; utils::to_log(LOG_LEVEL_DEBUG, "motorboard status = 0x%08x\n", val);
} if(s->keep_last_paper) // (val & 0x800)
utils::to_log(LOG_LEVEL_DEBUG, utils::format_string("motorboard status %08x\n", val).c_str());
//printf("\n reg 1 val =%d",val);
if(smb_status->keep_last_paper) // (val & 0x800)
{ {
//printf("\n keep_last_paper ");
keep_last_paper=true; keep_last_paper=true;
} }
if(smb_status->sleep_set) // (val & 0x1000) if(s->sleep_set) // (val & 0x1000)
{ {
cb_event_(MOTOR_BORD_EVENT_SLEEP, smb_status->sleep_conf); event_cb_(MOTOR_BORD_EVENT_SLEEP, s->sleep_conf);
} }
if(smb_status->ml_top_sin) // (val & 0x80000) if(s->arrival_top_int) // (val & 0x80000)
{ {
cb_event_(MOTOR_BORD_EVENT_LIFTER_READY, smb_status->ml_top_sin); event_cb_(MOTOR_BORD_EVENT_LIFTER_READY, 1);
} }
if(smb_status->paper_auto) if(s->auto_feed)
{ {
cb_event_(MOTOR_BORD_EVENT_PAPER_READY, smb_status->paper_auto); event_cb_(MOTOR_BORD_EVENT_PAPER_READY, 1);
} }
if (val & STATUS_ERROR_MASK) if (val & 0x7c003FE)
{ {
SetKeyState(false);
cv_error.notify_all(); cv_error.notify_all();
cb_event_(MOTOR_BORD_EVENT_ERROR, val & STATUS_ERROR_MASK); event_cb_(MOTOR_BORD_EVENT_ERROR, val & 0x30efe); //0xefe index of 16:aquireimage error index of bit 17 :size check error
if(val & 0x30efe){
cv_paper_out.notify_all();
m_paperout_count++;
}
errormsg(val & 0x1c003fa);
if((val & 0x4) ||(val & 0x02000000))
{
if(val & 0x4){
PutMsg((int)DisType::Dis_Err_CoverOpen, 0, (int)ClearScreen::All);
set_auto_paper(false,false);
autopaperkeystop?autopaperkeystop():void(0);
// if(m_statecontrol){
// m_statecontrol->setcoverstate(true);
// m_statecontrol->setmenuindex(0);
// }
}
else{
PutMsg((int)DisType::Dis_Idel,0,(int)ClearScreen::All);
// m_statecontrol?m_statecontrol->setcoverstate(false):void();
}
return;
}
// if(smb_status->double_clean_f)
PutMsg((int)DisType::Dis_Idel,0,(int)ClearScreen::All);
return; return;
} }
else else
{ {
if (!smb_status->scan_pulse) if (!s->scan_pulse)
{ {
cv_paper_in.notify_all(); cv_paper_in.notify_all();
paperinnum++; unsigned int papercount = 0;
cb_event_(MOTOR_BORD_EVENT_PAPER_PASSING, 1); read(0x02,papercount);
SMBMODE smbmode = *(SMBMODE*)&papercount;
printf("paper in arm count = %d ,motorcount = %d\n",++countindex,smbmode.scan_num);
startcapimage(true);
PutMsg((int)DisType::Dis_Scan_Page, smbmode.scan_num,(int)ClearScreen::BOT);
} }
if(s->paper_left)
if(smb_status->paper_left)
{ {
cv_paper_out.notify_all(); cv_paper_out.notify_all();
cb_event_(MOTOR_BORD_EVENT_PAPER_PASSING, 0); m_paperout_count++;
//printf("paper out time = %s \n",GetCurrentTimeStamp(2).c_str());
startcapimage(true);
utils::to_log(LOG_LEVEL_DEBUG, "m_paperout_count %d\n", (unsigned int)m_paperout_count);
} }
} }
if (smb_status->motor_status) // (val & 0x400) if (val & 0x400)
{ {
cv_scan_done.notify_all(); cv_scan_done.notify_all();
cb_event_(MOTOR_BORD_EVENT_SCAN_DONE, 1); event_cb_(MOTOR_BORD_EVENT_SCAN_DONE, 1);
cv_paper_out.notify_all();
clear_error();
SetKeyState(false);
} }
} }
void MotorBoard::scansensor_call(unsigned int pinNum)
{
// static int indexscansensor=0;
// m_uartEnable->setValue(Gpio::High);
// utils::to_log(LOG_LEVEL_DEBUG, string_format(" gpio149 call times -%d ", indexscansensor++));
// cv_paper_in.notify_all();
// m_uartEnable->setValue(Gpio::Low);
}
bool MotorBoard::write(unsigned int addr, unsigned int val) bool MotorBoard::write(unsigned int addr, unsigned int val)
{ {
return m_regsAccess->write(addr, val); return m_regsAccess.get()?m_regsAccess->write(addr, val):false;
} }
bool MotorBoard::read(unsigned int addr, unsigned int &val) bool MotorBoard::read(unsigned int addr, unsigned int &val)
{ {
return m_regsAccess->read(addr, val); return m_regsAccess.get()?m_regsAccess->read(addr, val):false;
} }
bool MotorBoard::set_time_error(int value){
unsigned int val;
if (!read(0x05, val))
return false;
SMBCONFIGTIME *smb_config = (SMBCONFIGTIME *)&val;
smb_config->error_time_set = value;
return write(0x05, val);
}
bool MotorBoard::set_screw_inpect(bool enable) bool MotorBoard::set_screw_inpect(bool enable)
{ {
unsigned int val; unsigned int val;
if (!read(PORT_CONFIG, val)) if (!read(0x00, val))
return false; return false;
SMBCONFIG *smb_config = (SMBCONFIG *)&val; SMBCONFIG *smb_config = (SMBCONFIG *)&val;
smb_config->skew_enable = enable; smb_config->skew_enable = enable;
return write(PORT_CONFIG, val); return write(0x00, val);
} }
bool MotorBoard::get_screw_inpect() bool MotorBoard::get_screw_inpect()
{ {
unsigned int val; unsigned int val;
read(PORT_CONFIG, val); read(0x00, val);
SMBCONFIG *smb_mode = (SMBCONFIG *)&val; SMBCONFIG *smb_mode = (SMBCONFIG *)&val;
return smb_mode->skew_enable; return smb_mode->skew_enable;
} }
@ -370,50 +532,175 @@ bool MotorBoard::get_screw_inpect()
bool MotorBoard::set_screw_level(int level) bool MotorBoard::set_screw_level(int level)
{ {
unsigned int val; unsigned int val;
if (!read(PORT_CONFIG, val)) if (!read(0x00, val))
return false; return false;
SMBCONFIG *smb_config = (SMBCONFIG *)&val; SMBCONFIG *smb_config = (SMBCONFIG *)&val;
smb_config->skew_parameter = level; smb_config->skew_parameter = level;
return write(PORT_CONFIG, val); return write(0x00, val);
}
bool MotorBoard::set_auto_paper(bool enable,bool enkey){
unsigned int val;
if (!read(0x00, val))
return false;
// m_statecontrol?m_statecontrol->setautopaperflag(enable,enkey):void(0);
SMBCONFIG *smb_config = (SMBCONFIG *)&val;
smb_config->autofeed_mode = enable;
return write(0x00, val);
} }
bool MotorBoard::set_long_paper(bool enable) bool MotorBoard::set_long_paper(bool enable)
{ {
unsigned int val; unsigned int val;
if (!read(PORT_CONFIG, val)) if (!read(0x00, val))
return false; return false;
SMBCONFIG *smb_config = (SMBCONFIG *)&val; SMBCONFIG *smb_config = (SMBCONFIG *)&val;
smb_config->paper = enable; smb_config->paper = enable;
return write(PORT_CONFIG, val); return write(0x00, val);
} }
int MotorBoard::get_screw_level() int MotorBoard::get_screw_level()
{ {
unsigned int val; unsigned int val;
auto ret= read(PORT_CONFIG, val); auto ret= read(0x00, val);
if(!ret) if(!ret)
return -1; return -1;
SMBCONFIG *smb_mode = (SMBCONFIG *)&val; SMBCONFIG *smb_mode = (SMBCONFIG *)&val;
return smb_mode->skew_parameter; return smb_mode->skew_parameter;
} }
bool MotorBoard::en_testbit(bool en) void MotorBoard::start_countmode()
{ {
unsigned int val; unsigned int regval=0;
auto ret= read(PORT_CONFIG, val);
if(!ret) read(0x06,regval);
return -1; utils::to_log(LOG_LEVEL_DEBUG, "func6 regval = 0x%08x\n", regval);
SMBCONFIG *smb_mode = (SMBCONFIG *)&val; SMBFUNC func = *(SMBFUNC*)&regval;
smb_mode->testbit = en?1:0; func.param.work_mode =1;
return write(PORT_CONFIG,val); func.param.func_feed_mid = 1;
func.param.func_clear_count = 1;
utils::to_log(LOG_LEVEL_DEBUG, "func6 value = 0x%08x\n", func.value);
write(0x06,func.value);
func.param.func_encount = 1;
func.param.key_sound = 1;
func.param.func_clear_count = 0;
utils::to_log(LOG_LEVEL_DEBUG, "func6 value = 0x%08x\n", func.value);
write(0x06,func.value);
func.param.func_encount = 0;
func.param.key_sound = 0;
utils::to_log(LOG_LEVEL_DEBUG, "func6 value = 0x%08x\n",func.value);
write(0x06,func.value);
} }
void MotorBoard::release_statecontrol()
{
set_auto_paper(false);
m_regsAccess.reset();
m_intPinMonitor.reset();
void MotorBoard::PutMsg(int type, int value, int clearscreen)
{
// if(m_statecontrol.get())
// m_statecontrol->PutMsg(type,value,clearscreen);
devui::display_message(type, clearscreen, value);
}
void MotorBoard::errormsg(uint value)
{
// if(value & 0x4)
// PutMsg((int)DisType::Dis_Err_CoverOpen,0,(int)ClearScreen::All);
// else if (value & 0x2)
// PutMsg((int)DisType::Dis_Err_NoPaper,0,(int)ClearScreen::All);
// else if (value & 0x8)
// PutMsg((int)DisType::Dis_Err_FeedError,0,(int)ClearScreen::All);
// // else if (value & 0x10)
// // PutMsg((int)DisType::Dis_Err_JamIn,0,(int)ClearScreen::All);
// else if (value & 0x20)
// PutMsg((int)DisType::Dis_Err_DoubleFeed,0,(int)ClearScreen::All);
// else if (value & 0x40)
// PutMsg((int)DisType::Dis_Err_Stable,0,(int)ClearScreen::All);
// else if (value & 0x80)
// PutMsg((int)DisType::Dis_Err_PaperScrew,0,(int)ClearScreen::All);
// else if (value & 0x00010000)
// PutMsg((int)DisType::Dis_Err_AqrImgTimeout,0,(int)ClearScreen::All);
// else if((value & 0x1000010) == 0x1000010)
// PutMsg((int)DisType::Dis_Err_JamIn,3,(int)ClearScreen::All);
// else if((value & 0x800010) == 0x800010)
// PutMsg((int)DisType::Dis_Err_JamIn,2,(int)ClearScreen::All);
// else if((value & 0x400010) == 0x400010)
// PutMsg((int)DisType::Dis_Err_JamIn,1,(int)ClearScreen::All);
}
void MotorBoard::SetKeyState(bool value)
{
// if(m_statecontrol)
// m_statecontrol->setrunstate(value);
}
void MotorBoard::set_keystopenable(bool value){
unsigned int regval=0;
read(0x06,regval);
utils::to_log(LOG_LEVEL_DEBUG, "func6 regval = 0x%08x\n", regval);
SMBFUNC func = *(SMBFUNC*)&regval;
func.param.key_stop_enable = value;
write(0x06, regval);
}
void MotorBoard::set_freq(int motor_choose,int speedmode,int colormode,int dpi)
{
// MotorConfig cf;
// auto params = cf.GetMotorSpeedParams(motor_choose == 1?0:1,MotorConfig::MTBDType::MT_DRV);
// MotorSpeedParam param;
// //printf("\n---node.dpi ==%d && node.colormode == %d && node.speed == %d----- ",dpi,colormode,speedmode);
// for(auto &node : params)
// {
// if(node.dpi == dpi && node.colormode == colormode && node.speed == speedmode)
// {
// param = node.mt_param;
// //printf("\n-------------------------------------------------");
// break;
// }
// }
// std::vector<std::uint32_t> table;
// if(motor_choose == 0)
// {
// int x = 0; // (dpi == 1?(Get_static_jsonconfig().getscannerinfo().chu_motor_speed_200):(dpi == 2?Get_static_jsonconfig().getscannerinfo().chu_motor_speed_300 : Get_static_jsonconfig().getscannerinfo().chu_motor_speed_600));
// unsigned int regval=0;
// read(0x06,regval);
// SMBFUNC func = *(SMBFUNC*)&regval;
// func.param.motor_choose = motor_choose;
// func.param.wr_en = 1;
// write(0x06,func.value);
// write(0x04,x);
// //func.param.wr_en = 0;
// //write(0x06,func.value);
// return ;
// }
// if(motor_choose == 1)
// table = frep_cfg(param.finalPeriod,param.Fmin,param.stepnum,param.a,param.offset,param.finalDelay,param.acceleration_time);
// if(motor_choose == 2)
// table = frep_cfg(param.finalPeriod,param.Fmin,param.stepnum,param.a,param.offset,param.finalDelay,param.acceleration_time);
// if(motor_choose == 3)
// table = frep_cfg(param.finalPeriod,param.Fmin,param.stepnum,param.a,param.offset,param.finalDelay,param.acceleration_time);
// unsigned int regval=0;
// read(0x06,regval);
// SMBFUNC func = *(SMBFUNC*)&regval;
// int start_addr_cuo = 0;
// #ifdef G200
// if(motor_choose ==1 && speedmode > 1 && dpi <3)
// start_addr_cuo = 63;
// if(motor_choose ==1 && dpi ==3)
// start_addr_cuo = 127;
// #endif
// printf("\nstart_addr_cuo =%d ",start_addr_cuo);
// for(int i =0;i<256;i++)
// {
// func.param.motor_choose = motor_choose;
// func.param.wr_en = 1;
// func.param.motor_addr =i;
// write(0x06,func.value);
// write(0x04,i<start_addr_cuo?0:table[i-start_addr_cuo]);
// //printf("\nfreq= %x addr =%d ",table[i-start_addr_cuo],i);
// }
// func.param.wr_en = 0;
// write(0x06,func.value);
} }
void MotorBoard::init_statecontrol() void MotorBoard::init_statecontrol()
@ -422,4 +709,150 @@ void MotorBoard::init_statecontrol()
m_intPinMonitor.reset(new PinMonitor(intport, std::bind(&MotorBoard::pin_call, this, std::placeholders::_1))); m_intPinMonitor.reset(new PinMonitor(intport, std::bind(&MotorBoard::pin_call, this, std::placeholders::_1)));
std::this_thread::sleep_for(std::chrono::milliseconds(10)); std::this_thread::sleep_for(std::chrono::milliseconds(10));
m_os_mode = os_mode(); m_os_mode = os_mode();
// m_statecontrol.reset(new StateControl(m_regsAccess,m_wake));
// m_statecontrol->setautopaperstopcallback([&]{
// autopaperkeystop?autopaperkeystop():void(0);
// if(m_config.g200params.is_autopaper)
// set_auto_paper(false,false);
// });
init_sensor_duty();
PutMsg((int)DisType::Dis_Idel,0,(int)ClearScreen::All);
} }
void MotorBoard::release_statecontrol()
{
if(autopaperkeystop.operator bool())
autopaperkeystop();
set_auto_paper(false,false);
// m_statecontrol.reset();
m_regsAccess.reset();
m_intPinMonitor.reset();
}
void MotorBoard::setautopaperkeystopcallback(std::function<void()> func){
if(func)
autopaperkeystop = func;
// m_statecontrol?m_statecontrol->setautopaperstopcallback([&]{
// autopaperkeystop?autopaperkeystop():void(0);
// set_auto_paper(false,false);
// }):void(0);
}
void MotorBoard::startcapimage(bool value)
{
// if(m_config.g200params.is_fixedpaper)
// return;
// FILE *fp = fopen("/sys/class/tty/ttyUSB0/device/huagao_scanner", "w");
// if (fp == NULL)
// perror("startcapimage open filed");
// else{
// fprintf(fp, "%d", value ? 1 : 0);
// fclose(fp);
// }
}
bool MotorBoard::set_sensor_pwm_duty(int sensorid,int duty)
{
//1扫描2开盖3歪斜—14歪斜-25出纸口6有无纸
printf("set_sensor_pwm_duty type = %d duty = %d \n",sensorid,duty);
unsigned int val;
if (!read(0x05, val))
return false;
if(sensorid< 1 || sensorid >6)
return false;
if(duty< 2 || duty > 90)
return false;
SMBCONFIGTIME *smb_config_time = (SMBCONFIGTIME *)&val;
smb_config_time->sen_duty_set_sel = sensorid;
smb_config_time->duty_set = duty*8+50;
write(0x05, val);
smb_config_time->sen_duty_set_sel = 0;
return write(0x05, val);
}
bool MotorBoard::enable_sensor_pwm(int sensorid,bool en)
{
std::uint32_t val;
if (!read(0x05, val))
return false;
if(sensorid< 1 || sensorid >6)
return false;
std::bitset<32> bit(val);
bit.set(sensorid+6,en);
val = bit.to_ulong();
printf("enable_sensor_pwm = %d \n",val);
return write(0x05, val);
}
bool MotorBoard::set_ultrasonic_param(int type,int value){
//1双张检测周期2有无纸检测周期3双张阈值4单张阈值
unsigned int val;
if (!read(0x07, val))
return false;
if(type< 1 || type >4)
return false;
printf("set_ultrasonic_param type = %d value = %d \n",type,value);
SMB_Ultrasonic_Config *tmp = (SMB_Ultrasonic_Config *)&val;
switch (type)
{
case 1:
tmp->param.double_check_cyc = value;
break;
case 2:
tmp->param.paper_check_cyc = value;
break;
case 3:
tmp->param.double_max = value;
break;
case 4:
tmp->param.single_max = value;
break;
default:
break;
}
printf("val = %d \n",val);
tmp->param.send_cyc_en = 1;
write(0x07,val);
tmp->param.send_cyc_en = 0;
return write(0x07,val);
}
void MotorBoard::init_sensor_duty()
{
// auto p = Get_Static_SC().get_mem_param();
// std::vector<uint32_t> params(sizeof(SensorConfig::SensorConfig_Param)/sizeof(uint32_t));
// memcpy(&params[0],&p,sizeof(SensorConfig::SensorConfig_Param));
// for(int i = 0;i<params.size();i++){
// if(((i >= 0) || (i < 6)) && (params[i] < 100))
// {
// set_sensor_pwm_duty(i+1,params[i]);
// }
// if((i >= 6) || (i < 10))
// {
// set_ultrasonic_param(i-5,params[i]);
// }
// }
}
std::uint32_t MotorBoard::get_ultrasonic_version(){
unsigned int val;
if (!read(0x07, val))
return 0;
SMB_Ultrasonic_Config *tmp = (SMB_Ultrasonic_Config *)&val;
tmp->param.rd_ver_en = 1;
write(0x07,val);
tmp->param.rd_ver_en = 0;
write(0x07,val);
std::this_thread::sleep_for(std::chrono::milliseconds(10));
read(0x08,val);
return val;
}
std::string MotorBoard::getmbversion(){
uint32_t value = 0;
read(0x03, value);
m_version = value;
printf("mb version: = %s \n", std::to_string(value).c_str());
return std::to_string(value);
}

View File

@ -4,11 +4,36 @@
#include <condition_variable> #include <condition_variable>
#include <functional> #include <functional>
#include "autoevent.hpp" #include "autoevent.hpp"
// #include "commondef.h"
#include <math.h>
#include <vector>
#include <atomic>
//static std::vector<std::uint32_t> frep_cfg(int a,int b,float k,int s)
static std::vector<std::uint32_t> frep_cfg(int finalPeriod, int Fmin, float stepnum, float a, float offset, float finalDelay,float acceleration_time)
{
std::vector<std::uint32_t> freq;
int freq_word = 0;
int pulse_word = 0;
for(int i =1;i<=256;i++)
{
freq_word = 8000000/((Fmin+(finalPeriod-Fmin)/(1+exp((-1)*(offset+a*(double)(i)*stepnum))))*2);
pulse_word = ((8000000/acceleration_time)/63)/freq_word;
//printf("\nfreq_word = %d pulse_word = %d",freq_word,pulse_word);
freq.push_back((pulse_word&0xffff)+((freq_word&0xffff)<<16));
}
return freq;
}
class IRegsAccess; class IRegsAccess;
class PinMonitor; class PinMonitor;
class Gpio; class Gpio;
class ICapturer; // class StateControl;
/*
Arm
*/
typedef struct SMB_CONFIG typedef struct SMB_CONFIG
{ {
@ -16,54 +41,60 @@ typedef struct SMB_CONFIG
unsigned int color_mode : 1; unsigned int color_mode : 1;
unsigned int paper : 1; unsigned int paper : 1;
unsigned int double_paper : 1; unsigned int double_paper : 1;
unsigned int staple_enable : 1; // 5 unsigned int staple_enable : 1;//5
unsigned int error_clean : 1; unsigned int error_clean : 1;
unsigned int status_init : 1; unsigned int status_init : 1;
unsigned int pick_paper : 1; unsigned int pick_paper : 1;
unsigned int skew_enable : 1; unsigned int skew_enable : 1;
unsigned int skew_parameter : 3; // 7 unsigned int skew_parameter : 3;
unsigned int key_staple_enable : 1; unsigned int key_staple_enable : 1;//8
unsigned int iic_config_addr : 7; unsigned int iic_config_addr : 7;
unsigned int iic_config : 1; unsigned int slow_moire : 1;
unsigned int v_setting : 2; // 11 unsigned int v_setting : 2;//10
unsigned int speed_set_enable : 1; unsigned int speed_set_enable : 1;
unsigned int scan_busy_motor_stop : 1; unsigned int double_out_en : 1;
unsigned int sleep_state : 1; unsigned int dpi_mode : 2;
unsigned int sleep_parameter : 3; // 6 // unsigned int sleep_parameter : 2;//6
unsigned int _600dpi : 1; // unsigned int dpi600:1;
unsigned int paper_auto_module : 1; // 2 unsigned int v_temp : 3;
unsigned int testbit : 1; unsigned int autofeed_mode:1;
unsigned int lifter_en:1;
} SMBCONFIG; } SMBCONFIG;
typedef struct SMB_STATUS typedef struct SMB_STATUS
{ {
unsigned int scan_pulse : 1; // 0x000001 unsigned int scan_pulse : 1;
unsigned int m1_paper_sin : 1; // 0x000002 unsigned int m1_paper_sin : 1;
unsigned int open_machine : 1; // 0x000004 unsigned int open_machine : 1;
unsigned int pick_failed : 1; // 0x000008 unsigned int pick_failed : 1;
unsigned int stop_jam : 1; // 5 // 0x000010 unsigned int stop_jam : 1;//5
unsigned int double_paper : 1; // 0x000020 unsigned int double_paper : 1;
unsigned int staple : 1; // 0x000040 unsigned int staple : 1;
unsigned int papertilted : 1; // 0x000080 unsigned int papertilted : 1;
unsigned int count_pulse : 1; // 0x000100 unsigned int count_pulse : 1;
unsigned int scan_mode_change : 1; // 5 // 0x000200 unsigned int scan_mode_change : 1;//5
unsigned int motor_status : 1; // 0x000400 unsigned int motor_status : 1;
unsigned int keep_last_paper : 1; // 0x000800 unsigned int keep_last_paper : 1;
unsigned int sleep_set : 1; // 0x001000 unsigned int sleep_set : 1;
unsigned int sleep_conf : 3; // 0x00e000 unsigned int sleep_conf : 3;//6
unsigned int dsp_get_paper_error : 1; // 0x010000 unsigned int dsp_get_paper_error : 1;
unsigned int paper_check_result : 1; // 0x020000 unsigned int paper_check_result : 1;
unsigned int top_wuzhi : 1; // 0x040000 unsigned int arrival_top:1;//顶部无纸
unsigned int ml_top_sin : 1; // 10 // 0x080000 unsigned int arrival_top_int:1;//到达顶部中断
unsigned int paper_auto : 1; // 0x100000 unsigned int auto_feed:1;//4
unsigned int paper_left : 1; // 0x200000 unsigned int paper_left:1;
unsigned int jam_1 : 1; //进纸口
unsigned int jam_2 : 1; //纸道
unsigned int jam_3 : 1; //出纸口
unsigned int cover_closed : 1; //已关盖
unsigned int double_clean_f : 1; //液晶双张错误清除
} SMBSTATUS; } SMBSTATUS;
#define STATUS_ERROR_MASK 0x30EFE
typedef struct SMB_MODE typedef struct SMB_MODE
{ {
@ -76,7 +107,7 @@ typedef struct SMB_MODE
unsigned int paper_jammed_out : 1; unsigned int paper_jammed_out : 1;
} SMBMODE; } SMBMODE;
//Reg 4
typedef struct SMB_CONFIG_EXT typedef struct SMB_CONFIG_EXT
{ {
unsigned int paper_infor : 5; unsigned int paper_infor : 5;
@ -84,24 +115,70 @@ typedef struct SMB_CONFIG_EXT
unsigned int error_range_set : 15; unsigned int error_range_set : 15;
unsigned int cuo_speed : 7; unsigned int cuo_speed : 7;
} SMBCONFIGEXT; } SMBCONFIGEXT;
//Reg 5
typedef struct SMB_CONFIG_TIME
enum
{ {
PORT_CONFIG = 0, unsigned int error_time_set : 7;
PORT_STATUS, unsigned int scan_ctr_en : 1;
PORT_MODE, unsigned int skew_ctr_en_1 : 1;
PORT_VERSION, unsigned int skew_ctr_en_2 : 1;
PORT_CONFIG_EX = 4, unsigned int open_machine_ctr_en : 1;
}; unsigned int paper_out_ctr_en : 1;
enum unsigned int paper_check_ctr_en : 1;
{ unsigned int sen_duty_set_sel : 3;
SPEED_PPM_BASE = 0, unsigned int duty_set : 10;
SPEED_PPM_BASE_10, } SMBCONFIGTIME;
SPEED_PPM_BASE_20,
SPEED_PPM_BASE_30,
};
//Reg 6
typedef union SMB_FUNC
{
struct{
unsigned int work_mode : 3;
unsigned int func_clean_passthro : 1;
unsigned int func_feed_low : 1;
unsigned int func_feed_mid : 1;
unsigned int func_feed_high : 1;
unsigned int key_sound : 1;
unsigned int key_endouble_feed : 1;
unsigned int func_encount : 1;
unsigned int func_clear_count : 1;
unsigned int motor_choose : 2;
unsigned int wr_en : 1;
unsigned int motor_addr : 8;
unsigned int key_stop_enable : 1;
unsigned int lift_init_set: 2;
}param;
unsigned int value;
} SMBFUNC;
//Reg 7
typedef union SMB_Ultrasonic_Config
{
struct
{
unsigned int double_check_cyc : 4;
unsigned int paper_check_cyc : 4;
unsigned int double_max : 8;
unsigned int single_max : 8;
unsigned int rd_ver_en : 1;
unsigned int send_cyc_en : 1;
unsigned int reserved : 6;
}param;
unsigned int value;
}SMBUltrasonicConfig;
enum motor_board_port
{
MB_PORT_CONFIG = 0,
MB_PORT_STATUS,
MB_PORT_MODE,
MB_PORT_VERSION,
MB_PORT_CONFIG_EX,
MB_PORT_TIME, // ???
MB_PORT_FUNCTION,
MB_PORT_ULTROSONIC,
};
enum enum
{ {
MOTOR_BORD_EVENT_MODE = 1, // os mode changed, value = new mode MOTOR_BORD_EVENT_MODE = 1, // os mode changed, value = new mode
@ -112,15 +189,22 @@ enum
MOTOR_BORD_EVENT_SCAN_DONE, MOTOR_BORD_EVENT_SCAN_DONE,
MOTOR_BORD_EVENT_ERROR, // value = SMBSTATUS MOTOR_BORD_EVENT_ERROR, // value = SMBSTATUS
}; };
enum
{
SPEED_PPM_BASE = 0,
SPEED_PPM_BASE_10,
SPEED_PPM_BASE_20,
SPEED_PPM_BASE_30,
};
class MotorBoard class MotorBoard
{ {
std::function<void(int, unsigned int)> cb_event_; std::function<void(int, unsigned int)> event_cb_;
public: public:
MotorBoard(std::function<void(int, unsigned int)> cbev = std::function<void(int, unsigned int)>()); MotorBoard(std::function<void(int, unsigned int)> evcb = std::function<void(int, unsigned int)>());
void start(); void start(void);
void stop(); void stop();
void clear_error(); void clear_error();
void pick_paper(); void pick_paper();
@ -128,22 +212,27 @@ public:
bool paper_ready(); bool paper_ready();
bool is_scanning(); bool is_scanning();
int paper_counter(); int paper_counter();
bool en_lifter();
bool set_long_paper(bool enable); bool set_long_paper(bool enable);
bool set_double_inpect(bool enable); bool set_double_inpect(bool enable);
bool get_doublle_inpect(); bool get_doublle_inpect();
bool set_double_out_en(bool enable);
bool get_double_out_en();
bool set_staple_inpect(bool enable); bool set_staple_inpect(bool enable);
bool set_auto_paper(bool enable);
bool get_staple_inpect(); bool get_staple_inpect();
bool set_color_mode(int mode); bool set_color_mode(int mode);
int get_color_mode(); int get_color_mode();
int get_speed_mode(); int get_speed_mode();
bool set_auto_paper(bool enable,bool enkey);
bool set_speed_mode(int mode); bool set_speed_mode(int mode);
bool set_speed_mode_v_temp(int mode);
bool set_screw_inpect(bool enable); bool set_screw_inpect(bool enable);
bool get_screw_inpect(); bool get_screw_inpect();
bool set_screw_level(int level); bool set_screw_level(int level);
int get_screw_level(); int get_screw_level();
bool wait_paper_out(int timeout_ms); bool wait_arrival_top(int timeout_ms);
bool wait_paper_in(int timeout_ms); bool wait_paper_in(int timeout_ms);
bool wait_paper_out(int timeout_ms);
bool wait_error(int timeout_ms); bool wait_error(int timeout_ms);
bool wait_done(int timeout_ms); bool wait_done(int timeout_ms);
bool read(unsigned int addr, unsigned int &val); bool read(unsigned int addr, unsigned int &val);
@ -151,31 +240,50 @@ public:
bool set_paper_inspect_param(unsigned int value = 1000); bool set_paper_inspect_param(unsigned int value = 1000);
bool set_paper_inpect_info(unsigned int value); bool set_paper_inpect_info(unsigned int value);
bool set_paper_inspect(bool enable = true); bool set_paper_inspect(bool enable = true);
bool set_cuospeed(unsigned int speed); bool set_cuospeed(int value);
bool get_keeplastpaper(); bool get_keeplastpaper();
bool en_testbit(bool en); //bool set_en600DPI(bool en);
bool set_time_error(int value);
void start_countmode();
std::shared_ptr<IRegsAccess> regs(); std::shared_ptr<IRegsAccess> regs();
void release_statecontrol(); void PutMsg(int type, int value, int clearscreen);
void SetKeyState(bool value);
void set_freq(int motor_choose,int speedmode,int colormode,int dpi);
void set_keystopenable(bool value);
void init_statecontrol(); void init_statecontrol();
void release_statecontrol() __attribute__((optimize("O0")));
void setautopaperkeystopcallback(std::function<void()> func);
void errormsg(uint value);
void startcapimage(bool value);
void clean_paper_road();
bool set_slowmoire(bool en);
bool set_sensor_pwm_duty(int sensorid,int duty);
bool enable_sensor_pwm(int sensorid,bool en);
bool set_ultrasonic_param(int type,int value);
void init_sensor_duty();
std::uint32_t get_ultrasonic_version();
std::string getmbversion();
private: private:
void pin_call(unsigned int pinNum); void pin_call(unsigned int pinNum);
void scansensor_call(unsigned int pinNum);
const std::string devPort; const std::string devPort;
const unsigned int bauds = 921600; const unsigned int bauds = 921600;
const int readflag = 0x07; const int readflag = 0x07;
const int writeflag = 0x87; const int writeflag = 0x87;
const unsigned int intport = 151; const unsigned int intport = 151;
uint32_t m_version;
std::shared_ptr<IRegsAccess> m_regsAccess; std::shared_ptr<IRegsAccess> m_regsAccess;
std::shared_ptr<PinMonitor> m_intPinMonitor; std::shared_ptr<PinMonitor> m_intPinMonitor;
std::shared_ptr<Gpio> m_uartEnable; // std::shared_ptr<StateControl> m_statecontrol;
AutoSemaphore cv_paper_out; std::atomic_uint m_paperout_count;
AutoSemaphore cv_paper_in; AutoSemaphore cv_paper_in;
AutoSemaphore cv_arrival_top;
AutoSemaphore cv_paper_out;
AutoSemaphore cv_error; AutoSemaphore cv_error;
AutoSemaphore cv_scan_done; AutoSemaphore cv_scan_done;
AutoSemaphore cv_os_mode; AutoSemaphore cv_os_mode;
unsigned int m_os_mode; unsigned int m_os_mode;
volatile bool keep_last_paper; volatile bool keep_last_paper;
bool b_paperin; std::function<void()> autopaperkeystop;
}; };

View File

@ -1,6 +1,6 @@
#include "PinMonitor.h" #include "PinMonitor.h"
#include "DevUtil.h" #include <uart/DevUtil.h>
#include <unistd.h> #include <unistd.h>
#include <fcntl.h> #include <fcntl.h>
#include <poll.h> #include <poll.h>

View File

@ -1,5 +1,5 @@
#pragma once #pragma once
#include "Gpio.h" #include <uart/Gpio.h>
#include <thread> #include <thread>
#include <functional> #include <functional>

View File

@ -4,7 +4,7 @@ target("hardware")
set_kind("static") set_kind("static")
add_syslinks("pthread", "dl") add_syslinks("pthread", "dl")
add_includedirs("../sdk") add_includedirs("../sdk")
add_files("*.cpp", "./cis/*.cpp", "./uart/*.cpp", "./motor/*.cpp", "../sdk/base/*.c*", "../sdk/json/*.c*", "../sdk/sane_opt_json/*.c*") add_files("*.cpp", "./cis/*.cpp", "./display/*.cpp", "./uart/*.cpp", "./motor/*.cpp", "../sdk/base/*.c*", "../sdk/uart/*.c*", "../sdk/json/*.c*", "../sdk/sane_opt_json/*.c*")
--add_deps("gusb", "applog") --add_deps("gusb", "applog")
--add_rules("utils.bin2c",{linewidth = 32,extension = {".bin"}}) --add_rules("utils.bin2c",{linewidth = 32,extension = {".bin"}})
--add_files("table.bin") --add_files("table.bin")

View File

@ -14,7 +14,8 @@
#include <huagao/hgscanner_error.h> #include <huagao/hgscanner_error.h>
#include "scanner_const_opts.h" #include "scanner_const_opts.h"
#include <hardware.h> #include <hardware.h>
#include <base/user.h> #include <sane_opt_json/user.h>
#include <base/ui.h>
@ -102,6 +103,7 @@ async_scanner::~async_scanner()
user_->release(); user_->release();
utils::uninit(); utils::uninit();
devui::uninit_ui();
} }
dyn_mem_ptr async_scanner::handle_bulk_cmd(LPPACK_BASE pack, uint32_t* used, packet_data_base_ptr* required) dyn_mem_ptr async_scanner::handle_bulk_cmd(LPPACK_BASE pack, uint32_t* used, packet_data_base_ptr* required)
@ -170,6 +172,14 @@ dyn_mem_ptr async_scanner::handle_bulk_cmd(LPPACK_BASE pack, uint32_t* used, pac
void async_scanner::init(void) void async_scanner::init(void)
{ {
cis_ = new scanner_hw(); cis_ = new scanner_hw();
auto uicb = [this](int ev_type) -> std::string
{
std::string ret("");
return ret;
};
devui::init_ui(uicb);
} }
bool async_scanner::on_energy_conservation(bool normal) bool async_scanner::on_energy_conservation(bool normal)
{ {
@ -440,9 +450,22 @@ dyn_mem_ptr async_scanner::handle_scan_start(LPPACK_BASE pack, uint32_t* used, p
scan_err_ = 0; scan_err_ = 0;
reply_start_ = false; reply_start_ = false;
auto receiver = [this](dyn_mem_ptr, bool, LPPACKIMAGE) -> void auto receiver = [this](dyn_mem_ptr data, bool img, LPPACKIMAGE lpinfo) -> void
{ {
if(img)
{
FILE* dst = fopen(("/tmp/scan_" + std::to_string(lpinfo->pos.paper_ind) + ".bmp").c_str(), "wb");
if(dst)
{
std::string bih(utils::bitmap_info_header(lpinfo->width, lpinfo->height, lpinfo->bpp, lpinfo->resolution_x, lpinfo->resolution_y)),
bfh(utils::bitmap_file_header((BITMAPINFOHEADER*)&bih[0]));
fwrite(bfh.c_str(), 1, bfh.length(), dst);
fwrite(bih.c_str(), 1, bih.length(), dst);
fwrite(data->ptr(), 1, data->get_rest(), dst);
fclose(dst);
}
data->release();
}
}; };
*used = base_head_size; *used = base_head_size;

View File

@ -20,7 +20,7 @@
///////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// /////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
// option json: // option json:
static std::string device_opt_json[] = { static std::string device_opt_json[] = {
"{\"dev-vid\":{\"cat\":\"base\",\"group\":\"\\u5173\\u4e8e\",\"title\":\"USB-VID\",\"desc\":\"\\u8bbe\\u5907\\u5236\\u9020\\u5546\\u5728USB\\u7ec4\\u7ec7\\u7684ID\",\"type\":\"string\",\"fix-id\":34898,\"ui-pos\":10,\"auth\":0,\"readonly\":true,\"size\":16,\"auto\":false,\"cur\":\"3072\",\"default\":\"3072\"},\"dev-pid\":{\"cat\":\"base\",\"group\":\"\\u5173\\u4e8e\",\"title\":\"USB-PID\",\"desc\":\"\\u8bbe\\u5907\\u5728USB\\u7ec4\\u7ec7\\u4e2d\\u7684\\u4ea7\\u54c1ID\",\"type\":\"string\",\"fix-id\":34899,\"ui-pos\":11,\"auth\":0,\"readonly\":true,\"size\":16,\"auto\":false,\"cur\":\"0306\",\"default\":\"0306\"},\"dev-name\":{\"cat\":\"base\",\"group\":\"\\u5173\\u4e8e\",\"title\":\"\\u8bbe\\u5907\\u540d\\u79f0\",\"desc\":\"\\u8bbe\\u5907\\u540d\\u79f0\",\"type\":\"string\",\"fix-id\":34900,\"ui-pos\":12,\"auth\":0,\"readonly\":true,\"size\":96,\"auto\":false,\"cur\":\"300NewTx\",\"default\":\"300NewTx\"},\"dev-model\":{\"cat\":\"base\",\"group\":\"\\u5173\\u4e8e\",\"title\":\"\\u4ea7\\u54c1\\u7cfb\\u5217\",\"desc\":\"\\u8bbe\\u5907\\u6240\\u5c5e\\u4ea7\\u54c1\\u7cfb\\u5217\\u540d\\u79f0\",\"type\":\"string\",\"fix-id\":34901,\"ui-pos\":13,\"auth\":0,\"readonly\":true,\"size\":96,\"auto\":false,\"cur\":\"G300\",\"default\":\"G300\"},\"dev-sn\":{\"cat\":\"base\",\"group\":\"\\u5173\\u4e8e\",\"title\":\"\\u5e8f\\u5217\\u53f7\",\"desc\":\"\\u8bbe\\u5907\\u5e8f\\u5217\\u53f7\",\"type\":\"string\",\"fix-id\":34902,\"ui-pos\":14,\"auth\":0,\"readonly\":true,\"size\":32,\"auto\":false,\"ownread\":true,\"cur\":\"GB20231201\",\"default\":\"GB20231201\"},\"fmw-ver\":{\"cat\":\"base\",\"group\":\"\\u5173\\u4e8e\",\"title\":\"\\u56fa\\u4ef6\\u7248\\u672c\",\"desc\":\"\\u8bbe\\u5907\\u56fa\\u4ef6\\u7248\\u672c\\u53f7\",\"type\":\"string\",\"fix-id\":34903,\"ui-pos\":15,\"auth\":0,\"readonly\":true,\"size\":32,\"auto\":false,\"cur\":\"G2393B0500\",\"default\":\"G2393B0500\"},\"roller-life\":{\"cat\":\"base\",\"group\":\"\\u5173\\u4e8e\",\"title\":\"\\u6eda\\u8f74\\u5bff\\u547d\",\"desc\":\"\\u8be5\\u8bbe\\u5907\\u6eda\\u8f74\\u8fc7\\u7eb8\\u7684\\u6700\\u5927\\u5f20\\u6570\",\"type\":\"int\",\"fix-id\":34907,\"ui-pos\":20,\"auth\":0,\"readonly\":true,\"size\":4,\"auto\":false,\"cur\":450000,\"default\":450000},\"ip-addr\":{\"cat\":\"base\",\"group\":\"\\u5173\\u4e8e\",\"title\":\"IP\",\"desc\":\"\\u8bbe\\u5907\\u8054\\u7f51\\u65f6\\u6240\\u5206\\u914d\\u7684IP\\u5730\\u5740\",\"type\":\"string\",\"fix-id\":34904,\"ui-pos\":21,\"auth\":0,\"readonly\":true,\"size\":96,\"auto\":false,\"ownread\":true,\"cur\":\"0\",\"default\":\"0\"},\"mac-addr\":{\"cat\":\"base\",\"group\":\"\\u5173\\u4e8e\",\"title\":\"MAC\",\"desc\":\"\\u8bbe\\u5907\\u7f51\\u5361\\u5730\\u5740\",\"type\":\"string\",\"fix-id\":34905,\"ui-pos\":22,\"auth\":0,\"readonly\":true,\"size\":96,\"auto\":false,\"ownread\":true,\"cur\":\"0\",\"default\":\"0\"}}" "{\"dev-vid\":{\"cat\":\"base\",\"group\":\"\\u5173\\u4e8e\",\"title\":\"USB-VID\",\"desc\":\"\\u8bbe\\u5907\\u5236\\u9020\\u5546\\u5728USB\\u7ec4\\u7ec7\\u7684ID\",\"type\":\"string\",\"fix-id\":34898,\"ui-pos\":10,\"auth\":0,\"readonly\":true,\"size\":16,\"auto\":false,\"cur\":\"3072\",\"default\":\"3072\"},\"dev-pid\":{\"cat\":\"base\",\"group\":\"\\u5173\\u4e8e\",\"title\":\"USB-PID\",\"desc\":\"\\u8bbe\\u5907\\u5728USB\\u7ec4\\u7ec7\\u4e2d\\u7684\\u4ea7\\u54c1ID\",\"type\":\"string\",\"fix-id\":34899,\"ui-pos\":11,\"auth\":0,\"readonly\":true,\"size\":16,\"auto\":false,\"cur\":\"0306\",\"default\":\"0306\"},\"dev-name\":{\"cat\":\"base\",\"group\":\"\\u5173\\u4e8e\",\"title\":\"\\u8bbe\\u5907\\u540d\\u79f0\",\"desc\":\"\\u8bbe\\u5907\\u540d\\u79f0\",\"type\":\"string\",\"fix-id\":34900,\"ui-pos\":12,\"auth\":0,\"readonly\":true,\"size\":96,\"auto\":false,\"cur\":\"300NewTx\",\"default\":\"300NewTx\"},\"dev-model\":{\"cat\":\"base\",\"group\":\"\\u5173\\u4e8e\",\"title\":\"\\u4ea7\\u54c1\\u7cfb\\u5217\",\"desc\":\"\\u8bbe\\u5907\\u6240\\u5c5e\\u4ea7\\u54c1\\u7cfb\\u5217\\u540d\\u79f0\",\"type\":\"string\",\"fix-id\":34901,\"ui-pos\":13,\"auth\":0,\"readonly\":true,\"size\":96,\"auto\":false,\"cur\":\"G200\",\"default\":\"G200\"},\"dev-sn\":{\"cat\":\"base\",\"group\":\"\\u5173\\u4e8e\",\"title\":\"\\u5e8f\\u5217\\u53f7\",\"desc\":\"\\u8bbe\\u5907\\u5e8f\\u5217\\u53f7\",\"type\":\"string\",\"fix-id\":34902,\"ui-pos\":14,\"auth\":0,\"readonly\":true,\"size\":32,\"auto\":false,\"ownread\":true,\"cur\":\"GB20231201\",\"default\":\"GB20231201\"},\"fmw-ver\":{\"cat\":\"base\",\"group\":\"\\u5173\\u4e8e\",\"title\":\"\\u56fa\\u4ef6\\u7248\\u672c\",\"desc\":\"\\u8bbe\\u5907\\u56fa\\u4ef6\\u7248\\u672c\\u53f7\",\"type\":\"string\",\"fix-id\":34903,\"ui-pos\":15,\"auth\":0,\"readonly\":true,\"size\":32,\"auto\":false,\"cur\":\"G2393B0500\",\"default\":\"G2393B0500\"},\"roller-life\":{\"cat\":\"base\",\"group\":\"\\u5173\\u4e8e\",\"title\":\"\\u6eda\\u8f74\\u5bff\\u547d\",\"desc\":\"\\u8be5\\u8bbe\\u5907\\u6eda\\u8f74\\u8fc7\\u7eb8\\u7684\\u6700\\u5927\\u5f20\\u6570\",\"type\":\"int\",\"fix-id\":34907,\"ui-pos\":20,\"auth\":0,\"readonly\":true,\"size\":4,\"auto\":false,\"cur\":450000,\"default\":450000},\"ip-addr\":{\"cat\":\"base\",\"group\":\"\\u5173\\u4e8e\",\"title\":\"IP\",\"desc\":\"\\u8bbe\\u5907\\u8054\\u7f51\\u65f6\\u6240\\u5206\\u914d\\u7684IP\\u5730\\u5740\",\"type\":\"string\",\"fix-id\":34904,\"ui-pos\":21,\"auth\":0,\"readonly\":true,\"size\":96,\"auto\":false,\"ownread\":true,\"cur\":\"0\",\"default\":\"0\"},\"mac-addr\":{\"cat\":\"base\",\"group\":\"\\u5173\\u4e8e\",\"title\":\"MAC\",\"desc\":\"\\u8bbe\\u5907\\u7f51\\u5361\\u5730\\u5740\",\"type\":\"string\",\"fix-id\":34905,\"ui-pos\":22,\"auth\":0,\"readonly\":true,\"size\":96,\"auto\":false,\"ownread\":true,\"cur\":\"0\",\"default\":\"0\"}}"
}; };

View File

@ -84,8 +84,8 @@ public:
// "readonly": true, // "readonly": true,
// "size": 96, // "size": 96,
// "auto": false, // "auto": false,
// "cur": "G300", // "cur": "G200",
// "default": "G300" // "default": "G200"
// }, // },
// "dev-sn": { // "dev-sn": {
// "cat": "base", // "cat": "base",

View File

@ -55,7 +55,7 @@ typedef struct BITMAPINFOHEADER
u_int32_t biYPelsPerMeter; u_int32_t biYPelsPerMeter;
u_int32_t biClrUsed; u_int32_t biClrUsed;
u_int32_t biClrImportant; u_int32_t biClrImportant;
}BITMAPINFODEADER; }BITMAPINFOHEADER;
#pragma pack(pop) #pragma pack(pop)
#define BI_RGB 0 #define BI_RGB 0
#define MAKEWORD(a, b) (((a) & 0x0ff) | (((b) & 0x0ff) << 8)) #define MAKEWORD(a, b) (((a) & 0x0ff) | (((b) & 0x0ff) << 8))

42
sdk/base/ui.cpp Normal file
View File

@ -0,0 +1,42 @@
#include "ui.h"
#include "utils.h"
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
// ipc class
class ui_messenger
{
public:
ui_messenger()
{}
~ui_messenger()
{}
};
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
// interface
static MUTEX msg_lk_;
static ui_messenger *msgr = nullptr;
namespace devui
{
void init_ui(std::function<std::string(int)> uicb)
{
SIMPLE_LOCK(msg_lk_);
}
void uninit_ui(void)
{
SIMPLE_LOCK(msg_lk_);
if(msgr)
delete msgr;
msgr = nullptr;
}
void display_message(uint32_t msgid, uint8_t clear_mode, uint8_t draw_mode)
{
SIMPLE_LOCK(msg_lk_);
}
};

20
sdk/base/ui.h Normal file
View File

@ -0,0 +1,20 @@
// Purpose: IPC methods between scanner and user-interface (keyboard, monitor, power, ...)
//
// Date: 2024-01-09
//
// Thinking: This module can provide services independently of the scanner-service program
//
#pragma once
#include <functional>
#include <string>
#include "../../ui/Displaydef.h"
namespace devui
{
void init_ui(std::function<std::string(int)> uicb);
void uninit_ui(void);
void display_message(uint32_t msgid, uint8_t clear_mode = (uint8_t)ClearScreen::All, uint8_t draw_mode = (uint8_t)DisDrawtype::DD_All); // see Displaydef.h
};

View File

@ -1245,7 +1245,7 @@ namespace utils
std::string bitmap_info_header(int pixel_w, int pixel_h, int bpp, int dpix, int dpiy) std::string bitmap_info_header(int pixel_w, int pixel_h, int bpp, int dpix, int dpiy)
{ {
BITMAPINFODEADER bih = {0}; BITMAPINFOHEADER bih = {0};
std::string stream(""); std::string stream("");
if(dpiy == 0) if(dpiy == 0)

View File

@ -234,6 +234,7 @@ enum opt_visible_level // "visible" field
#define SANE_STD_OPT_NAME_INITIAL_BOOT_TIME "initial-boot-time" // 设备的初始开机时间 #define SANE_STD_OPT_NAME_INITIAL_BOOT_TIME "initial-boot-time" // 设备的初始开机时间
#define SANE_STD_OPT_NAME_DUMP_IMG "dumpimg" // 是否输出算法各阶段中间图像 #define SANE_STD_OPT_NAME_DUMP_IMG "dumpimg" // 是否输出算法各阶段中间图像
#define SANE_STD_OPT_NAME_DUMP_IMG_PATH "dump-path" // 中间图像输出路径 #define SANE_STD_OPT_NAME_DUMP_IMG_PATH "dump-path" // 中间图像输出路径
#define SANE_STD_OPT_NAME_CIS_LENGTH "cis-len" // CIS 长度(采集图像的最大宽度)
// PART II: 参数类型与华高不一致需要通过“hgsane”组件在中间转换 // PART II: 参数类型与华高不一致需要通过“hgsane”组件在中间转换
#define SANE_STD_OPT_NAME_PAGE_W "page-width" // OPTION_TITLE_ZZCC #define SANE_STD_OPT_NAME_PAGE_W "page-width" // OPTION_TITLE_ZZCC

53
ui/DisplayCenter.cpp Normal file
View File

@ -0,0 +1,53 @@
#include "DisplayCenter.h"
#include "LCDDisplay.h"
DisplayCenter::DisplayCenter() : m_lcd(new LCDDisplay())
,brun(false), m_msgs("DisplayCenter")
{
m_showthread.reset(new std::thread(&DisplayCenter::runloop,this));
m_distype = DisType::Dis_Idel;
}
DisplayCenter::~DisplayCenter()
{
brun = false;
if(m_showthread.get()&& m_showthread->joinable())
{
m_showthread->join();
m_showthread.reset();
}
m_msgs.trigger();
m_msgs.clear();
m_lcd.reset();
}
void DisplayCenter::PutMsg(DisType distype,int pagenum,ClearScreen clearscreen)
{
m_msgs.save({distype,clearscreen,(unsigned int )pagenum,""}, true);
m_distype = distype;
printf("\n ----- distype = %d ",distype);
}
void DisplayCenter::ResetMsgQueue()
{
m_msgs.clear();
}
void DisplayCenter::runloop()
{
brun = true;
while (brun)
{
MsgPair msg;
if(m_msgs.take(msg, true))
m_lcd->DisplayState(msg.distype, msg.pagenum, msg.clearscree);
}
}
DisType DisplayCenter::getcurdistype()
{
return m_distype;
}

31
ui/DisplayCenter.h Normal file
View File

@ -0,0 +1,31 @@
#pragma once
#include <thread>
#include <base/utils.h>
#include "Displaydef.h"
class LCDDisplay;
class DisplayCenter
{
public:
DisplayCenter();
~DisplayCenter();
void PutMsg(DisType distype,int pagenum,ClearScreen clearscreen);
void ResetMsgQueue();
DisType getcurdistype();
private:
struct MsgPair{
DisType distype;
ClearScreen clearscree;
unsigned int pagenum;
std::string infomsg;
};
void runloop();
private:
safe_fifo<MsgPair> m_msgs;
std::shared_ptr<std::thread> m_showthread;
std::shared_ptr<LCDDisplay> m_lcd;
volatile DisType m_distype;
bool brun;
};

70
ui/Displaydef.h Normal file
View File

@ -0,0 +1,70 @@
#pragma once
enum class DisType{
Dis_Unkown,
Dis_Init,//启动欢迎界面
Dis_Welcome,
Dis_Idel,//就绪
Dis_Scan,
Dis_Err_JamIn,
Dis_Err_DoubleFeed,
Dis_Err_PaperScrew,
Dis_Err_Stable,
Dis_Err_AqrImgTimeout,
Dis_Err_CoverOpen,
Dis_Err_JamOut,
Dis_Err_HandModeJam,
Dis_Err_FeedError,
Dis_Err_NoPaper,
Dis_Err_DogEar,
Dis_Err_Size,
Dis_Set_PollPaperIntensity,
Dis_Set_PollPI_High,
Dis_Set_PollPI_Mid,
Dis_Set_PollPI_Low,
Dis_Count_Page,
Dis_Scan_Page,
Dis_Set_ClearPaperPass,
Dis_Set_Count,
Dis_Set_SleepMode,
Dis_Set_SleepMode_5M,
Dis_Set_SleepMode_10M,
Dis_Set_SleepMode_20M,
Dis_Set_SleepMode_30M,
Dis_Set_SleepMode_1H,
Dis_Set_SleepMode_2H,
Dis_Set_SleepMode_4H,
Dis_Set_SleepMode_NEVER,
Dis_Set_Poweroff,
Dis_Set_Return,
Dis_HandMode,
Dis_Set_Item_Return,
Dis_Set_TrayPosition,
Dis_Set_TrayPosition_Low,
Dis_Set_TrayPosition_Mid,
Dis_Set_TrayPosition_High,
Dis_Device_Lock,
Dis_Set_ScanNum_Option,
Dis_Set_Get_History_ScanNum,
Dis_Set_Clear_Roller_ScanNum,
Dis_Set_Get_Roller_ScanNum,
Dis_Set_Is_Sure,
Dis_Set_YES,
Dis_Set_No,
};
enum class DisDrawtype
{
DD_All,
DD_TopLeft,
DD_BotRight
};
enum class ClearScreen
{
All,
TOP,
BOT,
};

573
ui/HgLCDfont.h Normal file
View File

@ -0,0 +1,573 @@
#pragma once
#include "Displaydef.h"
#include <map>
#include <vector>
/*就绪*/
static unsigned char f_ready[]={
0x04,0xE4,0x25,0x26,0x24,0xE4,0x04,0x20,0x20,0xFF,0x20,0xE2,0x2C,0x20,0x20,0x00,
0x10,0x4B,0x82,0x7E,0x02,0x0B,0x90,0x60,0x1C,0x03,0x00,0x3F,0x40,0x40,0x70,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x20,0x30,0xAC,0x63,0x10,0x20,0x24,0x24,0xA4,0x7F,0x24,0x34,0x28,0x26,0x20,0x00,
0x22,0x67,0x22,0x12,0x12,0x04,0x02,0xFF,0x49,0x49,0x49,0x49,0xFF,0x00,0x00,0x00
};
/*图标*/
static unsigned char f_logo[]={
0xFF,0xFF,0xFF,0xFF,0x00,0x00,0x00,0x00,0x00,0x00,0xFF,0xFF,0x00,0x00,0x00,0x00,
0xFF,0xFF,0x00,0x00,0x00,0x00,0x00,0x00,0xFF,0xFF,0xFF,0x00,0x00,0x00,0x00,0x03,
0xFF,0xFF,0xFF,0xFF,0xFF,0xC0,0x00,0x00,0x00,0x00,0x00,0x00,0xC0,0xF0,0xFC,0xFC,
0x3C,0x3F,0x3F,0x3F,0x3C,0x3C,0x3C,0x00,0x00,0x00,0x00,0xC0,0xF0,0xFC,0xFC,0x3C,
0x3F,0x3F,0x3C,0xFC,0xFC,0xF0,0xC0,0x00,0x00,0x00,0x00,0xF0,0xFC,0x3C,0x3F,0x3F,
0x3F,0x3C,0x3C,0x3C,0x00,0x00,0x00,0xC0,0xF0,0xFC,0xFC,0x3F,0x3F,0x3F,0x3F,0x3C,
0x3C,0xFC,0x30,0x00,0x00,0x00,0x00,0x00,0xC3,0xFF,0xFF,0xFF,0xFF,0xFC,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0xFF,0xFF,0xFF,0xFC,0xC0,0x00,0x00,0x00,0x03,0xFF,0xFF,
0xFF,0xFF,0xFF,0xFF,0xF0,0xC0,0xC0,0xC0,0xC0,0xF0,0xFF,0xFF,0x00,0x00,0x00,0x00,
0xFF,0xFF,0x00,0x00,0x00,0x00,0x00,0x00,0xFF,0xFF,0xFF,0x00,0x00,0x00,0xC0,0xFC,
0xFF,0x3F,0x00,0x03,0xFF,0xFF,0xFC,0x00,0x00,0x00,0x00,0xFF,0xFF,0xFF,0x0F,0x00,
0x00,0xC0,0xC0,0xC0,0xC0,0xC0,0xC0,0x00,0x00,0x00,0xC0,0xFF,0xFF,0x03,0x00,0x00,
0x00,0x00,0x00,0x00,0x03,0xFF,0xFF,0xF0,0x00,0x00,0x0F,0xFF,0xFF,0xF0,0xF0,0xC0,
0xC0,0xC0,0x00,0x00,0x00,0x00,0xFC,0xFF,0x0F,0x03,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0xF0,0xFF,0x03,0x00,0x00,0x3F,0xFF,0xFF,0x00,
0x00,0x00,0x00,0x00,0x00,0xFF,0x03,0x0F,0x3F,0xFF,0xFC,0x00,0x00,0x00,0xFF,0xFF,
0xFF,0xFF,0xFF,0xFF,0x07,0x01,0x01,0x01,0x01,0x07,0xFF,0xFF,0x00,0x00,0x00,0x00,
0xFF,0xFF,0x80,0x00,0x00,0x00,0x00,0x00,0xFF,0xFF,0x7F,0x00,0x00,0x80,0xFF,0xFF,
0xF9,0xE0,0xE0,0xE0,0xE0,0xFF,0xFF,0xFF,0xF8,0x00,0x00,0xFF,0xFF,0xFF,0xE0,0x00,
0x00,0x00,0x07,0x07,0x07,0xFF,0xFF,0x00,0x00,0x00,0x01,0xFF,0xFF,0xE0,0x00,0x00,
0x00,0x00,0x00,0x00,0x80,0xFF,0xFF,0x1F,0x00,0x00,0x00,0x00,0x01,0x01,0x07,0x07,
0x1F,0xFF,0xFF,0xF8,0x00,0x00,0x7F,0xFF,0xF8,0x80,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0xE0,0xFE,0xFF,0xFF,0xE0,0xE0,0xE0,0xE0,0xF9,0xFF,0xFE,
0x80,0x00,0x00,0x00,0x00,0xFF,0x00,0x00,0x00,0x01,0x1F,0xF8,0x80,0x80,0xFF,0xFF,
0x7F,0x7F,0x7F,0x7F,0x00,0x00,0x00,0x00,0x00,0x00,0x7F,0x7F,0x00,0x00,0x00,0x00,
0x01,0x1F,0x7F,0x7E,0x78,0x78,0x7E,0x7E,0x1F,0x07,0x00,0x00,0x60,0x7F,0x1F,0x07,
0x01,0x01,0x01,0x01,0x01,0x01,0x07,0x7F,0x7F,0x60,0x00,0x01,0x07,0x1F,0x1F,0x7E,
0x7E,0x78,0x78,0x78,0x78,0x7F,0x7F,0x00,0x00,0x00,0x00,0x07,0x1F,0x1F,0x7E,0x7E,
0x78,0x78,0x7E,0x7E,0x7F,0x1F,0x01,0x00,0x00,0x00,0x00,0x78,0x78,0x78,0x78,0x7E,
0x7E,0x7F,0x1F,0x01,0x00,0x00,0x00,0x01,0x1F,0x7F,0x7E,0x7E,0x78,0x78,0x78,0x7E,
0x7E,0x1E,0x18,0x00,0x78,0x7F,0x7F,0x07,0x01,0x01,0x01,0x01,0x01,0x01,0x07,0x7F,
0x7F,0x78,0x00,0x00,0x00,0x7F,0x00,0x00,0x00,0x00,0x00,0x1F,0x7F,0x7F,0x7F,0x7F
};
/*欢迎使用*/
static unsigned char f_welcome[] = {
0x04,0x24,0x44,0x84,0x64,0x9C,0x40,0x30,0x0F,0xC8,0x08,0x08,0x28,0x18,0x00,0x00,
0x10,0x08,0x06,0x01,0x82,0x4C,0x20,0x18,0x06,0x01,0x06,0x18,0x20,0x40,0x80,0x00,
0x40,0x40,0x42,0xCC,0x00,0x00,0xFC,0x04,0x02,0x00,0xFC,0x04,0x04,0xFC,0x00,0x00,
0x00,0x40,0x20,0x1F,0x20,0x40,0x4F,0x44,0x42,0x40,0x7F,0x42,0x44,0x43,0x40,0x00,
0x80,0x60,0xF8,0x07,0x04,0xE4,0x24,0x24,0x24,0xFF,0x24,0x24,0x24,0xE4,0x04,0x00,
0x00,0x00,0xFF,0x00,0x80,0x81,0x45,0x29,0x11,0x2F,0x41,0x41,0x81,0x81,0x80,0x00,
0x00,0x00,0xFE,0x22,0x22,0x22,0x22,0xFE,0x22,0x22,0x22,0x22,0xFE,0x00,0x00,0x00,
0x80,0x60,0x1F,0x02,0x02,0x02,0x02,0x7F,0x02,0x02,0x42,0x82,0x7F,0x00,0x00,0x00,
};
/*清理纸道*/
static unsigned char f_clearpaperpass[]={
0x10,0x60,0x02,0x8C,0x00,0x44,0x54,0x54,0x54,0x7F,0x54,0x54,0x54,0x44,0x40,0x00,
0x04,0x04,0x7E,0x01,0x00,0x00,0xFF,0x15,0x15,0x15,0x55,0x95,0x7F,0x00,0x00,0x00,
0x04,0x84,0x84,0xFC,0x84,0x84,0x00,0xFE,0x92,0x92,0xFE,0x92,0x92,0xFE,0x00,0x00,
0x20,0x60,0x20,0x1F,0x10,0x10,0x40,0x44,0x44,0x44,0x7F,0x44,0x44,0x44,0x40,0x00,
0x20,0x30,0xAC,0x63,0x30,0x00,0xFC,0x84,0x84,0x84,0xFE,0x82,0x83,0x82,0x80,0x00,
0x22,0x67,0x22,0x12,0x12,0x00,0xFF,0x40,0x20,0x00,0x01,0x0E,0x30,0x40,0xF8,0x00,
0x40,0x40,0x42,0xCC,0x00,0x08,0xE9,0xAA,0xB8,0xA8,0xA8,0xAA,0xE9,0x08,0x00,0x00,
0x00,0x40,0x20,0x1F,0x20,0x40,0x5F,0x4A,0x4A,0x4A,0x4A,0x4A,0x5F,0x40,0x40,0x00
};
/*计数*/
static unsigned char f_countmode[] = {
0x40,0x40,0x42,0xCC,0x00,0x40,0x40,0x40,0x40,0xFF,0x40,0x40,0x40,0x40,0x40,0x00,
0x00,0x00,0x00,0x7F,0x20,0x10,0x00,0x00,0x00,0xFF,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x90,0x52,0x34,0x10,0xFF,0x10,0x34,0x52,0x80,0x70,0x8F,0x08,0x08,0xF8,0x08,0x00,
0x82,0x9A,0x56,0x63,0x22,0x52,0x8E,0x00,0x80,0x40,0x33,0x0C,0x33,0x40,0x80,0x00
};
static unsigned char f_dogear[] = {
0x10,0x10,0x10,0xFF,0x10,0x90,0x00,0xFC,0x44,0x44,0x44,0xC2,0x43,0x42,0x40,0x00,
0x04,0x44,0x82,0x7F,0x01,0x80,0x60,0x1F,0x00,0x00,0x00,0xFF,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x20,0x10,0xE8,0x24,0x27,0x24,0x24,0xE4,0x24,0x34,0x2C,0x20,0xE0,0x00,0x00,0x00,
0x80,0x60,0x1F,0x09,0x09,0x09,0x09,0x7F,0x09,0x09,0x49,0x89,0x7F,0x00,0x00,0x00,
};
static unsigned char f_size[] = {
0x00,0x00,0x00,0xFE,0x42,0x42,0x42,0x42,0xC2,0x42,0x42,0x42,0x7E,0x00,0x00,0x00,
0x80,0x40,0x30,0x0F,0x00,0x00,0x00,0x00,0x03,0x0C,0x10,0x20,0x40,0x80,0x80,0x00,
0x10,0x10,0x10,0x10,0x10,0x10,0x10,0x10,0x10,0xFF,0x10,0x10,0x10,0x10,0x10,0x00,
0x00,0x00,0x00,0x01,0x06,0x00,0x00,0x40,0x80,0x7F,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x02,0x02,0x02,0x02,0x82,0x42,0xF2,0x0E,0x42,0x82,0x02,0x02,0x02,0x00,0x00,
0x10,0x08,0x04,0x02,0x01,0x00,0x00,0xFF,0x00,0x00,0x00,0x01,0x02,0x0C,0x00,0x00,
0x10,0x08,0x04,0x87,0x6C,0x14,0x84,0x94,0x88,0x87,0x84,0xEC,0x94,0x84,0x84,0x00,
0x04,0x02,0x01,0xFF,0x00,0x00,0x00,0x02,0x0C,0x40,0x80,0x7F,0x00,0x00,0x00,0x00,
};
/*双张*/
static unsigned char f_doublefeed[] = {
0x04,0x34,0xC4,0x04,0xC4,0x3C,0x00,0x04,0xFC,0x04,0x04,0x04,0xC4,0x3C,0x00,0x00,
0x40,0x30,0x0C,0x03,0x0C,0x30,0x80,0x40,0x20,0x13,0x0C,0x13,0x20,0x40,0x80,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x02,0xE2,0x22,0x22,0x3E,0x80,0x80,0xFF,0x80,0xA0,0x90,0x88,0x86,0x80,0x80,0x00,
0x00,0x43,0x82,0x42,0x3E,0x00,0x00,0xFF,0x40,0x21,0x06,0x08,0x10,0x20,0x40,0x00
};
/*订书针*/
static unsigned char f_stable[] = {
0x10,0x10,0xD0,0xFF,0x90,0x50,0x20,0x50,0x4C,0x43,0x4C,0x50,0x20,0x40,0x40,0x00,
0x04,0x03,0x00,0xFF,0x00,0x41,0x44,0x58,0x41,0x4E,0x60,0x58,0x47,0x40,0x40,0x00,
0x10,0x60,0x02,0x8C,0x00,0xFE,0x02,0xF2,0x02,0xFE,0x00,0xF8,0x00,0xFF,0x00,0x00,
0x04,0x04,0x7E,0x01,0x80,0x47,0x30,0x0F,0x10,0x27,0x00,0x47,0x80,0x7F,0x00,0x00,
0x42,0x62,0x52,0x4A,0xC6,0x42,0x52,0x62,0xC2,0x00,0xF8,0x00,0x00,0xFF,0x00,0x00,
0x40,0xC4,0x44,0x44,0x7F,0x24,0x24,0x24,0x20,0x00,0x0F,0x40,0x80,0x7F,0x00,0x00,
0x40,0x40,0x42,0xCC,0x00,0x00,0x04,0x04,0x04,0x04,0xFC,0x04,0x04,0x04,0x04,0x00,
0x00,0x00,0x00,0x7F,0x20,0x10,0x00,0x00,0x40,0x80,0x7F,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x08,0x08,0x08,0x08,0xFF,0x08,0x08,0x08,0xF9,0x02,0x04,0x00,0x00,0x00,
0x01,0x01,0x01,0x01,0x01,0x01,0xFF,0x01,0x01,0x01,0x21,0x41,0x21,0x1F,0x00,0x00,
0x40,0x20,0x38,0xE7,0x24,0x24,0x44,0x40,0x40,0x40,0xFF,0x40,0x40,0x40,0x40,0x00,
0x01,0x01,0x01,0x7F,0x21,0x11,0x09,0x00,0x00,0x00,0xFF,0x00,0x00,0x00,0x00,0x00,
};
/*开盖*/
static unsigned char f_coveropen[] = {
0x40,0x40,0x42,0xCC,0x00,0x40,0xA0,0x9E,0x82,0x82,0x82,0x9E,0xA0,0x20,0x20,0x00,
0x00,0x00,0x00,0x3F,0x90,0x88,0x40,0x43,0x2C,0x10,0x28,0x46,0x41,0x80,0x80,0x00,
0x80,0x90,0x90,0x48,0x4C,0x57,0x24,0x24,0x24,0x54,0x4C,0x44,0x80,0x80,0x80,0x00,
0x00,0x00,0x00,0xFF,0x49,0x49,0x49,0x7F,0x49,0x49,0x49,0xFF,0x00,0x00,0x00,0x00,
0x80,0x82,0x82,0x82,0xFE,0x82,0x82,0x82,0x82,0x82,0xFE,0x82,0x82,0x82,0x80,0x00,
0x00,0x80,0x40,0x30,0x0F,0x00,0x00,0x00,0x00,0x00,0xFF,0x00,0x00,0x00,0x00,0x00,
0x00,0x04,0x24,0x24,0x25,0x26,0x24,0xFC,0x24,0x26,0x25,0x24,0x24,0x04,0x00,0x00,
0x81,0x81,0xF9,0x89,0x89,0xF9,0x89,0x89,0x89,0xF9,0x89,0x89,0xF9,0x81,0x81,0x00
};
/*手动模式卡纸*/
static unsigned char f_handmodepaperjam[] = {
0x00,0x00,0x24,0x24,0x24,0x24,0x24,0xFC,0x22,0x22,0x22,0x23,0x22,0x00,0x00,0x00,
0x02,0x02,0x02,0x02,0x02,0x42,0x82,0x7F,0x02,0x02,0x02,0x02,0x02,0x02,0x02,0x00,/*"手",0*/
0x40,0x44,0xC4,0x44,0x44,0x44,0x40,0x10,0x10,0xFF,0x10,0x10,0x10,0xF0,0x00,0x00,
0x10,0x3C,0x13,0x10,0x14,0xB8,0x40,0x30,0x0E,0x01,0x40,0x80,0x40,0x3F,0x00,0x00,/*"动",1*/
0x10,0x10,0xD0,0xFF,0x90,0x14,0xE4,0xAF,0xA4,0xA4,0xA4,0xAF,0xE4,0x04,0x00,0x00,
0x04,0x03,0x00,0xFF,0x00,0x89,0x4B,0x2A,0x1A,0x0E,0x1A,0x2A,0x4B,0x88,0x80,0x00,/*"模",2*/
0x10,0x10,0x90,0x90,0x90,0x90,0x90,0x10,0x10,0xFF,0x10,0x10,0x11,0x16,0x10,0x00,
0x00,0x20,0x60,0x20,0x3F,0x10,0x10,0x10,0x00,0x03,0x0C,0x10,0x20,0x40,0xF8,0x00,/*"式",3*/
0x40,0x40,0x40,0x40,0x40,0x40,0xFF,0x44,0x44,0x44,0x44,0x44,0x44,0x40,0x40,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0xFF,0x00,0x00,0x02,0x04,0x08,0x10,0x00,0x00,0x00,/*"卡",4*/
0x20,0x30,0xAC,0x63,0x30,0x00,0xFC,0x84,0x84,0x84,0xFE,0x82,0x83,0x82,0x80,0x00,
0x22,0x67,0x22,0x12,0x12,0x00,0xFF,0x40,0x20,0x00,0x01,0x0E,0x30,0x40,0xF8,0x00,/*"纸",5*/
};
/*手动模式*/
static unsigned char f_handmode[] = {
0x00,0x00,0x24,0x24,0x24,0x24,0x24,0xFC,0x22,0x22,0x22,0x23,0x22,0x00,0x00,0x00,
0x02,0x02,0x02,0x02,0x02,0x42,0x82,0x7F,0x02,0x02,0x02,0x02,0x02,0x02,0x02,0x00,
0x40,0x44,0xC4,0x44,0x44,0x44,0x40,0x10,0x10,0xFF,0x10,0x10,0x10,0xF0,0x00,0x00,
0x10,0x3C,0x13,0x10,0x14,0xB8,0x40,0x30,0x0E,0x01,0x40,0x80,0x40,0x3F,0x00,0x00,
0x10,0x10,0xD0,0xFF,0x90,0x14,0xE4,0xAF,0xA4,0xA4,0xA4,0xAF,0xE4,0x04,0x00,0x00,
0x04,0x03,0x00,0xFF,0x00,0x89,0x4B,0x2A,0x1A,0x0E,0x1A,0x2A,0x4B,0x88,0x80,0x00,
0x10,0x10,0x90,0x90,0x90,0x90,0x90,0x10,0x10,0xFF,0x10,0x10,0x11,0x16,0x10,0x00,
0x00,0x20,0x60,0x20,0x3F,0x10,0x10,0x10,0x00,0x03,0x0C,0x10,0x20,0x40,0xF8,0x00,
};
/*纸张歪斜*/
static unsigned char f_paperscrew[] = {
0x20,0x30,0xAC,0x63,0x30,0x00,0xFC,0x84,0x84,0x84,0xFE,0x82,0x83,0x82,0x80,0x00,
0x22,0x67,0x22,0x12,0x12,0x00,0xFF,0x40,0x20,0x00,0x01,0x0E,0x30,0x40,0xF8,0x00,
0x02,0xE2,0x22,0x22,0x3E,0x80,0x80,0xFF,0x80,0xA0,0x90,0x88,0x86,0x80,0x80,0x00,
0x00,0x43,0x82,0x42,0x3E,0x00,0x00,0xFF,0x40,0x21,0x06,0x08,0x10,0x20,0x40,0x00,
0x00,0x42,0x42,0x22,0x22,0x12,0x0A,0x7E,0x02,0x12,0x12,0x22,0x22,0x42,0x00,0x00,
0x40,0x41,0x41,0x7D,0x41,0x41,0x41,0x7F,0x49,0x49,0x49,0x49,0x49,0x41,0x40,0x00,
0x20,0x10,0x28,0x24,0xE3,0x24,0x28,0x10,0x00,0x22,0xCC,0x00,0xFF,0x00,0x00,0x00,
0x20,0x11,0x4D,0x81,0x7F,0x01,0x05,0x19,0x00,0x02,0x02,0x02,0xFF,0x01,0x01,0x00
};
/*卡纸*/
static unsigned char f_paperjam[] = {
0x40,0x40,0x40,0x40,0x40,0x40,0xFF,0x44,0x44,0x44,0x44,0x44,0x44,0x40,0x40,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0xFF,0x00,0x00,0x02,0x04,0x08,0x10,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x20,0x30,0xAC,0x63,0x30,0x00,0xFC,0x84,0x84,0x84,0xFE,0x82,0x83,0x82,0x80,0x00,
0x22,0x67,0x22,0x12,0x12,0x00,0xFF,0x40,0x20,0x00,0x01,0x0E,0x30,0x40,0xF8,0x00
};
/*卡纸001*/
static unsigned char f_paperjam001[] = {
0x40,0x40,0x40,0x40,0x40,0x40,0xFF,0x44,0x44,0x44,0x44,0x44,0x44,0x40,0x40,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0xFF,0x00,0x00,0x02,0x04,0x08,0x10,0x00,0x00,0x00,
0x20,0x30,0xAC,0x63,0x30,0x00,0xFC,0x84,0x84,0x84,0xFE,0x82,0x83,0x82,0x80,0x00,
0x22,0x67,0x22,0x12,0x12,0x00,0xFF,0x40,0x20,0x00,0x01,0x0E,0x30,0x40,0xF8,0x00,
0x00,0xE0,0x10,0x08,0x08,0x10,0xE0,0x00,0x00,0x0F,0x10,0x20,0x20,0x10,0x0F,0x00,
0x00,0xE0,0x10,0x08,0x08,0x10,0xE0,0x00,0x00,0x0F,0x10,0x20,0x20,0x10,0x0F,0x00,
0x00,0x00,0x10,0x10,0xF8,0x00,0x00,0x00,0x00,0x00,0x20,0x20,0x3F,0x20,0x20,0x00
};
/*卡纸002*/
static unsigned char f_paperjam002[] = {
0x40,0x40,0x40,0x40,0x40,0x40,0xFF,0x44,0x44,0x44,0x44,0x44,0x44,0x40,0x40,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0xFF,0x00,0x00,0x02,0x04,0x08,0x10,0x00,0x00,0x00,
0x20,0x30,0xAC,0x63,0x30,0x00,0xFC,0x84,0x84,0x84,0xFE,0x82,0x83,0x82,0x80,0x00,
0x22,0x67,0x22,0x12,0x12,0x00,0xFF,0x40,0x20,0x00,0x01,0x0E,0x30,0x40,0xF8,0x00,
0x00,0xE0,0x10,0x08,0x08,0x10,0xE0,0x00,0x00,0x0F,0x10,0x20,0x20,0x10,0x0F,0x00,
0x00,0xE0,0x10,0x08,0x08,0x10,0xE0,0x00,0x00,0x0F,0x10,0x20,0x20,0x10,0x0F,0x00,
0x00,0x70,0x08,0x08,0x08,0x08,0xF0,0x00,0x00,0x30,0x28,0x24,0x22,0x21,0x30,0x00
};
/*卡纸003*/
static unsigned char f_paperjam003[] = {
0x40,0x40,0x40,0x40,0x40,0x40,0xFF,0x44,0x44,0x44,0x44,0x44,0x44,0x40,0x40,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0xFF,0x00,0x00,0x02,0x04,0x08,0x10,0x00,0x00,0x00,
0x20,0x30,0xAC,0x63,0x30,0x00,0xFC,0x84,0x84,0x84,0xFE,0x82,0x83,0x82,0x80,0x00,
0x22,0x67,0x22,0x12,0x12,0x00,0xFF,0x40,0x20,0x00,0x01,0x0E,0x30,0x40,0xF8,0x00,
0x00,0xE0,0x10,0x08,0x08,0x10,0xE0,0x00,0x00,0x0F,0x10,0x20,0x20,0x10,0x0F,0x00,
0x00,0xE0,0x10,0x08,0x08,0x10,0xE0,0x00,0x00,0x0F,0x10,0x20,0x20,0x10,0x0F,0x00,
0x00,0x30,0x08,0x08,0x08,0x88,0x70,0x00,0x00,0x18,0x20,0x21,0x21,0x22,0x1C,0x00
};
/*搓纸失败*/
static unsigned char f_feederror[] = {
0x10,0x10,0x10,0xFF,0x10,0x90,0x88,0xA9,0xAE,0xF8,0xA8,0xAC,0xAB,0x88,0x80,0x00,
0x04,0x44,0x82,0x7F,0x21,0x10,0x48,0x46,0x45,0x44,0x7C,0x44,0x44,0x44,0x40,0x00,
0x20,0x30,0xAC,0x63,0x30,0x00,0xFC,0x84,0x84,0x84,0xFE,0x82,0x83,0x82,0x80,0x00,
0x22,0x67,0x22,0x12,0x12,0x00,0xFF,0x40,0x20,0x00,0x01,0x0E,0x30,0x40,0xF8,0x00,
0x00,0x40,0x30,0x1E,0x10,0x10,0x10,0xFF,0x10,0x10,0x10,0x10,0x10,0x00,0x00,0x00,
0x81,0x81,0x41,0x21,0x11,0x0D,0x03,0x01,0x03,0x0D,0x11,0x21,0x41,0x81,0x81,0x00,
0x00,0xFE,0x02,0xFA,0x02,0xFE,0x40,0x20,0xD8,0x17,0x10,0x10,0xF0,0x10,0x10,0x00,
0x80,0x47,0x30,0x0F,0x10,0x67,0x80,0x40,0x21,0x16,0x08,0x16,0x21,0x40,0x80,0x00
};
/*取图超时*/
static unsigned char f_aqrimgtimeout[] = {
0x02,0x02,0xFE,0x92,0x92,0x92,0xFE,0x02,0x06,0xFC,0x04,0x04,0x04,0xFC,0x00,0x00,
0x08,0x18,0x0F,0x08,0x08,0x04,0xFF,0x04,0x84,0x40,0x27,0x18,0x27,0x40,0x80,0x00,
0x00,0xFE,0x02,0x42,0x22,0x32,0x5E,0x92,0x52,0x32,0x12,0x02,0x02,0xFE,0x00,0x00,
0x00,0xFF,0x42,0x42,0x42,0x51,0x55,0x64,0x69,0x41,0x42,0x42,0x42,0xFF,0x00,0x00,
0x40,0x48,0x48,0x48,0xFF,0x48,0x48,0x42,0xA2,0x9E,0x82,0xA2,0xC2,0xBE,0x00,0x00,
0x80,0x60,0x1F,0x20,0x7F,0x44,0x44,0x40,0x4F,0x48,0x48,0x48,0x48,0x4F,0x40,0x00,
0x00,0xFC,0x84,0x84,0x84,0xFC,0x00,0x10,0x10,0x10,0x10,0x10,0xFF,0x10,0x10,0x00,
0x00,0x3F,0x10,0x10,0x10,0x3F,0x00,0x00,0x01,0x06,0x40,0x80,0x7F,0x00,0x00,0x00
};
/*分纸强度*/
static unsigned char f_pollpaperintensity[] = {
0x80,0x40,0x20,0x90,0x88,0x86,0x80,0x80,0x80,0x83,0x8C,0x10,0x20,0x40,0x80,0x00,
0x00,0x80,0x40,0x20,0x18,0x07,0x00,0x40,0x80,0x40,0x3F,0x00,0x00,0x00,0x00,0x00,
0x20,0x30,0xAC,0x63,0x30,0x00,0xFC,0x84,0x84,0x84,0xFE,0x82,0x83,0x82,0x80,0x00,
0x22,0x67,0x22,0x12,0x12,0x00,0xFF,0x40,0x20,0x00,0x01,0x0E,0x30,0x40,0xF8,0x00,
0x02,0xE2,0x22,0x22,0x3E,0x00,0x80,0x9E,0x92,0x92,0xF2,0x92,0x92,0x9E,0x80,0x00,
0x00,0x43,0x82,0x42,0x3E,0x40,0x47,0x44,0x44,0x44,0x7F,0x44,0x44,0x54,0xE7,0x00,
0x00,0x00,0xFC,0x24,0x24,0x24,0xFC,0x25,0x26,0x24,0xFC,0x24,0x24,0x24,0x04,0x00,
0x40,0x30,0x8F,0x80,0x84,0x4C,0x55,0x25,0x25,0x25,0x55,0x4C,0x80,0x80,0x80,0x00,
};
/*高*/
static unsigned char f_intensityHigh[] = {
0x04,0x04,0x04,0x04,0xF4,0x94,0x95,0x96,0x94,0x94,0xF4,0x04,0x04,0x04,0x04,0x00,
0x00,0xFE,0x02,0x02,0x7A,0x4A,0x4A,0x4A,0x4A,0x4A,0x7A,0x02,0x82,0xFE,0x00,0x00
};
/*中*/
static unsigned char f_intensityMid[] = {
0x00,0x00,0xF0,0x10,0x10,0x10,0x10,0xFF,0x10,0x10,0x10,0x10,0xF0,0x00,0x00,0x00,
0x00,0x00,0x0F,0x04,0x04,0x04,0x04,0xFF,0x04,0x04,0x04,0x04,0x0F,0x00,0x00,0x00
};
/*弱*/
static unsigned char f_intensityLow[] = {
0x00,0xF2,0x92,0x92,0x92,0x92,0x9E,0x00,0xF2,0x92,0x92,0x92,0x92,0x9E,0x00,0x00,
0x00,0x10,0x11,0x4A,0x88,0x44,0x3F,0x00,0x10,0x11,0x4A,0x88,0x44,0x3F,0x00,0x00
};
/*低*/
static unsigned char f_traypositionLow[] = {
0x00,0x80,0x60,0xF8,0x07,0x00,0xFC,0x84,0x84,0x84,0xFE,0x82,0x83,0x82,0x80,0x00,
0x01,0x00,0x00,0xFF,0x00,0x00,0xFF,0x40,0x20,0x00,0x41,0x8E,0x30,0x40,0xF8,0x00
};
/*张*/
static unsigned char f_page[] = {
0x02,0xE2,0x22,0x22,0x3E,0x80,0x80,0xFF,0x80,0xA0,0x90,0x88,0x86,0x80,0x80,0x00,
0x00,0x43,0x82,0x42,0x3E,0x00,0x00,0xFF,0x40,0x21,0x06,0x08,0x10,0x20,0x40,0x00
};
/*扫描*/
static unsigned char f_scan[] = {
0x10,0x10,0x10,0xFF,0x10,0x90,0x04,0x84,0x84,0x84,0x84,0x84,0x84,0xFC,0x00,0x00,
0x04,0x44,0x82,0x7F,0x01,0x00,0x20,0x20,0x20,0x20,0x20,0x20,0x20,0x7F,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x10,0x10,0x10,0xFF,0x10,0x90,0x04,0xC4,0x5F,0x44,0xC4,0x44,0x5F,0xC4,0x04,0x00,
0x04,0x44,0x82,0x7F,0x01,0x00,0x00,0xFF,0x44,0x44,0x7F,0x44,0x44,0xFF,0x00,0x00
};
/*返回*/
static unsigned char f_back[] = {
0x40,0x40,0x42,0xCE,0xCC,0x00,0xFC,0xFC,0xA4,0xA4,0x26,0x22,0xA3,0xE3,0x62,0x00,
0x00,0x40,0x60,0x3F,0x3F,0x78,0x5F,0x57,0x58,0x4D,0x47,0x47,0x4D,0x58,0x50,0x40,
0x00,0x00,0xFE,0xFE,0x02,0xF2,0xF2,0x12,0x12,0xF2,0xF2,0x02,0xFE,0xFE,0x00,0x00,
0x00,0x00,0x7F,0x7F,0x20,0x27,0x27,0x24,0x24,0x27,0x27,0x20,0x7F,0x7F,0x00,0x00
};
/*确认*/
static unsigned char f_confirm[] = {
0x04,0x84,0xE4,0x5C,0x44,0xC4,0x20,0x10,0xE8,0x27,0x24,0xE4,0x34,0x2C,0xE0,0x00,
0x02,0x01,0x7F,0x10,0x10,0x3F,0x80,0x60,0x1F,0x09,0x09,0x3F,0x49,0x89,0x7F,0x00,
0x40,0x40,0x42,0xCC,0x00,0x00,0x00,0x00,0x00,0xFF,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x3F,0x90,0x48,0x20,0x18,0x07,0x00,0x07,0x18,0x20,0x40,0x80,0x00
};
/*开*/
static unsigned char f_opened[] = {
0x80,0x82,0x82,0x82,0xFE,0x82,0x82,0x82,0x82,0x82,0xFE,0x82,0x82,0x82,0x80,0x00,
0x00,0x80,0x40,0x30,0x0F,0x00,0x00,0x00,0x00,0x00,0xFF,0x00,0x00,0x00,0x00,0x00
};
/*关*/
static unsigned char f_closed[] = {
0x80,0x82,0x82,0x82,0xFE,0x82,0x82,0x82,0x82,0x82,0xFE,0x82,0x82,0x82,0x80,0x00,
0x00,0x80,0x40,0x30,0x0F,0x00,0x00,0x00,0x00,0x00,0xFF,0x00,0x00,0x00,0x00,0x00
};
/*无纸*/
static unsigned char f_nopaper[] = {
0x00,0x40,0x42,0x42,0x42,0xC2,0x7E,0x42,0xC2,0x42,0x42,0x42,0x40,0x40,0x00,0x00,
0x80,0x40,0x20,0x10,0x0C,0x03,0x00,0x00,0x3F,0x40,0x40,0x40,0x40,0x70,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x20,0x30,0xAC,0x63,0x30,0x00,0xFC,0x84,0x84,0x84,0xFE,0x82,0x83,0x82,0x80,0x00,
0x22,0x67,0x22,0x12,0x12,0x00,0xFF,0x40,0x20,0x00,0x01,0x0E,0x30,0x40,0xF8,0x00
};
/*休眠模式*/
static unsigned char f_sleepmode[] = {
0x00,0x80,0x60,0xF8,0x07,0x10,0x10,0x10,0xD0,0xFF,0xD0,0x10,0x10,0x10,0x10,0x00,
0x01,0x00,0x00,0xFF,0x10,0x08,0x04,0x03,0x00,0xFF,0x00,0x03,0x04,0x08,0x10,0x00,
0x00,0xFC,0x24,0x24,0x24,0xFC,0x00,0xFE,0x22,0x22,0xE2,0x22,0x22,0x3E,0x00,0x00,
0x00,0x3F,0x11,0x11,0x11,0x3F,0x00,0xFF,0x41,0x21,0x07,0x19,0x21,0x41,0xF1,0x00,
0x10,0x10,0xD0,0xFF,0x90,0x14,0xE4,0xAF,0xA4,0xA4,0xA4,0xAF,0xE4,0x04,0x00,0x00,
0x04,0x03,0x00,0xFF,0x00,0x89,0x4B,0x2A,0x1A,0x0E,0x1A,0x2A,0x4B,0x88,0x80,0x00,
0x10,0x10,0x90,0x90,0x90,0x90,0x90,0x10,0x10,0xFF,0x10,0x10,0x11,0x16,0x10,0x00,
0x00,0x20,0x60,0x20,0x3F,0x10,0x10,0x10,0x00,0x03,0x0C,0x10,0x20,0x40,0xF8,0x00
};
/*三十分钟*/
static unsigned char f_30min[] = {
0x00,0x04,0x84,0x84,0x84,0x84,0x84,0x84,0x84,0x84,0x84,0x84,0x84,0x04,0x00,0x00,
0x20,0x20,0x20,0x20,0x20,0x20,0x20,0x20,0x20,0x20,0x20,0x20,0x20,0x20,0x20,0x00,
0x40,0x40,0x40,0x40,0x40,0x40,0x40,0xFF,0x40,0x40,0x40,0x40,0x40,0x40,0x40,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0xFF,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x80,0x40,0x20,0x90,0x88,0x86,0x80,0x80,0x80,0x83,0x8C,0x10,0x20,0x40,0x80,0x00,
0x00,0x80,0x40,0x20,0x18,0x07,0x00,0x40,0x80,0x40,0x3F,0x00,0x00,0x00,0x00,0x00,
0x20,0x10,0x2C,0xE7,0x24,0x24,0x00,0xF0,0x10,0x10,0xFF,0x10,0x10,0xF0,0x00,0x00,
0x01,0x01,0x01,0x7F,0x21,0x11,0x00,0x07,0x02,0x02,0xFF,0x02,0x02,0x07,0x00,0x00,
};
/*一小时*/
static unsigned char f_1hour[] = {
0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x00,
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0xE0,0x00,0x00,0x00,0xFF,0x00,0x00,0x00,0x20,0x40,0x80,0x00,0x00,
0x08,0x04,0x03,0x00,0x00,0x40,0x80,0x7F,0x00,0x00,0x00,0x00,0x00,0x01,0x0E,0x00,
0x00,0xFC,0x84,0x84,0x84,0xFC,0x00,0x10,0x10,0x10,0x10,0x10,0xFF,0x10,0x10,0x00,
0x00,0x3F,0x10,0x10,0x10,0x3F,0x00,0x00,0x01,0x06,0x40,0x80,0x7F,0x00,0x00,0x00
};
/*二小时*/
static unsigned char f_2hour[] = {
0x02,0xE2,0x22,0x22,0x22,0xFE,0x22,0x22,0x22,0xFE,0x22,0x22,0x22,0xE2,0x02,0x00,
0x00,0xFF,0x00,0x08,0x06,0x01,0x16,0x08,0x06,0x01,0x02,0x4C,0x80,0x7F,0x00,0x00,
0x00,0x00,0x00,0xE0,0x00,0x00,0x00,0xFF,0x00,0x00,0x00,0x20,0x40,0x80,0x00,0x00,
0x08,0x04,0x03,0x00,0x00,0x40,0x80,0x7F,0x00,0x00,0x00,0x00,0x00,0x01,0x0E,0x00,
0x00,0xFC,0x84,0x84,0x84,0xFC,0x00,0x10,0x10,0x10,0x10,0x10,0xFF,0x10,0x10,0x00,
0x00,0x3F,0x10,0x10,0x10,0x3F,0x00,0x00,0x01,0x06,0x40,0x80,0x7F,0x00,0x00,0x00
};
/*不休眠*/
static unsigned char f_never[] = {
0x00,0x02,0x02,0x02,0x02,0x82,0x42,0xF2,0x0E,0x42,0x82,0x02,0x02,0x02,0x00,0x00,
0x10,0x08,0x04,0x02,0x01,0x00,0x00,0xFF,0x00,0x00,0x00,0x01,0x02,0x0C,0x00,0x00,
0x00,0x80,0x60,0xF8,0x07,0x10,0x10,0x10,0xD0,0xFF,0xD0,0x10,0x10,0x10,0x10,0x00,
0x01,0x00,0x00,0xFF,0x10,0x08,0x04,0x03,0x00,0xFF,0x00,0x03,0x04,0x08,0x10,0x00,
0x00,0xFC,0x24,0x24,0x24,0xFC,0x00,0xFE,0x22,0x22,0xE2,0x22,0x22,0x3E,0x00,0x00,
0x00,0x3F,0x11,0x11,0x11,0x3F,0x00,0xFF,0x41,0x21,0x07,0x19,0x21,0x41,0xF1,0x00
};
/*返回*/
static unsigned char f_return[] = {
0x40,0x40,0x42,0xCC,0x00,0x00,0xFC,0x24,0xA4,0x24,0x22,0x22,0xA3,0x62,0x00,0x00,
0x00,0x40,0x20,0x1F,0x20,0x58,0x47,0x50,0x48,0x45,0x42,0x45,0x48,0x50,0x40,0x00,
0x00,0x00,0xFE,0x02,0x02,0xF2,0x12,0x12,0x12,0xF2,0x02,0x02,0xFE,0x00,0x00,0x00,
0x00,0x00,0x7F,0x20,0x20,0x27,0x24,0x24,0x24,0x27,0x20,0x20,0x7F,0x00,0x00,0x00
};
/*关机*/
static unsigned char f_powerof[] = {
0x00,0x00,0x10,0x11,0x16,0x10,0x10,0xF0,0x10,0x10,0x14,0x13,0x10,0x00,0x00,0x00,
0x81,0x81,0x41,0x41,0x21,0x11,0x0D,0x03,0x0D,0x11,0x21,0x41,0x41,0x81,0x81,0x00,
0x10,0x10,0xD0,0xFF,0x90,0x10,0x00,0xFE,0x02,0x02,0x02,0xFE,0x00,0x00,0x00,0x00,
0x04,0x03,0x00,0xFF,0x00,0x83,0x60,0x1F,0x00,0x00,0x00,0x3F,0x40,0x40,0x78,0x00
};
/*托盘位置*/
static unsigned char f_trayposition[] = {
0x10,0x10,0x10,0xFF,0x10,0x90,0x04,0x04,0x04,0xFC,0x82,0x82,0x83,0x82,0x80,0x00,
0x04,0x44,0x82,0x7F,0x01,0x00,0x01,0x01,0x01,0x3F,0x40,0x40,0x40,0x40,0x78,0x00,
0x20,0x20,0x20,0xFC,0x24,0x26,0xA5,0x2C,0x34,0x24,0x24,0xFC,0x20,0x20,0x20,0x00,
0x40,0x42,0x7D,0x44,0x44,0x7C,0x44,0x45,0x44,0x7D,0x46,0x45,0x7C,0x40,0x40,0x00,
0x00,0x80,0x60,0xF8,0x07,0x10,0x90,0x10,0x11,0x16,0x10,0x10,0xD0,0x10,0x00,0x00,
0x01,0x00,0x00,0xFF,0x40,0x40,0x41,0x5E,0x40,0x40,0x70,0x4E,0x41,0x40,0x40,0x00,
0x00,0x17,0x15,0xD5,0x55,0x57,0x55,0x7D,0x55,0x57,0x55,0xD5,0x15,0x17,0x00,0x00,
0x40,0x40,0x40,0x7F,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x7F,0x40,0x40,0x40,0x00
};
/*设备已锁定*/
static unsigned char f_deviceLock[] = {
0x40,0x40,0x42,0xCC,0x00,0x40,0xA0,0x9E,0x82,0x82,0x82,0x9E,0xA0,0x20,0x20,0x00,
0x00,0x00,0x00,0x3F,0x90,0x88,0x40,0x43,0x2C,0x10,0x28,0x46,0x41,0x80,0x80,0x00,/*"设",0*/
0x80,0x90,0x90,0x48,0x4C,0x57,0x24,0x24,0x24,0x54,0x4C,0x44,0x80,0x80,0x80,0x00,
0x00,0x00,0x00,0xFF,0x49,0x49,0x49,0x7F,0x49,0x49,0x49,0xFF,0x00,0x00,0x00,0x00,/*"备",1*/
0x00,0x00,0xE2,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0xFE,0x00,0x00,0x00,0x00,
0x00,0x00,0x3F,0x40,0x40,0x40,0x40,0x40,0x40,0x40,0x40,0x40,0x40,0x78,0x00,0x00,/*"已",2*/
0x20,0x10,0x2C,0xE7,0x24,0x24,0x00,0xE2,0x2C,0x20,0xBF,0x20,0x28,0xE6,0x00,0x00,
0x01,0x01,0x01,0x7F,0x21,0x11,0x80,0x4F,0x20,0x10,0x0F,0x10,0x20,0x4F,0x80,0x00,/*"锁",3*/
0x10,0x0C,0x44,0x44,0x44,0x44,0x45,0xC6,0x44,0x44,0x44,0x44,0x44,0x14,0x0C,0x00,
0x80,0x40,0x20,0x1E,0x20,0x40,0x40,0x7F,0x44,0x44,0x44,0x44,0x44,0x40,0x40,0x00,/*"定",4*/
};
/*耗材查询*/
static unsigned char f_scannum[] ={
0x88,0xA8,0xA8,0xFF,0xA8,0xA8,0x88,0x00,0x44,0x44,0xFC,0x22,0x23,0x22,0x00,0x00,
0x20,0x18,0x06,0xFF,0x02,0x0C,0x00,0x04,0x04,0x04,0x7F,0x82,0x82,0x82,0xF2,0x00,/*"耗",0*/
0x10,0x10,0x10,0xD0,0xFF,0x90,0x10,0x00,0x10,0x10,0x10,0xD0,0xFF,0x10,0x10,0x00,
0x08,0x04,0x03,0x00,0xFF,0x00,0x03,0x00,0x08,0x04,0x43,0x80,0x7F,0x00,0x00,0x00,/*"材",1*/
0x40,0x44,0x24,0xA4,0x94,0x8C,0x84,0xFF,0x84,0x8C,0x94,0xA4,0x24,0x44,0x40,0x00,
0x40,0x40,0x40,0x5F,0x4A,0x4A,0x4A,0x4A,0x4A,0x4A,0x4A,0x5F,0x40,0x40,0x40,0x00,/*"查",2*/
0x40,0x40,0x42,0xCC,0x00,0x20,0xD0,0x4C,0x4B,0x48,0xC8,0x08,0x08,0xF8,0x00,0x00,
0x00,0x00,0x00,0x7F,0x20,0x10,0x1F,0x12,0x12,0x12,0x5F,0x80,0x40,0x3F,0x00,0x00,/*"询",3*/
};
/*历史张数*/
static unsigned char f_history_num[] ={
0x00,0x00,0xFE,0x02,0x42,0x42,0x42,0x42,0xFA,0x42,0x42,0x42,0x42,0xC2,0x02,0x00,
0x80,0x60,0x1F,0x80,0x40,0x20,0x18,0x06,0x01,0x00,0x40,0x80,0x40,0x3F,0x00,0x00,/*"历",0*/
0x00,0x00,0xF8,0x88,0x88,0x88,0x88,0xFF,0x88,0x88,0x88,0x88,0xF8,0x00,0x00,0x00,
0x80,0x80,0x81,0x44,0x48,0x30,0x10,0x2F,0x20,0x40,0x40,0x40,0x81,0x80,0x80,0x00,/*"史",1*/
0x02,0xE2,0x22,0x22,0x3E,0x80,0x80,0xFF,0x80,0xA0,0x90,0x88,0x86,0x80,0x80,0x00,
0x00,0x43,0x82,0x42,0x3E,0x00,0x00,0xFF,0x40,0x21,0x06,0x08,0x10,0x20,0x40,0x00,/*"张",2*/
0x90,0x52,0x34,0x10,0xFF,0x10,0x34,0x52,0x80,0x70,0x8F,0x08,0x08,0xF8,0x08,0x00,
0x82,0x9A,0x56,0x63,0x22,0x52,0x8E,0x00,0x80,0x40,0x33,0x0C,0x33,0x40,0x80,0x00/*"数",3*/
};
/*滚轴张数*/
static unsigned char f_roller_num[] ={
0x10,0x60,0x02,0x8C,0x00,0x24,0x94,0xCC,0xA5,0x96,0xC4,0x8C,0x14,0x24,0x00,0x00,
0x04,0x04,0x7E,0x01,0x20,0x10,0x08,0xFC,0x42,0x24,0x08,0x15,0x22,0x40,0x40,0x00,/*"滚",0*/
0xC8,0xB8,0x8F,0xE8,0x88,0x88,0x00,0xF0,0x10,0x10,0xFF,0x10,0x10,0xF0,0x00,0x00,
0x08,0x18,0x08,0xFF,0x04,0x04,0x00,0xFF,0x42,0x42,0x7F,0x42,0x42,0xFF,0x00,0x00,/*"轴",1*/
0x02,0xE2,0x22,0x22,0x3E,0x80,0x80,0xFF,0x80,0xA0,0x90,0x88,0x86,0x80,0x80,0x00,
0x00,0x43,0x82,0x42,0x3E,0x00,0x00,0xFF,0x40,0x21,0x06,0x08,0x10,0x20,0x40,0x00,/*"张",2*/
0x90,0x52,0x34,0x10,0xFF,0x10,0x34,0x52,0x80,0x70,0x8F,0x08,0x08,0xF8,0x08,0x00,
0x82,0x9A,0x56,0x63,0x22,0x52,0x8E,0x00,0x80,0x40,0x33,0x0C,0x33,0x40,0x80,0x00/*"数",3*/
};
/*滚轴清零*/
static unsigned char f_clrea_roller[] ={
0x10,0x60,0x02,0x8C,0x00,0x24,0x94,0xCC,0xA5,0x96,0xC4,0x8C,0x14,0x24,0x00,0x00,
0x04,0x04,0x7E,0x01,0x20,0x10,0x08,0xFC,0x42,0x24,0x08,0x15,0x22,0x40,0x40,0x00,/*"滚",0*/
0xC8,0xB8,0x8F,0xE8,0x88,0x88,0x00,0xF0,0x10,0x10,0xFF,0x10,0x10,0xF0,0x00,0x00,
0x08,0x18,0x08,0xFF,0x04,0x04,0x00,0xFF,0x42,0x42,0x7F,0x42,0x42,0xFF,0x00,0x00,/*"轴",1*/
0x10,0x60,0x02,0x8C,0x00,0x44,0x54,0x54,0x54,0x7F,0x54,0x54,0x54,0x44,0x40,0x00,
0x04,0x04,0x7E,0x01,0x00,0x00,0xFF,0x15,0x15,0x15,0x55,0x95,0x7F,0x00,0x00,0x00,/*"清",2*/
0x10,0x0C,0x05,0x55,0x55,0x55,0x85,0x7F,0x85,0x55,0x55,0x55,0x05,0x14,0x0C,0x00,
0x04,0x04,0x02,0x0A,0x09,0x29,0x2A,0x4C,0x48,0xA9,0x19,0x02,0x02,0x04,0x04,0x00,/*"零",3*/
};
/*是否确认?*/
static unsigned char f_is_sure[] ={
0x00,0x00,0x00,0x7F,0x49,0x49,0x49,0x49,0x49,0x49,0x49,0x7F,0x00,0x00,0x00,0x00,
0x81,0x41,0x21,0x1D,0x21,0x41,0x81,0xFF,0x89,0x89,0x89,0x89,0x89,0x81,0x81,0x00,/*"是",0*/
0x00,0x02,0x82,0x82,0x42,0x22,0x12,0xFA,0x06,0x22,0x22,0x42,0x42,0x82,0x00,0x00,
0x01,0x01,0x00,0xFC,0x44,0x44,0x44,0x45,0x44,0x44,0x44,0xFC,0x00,0x00,0x01,0x00,/*"否",1*/
0x04,0x84,0xE4,0x5C,0x44,0xC4,0x20,0x10,0xE8,0x27,0x24,0xE4,0x34,0x2C,0xE0,0x00,
0x02,0x01,0x7F,0x10,0x10,0x3F,0x80,0x60,0x1F,0x09,0x09,0x3F,0x49,0x89,0x7F,0x00,/*"确",2*/
0x40,0x40,0x42,0xCC,0x00,0x00,0x00,0x00,0x00,0xFF,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x3F,0x90,0x48,0x20,0x18,0x07,0x00,0x07,0x18,0x20,0x40,0x80,0x00,/*"认",3*/
0x00,0x00,0x38,0x34,0x02,0x82,0xC2,0x7C,0x38,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
0x00,0x00,0x00,0x00,0x00,0x37,0x37,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,/*"",4*/
};
/*"是"*/
static unsigned char f_yes[] ={
0x00,0x00,0x00,0x7F,0x49,0x49,0x49,0x49,0x49,0x49,0x49,0x7F,0x00,0x00,0x00,0x00,
0x81,0x41,0x21,0x1D,0x21,0x41,0x81,0xFF,0x89,0x89,0x89,0x89,0x89,0x81,0x81,0x00,/*"是",0*/
};
/*"否"*/
static unsigned char f_no[] ={
0x00,0x02,0x82,0x82,0x42,0x22,0x12,0xFA,0x06,0x22,0x22,0x42,0x42,0x82,0x00,0x00,
0x01,0x01,0x00,0xFC,0x44,0x44,0x44,0x45,0x44,0x44,0x44,0xFC,0x00,0x00,0x01,0x00,/*"否",1*/
};
struct DisInfo{
unsigned char page;
unsigned char col;
DisDrawtype drawtype;
std::vector<unsigned char> str;
};
static std::map<DisType,DisInfo> map_Display={
{DisType::Dis_Welcome,{1,1,DisDrawtype::DD_All,std::vector<unsigned char>(f_logo,f_logo+sizeof(f_logo))}},
{DisType::Dis_Init,{1,1,DisDrawtype::DD_All,std::vector<unsigned char>(f_welcome,f_welcome+sizeof(f_welcome))}},
{DisType::Dis_Idel,{1,1,DisDrawtype::DD_TopLeft,std::vector<unsigned char>(f_ready,f_ready+sizeof(f_ready))}},
{DisType::Dis_Scan,{1,1,DisDrawtype::DD_TopLeft,std::vector<unsigned char>(f_scan,f_scan+sizeof(f_scan))}},
{DisType::Dis_Set_ClearPaperPass,{1,1,DisDrawtype::DD_TopLeft,std::vector<unsigned char>(f_clearpaperpass,f_clearpaperpass+sizeof(f_clearpaperpass))}},
{DisType::Dis_Set_Count,{1,1,DisDrawtype::DD_TopLeft,std::vector<unsigned char>(f_countmode,f_countmode+sizeof(f_countmode))}},
{DisType::Dis_Err_DoubleFeed,{1,1,DisDrawtype::DD_TopLeft,std::vector<unsigned char>(f_doublefeed,f_doublefeed+sizeof(f_doublefeed))}},
{DisType::Dis_Err_Stable,{1,1,DisDrawtype::DD_TopLeft,std::vector<unsigned char>(f_stable,f_stable+sizeof(f_stable))}},
{DisType::Dis_Err_CoverOpen,{1,1,DisDrawtype::DD_TopLeft,std::vector<unsigned char>(f_coveropen,f_coveropen+sizeof(f_coveropen))}},
{DisType::Dis_Err_JamIn,{1,1,DisDrawtype::DD_TopLeft,std::vector<unsigned char>(f_paperjam,f_paperjam+sizeof(f_paperjam))}},
{DisType::Dis_Err_JamOut,{1,1,DisDrawtype::DD_TopLeft,std::vector<unsigned char>(f_paperjam,f_paperjam+sizeof(f_paperjam))}},
{DisType::Dis_Err_HandModeJam,{1,1,DisDrawtype::DD_TopLeft,std::vector<unsigned char>(f_handmodepaperjam,f_handmodepaperjam+sizeof(f_handmodepaperjam))}},
{DisType::Dis_Err_PaperScrew,{1,1,DisDrawtype::DD_TopLeft,std::vector<unsigned char>(f_paperscrew,f_paperscrew+sizeof(f_paperscrew))}},
{DisType::Dis_Err_FeedError,{1,1,DisDrawtype::DD_TopLeft,std::vector<unsigned char>(f_feederror,f_feederror+sizeof(f_feederror))}},
{DisType::Dis_Err_AqrImgTimeout,{1,1,DisDrawtype::DD_TopLeft,std::vector<unsigned char>(f_aqrimgtimeout,f_aqrimgtimeout+sizeof(f_aqrimgtimeout))}},
{DisType::Dis_Err_DogEar,{1,1,DisDrawtype::DD_TopLeft,std::vector<unsigned char>(f_dogear,f_dogear+sizeof(f_dogear))}},
{DisType::Dis_Err_Size,{1,1,DisDrawtype::DD_TopLeft,std::vector<unsigned char>(f_size,f_size+sizeof(f_size))}},
{DisType::Dis_Set_PollPaperIntensity,{1,1,DisDrawtype::DD_TopLeft,std::vector<unsigned char>(f_pollpaperintensity,f_pollpaperintensity+sizeof(f_pollpaperintensity))}},
{DisType::Dis_Set_PollPI_High,{3,96,DisDrawtype::DD_BotRight,std::vector<unsigned char>(f_intensityHigh,f_intensityHigh+sizeof(f_intensityHigh))}},
{DisType::Dis_Set_PollPI_Mid,{3,96,DisDrawtype::DD_BotRight,std::vector<unsigned char>(f_intensityMid,f_intensityMid+sizeof(f_intensityMid))}},
{DisType::Dis_Set_PollPI_Low,{3,96,DisDrawtype::DD_BotRight,std::vector<unsigned char>(f_intensityLow,f_intensityLow+sizeof(f_intensityLow))}},
{DisType::Dis_Set_TrayPosition,{1,1,DisDrawtype::DD_TopLeft,std::vector<unsigned char>(f_trayposition,f_trayposition+sizeof(f_trayposition))}},
{DisType::Dis_Set_TrayPosition_High,{3,96,DisDrawtype::DD_BotRight,std::vector<unsigned char>(f_intensityHigh,f_intensityHigh+sizeof(f_intensityHigh))}},
{DisType::Dis_Set_TrayPosition_Mid,{3,96,DisDrawtype::DD_BotRight,std::vector<unsigned char>(f_intensityMid,f_intensityMid+sizeof(f_intensityMid))}},
{DisType::Dis_Set_TrayPosition_Low,{3,96,DisDrawtype::DD_BotRight,std::vector<unsigned char>(f_traypositionLow,f_traypositionLow+sizeof(f_traypositionLow))}},
{DisType::Dis_Count_Page,{3,112,DisDrawtype::DD_BotRight,std::vector<unsigned char>(f_page,f_page+sizeof(f_page))}},
{DisType::Dis_Scan_Page,{3,112,DisDrawtype::DD_BotRight,std::vector<unsigned char>(f_page,f_page+sizeof(f_page))}},
{DisType::Dis_Err_NoPaper,{1,1,DisDrawtype::DD_TopLeft,std::vector<unsigned char>(f_nopaper,f_nopaper+sizeof(f_nopaper))}},
{DisType::Dis_Set_SleepMode,{1,1,DisDrawtype::DD_TopLeft,std::vector<unsigned char>(f_sleepmode,f_sleepmode+sizeof(f_sleepmode))}},
// {DisType::Dis_Set_SleepMode_30M,{3,64,DisDrawtype::DD_BotRight,std::vector<unsigned char>(f_30min,f_30min+sizeof(f_30min))}},
// {DisType::Dis_Set_SleepMode_1H,{3,80,DisDrawtype::DD_BotRight,std::vector<unsigned char>(f_1hour,f_1hour+sizeof(f_1hour))}},
// {DisType::Dis_Set_SleepMode_2H,{3,80,DisDrawtype::DD_BotRight,std::vector<unsigned char>(f_2hour,f_2hour+sizeof(f_2hour))}},
{DisType::Dis_Set_SleepMode_NEVER,{3,80,DisDrawtype::DD_BotRight,std::vector<unsigned char>(f_never,f_never+sizeof(f_never))}},
{DisType::Dis_Set_Return,{1,1,DisDrawtype::DD_TopLeft,std::vector<unsigned char>(f_return,f_return+sizeof(f_return))}},
{DisType::Dis_Set_Poweroff,{1,1,DisDrawtype::DD_TopLeft,std::vector<unsigned char>(f_powerof,f_powerof+sizeof(f_powerof))}},
{DisType::Dis_HandMode,{1,1,DisDrawtype::DD_TopLeft,std::vector<unsigned char>(f_handmode,f_handmode+sizeof(f_handmode))}},
{DisType::Dis_Set_Item_Return,{3,96,DisDrawtype::DD_BotRight,std::vector<unsigned char>(f_return,f_return+sizeof(f_return))}},
{DisType::Dis_Device_Lock,{1,1,DisDrawtype::DD_TopLeft,std::vector<unsigned char>(f_deviceLock,f_deviceLock+sizeof(f_deviceLock))}},
{DisType::Dis_Set_ScanNum_Option,{1,1,DisDrawtype::DD_TopLeft,std::vector<unsigned char>(f_scannum,f_scannum+sizeof(f_scannum))}},
{DisType::Dis_Set_Get_History_ScanNum,{3,1,DisDrawtype::DD_BotRight,std::vector<unsigned char>(f_history_num,f_history_num+sizeof(f_history_num))}},
{DisType::Dis_Set_Get_Roller_ScanNum,{3,1,DisDrawtype::DD_BotRight,std::vector<unsigned char>(f_roller_num,f_roller_num+sizeof(f_roller_num))}},
{DisType::Dis_Set_Clear_Roller_ScanNum,{3,64,DisDrawtype::DD_BotRight,std::vector<unsigned char>(f_clrea_roller,f_clrea_roller+sizeof(f_clrea_roller))}},
{DisType::Dis_Set_Is_Sure,{1,1,DisDrawtype::DD_TopLeft,std::vector<unsigned char>(f_is_sure,f_is_sure+sizeof(f_is_sure))}},
{DisType::Dis_Set_YES,{3,112,DisDrawtype::DD_BotRight,std::vector<unsigned char>(f_yes,f_yes+sizeof(f_yes))}},
{DisType::Dis_Set_No,{3,112,DisDrawtype::DD_BotRight,std::vector<unsigned char>(f_no,f_no+sizeof(f_no))}},
};

164
ui/LCDDisplay.cpp Normal file
View File

@ -0,0 +1,164 @@
#include "LCDDisplay.h"
#include "Lcd.h"
#include <iostream>
#include <thread>
#include <algorithm>
LCDDisplay::LCDDisplay()
{
lcd.reset(new Lcd());
lcd->Lcd_Initial_Lcd(false);
// lcd->Lcd_Clear_screen();
// lcd->Lcd_Display_Graphic_16x16(map_Display[DisType::Dis_Init].page, map_Display[DisType::Dis_Init].col, map_Display[DisType::Dis_Init].str.data(),map_Display[DisType::Dis_Init].str.size()/32);
}
LCDDisplay::~LCDDisplay()
{
lcd->Lcd_Clear_screen();
lcd.reset();
}
void LCDDisplay::DisplayState(DisType ds, unsigned int pagenum,ClearScreen clearscree)
{
if(clearscree == ClearScreen::All)
lcd->Lcd_Clear_screen();
if(clearscree == ClearScreen::TOP)
lcd->Lcd_Clear_Half_Screen(true);
if(clearscree == ClearScreen::BOT)
lcd->Lcd_Clear_Half_Screen(false);
if (map_Display.count(ds) > 0)
{
m_status = ds;
auto dsinfo = map_Display[ds];
if (ds == DisType::Dis_Welcome)//show logo
{
lcd->Lcd_Display_Graphic_128x64(dsinfo.page, dsinfo.col, dsinfo.str.data());
}
else
{
lcd->Lcd_Display_Graphic_16x16(dsinfo.page, dsinfo.col, dsinfo.str.data(), dsinfo.str.size() / 32);
//if (ds == DisType::Dis_Scan || ds == DisType::Dis_Set_Count) //扫描或者计数 更新下半部分内容
//{
//lcd->Lcd_Clear_Half_Screen(false);
//lcd->Lcd_Display_String_8x16(3, 96, "0");
//lcd->Lcd_Display_Graphic_16x16(map_Display[DisType::Dis_Scan_Page].page, map_Display[DisType::Dis_Scan_Page].col, map_Display[DisType::Dis_Scan_Page].str.data(), map_Display[DisType::Dis_Scan_Page].str.size() / 32);
//}
}
switch (ds)
{
case DisType::Dis_Count_Page:
case DisType::Dis_Scan_Page:
{
//std::string val = std::to_string(pagenum);
//auto offsetdot = bitnum(pagenum) - 1;
std::string val(std::to_string(pagenum));
int offsetdot = val.length();
//printf("\n val = %s lenght = %d",val.c_str(),val.size());
lcd->Lcd_Display_String_8x16(3, 112 - offsetdot * 8, val.c_str()); //8 -> 一个数字所占点个数宽度
lcd->Lcd_Display_Graphic_16x16(map_Display[DisType::Dis_Scan_Page].page, map_Display[DisType::Dis_Scan_Page].col, map_Display[DisType::Dis_Scan_Page].str.data(), map_Display[DisType::Dis_Scan_Page].str.size() / 32);
break;
}
case DisType::Dis_Err_JamIn:
{
if(pagenum == 1)
lcd->Lcd_Display_String_8x16(3, 56, "P a 1 0 1"); //8 -> 一个数字所占点个数宽度
else if(pagenum == 2)
lcd->Lcd_Display_String_8x16(3, 56, "P a 1 0 2");
else if(pagenum == 3)
lcd->Lcd_Display_String_8x16(3, 56, "P a 1 0 3");
break;
}
case DisType::Dis_Err_AqrImgTimeout:
lcd->Lcd_Display_String_8x16(3, 56, "G p 0 0 1");
break;
case DisType::Dis_Err_CoverOpen:
lcd->Lcd_Display_String_8x16(3, 56, "C o 0 0 1");
break;
case DisType::Dis_Err_PaperScrew:
lcd->Lcd_Display_String_8x16(3, 56, "S K 0 0 1");
break;
case DisType::Dis_Err_DoubleFeed:
lcd->Lcd_Display_String_8x16(3, 56, "D b 0 0 1");
break;
case DisType::Dis_Err_NoPaper:
lcd->Lcd_Display_String_8x16(3, 56, "N o 0 0 1");
break;
case DisType::Dis_Err_Stable:
lcd->Lcd_Display_String_8x16(3, 56, "S T 0 0 1");
break;
case DisType::Dis_Err_FeedError:
lcd->Lcd_Display_String_8x16(3, 56, "P f 0 0 1");
break;
case DisType::Dis_Err_DogEar:
lcd->Lcd_Display_String_8x16(3, 56, "Z J 0 0 1");
break;
case DisType::Dis_Err_Size:
lcd->Lcd_Display_String_8x16(3, 56, "C C 0 0 1");
break;
case DisType::Dis_Set_Get_History_ScanNum:
{
std::string val = std::to_string(pagenum);
int offsetdot = 8 > val.length() ? val.length() : 8;
lcd->Lcd_Display_String_8x16(3, 128 - offsetdot * 8, val.c_str()); //8 -> 一个数字所占点个数宽度
break;
}
case DisType::Dis_Set_Get_Roller_ScanNum:
{
std::string val = std::to_string(pagenum);
int offsetdot = 8 > val.length() ? val.length() : 8;
lcd->Lcd_Display_String_8x16(3, 128 - offsetdot * 8, val.c_str()); //8 -> 一个数字所占点个数宽度
break;
}
default:
break;
}
}
else
{
switch (ds){
case DisType::Dis_Set_SleepMode_5M:
lcd->Lcd_Display_String_8x16(3, 112, "5M");
break;
case DisType::Dis_Set_SleepMode_10M:
lcd->Lcd_Display_String_8x16(3, 104, "10M");
break;
case DisType::Dis_Set_SleepMode_20M:
lcd->Lcd_Display_String_8x16(3, 104, "20M");
break;
case DisType::Dis_Set_SleepMode_30M:
lcd->Lcd_Display_String_8x16(3, 104, "30M");
break;
case DisType::Dis_Set_SleepMode_1H:
lcd->Lcd_Display_String_8x16(3, 112, "1H");
break;
case DisType::Dis_Set_SleepMode_2H:
lcd->Lcd_Display_String_8x16(3, 112, "2H");
break;
case DisType::Dis_Set_SleepMode_4H:
lcd->Lcd_Display_String_8x16(3, 112, "4H");
break;
default:
m_status= DisType::Dis_Unkown;
break;
}
}
}
int LCDDisplay::bitnum(unsigned int num)
{
int count = 0;
do
{
num = num / 10;
count++;
} while (num > 0);
return count;
}
DisType LCDDisplay::GetCurrentStatus() const
{
return m_status;
}

22
ui/LCDDisplay.h Normal file
View File

@ -0,0 +1,22 @@
#pragma once
#include <map>
#include <memory>
#include "HgLCDfont.h"
class Lcd;
class LCDDisplay
{
private:
/* data */
public:
LCDDisplay(/* args */);
~LCDDisplay();
void DisplayState(DisType ds,unsigned int pagenum,ClearScreen clearscree);
DisType GetCurrentStatus() const;
private:
int bitnum(unsigned int num);
private:
std::shared_ptr<Lcd> lcd;
DisType m_status;
};

781
ui/Lcd.cpp Normal file
View File

@ -0,0 +1,781 @@
#include "Lcd.h"
#include <thread>
#include <iostream>
#include <fstream>
#include <uart/DevUtil.h>
using namespace std;
#define IOEXPORTPATH "/sys/class/gpio/export"
#define DELAY_US(t) this_thread::sleep_for(chrono::microseconds((t)))
#define DELAY_MS(t) this_thread::sleep_for(chrono::milliseconds((t)))
static unsigned char ascii_table_8x16[95][16] = {
/*-- 文字: --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
/*-- 文字: ! --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x33, 0x30, 0x00, 0x00, 0x00,
/*-- 文字: " --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x10, 0x0C, 0x06, 0x10, 0x0C, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
/*-- 文字: # --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x40, 0xC0, 0x78, 0x40, 0xC0, 0x78, 0x40, 0x00, 0x04, 0x3F, 0x04, 0x04, 0x3F, 0x04, 0x04, 0x00,
/*-- 文字: $ --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x70, 0x88, 0xFC, 0x08, 0x30, 0x00, 0x00, 0x00, 0x18, 0x20, 0xFF, 0x21, 0x1E, 0x00, 0x00,
/*-- 文字: % --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0xF0, 0x08, 0xF0, 0x00, 0xE0, 0x18, 0x00, 0x00, 0x00, 0x21, 0x1C, 0x03, 0x1E, 0x21, 0x1E, 0x00,
/*-- 文字: & --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0xF0, 0x08, 0x88, 0x70, 0x00, 0x00, 0x00, 0x1E, 0x21, 0x23, 0x24, 0x19, 0x27, 0x21, 0x10,
/*-- 文字: ' --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x10, 0x16, 0x0E, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
/*-- 文字: ( --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x00, 0x00, 0xE0, 0x18, 0x04, 0x02, 0x00, 0x00, 0x00, 0x00, 0x07, 0x18, 0x20, 0x40, 0x00,
/*-- 文字: ) --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x02, 0x04, 0x18, 0xE0, 0x00, 0x00, 0x00, 0x00, 0x40, 0x20, 0x18, 0x07, 0x00, 0x00, 0x00,
/*-- 文字: * --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x40, 0x40, 0x80, 0xF0, 0x80, 0x40, 0x40, 0x00, 0x02, 0x02, 0x01, 0x0F, 0x01, 0x02, 0x02, 0x00,
/*-- 文字: + --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x00, 0x00, 0x01, 0x01, 0x01, 0x1F, 0x01, 0x01, 0x01, 0x00,
/*-- 文字: , --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0xB0, 0x70, 0x00, 0x00, 0x00, 0x00, 0x00,
/*-- 文字: - --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01,
/*-- 文字: . --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x30, 0x30, 0x00, 0x00, 0x00, 0x00, 0x00,
/*-- 文字: / --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x00, 0x00, 0x00, 0x80, 0x60, 0x18, 0x04, 0x00, 0x60, 0x18, 0x06, 0x01, 0x00, 0x00, 0x00,
/*-- 文字: 0 --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0xE0, 0x10, 0x08, 0x08, 0x10, 0xE0, 0x00, 0x00, 0x0F, 0x10, 0x20, 0x20, 0x10, 0x0F, 0x00,
/*-- 文字: 1 --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x10, 0x10, 0xF8, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x20, 0x3F, 0x20, 0x20, 0x00, 0x00,
/*-- 文字: 2 --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x70, 0x08, 0x08, 0x08, 0x88, 0x70, 0x00, 0x00, 0x30, 0x28, 0x24, 0x22, 0x21, 0x30, 0x00,
/*-- 文字: 3 --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x30, 0x08, 0x88, 0x88, 0x48, 0x30, 0x00, 0x00, 0x18, 0x20, 0x20, 0x20, 0x11, 0x0E, 0x00,
/*-- 文字: 4 --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x00, 0xC0, 0x20, 0x10, 0xF8, 0x00, 0x00, 0x00, 0x07, 0x04, 0x24, 0x24, 0x3F, 0x24, 0x00,
/*-- 文字: 5 --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0xF8, 0x08, 0x88, 0x88, 0x08, 0x08, 0x00, 0x00, 0x19, 0x21, 0x20, 0x20, 0x11, 0x0E, 0x00,
/*-- 文字: 6 --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0xE0, 0x10, 0x88, 0x88, 0x18, 0x00, 0x00, 0x00, 0x0F, 0x11, 0x20, 0x20, 0x11, 0x0E, 0x00,
/*-- 文字: 7 --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x38, 0x08, 0x08, 0xC8, 0x38, 0x08, 0x00, 0x00, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x00, 0x00,
/*-- 文字: 8 --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x70, 0x88, 0x08, 0x08, 0x88, 0x70, 0x00, 0x00, 0x1C, 0x22, 0x21, 0x21, 0x22, 0x1C, 0x00,
/*-- 文字: 9 --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0xE0, 0x10, 0x08, 0x08, 0x10, 0xE0, 0x00, 0x00, 0x00, 0x31, 0x22, 0x22, 0x11, 0x0F, 0x00,
/*-- 文字: : --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x00, 0x00, 0xC0, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x30, 0x30, 0x00, 0x00, 0x00,
/*-- 文字: ; --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x60, 0x00, 0x00, 0x00, 0x00,
/*-- 文字: < --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x00, 0x80, 0x40, 0x20, 0x10, 0x08, 0x00, 0x00, 0x01, 0x02, 0x04, 0x08, 0x10, 0x20, 0x00,
/*-- 文字: = --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x40, 0x00, 0x04, 0x04, 0x04, 0x04, 0x04, 0x04, 0x04, 0x00,
/*-- 文字: > --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x08, 0x10, 0x20, 0x40, 0x80, 0x00, 0x00, 0x00, 0x20, 0x10, 0x08, 0x04, 0x02, 0x01, 0x00,
/*-- 文字: ? --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x70, 0x48, 0x08, 0x08, 0x08, 0xF0, 0x00, 0x00, 0x00, 0x00, 0x30, 0x36, 0x01, 0x00, 0x00,
/*-- 文字: @ --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0xC0, 0x30, 0xC8, 0x28, 0xE8, 0x10, 0xE0, 0x00, 0x07, 0x18, 0x27, 0x24, 0x23, 0x14, 0x0B, 0x00,
/*-- 文字: A --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x00, 0xC0, 0x38, 0xE0, 0x00, 0x00, 0x00, 0x20, 0x3C, 0x23, 0x02, 0x02, 0x27, 0x38, 0x20,
/*-- 文字: B --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x08, 0xF8, 0x88, 0x88, 0x88, 0x70, 0x00, 0x00, 0x20, 0x3F, 0x20, 0x20, 0x20, 0x11, 0x0E, 0x00,
/*-- 文字: C --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0xC0, 0x30, 0x08, 0x08, 0x08, 0x08, 0x38, 0x00, 0x07, 0x18, 0x20, 0x20, 0x20, 0x10, 0x08, 0x00,
/*-- 文字: D --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x08, 0xF8, 0x08, 0x08, 0x08, 0x10, 0xE0, 0x00, 0x20, 0x3F, 0x20, 0x20, 0x20, 0x10, 0x0F, 0x00,
/*-- 文字: E --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x08, 0xF8, 0x88, 0x88, 0xE8, 0x08, 0x10, 0x00, 0x20, 0x3F, 0x20, 0x20, 0x23, 0x20, 0x18, 0x00,
/*-- 文字: F --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x08, 0xF8, 0x88, 0x88, 0xE8, 0x08, 0x10, 0x00, 0x20, 0x3F, 0x20, 0x00, 0x03, 0x00, 0x00, 0x00,
/*-- 文字: G --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0xC0, 0x30, 0x08, 0x08, 0x08, 0x38, 0x00, 0x00, 0x07, 0x18, 0x20, 0x20, 0x22, 0x1E, 0x02, 0x00,
/*-- 文字: H --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x08, 0xF8, 0x08, 0x00, 0x00, 0x08, 0xF8, 0x08, 0x20, 0x3F, 0x21, 0x01, 0x01, 0x21, 0x3F, 0x20,
/*-- 文字: I --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x08, 0x08, 0xF8, 0x08, 0x08, 0x00, 0x00, 0x00, 0x20, 0x20, 0x3F, 0x20, 0x20, 0x00, 0x00,
/*-- 文字: J --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x00, 0x08, 0x08, 0xF8, 0x08, 0x08, 0x00, 0xC0, 0x80, 0x80, 0x80, 0x7F, 0x00, 0x00, 0x00,
/*-- 文字: K --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x08, 0xF8, 0x88, 0xC0, 0x28, 0x18, 0x08, 0x00, 0x20, 0x3F, 0x20, 0x01, 0x26, 0x38, 0x20, 0x00,
/*-- 文字: L --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x08, 0xF8, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x3F, 0x20, 0x20, 0x20, 0x20, 0x30, 0x00,
/*-- 文字: M --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x08, 0xF8, 0xF8, 0x00, 0xF8, 0xF8, 0x08, 0x00, 0x20, 0x3F, 0x00, 0x3F, 0x00, 0x3F, 0x20, 0x00,
/*-- 文字: N --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x08, 0xF8, 0x30, 0xC0, 0x00, 0x08, 0xF8, 0x08, 0x20, 0x3F, 0x20, 0x00, 0x07, 0x18, 0x3F, 0x00,
/*-- 文字: O --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0xE0, 0x10, 0x08, 0x08, 0x08, 0x10, 0xE0, 0x00, 0x0F, 0x10, 0x20, 0x20, 0x20, 0x10, 0x0F, 0x00,
/*-- 文字: P --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x08, 0xF8, 0x08, 0x08, 0x08, 0x08, 0xF0, 0x00, 0x20, 0x3F, 0x21, 0x01, 0x01, 0x01, 0x00, 0x00,
/*-- 文字: Q --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0xE0, 0x10, 0x08, 0x08, 0x08, 0x10, 0xE0, 0x00, 0x0F, 0x18, 0x24, 0x24, 0x38, 0x50, 0x4F, 0x00,
/*-- 文字: R --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x08, 0xF8, 0x88, 0x88, 0x88, 0x88, 0x70, 0x00, 0x20, 0x3F, 0x20, 0x00, 0x03, 0x0C, 0x30, 0x20,
/*-- 文字: S --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x70, 0x88, 0x08, 0x08, 0x08, 0x38, 0x00, 0x00, 0x38, 0x20, 0x21, 0x21, 0x22, 0x1C, 0x00,
/*-- 文字: T --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x18, 0x08, 0x08, 0xF8, 0x08, 0x08, 0x18, 0x00, 0x00, 0x00, 0x20, 0x3F, 0x20, 0x00, 0x00, 0x00,
/*-- 文字: U --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x08, 0xF8, 0x08, 0x00, 0x00, 0x08, 0xF8, 0x08, 0x00, 0x1F, 0x20, 0x20, 0x20, 0x20, 0x1F, 0x00,
/*-- 文字: V --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x08, 0x78, 0x88, 0x00, 0x00, 0xC8, 0x38, 0x08, 0x00, 0x00, 0x07, 0x38, 0x0E, 0x01, 0x00, 0x00,
/*-- 文字: W --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0xF8, 0x08, 0x00, 0xF8, 0x00, 0x08, 0xF8, 0x00, 0x03, 0x3C, 0x07, 0x00, 0x07, 0x3C, 0x03, 0x00,
/*-- 文字: X --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x08, 0x18, 0x68, 0x80, 0x80, 0x68, 0x18, 0x08, 0x20, 0x30, 0x2C, 0x03, 0x03, 0x2C, 0x30, 0x20,
/*-- 文字: Y --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x08, 0x38, 0xC8, 0x00, 0xC8, 0x38, 0x08, 0x00, 0x00, 0x00, 0x20, 0x3F, 0x20, 0x00, 0x00, 0x00,
/*-- 文字: Z --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x10, 0x08, 0x08, 0x08, 0xC8, 0x38, 0x08, 0x00, 0x20, 0x38, 0x26, 0x21, 0x20, 0x20, 0x18, 0x00,
/*-- 文字: [ --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x00, 0x00, 0xFE, 0x02, 0x02, 0x02, 0x00, 0x00, 0x00, 0x00, 0x7F, 0x40, 0x40, 0x40, 0x00,
/*-- 文字: \ --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x0C, 0x30, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x06, 0x38, 0xC0, 0x00,
/*-- 文字: ] --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x02, 0x02, 0x02, 0xFE, 0x00, 0x00, 0x00, 0x00, 0x40, 0x40, 0x40, 0x7F, 0x00, 0x00, 0x00,
/*-- 文字: ^ --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x00, 0x04, 0x02, 0x02, 0x02, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
/*-- 文字: _ --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80,
/*-- 文字: ` --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x02, 0x02, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
/*-- 文字: a --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x00, 0x80, 0x80, 0x80, 0x80, 0x00, 0x00, 0x00, 0x19, 0x24, 0x22, 0x22, 0x22, 0x3F, 0x20,
/*-- 文字: b --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x08, 0xF8, 0x00, 0x80, 0x80, 0x00, 0x00, 0x00, 0x00, 0x3F, 0x11, 0x20, 0x20, 0x11, 0x0E, 0x00,
/*-- 文字: c --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x00, 0x00, 0x80, 0x80, 0x80, 0x00, 0x00, 0x00, 0x0E, 0x11, 0x20, 0x20, 0x20, 0x11, 0x00,
/*-- 文字: d --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x00, 0x00, 0x80, 0x80, 0x88, 0xF8, 0x00, 0x00, 0x0E, 0x11, 0x20, 0x20, 0x10, 0x3F, 0x20,
/*-- 文字: e --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x00, 0x80, 0x80, 0x80, 0x80, 0x00, 0x00, 0x00, 0x1F, 0x22, 0x22, 0x22, 0x22, 0x13, 0x00,
/*-- 文字: f --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x80, 0x80, 0xF0, 0x88, 0x88, 0x88, 0x18, 0x00, 0x20, 0x20, 0x3F, 0x20, 0x20, 0x00, 0x00,
/*-- 文字: g --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x00, 0x80, 0x80, 0x80, 0x80, 0x80, 0x00, 0x00, 0x6B, 0x94, 0x94, 0x94, 0x93, 0x60, 0x00,
/*-- 文字: h --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x08, 0xF8, 0x00, 0x80, 0x80, 0x80, 0x00, 0x00, 0x20, 0x3F, 0x21, 0x00, 0x00, 0x20, 0x3F, 0x20,
/*-- 文字: i --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x80, 0x98, 0x98, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x20, 0x3F, 0x20, 0x20, 0x00, 0x00,
/*-- 文字: j --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x00, 0x00, 0x80, 0x98, 0x98, 0x00, 0x00, 0x00, 0xC0, 0x80, 0x80, 0x80, 0x7F, 0x00, 0x00,
/*-- 文字: k --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x08, 0xF8, 0x00, 0x00, 0x80, 0x80, 0x80, 0x00, 0x20, 0x3F, 0x24, 0x02, 0x2D, 0x30, 0x20, 0x00,
/*-- 文字: l --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x08, 0x08, 0xF8, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x20, 0x3F, 0x20, 0x20, 0x00, 0x00,
/*-- 文字: m --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x00, 0x20, 0x3F, 0x20, 0x00, 0x3F, 0x20, 0x00, 0x3F,
/*-- 文字: n --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x80, 0x80, 0x00, 0x80, 0x80, 0x80, 0x00, 0x00, 0x20, 0x3F, 0x21, 0x00, 0x00, 0x20, 0x3F, 0x20,
/*-- 文字: o --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x00, 0x80, 0x80, 0x80, 0x80, 0x00, 0x00, 0x00, 0x1F, 0x20, 0x20, 0x20, 0x20, 0x1F, 0x00,
/*-- 文字: p --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x80, 0x80, 0x00, 0x80, 0x80, 0x00, 0x00, 0x00, 0x80, 0xFF, 0xA1, 0x20, 0x20, 0x11, 0x0E, 0x00,
/*-- 文字: q --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x00, 0x00, 0x80, 0x80, 0x80, 0x80, 0x00, 0x00, 0x0E, 0x11, 0x20, 0x20, 0xA0, 0xFF, 0x80,
/*-- 文字: r --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x80, 0x80, 0x80, 0x00, 0x80, 0x80, 0x80, 0x00, 0x20, 0x20, 0x3F, 0x21, 0x20, 0x00, 0x01, 0x00,
/*-- 文字: s --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x00, 0x80, 0x80, 0x80, 0x80, 0x80, 0x00, 0x00, 0x33, 0x24, 0x24, 0x24, 0x24, 0x19, 0x00,
/*-- 文字: t --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x80, 0x80, 0xE0, 0x80, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1F, 0x20, 0x20, 0x00, 0x00,
/*-- 文字: u --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x80, 0x80, 0x00, 0x00, 0x00, 0x80, 0x80, 0x00, 0x00, 0x1F, 0x20, 0x20, 0x20, 0x10, 0x3F, 0x20,
/*-- 文字: v --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x80, 0x80, 0x80, 0x00, 0x00, 0x80, 0x80, 0x80, 0x00, 0x01, 0x0E, 0x30, 0x08, 0x06, 0x01, 0x00,
/*-- 文字: w --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x80, 0x80, 0x00, 0x80, 0x00, 0x80, 0x80, 0x80, 0x0F, 0x30, 0x0C, 0x03, 0x0C, 0x30, 0x0F, 0x00,
/*-- 文字: x --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x80, 0x80, 0x00, 0x80, 0x80, 0x80, 0x00, 0x00, 0x20, 0x31, 0x2E, 0x0E, 0x31, 0x20, 0x00,
/*-- 文字: y --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x80, 0x80, 0x80, 0x00, 0x00, 0x80, 0x80, 0x80, 0x80, 0x81, 0x8E, 0x70, 0x18, 0x06, 0x01, 0x00,
/*-- 文字: z --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x80, 0x80, 0x80, 0x80, 0x80, 0x80, 0x00, 0x00, 0x21, 0x30, 0x2C, 0x22, 0x21, 0x30, 0x00,
/*-- 文字: { --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x00, 0x00, 0x00, 0x80, 0x7C, 0x02, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3F, 0x40, 0x40,
/*-- 文字: | --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x00, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x00,
/*-- 文字: } --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x02, 0x02, 0x7C, 0x80, 0x00, 0x00, 0x00, 0x00, 0x40, 0x40, 0x3F, 0x00, 0x00, 0x00, 0x00,
/*-- 文字: ~ --*/
/*-- Comic Sans MS12; 此字体下对应的点阵为宽x高=8x16 --*/
0x00, 0x06, 0x01, 0x01, 0x02, 0x02, 0x04, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
};
static unsigned char ascii_table_5x8[95][5] = {
/*全体ASCII 列表:5x8点阵*/
0x00, 0x00, 0x00, 0x00, 0x00, //space
0x00, 0x00, 0x4f, 0x00, 0x00, //!
0x00, 0x07, 0x00, 0x07, 0x00, //"
0x14, 0x7f, 0x14, 0x7f, 0x14, //#
0x24, 0x2a, 0x7f, 0x2a, 0x12, //$
0x23, 0x13, 0x08, 0x64, 0x62, //%
0x36, 0x49, 0x55, 0x22, 0x50, //&
0x00, 0x05, 0x07, 0x00, 0x00, //]
0x00, 0x1c, 0x22, 0x41, 0x00, //(
0x00, 0x41, 0x22, 0x1c, 0x00, //)
0x14, 0x08, 0x3e, 0x08, 0x14, //*
0x08, 0x08, 0x3e, 0x08, 0x08, //+
0x00, 0x50, 0x30, 0x00, 0x00, //,
0x08, 0x08, 0x08, 0x08, 0x08, //-
0x00, 0x60, 0x60, 0x00, 0x00, //.
0x20, 0x10, 0x08, 0x04, 0x02, ///
0x3e, 0x51, 0x49, 0x45, 0x3e, //0
0x00, 0x42, 0x7f, 0x40, 0x00, //1
0x42, 0x61, 0x51, 0x49, 0x46, //2
0x21, 0x41, 0x45, 0x4b, 0x31, //3
0x18, 0x14, 0x12, 0x7f, 0x10, //4
0x27, 0x45, 0x45, 0x45, 0x39, //5
0x3c, 0x4a, 0x49, 0x49, 0x30, //6
0x01, 0x71, 0x09, 0x05, 0x03, //7
0x36, 0x49, 0x49, 0x49, 0x36, //8
0x06, 0x49, 0x49, 0x29, 0x1e, //9
0x00, 0x36, 0x36, 0x00, 0x00, //:
0x00, 0x56, 0x36, 0x00, 0x00, //;
0x08, 0x14, 0x22, 0x41, 0x00, //<
0x14, 0x14, 0x14, 0x14, 0x14, //=
0x00, 0x41, 0x22, 0x14, 0x08, //>
0x02, 0x01, 0x51, 0x09, 0x06, //?
0x32, 0x49, 0x79, 0x41, 0x3e, //@
0x7e, 0x11, 0x11, 0x11, 0x7e, //A
0x7f, 0x49, 0x49, 0x49, 0x36, //B
0x3e, 0x41, 0x41, 0x41, 0x22, //C
0x7f, 0x41, 0x41, 0x22, 0x1c, //D
0x7f, 0x49, 0x49, 0x49, 0x41, //E
0x7f, 0x09, 0x09, 0x09, 0x01, //F
0x3e, 0x41, 0x49, 0x49, 0x7a, //G
0x7f, 0x08, 0x08, 0x08, 0x7f, //H
0x00, 0x41, 0x7f, 0x41, 0x00, //I
0x20, 0x40, 0x41, 0x3f, 0x01, //J
0x7f, 0x08, 0x14, 0x22, 0x41, //K
0x7f, 0x40, 0x40, 0x40, 0x40, //L
0x7f, 0x02, 0x0c, 0x02, 0x7f, //M
0x7f, 0x04, 0x08, 0x10, 0x7f, //N
0x3e, 0x41, 0x41, 0x41, 0x3e, //O
0x7f, 0x09, 0x09, 0x09, 0x06, //P
0x3e, 0x41, 0x51, 0x21, 0x5e, //Q
0x7f, 0x09, 0x19, 0x29, 0x46, //R
0x46, 0x49, 0x49, 0x49, 0x31, //S
0x01, 0x01, 0x7f, 0x01, 0x01, //T
0x3f, 0x40, 0x40, 0x40, 0x3f, //U
0x1f, 0x20, 0x40, 0x20, 0x1f, //V
0x3f, 0x40, 0x38, 0x40, 0x3f, //W
0x63, 0x14, 0x08, 0x14, 0x63, //X
0x07, 0x08, 0x70, 0x08, 0x07, //Y
0x61, 0x51, 0x49, 0x45, 0x43, //Z
0x00, 0x7f, 0x41, 0x41, 0x00, //[
0x02, 0x04, 0x08, 0x10, 0x20, //\
0x00,0x41,0x41,0x7f,0x00,//]
0x04, 0x02, 0x01, 0x02, 0x04, //^
0x40, 0x40, 0x40, 0x40, 0x40, //_
0x01, 0x02, 0x04, 0x00, 0x00, //`
0x20, 0x54, 0x54, 0x54, 0x78, //a
0x7f, 0x48, 0x48, 0x48, 0x30, //b
0x38, 0x44, 0x44, 0x44, 0x44, //c
0x30, 0x48, 0x48, 0x48, 0x7f, //d
0x38, 0x54, 0x54, 0x54, 0x58, //e
0x00, 0x08, 0x7e, 0x09, 0x02, //f
0x48, 0x54, 0x54, 0x54, 0x3c, //g
0x7f, 0x08, 0x08, 0x08, 0x70, //h
0x00, 0x00, 0x7a, 0x00, 0x00, //i
0x20, 0x40, 0x40, 0x3d, 0x00, //j
0x7f, 0x20, 0x28, 0x44, 0x00, //k
0x00, 0x41, 0x7f, 0x40, 0x00, //l
0x7c, 0x04, 0x38, 0x04, 0x7c, //m
0x7c, 0x08, 0x04, 0x04, 0x78, //n
0x38, 0x44, 0x44, 0x44, 0x38, //o
0x7c, 0x14, 0x14, 0x14, 0x08, //p
0x08, 0x14, 0x14, 0x14, 0x7c, //q
0x7c, 0x08, 0x04, 0x04, 0x08, //r
0x48, 0x54, 0x54, 0x54, 0x24, //s
0x04, 0x04, 0x3f, 0x44, 0x24, //t
0x3c, 0x40, 0x40, 0x40, 0x3c, //u
0x1c, 0x20, 0x40, 0x20, 0x1c, //v
0x3c, 0x40, 0x30, 0x40, 0x3c, //w
0x44, 0x28, 0x10, 0x28, 0x44, //x
0x04, 0x48, 0x30, 0x08, 0x04, //y
0x44, 0x64, 0x54, 0x4c, 0x44, //z
0x08, 0x36, 0x41, 0x41, 0x00, //{
0x00, 0x00, 0x77, 0x00, 0x00, //|
0x00, 0x41, 0x41, 0x36, 0x08, //}
0x04, 0x02, 0x02, 0x02, 0x01, //~
};
Lcd::Lcd() : spi_sck(51), spi_sda(72), spi_cs(154), spi_reset(150), spi_rs(156),COM_BOOT0(153)
{
printf("Lcd()\n");
write_dev(IOEXPORTPATH,51);
write_dev(IOEXPORTPATH,72);
write_dev(IOEXPORTPATH,154);
write_dev(IOEXPORTPATH,150);
write_dev(IOEXPORTPATH,156);
write_dev(IOEXPORTPATH,153);
COM_BOOT0.setDirection(Gpio::out);
spi_sck.setDirection(Gpio::out);
spi_sda.setDirection(Gpio::out);
spi_cs.setDirection(Gpio::out);
spi_reset.setDirection(Gpio::out);
spi_rs.setDirection(Gpio::out);
COM_BOOT0.setValue(Gpio::Low);
spi_sck.setValue(Gpio::High);
spi_sda.setValue(Gpio::High);
spi_cs.setValue(Gpio::High);
spi_reset.setValue(Gpio::High);
spi_rs.setValue(Gpio::High);
}
/*=======写指令========*/
void Lcd::Lcd_Transfer_Command(int data1)
{
spi_cs.setValue(Gpio::Low);
spi_rs.setValue(Gpio::Low);
for (int i = 0; i < 8; i++)
{
spi_sck.setValue(Gpio::Low);
if (data1 & 0x80)
spi_sda.setValue(Gpio::High);
else
spi_sda.setValue(Gpio::Low);
spi_sck.setValue(Gpio::High);
data1 = data1 <<= 1;
}
spi_cs.setValue(Gpio::High);
}
/*--------写数据------------*/
void Lcd::Lcd_Transfer_data(int data1)
{
spi_cs.setValue(Gpio::Low);
spi_rs.setValue(Gpio::High);
for (int i = 0; i < 8; i++)
{
spi_sck.setValue(Gpio::Low);
if (data1 & 0x80)
spi_sda.setValue(Gpio::High);
else
spi_sda.setValue(Gpio::Low);
spi_sck.setValue(Gpio::High);
data1 = data1 <<= 1;
}
spi_cs.setValue(Gpio::High);
}
/*LCD模块初始化*/
void Lcd::Lcd_Initial_Lcd(bool biglcd)
{
spi_cs.setValue(Gpio::Low);
spi_reset.setValue(Gpio::Low); /*低电平复位*/
DELAY_MS(20);
spi_reset.setValue(Gpio::High); /*复位完毕*/
DELAY_MS(20);
Lcd_Transfer_Command(0xe2); /*软复位*/
DELAY_MS(50);
Lcd_Transfer_Command(0x2c); /*升压步聚1*/
DELAY_MS(50);
Lcd_Transfer_Command(0x2e); /*升压步聚2*/
DELAY_MS(50);
Lcd_Transfer_Command(0x2f); /*升压步聚3*/
DELAY_MS(50);
Lcd_Transfer_Command(biglcd?0x21:0x24); /*0X24粗调对比度可设置范围0x200x27*/
Lcd_Transfer_Command(0x81); /*微调对比度*/
Lcd_Transfer_Command(biglcd?0x28:0x15); /*45微调对比度的值可设置范围0x000x3f 1f*/ // 0~63
Lcd_Transfer_Command(0xa2); /*1/9偏压比bias0xa2 ,1/7bias 0xa3*/
Lcd_Transfer_Command(0xc8); /*行扫描顺序:从上到下*/ //原 c0 字体倒置 CF /////////////////////////////////////////////////////////////
Lcd_Transfer_Command(0xa0); /*列扫描顺序:从左到右*/ //原 a1 字体倒置 A0 ////////////////////////////////////////////////
Lcd_Transfer_Command(0x40); /*起始行:第一行开始*/
Lcd_Transfer_Command(0xaf); /*开显示*/
spi_cs.setValue(Gpio::High);
}
void Lcd::Lcd_Address(unsigned char page, unsigned char column)
{
spi_cs.setValue(Gpio::Low);
column = column - 1;
page = page - 1;
Lcd_Transfer_Command(0xb0 + page); //设置页地址。每页是8行。一个画面的64行被分成8个页。我们平常所说的第1页在LCD驱动IC里是第0页所以在这里减去1*/
Lcd_Transfer_Command(((column >> 4) & 0x0f) + 0x10); //设置列地址的高4位
Lcd_Transfer_Command(column & 0x0f); //设置列地址的低4位
}
/*全屏清屏*/
void Lcd::Lcd_Clear_screen()
{
unsigned char i, j;
spi_cs.setValue(Gpio::Low);
for (i = 0; i < 4; i++)
{
Lcd_Address(1 + i, 1);
for (j = 0; j < 132; j++)
{
Lcd_Transfer_data(0x00);
}
}
spi_cs.setValue(Gpio::High);
}
//===显示测试画面:例如全显示,隔行显示,隔列显示,雪花显示=====
void Lcd::Lcd_Test_Display(unsigned char data1, unsigned char data2)
{
int i, j;
for (j = 0; j < 8; j++)
{
spi_cs.setValue(Gpio::Low);
Lcd_Address(j + 1, 1);
for (i = 0; i < 128; i++)
{
Lcd_Transfer_data(data1);
Lcd_Transfer_data(data2);
}
}
}
/*显示128x64点阵图像*/
void Lcd::Lcd_Display_Graphic_128x64(unsigned char page, unsigned char column, unsigned char *dp)
{
int i, j;
for (j = 0; j < 8; j++)
{
spi_cs.setValue(Gpio::Low);
Lcd_Address(page + j, column);
for (i = 0; i < 128; i++)
{
Lcd_Transfer_data(*dp);
dp++;
}
}
}
/*显示32x32点阵图像、汉字、生僻字或32x32点阵的其他图标*/
void Lcd::Lcd_Display_graphic_32x32(unsigned char page, unsigned char column, unsigned char *dp)
{
unsigned char i, j;
spi_cs.setValue(Gpio::Low);
for (j = 0; j < 4; j++)
{
Lcd_Address(page + j, column);
for (i = 0; i < 31; i++)
{
Lcd_Transfer_data(*dp); /*写数据到LCD,每写完一个8位的数据后列地址自动加1*/
dp++;
}
}
}
/*显示16x16点阵图像、汉字、生僻字或16x16点阵的其他图标*/
void Lcd::Lcd_Display_Graphic_16x16_2(unsigned char reverse, unsigned char page, unsigned char column, unsigned char *dp)
{
unsigned char i, j;
spi_cs.setValue(Gpio::Low);
for (j = 0; j < 2; j++)
{
Lcd_Address(page + j, column);
for (i = 0; i < 16; i++)
{
if (reverse == 1)
Lcd_Transfer_data(*dp); /*写数据到LCD,每写完一个8位的数据后列地址自动加1*/
else
Lcd_Transfer_data(~*dp); /*写数据到LCD,每写完一个8位的数据后列地址自动加1*/
dp++;
}
}
spi_cs.setValue(Gpio::High);
}
/*显示16x16点阵图像、汉字、生僻字或16x16点阵的其他图标*/
void Lcd::Lcd_Display_Graphic_16x16(unsigned char page, unsigned char column, unsigned char *dp, unsigned int wordcount)
{
unsigned char i, j, k;
spi_cs.setValue(Gpio::Low);
for (k = 0; k < wordcount; k++)
{
for (j = 0; j < 2; j++)
{
Lcd_Address(page + j, column + 16 * k);
for (i = 0; i < 16; i++)
{
Lcd_Transfer_data(*dp); /*写数据到LCD,每写完一个8位的数据后列地址自动加1*/
dp++;
}
}
}
spi_cs.setValue(Gpio::High);
}
/*显示8x16点阵图像、ASCII, 或8x16点阵的自造字符、其他图标*/
void Lcd::Lcd_Display_Graphic_8x16(unsigned char page, unsigned char column, unsigned char *dp)
{
unsigned char i, j;
spi_cs.setValue(Gpio::Low);
for (j = 0; j < 2; j++)
{
Lcd_Address(page + j, column);
for (i = 0; i < 8; i++)
{
Lcd_Transfer_data(*dp); /*写数据到LCD,每写完一个8位的数据后列地址自动加1*/
dp++;
}
}
spi_cs.setValue(Gpio::High);
}
void Lcd::Lcd_Display_String_8x16(unsigned int page, unsigned int column, const char *text)
{
unsigned int i = 0, j, k, n;
spi_cs.setValue(Gpio::Low);
while (text[i] > 0x00)
{
if ((text[i] >= 0x20) && (text[i] <= 0x7e))
{
j = text[i] - 0x20;
for (n = 0; n < 2; n++)
{
Lcd_Address(page + n, column);
for (k = 0; k < 8; k++)
{
Lcd_Transfer_data(ascii_table_8x16[j][k + 8 * n]); /*显示5x7的ASCII字到LCD上y为页地址x为列地址最后为数据*/
}
}
i++;
column += 8;
}
else
i++;
}
}
void Lcd::Lcd_Display_String_5x8(unsigned int page, unsigned int column, const char *text)
{
unsigned int i = 0, j, k;
spi_cs.setValue(Gpio::Low);
while (text[i] > 0x00)
{
if ((text[i] >= 0x20) && (text[i] < 0x7e))
{
j = text[i] - 0x20;
Lcd_Address(page, column);
for (k = 0; k < 5; k++)
{
Lcd_Transfer_data(ascii_table_5x8[j][k]); /*显示5x7的ASCII字到LCD上y为页地址x为列地址最后为数据*/
}
i++;
column += 6;
}
else
i++;
}
}
void Lcd::Lcd_Clear_Half_Screen(bool top)
{
int pageindex = top ? 0 : 2;
int pagemaxindex = top ? 2 : 4;
spi_cs.setValue(Gpio::Low);
for (int i = pageindex; i < pagemaxindex; i++)
{
Lcd_Address(1 + i, 1);
for (int j = 0; j < 132; j++)
{
Lcd_Transfer_data(0x00);
}
}
spi_cs.setValue(Gpio::High);
}

61
ui/Lcd.h Normal file
View File

@ -0,0 +1,61 @@
#pragma once
#include <stdio.h>
#include <stdlib.h>
#include <sstream>
#include <time.h>
#include <unistd.h>
#include <uart/Gpio.h>
class Lcd
{
private:
Gpio spi_sck;
Gpio spi_sda;
Gpio spi_cs;
Gpio spi_reset;
Gpio spi_rs;
Gpio COM_BOOT0;
public:
Lcd();
/*=======写指令========*/
void Lcd_Transfer_Command(int data1);
/*--------写数据------------*/
void Lcd_Transfer_data(int data1);
/*LCD模块初始化*/
void Lcd_Initial_Lcd(bool biglcd);
void Lcd_Address(unsigned char page, unsigned char column);
/*全屏清屏*/
void Lcd_Clear_screen();
void Lcd_Clear_Half_Screen(bool top);
//===显示测试画面:例如全显示,隔行显示,隔列显示,雪花显示=====
void Lcd_Test_Display(unsigned char data1, unsigned char data2);
/*显示128x64点阵图像*/
void Lcd_Display_Graphic_128x64(unsigned char page, unsigned char column, unsigned char *dp);
/*显示32x32点阵图像、汉字、生僻字或32x32点阵的其他图标*/
void Lcd_Display_graphic_32x32(unsigned char page, unsigned char column, unsigned char *dp);
/*显示16x16点阵图像、汉字、生僻字或16x16点阵的其他图标*/
void Lcd_Display_Graphic_16x16_2(unsigned char reverse,unsigned char page,unsigned char column,unsigned char *dp);
/*显示16x16点阵图像、汉字、生僻字或16x16点阵的其他图标*/
void Lcd_Display_Graphic_16x16(unsigned char page, unsigned char column, unsigned char *dp,unsigned int wordcount);
/*显示8x16点阵图像、ASCII, 或8x16点阵的自造字符、其他图标*/
void Lcd_Display_Graphic_8x16(unsigned char page, unsigned char column,unsigned char *dp);
void Lcd_Display_String_8x16(unsigned int page, unsigned int column, const char *text);
void Lcd_Display_String_5x8(unsigned int page, unsigned int column, const char *text);
};

67
ui/main.cpp Normal file
View File

@ -0,0 +1,67 @@
#include <iostream>
#include <iomanip>
#include <memory>
#include <thread>
#include <chrono>
#include <stdio.h>
#include <stdlib.h>
#include <signal.h>
#include <errno.h>
#include <unistd.h>
#include <sys/file.h>
#include <functional>
#include "DisplayCenter.h"
#define BUF_LEN_FOR_PID 64
static void sigHandler(int sig)
{
// if (sig == SIGINT || sig == SIGTERM)
// remove(MY_PID_FILE);
printf("exit now for signal: %d\n", sig);
_exit(0);
}
int main()
{
/* Ctrl + C */
if (signal(SIGINT, sigHandler) == SIG_ERR)
{
exit(-1);
}
/* kill pid / killall name */
if (signal(SIGTERM, sigHandler) == SIG_ERR)
{
exit(-1);
}
int err = 0;
DisplayCenter monitor;
monitor.PutMsg(DisType::Dis_Welcome, 0, ClearScreen::All);
if(err == 0)
{
while(1)
{
if(getchar() == 'e')
{
if(getchar() == 'x')
{
if(getchar() == 'i')
{
if(getchar() == 't')
break;
}
}
}
}
}
return 0;
}

9
ui/xmake.lua Normal file
View File

@ -0,0 +1,9 @@
add_rules("mode.debug", "mode.release")
target("monitor")
set_kind("binary")
add_syslinks("pthread", "dl")
add_includedirs("../sdk")
add_files("*.cpp", "../sdk/base/*.c*", "../sdk/uart/*.c*", "../sdk/json/*.c*")
add_packages("sdk")

View File

@ -60,8 +60,8 @@ add_packagedirs("sdk")
add_defines("BUILD_AS_DEVICE") add_defines("BUILD_AS_DEVICE")
add_defines("VER_MAIN=2") add_defines("VER_MAIN=2")
add_defines("VER_FAMILY=300") add_defines("VER_FAMILY=300")
add_defines("VER_DATE=20240105") add_defines("VER_DATE=20240109")
add_defines("VER_BUILD=3") add_defines("VER_BUILD=14")
target("conf") target("conf")
set_kind("phony") set_kind("phony")
@ -70,7 +70,7 @@ target("conf")
add_configfiles("config.h.in", {prefixdir = "header"}) add_configfiles("config.h.in", {prefixdir = "header"})
add_includedirs("$(buildir)/config/header", { public = true }) add_includedirs("$(buildir)/config/header", { public = true })
includes("usb", "hardware", "scanner") includes("usb", "hardware", "scanner", "ui")