From 7181da95dee0865ec147d3b1d028dd673650d5e7 Mon Sep 17 00:00:00 2001 From: CaoWangrenbo Date: Wed, 31 Jan 2024 09:24:26 +0800 Subject: [PATCH 01/19] doc: update Readme.md --- Readme.md | 11 +++++------ 1 file changed, 5 insertions(+), 6 deletions(-) diff --git a/Readme.md b/Readme.md index 8972d31..b722b56 100644 --- a/Readme.md +++ b/Readme.md @@ -1,11 +1,13 @@ -# fireware_violet +# fireware_clover + +> 白塔岭143-气垫船组-图像处理板固件仓库 ## 1 使用 VSCode + EIDE + GCC + OpenOCD 开发 ### 1.1 前提要求 -1. VSCode 安装了 `EIDE` 插件 -2. 有 Python3 环境 +1. VSCode 安装了 `EIDE` 插件 +2. 有 Python3 环境 3. 已有沁恒 risc-v 工具链 (MRS 集成开发环境自带) ### 1.2 在工作区目录下运行配置脚本 @@ -21,9 +23,6 @@ pyhton ./set_eide_env.py ## 2 常用快捷键 * 编译:`F7` - * 下载:`Ctrl + Alt + D` - * 擦除:`Ctrl + Alt + E`(虽然没什么用) - * 调试:`F5` (需配合 Cortex-Debug 插件,由于不支持 `gdb version < 9` 设置起来稍微复杂,后面再补说明) From 64e95d278ce14ae7cfa89821e0b20e5fd3c4fb41 Mon Sep 17 00:00:00 2001 From: CaoWangrenbo Date: Wed, 31 Jan 2024 17:20:09 +0800 Subject: [PATCH 02/19] =?UTF-8?q?feat:=20=E5=AE=8C=E6=88=90=E6=8C=89?= =?UTF-8?q?=E9=94=AE=E3=80=81=E5=B1=8F=E5=B9=95=E5=92=8C=E8=9C=82=E9=B8=A3?= =?UTF-8?q?=E5=99=A8=E9=80=82=E9=85=8D?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .eide/eide.json | 5 +- .vscode/launch.json | 2 +- 3rd-lib/PID-Library/LICENSE | 21 -- 3rd-lib/PID-Library/README.md | 164 ----------- 3rd-lib/PID-Library/pid.c | 293 -------------------- 3rd-lib/PID-Library/pid.h | 176 ------------ app/by_button.c | 29 ++ app/by_button.h | 33 +++ app/by_buzzer.c | 23 +- app/by_buzzer.h | 19 +- app/by_fan_control.c | 58 ---- app/by_fan_control.h | 11 - app/by_imu.c | 192 ------------- app/by_imu.h | 47 ---- app/by_rt_button.c | 34 +-- app/by_rt_button.h | 3 - app/isr.c | 98 +++---- app/jj_blueteeth.c | 92 ------ app/jj_blueteeth.h | 14 - app/jj_motion.c | 60 ---- app/jj_motion.h | 18 -- app/jj_param.c | 15 +- app/main.c | 62 ++--- app/page/page.c | 8 +- app/page/page.h | 28 +- app/page/page_param.c | 4 +- libraries/sdk/Ld/Link.ld | 186 ++++++++++++- libraries/zf_device/zf_device_ips200.c | 4 +- libraries/zf_device/zf_device_ips200.h | 2 +- libraries/zf_device/zf_device_k24c02.h | 6 +- libraries/zf_device/zf_device_mt9v03x_dvp.h | 16 +- 31 files changed, 385 insertions(+), 1338 deletions(-) delete mode 100644 3rd-lib/PID-Library/LICENSE delete mode 100644 3rd-lib/PID-Library/README.md delete mode 100644 3rd-lib/PID-Library/pid.c delete mode 100644 3rd-lib/PID-Library/pid.h create mode 100644 app/by_button.c create mode 100644 app/by_button.h delete mode 100644 app/by_fan_control.c delete mode 100644 app/by_fan_control.h delete mode 100644 app/by_imu.c delete mode 100644 app/by_imu.h delete mode 100644 app/jj_blueteeth.c delete mode 100644 app/jj_blueteeth.h delete mode 100644 app/jj_motion.c delete mode 100644 app/jj_motion.h diff --git a/.eide/eide.json b/.eide/eide.json index b4e7241..a9a788f 100644 --- a/.eide/eide.json +++ b/.eide/eide.json @@ -1,5 +1,5 @@ { - "name": "violet_firmware_zf", + "name": "firmware_clover", "type": "RISC-V", "dependenceList": [], "srcDirs": [ @@ -7,8 +7,7 @@ "libraries/sdk", "libraries/zf_common", "libraries/zf_device", - "libraries/zf_driver", - "3rd-lib/PID-Library" + "libraries/zf_driver" ], "virtualFolder": { "name": "", diff --git a/.vscode/launch.json b/.vscode/launch.json index a467a37..a02ddac 100644 --- a/.vscode/launch.json +++ b/.vscode/launch.json @@ -7,7 +7,7 @@ "request": "launch", "name": "openocd", "servertype": "openocd", - "executable": "build\\Debug\\violet_firmware_zf.elf", + "executable": "build\\Debug\\firmware_clover.elf", "runToEntryPoint": "main", "configFiles": [ "${workspaceFolder}/tools/wch-riscv.cfg" diff --git a/3rd-lib/PID-Library/LICENSE b/3rd-lib/PID-Library/LICENSE deleted file mode 100644 index 4fbde9a..0000000 --- a/3rd-lib/PID-Library/LICENSE +++ /dev/null @@ -1,21 +0,0 @@ -MIT License - -Copyright (c) 2021 Majid Derhambakhsh - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. diff --git a/3rd-lib/PID-Library/README.md b/3rd-lib/PID-Library/README.md deleted file mode 100644 index 78a691c..0000000 --- a/3rd-lib/PID-Library/README.md +++ /dev/null @@ -1,164 +0,0 @@ -![Banner](Banner.png) - -# PID-Library (C Version) -PID Controller library for ARM Cortex M (STM32) - -> #### Download Arduino Library : [Arduino-PID-Library](https://github.com/br3ttb/Arduino-PID-Library) - -## Release -- #### Version : 1.0.0 - -- #### Type : Embedded Software. - -- #### Support : - - ARM STM32 series - -- #### Program Language : C/C++ - -- #### Properties : - -- #### Changes : - -- #### Required Library/Driver : - - -## Overview -### Initialization and de-initialization functions: -```c++ -void PID(PID_TypeDef *uPID, float *Input, float *Output, float *Setpoint, float Kp, float Ki, float Kd, PIDPON_TypeDef POn, PIDCD_TypeDef ControllerDirection); -void PID2(PID_TypeDef *uPID, float *Input, float *Output, float *Setpoint, float Kp, float Ki, float Kd, PIDCD_TypeDef ControllerDirection); -``` - -### Operation functions: -```c++ -/* ::::::::::: Computing ::::::::::: */ -uint8_t PID_Compute(PID_TypeDef *uPID); - -/* ::::::::::: PID Mode :::::::::::: */ -void PID_SetMode(PID_TypeDef *uPID, PIDMode_TypeDef Mode); -PIDMode_TypeDef PID_GetMode(PID_TypeDef *uPID); - -/* :::::::::: PID Limits ::::::::::: */ -void PID_SetOutputLimits(PID_TypeDef *uPID, float Min, float Max); - -/* :::::::::: PID Tunings :::::::::: */ -void PID_SetTunings(PID_TypeDef *uPID, float Kp, float Ki, float Kd); -void PID_SetTunings2(PID_TypeDef *uPID, float Kp, float Ki, float Kd, PIDPON_TypeDef POn); - -/* ::::::::: PID Direction ::::::::: */ -void PID_SetControllerDirection(PID_TypeDef *uPID, PIDCD_TypeDef Direction); -PIDCD_TypeDef PID_GetDirection(PID_TypeDef *uPID); - -/* ::::::::: PID Sampling :::::::::: */ -void PID_SetSampleTime(PID_TypeDef *uPID, int32_t NewSampleTime); - -/* ::::::: Get Tunings Param ::::::: */ -float PID_GetKp(PID_TypeDef *uPID); -float PID_GetKi(PID_TypeDef *uPID); -float PID_GetKd(PID_TypeDef *uPID); -``` - -### Macros: -```diff -non -``` - -## Guide - -#### This library can be used as follows: -#### 1. Add pid.h header -#### 2. Create PID struct and initialize it, for example: -* Initializer: - ```c++ - PID(PID_TypeDef *uPID, float *Input, float *Output, float *Setpoint, float Kp, float Ki, float Kd, PIDPON_TypeDef POn, PIDCD_TypeDef ControllerDirection); - ``` -* Parameters: - * uPID : Pointer to pid struct - * Input : The variable we're trying to control (float) - * Output : The variable that will be adjusted by the pid (float) - * Setpoint : The value we want to Input to maintain (float) - * Kp,Ki,Kd : Tuning Parameters. these affect how the pid will change the output (float>=0) - * POn : Either P_ON_E (Default) or P_ON_M. Allows Proportional on Measurement to be specified. - * ControllerDirection : Either DIRECT or REVERSE. determines which direction the output will move when faced with a given error. DIRECT is most common - - -* Example: - ```c++ - PID_TypeDef TPID; - - float Temp, PIDOut, TempSetpoint; - - PID(&TPID, &Temp, &PIDOut, &TempSetpoint, 2, 5, 1, _PID_P_ON_E, _PID_CD_DIRECT); - ``` -#### 3. Set 'mode', 'sample time' and 'output limit', for example: -* Functions: - ```c++ - void PID_SetMode(PID_TypeDef *uPID, PIDMode_TypeDef Mode); - void PID_SetOutputLimits(PID_TypeDef *uPID, float Min, float Max); - void PID_SetSampleTime(PID_TypeDef *uPID, int32_t NewSampleTime); - ``` -* Parameters: - * uPID : Pointer to pid struct - * Mode : _PID_MODE_AUTOMATIC or _PID_MODE_MANUAL - * Min : Low end of the range. must be < max (float) - * Max : High end of the range. must be > min (float) - * NewSampleTime : How often, in milliseconds, the PID will be evaluated. (int>0) - -* Example: - ```c++ - PID_SetMode(&TPID, _PID_MODE_AUTOMATIC); - PID_SetSampleTime(&TPID, 500); - PID_SetOutputLimits(&TPID, 1, 100); - ``` - -#### 4. Using Compute function, for example: - -```c++ -PID_Compute(&TPID); -``` - -## Examples - -#### Example 1: PID Compute for temperature -```c++ -#include "main.h" -#include "pid.h" - -PID_TypeDef TPID; - -char OutBuf[50]; -float Temp, PIDOut, TempSetpoint; - -int main(void) -{ - - HW_Init(); - - PID(&TPID, &Temp, &PIDOut, &TempSetpoint, 2, 5, 1, _PID_P_ON_E, _PID_CD_DIRECT); - - PID_SetMode(&TPID, _PID_MODE_AUTOMATIC); - PID_SetSampleTime(&TPID, 500); - PID_SetOutputLimits(&TPID, 1, 100); - - while (1) - { - - Temp = GetTemp(); - PID_Compute(&TPID); - - sprintf(OutBuf, "Temp%3.2f : %u\n", Temp, (uint16_t)PIDOut); - UART_Transmit((uint8_t *)OutBuf, strlen(OutBuf)); - - Delay_ms(500); - - } -} - -``` - -## Tests performed: -- [x] Run on STM32 Fx cores - -## Developers: -- ### Majid Derhambakhsh - diff --git a/3rd-lib/PID-Library/pid.c b/3rd-lib/PID-Library/pid.c deleted file mode 100644 index 650e38a..0000000 --- a/3rd-lib/PID-Library/pid.c +++ /dev/null @@ -1,293 +0,0 @@ - /* ------------------------------------------------------------------------------- -~ File : pid.c -~ Author : Majid Derhambakhsh -~ Version: V1.0.0 -~ Created: 02/11/2021 03:43:00 AM -~ Brief : -~ Support: - E-Mail : Majid.do16@gmail.com (subject : Embedded Library Support) - - Github : https://github.com/Majid-Derhambakhsh ------------------------------------------------------------------------------- -~ Description: - -~ Attention : - -~ Changes : ------------------------------------------------------------------------------- -*/ - -#include "pid.h" - -/* ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ Functions ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ */ -/* ~~~~~~~~~~~~~~~~~ Initialize ~~~~~~~~~~~~~~~~ */ -void PID_Init(PID_TypeDef *uPID) -{ - /* ~~~~~~~~~~ Set parameter ~~~~~~~~~~ */ - uPID->OutputSum = *uPID->MyOutput; - uPID->LastInput = *uPID->MyInput; - - if (uPID->OutputSum > uPID->OutMax) - { - uPID->OutputSum = uPID->OutMax; - } - else if (uPID->OutputSum < uPID->OutMin) - { - uPID->OutputSum = uPID->OutMin; - } - - -} - -void PID(PID_TypeDef *uPID, float *Input, float *Output, float *Setpoint, float Kp, float Ki, float Kd, PIDPON_TypeDef POn, PIDCD_TypeDef ControllerDirection) -{ - /* ~~~~~~~~~~ Set parameter ~~~~~~~~~~ */ - uPID->MyOutput = Output; - uPID->MyInput = Input; - uPID->MySetpoint = Setpoint; - uPID->InAuto = (PIDMode_TypeDef)_FALSE; - - PID_SetOutputLimits(uPID, 0, _PID_8BIT_PWM_MAX); - - uPID->SampleTime = _PID_SAMPLE_TIME_MS_DEF; /* default Controller Sample Time is 0.1 seconds */ - - PID_SetControllerDirection(uPID, ControllerDirection); - PID_SetTunings2(uPID, Kp, Ki, Kd, POn); - -} - -void PID2(PID_TypeDef *uPID, float *Input, float *Output, float *Setpoint, float Kp, float Ki, float Kd, PIDCD_TypeDef ControllerDirection) -{ - PID(uPID, Input, Output, Setpoint, Kp, Ki, Kd, _PID_P_ON_E, ControllerDirection); -} - -/* ~~~~~~~~~~~~~~~~~ Computing ~~~~~~~~~~~~~~~~~ */ -uint8_t PID_Compute(PID_TypeDef *uPID) -{ - - float input=0; - float error=0; - float dInput=0; - float output=0; - - /* ~~~~~~~~~~ Check PID mode ~~~~~~~~~~ */ - if (!uPID->InAuto) - { - return _FALSE; - } - - - /* ..... Compute all the working error variables ..... */ - input = *uPID->MyInput; - error = *uPID->MySetpoint - input; - dInput = (input - uPID->LastInput); - - uPID->OutputSum += (uPID->Ki * error); - - /* ..... Add Proportional on Measurement, if P_ON_M is specified ..... */ - if (!uPID->POnE) - { - uPID->OutputSum -= uPID->Kp * dInput; - } - - if (uPID->OutputSum > uPID->OutMax) - { - uPID->OutputSum = uPID->OutMax; - } - else if (uPID->OutputSum < uPID->OutMin) - { - uPID->OutputSum = uPID->OutMin; - } - else { } - - /* ..... Add Proportional on Error, if P_ON_E is specified ..... */ - if (uPID->POnE) - { - output = uPID->Kp * error; - } - else - { - output = 0; - } - - /* ..... Compute Rest of PID Output ..... */ - output += uPID->OutputSum - uPID->Kd * dInput; - - if (output > uPID->OutMax) - { - output = uPID->OutMax; - } - else if (output < uPID->OutMin) - { - output = uPID->OutMin; - } - else { } - - *uPID->MyOutput = output; - - /* ..... Remember some variables for next time ..... */ - uPID->LastInput = input; - - return _TRUE; -} - -/* ~~~~~~~~~~~~~~~~~ PID Mode ~~~~~~~~~~~~~~~~~~ */ -void PID_SetMode(PID_TypeDef *uPID, PIDMode_TypeDef Mode) -{ - - uint8_t newAuto = (Mode == _PID_MODE_AUTOMATIC); - - /* ~~~~~~~~~~ Initialize the PID ~~~~~~~~~~ */ - if (newAuto && !uPID->InAuto) - { - PID_Init(uPID); - } - - uPID->InAuto = (PIDMode_TypeDef)newAuto; - -} -PIDMode_TypeDef PID_GetMode(PID_TypeDef *uPID) -{ - return uPID->InAuto ? _PID_MODE_AUTOMATIC : _PID_MODE_MANUAL; -} - -/* ~~~~~~~~~~~~~~~~ PID Limits ~~~~~~~~~~~~~~~~~ */ -void PID_SetOutputLimits(PID_TypeDef *uPID, float Min, float Max) -{ - /* ~~~~~~~~~~ Check value ~~~~~~~~~~ */ - if (Min >= Max) - { - return; - } - - uPID->OutMin = Min; - uPID->OutMax = Max; - - /* ~~~~~~~~~~ Check PID Mode ~~~~~~~~~~ */ - if (uPID->InAuto) - { - - /* ..... Check out value ..... */ - if (*uPID->MyOutput > uPID->OutMax) - { - *uPID->MyOutput = uPID->OutMax; - } - else if (*uPID->MyOutput < uPID->OutMin) - { - *uPID->MyOutput = uPID->OutMin; - } - else { } - - /* ..... Check out value ..... */ - if (uPID->OutputSum > uPID->OutMax) - { - uPID->OutputSum = uPID->OutMax; - } - else if (uPID->OutputSum < uPID->OutMin) - { - uPID->OutputSum = uPID->OutMin; - } - else { } - - } - -} - -/* ~~~~~~~~~~~~~~~~ PID Tunings ~~~~~~~~~~~~~~~~ */ -void PID_SetTunings(PID_TypeDef *uPID, float Kp, float Ki, float Kd) -{ - PID_SetTunings2(uPID, Kp, Ki, Kd, uPID->POn); -} -void PID_SetTunings2(PID_TypeDef *uPID, float Kp, float Ki, float Kd, PIDPON_TypeDef POn) -{ - - float SampleTimeInSec; - - /* ~~~~~~~~~~ Check value ~~~~~~~~~~ */ - if (Kp < 0 || Ki < 0 || Kd < 0) - { - return; - } - - /* ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ */ - uPID->POn = POn; - uPID->POnE = (PIDPON_TypeDef)(POn == _PID_P_ON_E); - - uPID->DispKp = Kp; - uPID->DispKi = Ki; - uPID->DispKd = Kd; - - /* ~~~~~~~~~ Calculate time ~~~~~~~~ */ - SampleTimeInSec = ((float)uPID->SampleTime) / 1000; - - uPID->Kp = Kp; - uPID->Ki = Ki * SampleTimeInSec; - uPID->Kd = Kd / SampleTimeInSec; - - /* ~~~~~~~~ Check direction ~~~~~~~~ */ - if (uPID->ControllerDirection == _PID_CD_REVERSE) - { - - uPID->Kp = (0 - uPID->Kp); - uPID->Ki = (0 - uPID->Ki); - uPID->Kd = (0 - uPID->Kd); - - } - -} - -/* ~~~~~~~~~~~~~~~ PID Direction ~~~~~~~~~~~~~~~ */ -void PID_SetControllerDirection(PID_TypeDef *uPID, PIDCD_TypeDef Direction) -{ - /* ~~~~~~~~~~ Check parameters ~~~~~~~~~~ */ - if ((uPID->InAuto) && (Direction !=uPID->ControllerDirection)) - { - - uPID->Kp = (0 - uPID->Kp); - uPID->Ki = (0 - uPID->Ki); - uPID->Kd = (0 - uPID->Kd); - - } - - uPID->ControllerDirection = Direction; - -} -PIDCD_TypeDef PID_GetDirection(PID_TypeDef *uPID) -{ - return uPID->ControllerDirection; -} - -/* ~~~~~~~~~~~~~~~ PID Sampling ~~~~~~~~~~~~~~~~ */ -void PID_SetSampleTime(PID_TypeDef *uPID, int32_t NewSampleTime) -{ - - float ratio; - - /* ~~~~~~~~~~ Check value ~~~~~~~~~~ */ - if (NewSampleTime > 0) - { - - ratio = (float)NewSampleTime / (float)uPID->SampleTime; - - uPID->Ki *= ratio; - uPID->Kd /= ratio; - uPID->SampleTime = (uint32_t)NewSampleTime; - - } - -} - -/* ~~~~~~~~~~~~~ Get Tunings Param ~~~~~~~~~~~~~ */ -float PID_GetKp(PID_TypeDef *uPID) -{ - return uPID->DispKp; -} -float PID_GetKi(PID_TypeDef *uPID) -{ - return uPID->DispKi; -} -float PID_GetKd(PID_TypeDef *uPID) -{ - return uPID->DispKd; -} diff --git a/3rd-lib/PID-Library/pid.h b/3rd-lib/PID-Library/pid.h deleted file mode 100644 index 7583788..0000000 --- a/3rd-lib/PID-Library/pid.h +++ /dev/null @@ -1,176 +0,0 @@ - /* ------------------------------------------------------------------------------- -~ File : pid.h -~ Author : Majid Derhambakhsh -~ Version: V1.0.0 -~ Created: 02/11/2021 03:43:00 AM -~ Brief : -~ Support: - E-Mail : Majid.do16@gmail.com (subject : Embedded Library Support) - - Github : https://github.com/Majid-Derhambakhsh ------------------------------------------------------------------------------- -~ Description: - -~ Attention : - -~ Changes : ------------------------------------------------------------------------------- -*/ - -#ifndef __PID_H_ -#define __PID_H_ - -/* ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ Include ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ */ -#include -#include - -#include "zf_common_headfile.h" - -/* ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ Defines ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ */ -/* ------------------------ Library ------------------------ */ -#define _PID_LIBRARY_VERSION 1.0.0 - -/* ------------------------ Public ------------------------- */ -#define _PID_8BIT_PWM_MAX UINT8_MAX -#define _PID_SAMPLE_TIME_MS_DEF 100 - -#ifndef _FALSE - - #define _FALSE 0 - -#endif - -#ifndef _TRUE - - #define _TRUE 1 - -#endif - -/* ---------------------- By compiler ---------------------- */ -#ifndef GetTime - - /* ---------------------- By compiler ---------------------- */ - - #ifdef __CODEVISIONAVR__ /* Check compiler */ - - #define GetTime() 0 - - /* ------------------------------------------------------------------ */ - - #elif defined(__GNUC__) /* Check compiler */ - - #define GetTime() 0 - - /* ------------------------------------------------------------------ */ - - - #else - #endif /* __CODEVISIONAVR__ */ - /* ------------------------------------------------------------------ */ - -#endif - -/* --------------------------------------------------------- */ - -/* ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ Types ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ */ -/* PID Mode */ -typedef enum -{ - - _PID_MODE_MANUAL = 0, - _PID_MODE_AUTOMATIC = 1 - -}PIDMode_TypeDef; - -/* PID P On x */ -typedef enum -{ - - _PID_P_ON_M = 0, /* Proportional on Measurement */ - _PID_P_ON_E = 1 - -}PIDPON_TypeDef; - -/* PID Control direction */ -typedef enum -{ - - _PID_CD_DIRECT = 0, - _PID_CD_REVERSE = 1 - -}PIDCD_TypeDef; - -/* PID Structure */ -typedef struct -{ - - PIDPON_TypeDef POnE; - PIDMode_TypeDef InAuto; - - PIDPON_TypeDef POn; - PIDCD_TypeDef ControllerDirection; - - uint32_t LastTime; - uint32_t SampleTime; - - float DispKp; - float DispKi; - float DispKd; - - float Kp; - float Ki; - float Kd; - - float *MyInput; - float *MyOutput; - float *MySetpoint; - - float OutputSum; - float LastInput; - - float OutMin; - float OutMax; - -}PID_TypeDef; - -/* ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ Variables ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ */ -/* ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ Enum ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ */ -/* ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ Struct ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ */ -/* ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ Class ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ */ -/* ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ Prototype ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ */ -/* :::::::::::::: Init ::::::::::::: */ -void PID_Init(PID_TypeDef *uPID); - -void PID(PID_TypeDef *uPID, float *Input, float *Output, float *Setpoint, float Kp, float Ki, float Kd, PIDPON_TypeDef POn, PIDCD_TypeDef ControllerDirection); -void PID2(PID_TypeDef *uPID, float *Input, float *Output, float *Setpoint, float Kp, float Ki, float Kd, PIDCD_TypeDef ControllerDirection); - -/* ::::::::::: Computing ::::::::::: */ -uint8_t PID_Compute(PID_TypeDef *uPID); - -/* ::::::::::: PID Mode :::::::::::: */ -void PID_SetMode(PID_TypeDef *uPID, PIDMode_TypeDef Mode); -PIDMode_TypeDef PID_GetMode(PID_TypeDef *uPID); - -/* :::::::::: PID Limits ::::::::::: */ -void PID_SetOutputLimits(PID_TypeDef *uPID, float Min, float Max); - -/* :::::::::: PID Tunings :::::::::: */ -void PID_SetTunings(PID_TypeDef *uPID, float Kp, float Ki, float Kd); -void PID_SetTunings2(PID_TypeDef *uPID, float Kp, float Ki, float Kd, PIDPON_TypeDef POn); - -/* ::::::::: PID Direction ::::::::: */ -void PID_SetControllerDirection(PID_TypeDef *uPID, PIDCD_TypeDef Direction); -PIDCD_TypeDef PID_GetDirection(PID_TypeDef *uPID); - -/* ::::::::: PID Sampling :::::::::: */ -void PID_SetSampleTime(PID_TypeDef *uPID, int32_t NewSampleTime); - -/* ::::::: Get Tunings Param ::::::: */ -float PID_GetKp(PID_TypeDef *uPID); -float PID_GetKi(PID_TypeDef *uPID); -float PID_GetKd(PID_TypeDef *uPID); - -/* ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ End of the program ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ */ - -#endif /* __PID_H_ */ diff --git a/app/by_button.c b/app/by_button.c new file mode 100644 index 0000000..b68a838 --- /dev/null +++ b/app/by_button.c @@ -0,0 +1,29 @@ +#include "by_button.h" + +#include "zf_common_headfile.h" + +button_event_t button_event; + +void by_button_init(void) +{ + gpio_init(BUTTON_LEFT_PIN, GPI, 1, GPI_PULL_UP); + gpio_init(BUTTON_DOWN_PIN, GPI, 1, GPI_PULL_UP); + gpio_init(BUTTON_UP_PIN, GPI, 1, GPI_PULL_UP); + gpio_init(BUTTON_CENTER_PIN, GPI, 1, GPI_PULL_UP); + gpio_init(BUTTON_RIGHT_PIN, GPI, 1, GPI_PULL_UP); + gpio_init(BUTTON_SIDE_PIN, GPI, 1, GPI_PULL_UP); + + exti_init(BUTTON_LEFT_PIN, EXTI_TRIGGER_FALLING); + exti_init(BUTTON_DOWN_PIN, EXTI_TRIGGER_FALLING); + exti_init(BUTTON_UP_PIN, EXTI_TRIGGER_FALLING); + exti_init(BUTTON_CENTER_PIN, EXTI_TRIGGER_BOTH); + exti_init(BUTTON_RIGHT_PIN, EXTI_TRIGGER_FALLING); + exti_init(BUTTON_SIDE_PIN, EXTI_TRIGGER_FALLING); +} + +uint8_t by_button_get_status(void) +{ + uint8_t temp_s = (uint8_t)button_event; + button_event = button_event_none; + return temp_s; +} \ No newline at end of file diff --git a/app/by_button.h b/app/by_button.h new file mode 100644 index 0000000..12e2877 --- /dev/null +++ b/app/by_button.h @@ -0,0 +1,33 @@ +#ifndef _BY_BUTTON_H__ +#define _BY_BUTTON_H__ + +#include +#include + +#define LONG_PRESS_THRESHOLD_MS (300ULL) +#define LONG_PRESS_THRESHOLD_TICK (LONG_PRESS_THRESHOLD_MS * 18000ULL) + +#define BUTTON_UP_PIN E12 +#define BUTTON_DOWN_PIN E11 +#define BUTTON_LEFT_PIN E10 +#define BUTTON_RIGHT_PIN E14 +#define BUTTON_CENTER_PIN E13 +#define BUTTON_SIDE_PIN E15 + +typedef enum button_event_t{ + button_event_none = 0, + button_event_up, + button_event_down, + button_event_left, + button_event_right, + button_event_center_sp, + button_event_center_lp, + button_event_side, +}button_event_t; + +extern button_event_t button_event; + +void by_button_init(void); +uint8_t by_button_get_status(void); + +#endif diff --git a/app/by_buzzer.c b/app/by_buzzer.c index 52188df..6af01c9 100644 --- a/app/by_buzzer.c +++ b/app/by_buzzer.c @@ -1,12 +1,13 @@ #include "by_buzzer.h" -#include "by_rt_button.h" -#include "zf_common_headfile.h" #include +#include "zf_common_headfile.h" + +#define BUZZER_QUEUE_LENGTH 40 + +uint16_t queue_long = 0; +uint32_t a[40] = {0}; -uint16_t queue_long = 0; -const uint32_t max_long = 40; -uint32_t a[40]; void queue_init(void) { memset(a, 0, sizeof(a)); @@ -14,7 +15,7 @@ void queue_init(void) void queue_add_element(int element) { - if (queue_long < max_long) { + if (queue_long < BUZZER_QUEUE_LENGTH) { a[queue_long] = element; queue_long += 1; } @@ -38,5 +39,15 @@ void queue_pop_read(void) void by_buzzer_init(void) { + queue_init(); pwm_init(BUZZER_PIN, 2000, 0); + + by_buzzer_add(1250); + by_buzzer_add(1500); + by_buzzer_add(1750); +} + +void by_buzzer_add(uint16_t tone) +{ + queue_add_element(tone); } diff --git a/app/by_buzzer.h b/app/by_buzzer.h index c410955..060c1b8 100644 --- a/app/by_buzzer.h +++ b/app/by_buzzer.h @@ -1,24 +1,23 @@ #ifndef _BY_BUZZER_H__ #define _BY_BUZZER_H__ -#include "by_rt_button.h" - -#include "stdio.h" -#include "ch32v30x.h" +#include "zf_common_headfile.h" #define BY_PRESS_SHORT 2000 #define BY_PRESS_LONG 2500 #define BY_FORWARD 1500 #define BY_BACKWARD 1800 -#define BUZZER_PIN TIM3_PWM_MAP0_CH2_A7 -extern void by_buzzer_init(void); -extern void queue_init(void); -extern void queue_add_element(int element); -extern void queue_pop_element(void); -extern void queue_pop_read(void); +#define BUZZER_PIN TIM4_PWM_MAP1_CH3_D14 extern uint32_t a[40]; extern uint16_t queue_long; extern const uint32_t max_long; extern uint8_t queue_flag; + +extern void queue_init(void); +extern void queue_add_element(int element); +extern void queue_pop_element(void); +extern void queue_pop_read(void); +extern void by_buzzer_init(void); +extern void by_buzzer_add(uint16_t tone); #endif \ No newline at end of file diff --git a/app/by_fan_control.c b/app/by_fan_control.c deleted file mode 100644 index 22a4463..0000000 --- a/app/by_fan_control.c +++ /dev/null @@ -1,58 +0,0 @@ -#include "by_fan_control.h" -#include "zf_common_headfile.h" -#define Fan_pwm_up1 TIM8_PWM_MAP0_CH1_C6 -#define Fan_pwm_up2 TIM8_PWM_MAP0_CH2_C7 -#define Fan_pwm_power1 TIM4_PWM_MAP1_CH3_D14 -#define Fan_pwm_power2 TIM4_PWM_MAP1_CH4_D15 -#define Fan_pwm_power3 TIM4_PWM_MAP1_CH2_D13 -#define Fan_pwm_power4 TIM4_PWM_MAP1_CH1_D12 - -uint32_t myclip(uint32_t x, uint32_t low, uint32_t up) -{ - return (x > up ? up : x < low ? low - : x); -} - -void by_pwm_init(void) -{ - pwm_init(Fan_pwm_up1, 50, 500); // 浮力风扇左 - pwm_init(Fan_pwm_up2, 50, 500); // 浮力风扇右 - - pwm_init(Fan_pwm_power1, 50, 500); // 动力风扇左1 - pwm_init(Fan_pwm_power2, 50, 500); // 动力风扇右1 - pwm_init(Fan_pwm_power3, 50, 500); // 动力风扇左2 - pwm_init(Fan_pwm_power4, 50, 500); // 动力风扇右2 - // system_delay_ms(3000); - // // pwm_init(Fan_pwm_power1, 50, 1000); // 动力风扇左1 - // // pwm_init(Fan_pwm_power2, 50, 1000); // 动力风扇右1 - // // pwm_init(Fan_pwm_power3, 50, 1000); // 动力风扇左2 - // // pwm_init(Fan_pwm_power4, 50, 1000); // 动力风扇右2 - // // system_delay_ms(5000); - // pwm_set_duty(Fan_pwm_power1, 600); - // pwm_set_duty(Fan_pwm_power2, 600); - // pwm_set_duty(Fan_pwm_power3, 600); - // pwm_set_duty(Fan_pwm_power4, 600); - // while(1); -} - -void by_pwm_update_duty(uint32_t update_pwm_duty1, uint32_t update_pwm_duty2) -{ - update_pwm_duty1=myclip(update_pwm_duty1, 500, 900); - update_pwm_duty2=myclip(update_pwm_duty2, 500, 900); - pwm_set_duty(Fan_pwm_up1, update_pwm_duty1); - pwm_set_duty(Fan_pwm_up2, update_pwm_duty2); -} - -void by_pwm_power_duty(uint32_t power_pwm_duty_l1, uint32_t power_pwm_duty_r1, uint32_t power_pwm_duty_l2, uint32_t power_pwm_duty_r2) -{ - - power_pwm_duty_l1=myclip(power_pwm_duty_l1, 500, 900); - power_pwm_duty_r1=myclip(power_pwm_duty_r1, 500, 900); - power_pwm_duty_l2=myclip(power_pwm_duty_l2, 500, 900); - power_pwm_duty_r2=myclip(power_pwm_duty_r2, 500, 900); - - pwm_set_duty(Fan_pwm_power1, power_pwm_duty_l1); - pwm_set_duty(Fan_pwm_power2, power_pwm_duty_r1); - pwm_set_duty(Fan_pwm_power3, power_pwm_duty_l2); - pwm_set_duty(Fan_pwm_power4, power_pwm_duty_r2); -} diff --git a/app/by_fan_control.h b/app/by_fan_control.h deleted file mode 100644 index d06fd22..0000000 --- a/app/by_fan_control.h +++ /dev/null @@ -1,11 +0,0 @@ -#ifndef _BY_FAN_CONTROL_H_ -#define _BY_FAN_CONTROL_H_ - -#include "stdio.h" -#include "ch32v30x.h" - -extern void by_pwm_init(void); -void by_pwm_update_duty(uint32_t update_pwm_duty1,uint32_t update_pwm_duty2); -void by_pwm_power_duty(uint32_t power_pwm_duty_l1, uint32_t power_pwm_duty_r1,uint32_t power_pwm_duty_l2, uint32_t power_pwm_duty_r2); - -#endif \ No newline at end of file diff --git a/app/by_imu.c b/app/by_imu.c deleted file mode 100644 index 5a0e864..0000000 --- a/app/by_imu.c +++ /dev/null @@ -1,192 +0,0 @@ -#include "by_imu.h" -#include "zf_common_headfile.h" -#include - -#define delta_T 0.002f // 2ms 计算一次 - -float I_ex, I_ey, I_ez; // 误差积分 - -quater_param_t Q_info = {1, 0, 0}; // 全局四元数 -euler_param_t eulerAngle; // 欧拉角 - -icm_param_t icm_data; -gyro_param_t GyroOffset; - -bool GyroOffset_init = 0; - -float param_Kp = 0.17f; // 加速度计的收敛速率比例增益 0.17 -float param_Ki = 0.004f; // 陀螺仪收敛速率的积分增益 0.004 - -float fast_sqrt(float x) -{ - float halfx = 0.5f * x; - float y = x; - long i = *(long *)&y; - i = 0x5f3759df - (i >> 1); - y = *(float *)&i; - y = y * (1.5f - (halfx * y * y)); - return y; -} - -void gyroOffset_init(void) /////////陀螺仪零飘初始化 -{ - float xdata_temp = 0; - float ydata_temp = 0; - float zdata_temp = 0; - - imu660ra_get_gyro(); - xdata_temp = imu660ra_gyro_x; - ydata_temp = imu660ra_gyro_y; - zdata_temp = imu660ra_gyro_z; - - GyroOffset.Xdata = 0; - GyroOffset.Ydata = 0; - GyroOffset.Zdata = 0; - for (uint16_t i = 0; i < 5000; i++) { - imu660ra_get_gyro(); - - xdata_temp = imu660ra_gyro_x * 0.3f + xdata_temp * 0.7f; - ydata_temp = imu660ra_gyro_y * 0.3f + ydata_temp * 0.7f; - zdata_temp = imu660ra_gyro_z * 0.3f + zdata_temp * 0.7f; - - GyroOffset.Xdata += xdata_temp; - GyroOffset.Ydata += ydata_temp; - GyroOffset.Zdata += zdata_temp; - system_delay_ms(5); - } - - GyroOffset.Xdata /= 5000.0f; - GyroOffset.Ydata /= 5000.0f; - GyroOffset.Zdata /= 5000.0f; - - // GyroOffset.Xdata = -1.034f; - // GyroOffset.Ydata = -2.21f; - // GyroOffset.Zdata = -3.15f; - - GyroOffset_init = 1; -} -// 转化为实际物理值 -void ICM_getValues() -{ -#define alpha 0.2738f - // icm_data.acc_x = imu660ra_acc_x * alpha + icm_data.acc_x * (1 - alpha); - // icm_data.acc_y = imu660ra_acc_y * alpha + icm_data.acc_y * (1 - alpha); - // icm_data.acc_z = imu660ra_acc_z * alpha + icm_data.acc_z * (1 - alpha); - - icm_data.acc_x = imu660ra_acc_x; - icm_data.acc_y = imu660ra_acc_y; - icm_data.acc_z = imu660ra_acc_z; - - icm_data.gyro_x = icm_data.gyro_x * alpha + ((imu660ra_gyro_x - GyroOffset.Xdata) / 939.65f) * (1 - alpha); - icm_data.gyro_y = icm_data.gyro_y * alpha + ((imu660ra_gyro_y - GyroOffset.Ydata) / 939.65f) * (1 - alpha); - icm_data.gyro_z = icm_data.gyro_z * alpha + ((imu660ra_gyro_z - GyroOffset.Zdata) / 939.65f) * (1 - alpha); -} - -// 互补滤波 -void ICM_AHRSupdate(float gx, float gy, float gz, float ax, float ay, float az) -{ - float halfT = 0.5 * delta_T; - float vx, vy, vz; // 当前的机体坐标系上的重力单位向量 - float ex, ey, ez; // 四元数计算值与加速度计测量值的误差 - float q0 = Q_info.q0; - float q1 = Q_info.q1; - float q2 = Q_info.q2; - float q3 = Q_info.q3; - float q0q0 = q0 * q0; - float q0q1 = q0 * q1; - float q0q2 = q0 * q2; - // float q0q3 = q0 * q3; - float q1q1 = q1 * q1; - // float q1q2 = q1 * q2; - float q1q3 = q1 * q3; - float q2q2 = q2 * q2; - float q2q3 = q2 * q3; - float q3q3 = q3 * q3; - // float delta_2 = 0; - - // 对加速度数据进行归一化 得到单位加速度 - float norm = fast_sqrt(ax * ax + ay * ay + az * az); - ax = ax * norm; - ay = ay * norm; - az = az * norm; - - // 根据当前四元数的姿态值来估算出各重力分量。用于和加速计实际测量出来的各重力分量进行对比,从而实现对四轴姿态的修正 - vx = 2.0f * (q1q3 - q0q2); - vy = 2.0f * (q0q1 + q2q3); - vz = q0q0 - q1q1 - q2q2 + q3q3; - // vz = 1.0f - 2.0f * q1q1 - 2.0f * q2q2; - // vz = (q0*q0-0.5f+q3 * q3) * 2; - - // 叉积来计算估算的重力和实际测量的重力这两个重力向量之间的误差。 - ex = ay * vz - az * vy; - ey = az * vx - ax * vz; - ez = ax * vy - ay * vx; - - // 用叉乘误差来做 PI 修正陀螺零偏, - // 通过调节 param_Kp,param_Ki 两个参数, - // 可以控制加速度计修正陀螺仪积分姿态的速度。 - I_ex += halfT * ex; // integral error scaled by Ki - I_ey += halfT * ey; - I_ez += halfT * ez; - - gx = gx + param_Kp * ex + param_Ki * I_ex; - gy = gy + param_Kp * ey + param_Ki * I_ey; - gz = gz + param_Kp * ez + param_Ki * I_ez; - - /*数据修正完成,下面是四元数微分方程*/ - - // 四元数微分方程,其中 halfT 为测量周期的 1/2,gx gy gz 为陀螺仪角速度,以下都是已知量,这里使用了一阶龙哥库塔求解四元数微分方程 - q0 = q0 + (-q1 * gx - q2 * gy - q3 * gz) * halfT; - q1 = q1 + (q0 * gx + q2 * gz - q3 * gy) * halfT; - q2 = q2 + (q0 * gy - q1 * gz + q3 * gx) * halfT; - q3 = q3 + (q0 * gz + q1 * gy - q2 * gx) * halfT; - // delta_2=(2*halfT*gx)*(2*halfT*gx)+(2*halfT*gy)*(2*halfT*gy)+(2*halfT*gz)*(2*halfT*gz); - // 整合四元数率 四元数微分方程 四元数更新算法,二阶毕卡法 - // q0 = (1-delta_2/8)*q0 + (-q1*gx - q2*gy - q3*gz)*halfT; - // q1 = (1-delta_2/8)*q1 + (q0*gx + q2*gz - q3*gy)*halfT; - // q2 = (1-delta_2/8)*q2 + (q0*gy - q1*gz + q3*gx)*halfT; - // q3 = (1-delta_2/8)*q3 + (q0*gz + q1*gy - q2*gx)*halfT - - // normalise quaternion - norm = fast_sqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3); - Q_info.q0 = q0 * norm; - Q_info.q1 = q1 * norm; - Q_info.q2 = q2 * norm; - Q_info.q3 = q3 * norm; -} -void ICM_getEulerianAngles(void) -{ - - // 采集陀螺仪数据 - imu660ra_get_acc(); - imu660ra_get_gyro(); - imu660ra_get_temperature(); - - ICM_getValues(); - ICM_AHRSupdate(icm_data.gyro_x, icm_data.gyro_y, icm_data.gyro_z, icm_data.acc_x, icm_data.acc_y, icm_data.acc_z); - float q0 = Q_info.q0; - float q1 = Q_info.q1; - float q2 = Q_info.q2; - float q3 = Q_info.q3; - - // 四元数计算欧拉角 - eulerAngle.pitch = asinf(-2 * q1 * q3 + 2 * q0 * q2) * 180.0f / M_PI; // pitch - eulerAngle.roll = atan2f(2 * q2 * q3 + 2 * q0 * q1, -2 * q1 * q1 - 2 * q2 * q2 + 1) * 180.0f / M_PI; // roll - eulerAngle.yaw = atan2f(2 * q1 * q2 + 2 * q0 * q3, -2 * q2 * q2 - 2 * q3 * q3 + 1) * 180.0f / M_PI; // yaw - - /* 姿态限制*/ - if (eulerAngle.roll > 90 || eulerAngle.roll < -90) { - if (eulerAngle.pitch > 0) { - eulerAngle.pitch = 180 - eulerAngle.pitch; - } - if (eulerAngle.pitch < 0) { - eulerAngle.pitch = -(180 + eulerAngle.pitch); - } - } - - if (eulerAngle.yaw > 180) { - eulerAngle.yaw -= 180; - } else if (eulerAngle.yaw < -180) { - eulerAngle.yaw += 180; - } -} diff --git a/app/by_imu.h b/app/by_imu.h deleted file mode 100644 index 63b681b..0000000 --- a/app/by_imu.h +++ /dev/null @@ -1,47 +0,0 @@ -#ifndef _BY_IMU_H__ -#define _BY_IMU_H__ - -#include -#include "ch32v30x.h" -typedef struct { - float gyro_x; - float gyro_y; - float gyro_z; - float acc_x; - float acc_y; - float acc_z; -} icm_param_t; - -typedef struct { - float q0; - float q1; - float q2; - float q3; -} quater_param_t; - -typedef struct { - float pitch; //俯仰角 - float roll; //偏航角 - float yaw; //翻滚角 -} euler_param_t; - -typedef struct { - float Xdata; - float Ydata; - float Zdata; -} gyro_param_t; - -extern icm_param_t icm_data; -extern euler_param_t eulerAngle; -extern gyro_param_t GyroOffset; - -void gyroOffset_init(void); - -float fast_sqrt(float x); - -void ICM_AHRSupdate(float gx, float gy, float gz, float ax, float ay, float az); - -void ICM_getValues(); - -void ICM_getEulerianAngles(void); -#endif \ No newline at end of file diff --git a/app/by_rt_button.c b/app/by_rt_button.c index 40b5471..d14c013 100644 --- a/app/by_rt_button.c +++ b/app/by_rt_button.c @@ -1,6 +1,5 @@ #include "by_rt_button.h" #include "zf_common_headfile.h" -#include "by_imu.h" uint8_t rotate_button; void by_gpio_init(void) @@ -24,35 +23,4 @@ uint8_t by_get_rb_status(void) uint8_t temp_s = rotate_button; rotate_button = 0; return temp_s; -} - -void by_ips_show(void) -{ - ips200_show_string(0, 0, "button status:"); - // ips200_show_uint(104, 0, by_get_rb_status(), 1); - switch (by_get_rb_status()) { - case 1: - ips200_show_string(104, 0, "press"); - break; - case 2: - ips200_show_string(104, 0, "up "); - break; - case 3: - ips200_show_string(104, 0, "down "); - break; - - default: - ips200_show_string(104, 0, " "); - break; - } - // 按钮 - ips200_show_string(0, 16, "imu:"); - ips200_show_float(46, 32, eulerAngle.pitch, 3, 2); - ips200_show_float(46, 48, eulerAngle.roll, 3, 2); - ips200_show_float(46, 64, eulerAngle.yaw, 3, 2); - // ips200_show_float(46 , 32, icm_data.gyro_x, 2, 2); - // ips200_show_float(106, 32, icm_data.gyro_y, 2, 2); - // ips200_show_float(166, 32, icm_data.gyro_z, 2, 2); - ips200_show_float(46, 80, imu660ra_temperature, 2, 2); - // printf("%d,%d,%d\n", (int16_t)(icm_data.gyro_x * 10), (int16_t)(icm_data.gyro_y * 10), (int16_t)(icm_data.gyro_z * 10)); -} +} \ No newline at end of file diff --git a/app/by_rt_button.h b/app/by_rt_button.h index c42d6e0..714e02f 100644 --- a/app/by_rt_button.h +++ b/app/by_rt_button.h @@ -4,9 +4,6 @@ #include "stdio.h" #include "ch32v30x.h" -#define LONG_PRESS_THRESHOLD_MS (300ULL) -#define LONG_PRESS_THRESHOLD_TICK (LONG_PRESS_THRESHOLD_MS * 18000ULL) - typedef enum rotate_button_event { rotate_button_press_short = 1, rotate_button_press_long = 2, diff --git a/app/isr.c b/app/isr.c index 33d4983..137e5f6 100644 --- a/app/isr.c +++ b/app/isr.c @@ -35,11 +35,8 @@ #include "zf_common_headfile.h" #include "by_rt_button.h" -#include "by_imu.h" -#include "jj_blueteeth.h" +#include "by_button.h" #include "by_buzzer.h" -#include "jj_motion.h" -#include "jj_blueteeth.h" void NMI_Handler(void) __attribute__((interrupt())); void HardFault_Handler(void) __attribute__((interrupt())); @@ -94,8 +91,6 @@ void USART1_IRQHandler(void) void USART2_IRQHandler(void) { if (USART_GetITStatus(USART2, USART_IT_RXNE) != RESET) { - uart_query_byte(UART_2, &bt_buffer); - bt_rx_flag = true; USART_ClearITPendingBit(USART2, USART_IT_RXNE); } } @@ -201,14 +196,6 @@ void EXTI9_5_IRQHandler(void) EXTI_ClearITPendingBit(EXTI_Line8); } if (SET == EXTI_GetITStatus(EXTI_Line9)) { - - if (SET == gpio_get_level(E10)) { - rotate_button = rotate_button_backward; - queue_add_element(BY_BACKWARD); - } else { - rotate_button = rotate_button_forward; - queue_add_element(BY_FORWARD); - } EXTI_ClearITPendingBit(EXTI_Line9); } } @@ -216,57 +203,63 @@ void EXTI9_5_IRQHandler(void) void EXTI15_10_IRQHandler(void) { if (SET == EXTI_GetITStatus(EXTI_Line10)) { - - // ˴дû (A10/B10..E10) Ŵ - - // ˴дû (A10/B10..E10) Ŵ - + system_delay_ms(10); + if (RESET == gpio_get_level(BUTTON_LEFT_PIN)) { + button_event = button_event_left; + } + by_buzzer_add(1250); EXTI_ClearITPendingBit(EXTI_Line10); } if (SET == EXTI_GetITStatus(EXTI_Line11)) { + system_delay_ms(10); + if (RESET == gpio_get_level(BUTTON_DOWN_PIN)) { + button_event = button_event_down; + } + by_buzzer_add(1250); + EXTI_ClearITPendingBit(EXTI_Line11); + } + if (SET == EXTI_GetITStatus(EXTI_Line12)) { + system_delay_ms(10); + if (RESET == gpio_get_level(BUTTON_UP_PIN)) { + button_event = button_event_up; + } + by_buzzer_add(1250); + EXTI_ClearITPendingBit(EXTI_Line12); + } + if (SET == EXTI_GetITStatus(EXTI_Line13)) { static uint64_t time_via = 0; system_delay_ms(10); - if (RESET == gpio_get_level(E11)) { + if (RESET == gpio_get_level(BUTTON_CENTER_PIN)) { time_via = system_get_tick(); - EXTI_ClearITPendingBit(EXTI_Line11); - } else if (SET == gpio_get_level(E11)) { + } else if (SET == gpio_get_level(BUTTON_CENTER_PIN)) { time_via = system_get_tick() - time_via; if (time_via > LONG_PRESS_THRESHOLD_TICK) { - rotate_button = rotate_button_press_long; - queue_add_element(BY_PRESS_LONG); - + button_event = button_event_center_lp; + by_buzzer_add(2000); } else { - rotate_button = rotate_button_press_short; - queue_add_element(BY_PRESS_SHORT); + button_event = button_event_center_sp; + by_buzzer_add(1800); } time_via = 0; - EXTI_ClearITPendingBit(EXTI_Line11); } - if (SET == EXTI_GetITStatus(EXTI_Line12)) { - EXTI_ClearITPendingBit(EXTI_Line12); + EXTI_ClearITPendingBit(EXTI_Line13); + } + if (SET == EXTI_GetITStatus(EXTI_Line14)) { + system_delay_ms(10); + if (RESET == gpio_get_level(BUTTON_RIGHT_PIN)) { + button_event = button_event_right; + by_buzzer_add(1250); } - if (SET == EXTI_GetITStatus(EXTI_Line13)) { - // -----------------* ToF INT ж Ԥжϴ *----------------- - tof_module_exti_handler(); - // -----------------* ToF INT ж Ԥжϴ *----------------- - // ˴дû (A13/B13..E13) Ŵ - - // ˴дû (A13/B13..E13) Ŵ - - EXTI_ClearITPendingBit(EXTI_Line13); - } - if (SET == EXTI_GetITStatus(EXTI_Line14)) { - // -----------------* DM1XA ź Ԥжϴ *----------------- - dm1xa_light_callback(); - // -----------------* DM1XA ź Ԥжϴ *----------------- - EXTI_ClearITPendingBit(EXTI_Line14); - } - if (SET == EXTI_GetITStatus(EXTI_Line15)) { - // -----------------* DM1XA /ź Ԥжϴ *----------------- - dm1xa_sound_callback(); - // -----------------* DM1XA /ź Ԥжϴ *----------------- - EXTI_ClearITPendingBit(EXTI_Line15); + EXTI_ClearITPendingBit(EXTI_Line14); + } + if (SET == EXTI_GetITStatus(EXTI_Line15)) { + system_delay_ms(10); + if (RESET == gpio_get_level(BUTTON_SIDE_PIN)) { + button_event = button_event_side; + by_buzzer_add(2000); + by_buzzer_add(1500); } + EXTI_ClearITPendingBit(EXTI_Line15); } } @@ -274,8 +267,6 @@ void TIM1_UP_IRQHandler(void) { if (TIM_GetITStatus(TIM1, TIM_IT_Update) != RESET) { TIM_ClearITPendingBit(TIM1, TIM_IT_Update); - - sport_motion2(bt_fly); } } @@ -310,7 +301,6 @@ void TIM5_IRQHandler(void) void TIM6_IRQHandler(void) { if (TIM_GetITStatus(TIM6, TIM_IT_Update) != RESET) { - ICM_getEulerianAngles(); TIM_ClearITPendingBit(TIM6, TIM_IT_Update); } } diff --git a/app/jj_blueteeth.c b/app/jj_blueteeth.c deleted file mode 100644 index 7e47f67..0000000 --- a/app/jj_blueteeth.c +++ /dev/null @@ -1,92 +0,0 @@ -#include "jj_blueteeth.h" -#include "jj_motion.h" -#include "by_fan_control.h" -bool bt_rx_flag = false; -uint8 bt_buffer; // 接收字符存入 -float bt_angle = 0.0f; -uint32_t bt_run_flag = 0; -uint8_t bt_flow_flag = 0; -uint32_t bt_fly = 0; -uint32_t bt_flow = 0; -enum bt_order { - Start_work = 0x01, - Turn_Left = 0x02, - Turn_Right = 0x03, - Speed_up = 0x04, - Speed_down = 0x05, - Stop_fly = 0x06, - Flow_on = 0x08, - Flow_up = 0x09, - Flow_down = 0x10, -}; -/** - * @brief 蓝牙初始化 - * @retval 无 - */ -void jj_bt_init() -{ - uart_init(UART_2, 115200, UART2_MAP1_TX_D5, UART2_MAP1_RX_D6); - // uart_tx_interrupt(UART_2, 1); - uart_rx_interrupt(UART_2, ENABLE); -} -/** - *@brief 蓝牙中断回调函数 - */ -void jj_bt_run() -{ - if (bt_rx_flag) { - switch (bt_buffer) { - case Start_work: - bt_angle = 0.0f; - break; - case Turn_Left: - bt_angle = 10.0f; - break; - case Turn_Right: - bt_angle = -10.0f; - break; - case Speed_down: - bt_fly -= 10; - break; - case Speed_up: - bt_fly += 10; - break; - case Stop_fly: - bt_run_flag = !bt_run_flag; - break; - case Flow_on: - bt_flow_flag = !bt_flow_flag; - break; - case Flow_up: - bt_flow += 20; - break; - case Flow_down: - bt_flow -= 20; - break; - default: - break; - } - - if (bt_flow_flag == 0) { - bt_flow = 0; - } - by_pwm_update_duty(bt_flow + 500, bt_flow + 500); - bt_rx_flag = false; - } -} - -void bt_printf(const char *format, ...) -{ - char sbuf[40]; - va_list args; - va_start(args, format); - vsnprintf(sbuf, 40, format, args); - va_end(args); - - for (uint16_t i = 0; i < strlen(sbuf); i++) { - while (USART_GetFlagStatus((USART_TypeDef *)uart_index[UART_2], USART_FLAG_TC) == RESET) - ; - USART_SendData((USART_TypeDef *)uart_index[UART_2], sbuf[i]); - } - -} \ No newline at end of file diff --git a/app/jj_blueteeth.h b/app/jj_blueteeth.h deleted file mode 100644 index 11f1a64..0000000 --- a/app/jj_blueteeth.h +++ /dev/null @@ -1,14 +0,0 @@ -#ifndef _JJ_BLUETEETH_H_ -#define _JJ_BLUETEETH_H_ -#include "stdio.h" -#include "zf_driver_uart.h" - -extern bool bt_rx_flag; -extern uint8_t bt_buffer; -extern uint32_t bt_fly; -extern uint32_t bt_run_flag; -extern float bt_angle; -void jj_bt_init(); -void jj_bt_run(); -void bt_printf(const char *format, ...); -#endif \ No newline at end of file diff --git a/app/jj_motion.c b/app/jj_motion.c deleted file mode 100644 index 3dbdb66..0000000 --- a/app/jj_motion.c +++ /dev/null @@ -1,60 +0,0 @@ -#include "jj_motion.h" -#include "by_fan_control.h" -#include "by_imu.h" -#include "../3rd-lib/PID-Library/pid.h" -#include "jj_blueteeth.h" -#include "gl_common.h" -PID_TypeDef angle_pid; -PID_TypeDef gyro_z_pid; -PID_TypeDef img_x_pid; -float an_Kp = 8.0f; -float an_Ki = 0.0f; -float an_Kd = 2.0f; -float im_Kp = 1.0f; -float im_Ki = 0.0f; -float im_Kd = 0.0f; -float set_x = 0.0f; -float img_x = 40.0f; -float yaw0 = 0; -float out_M = 0; -float out_yaw; -uint32_t cnt1 = 0; -/** - * @brief - * - * @param fy y轴的加速度 - */ -void sport_motion2(uint32_t fy) -{ - cnt1++; - yaw0 = imu660ra_gyro_z; - if (cnt1 >= 50) { - PID_Compute(&angle_pid); - cnt1 = 0; - } - PID_Compute(&gyro_z_pid); - if (bt_run_flag == 1) { - by_pwm_power_duty((int32_t)(500 + fy + out_M), (int32_t)(500 + fy - out_M), - (int32_t)(500 + fy + out_M), (int32_t)(500 + fy - out_M)); - } else { - by_pwm_power_duty(500, 500, 500, 500); - } -} -/** - * @brief 结构体初始化 - * - */ -void sport_pid_init() -{ - - PID(&angle_pid, &bt_angle, &out_yaw, &set_x, im_Kp, im_Ki, im_Kd, 0, 0); - PID(&gyro_z_pid, &yaw0, &out_M, &out_yaw, an_Kp, an_Ki, an_Kd, 1, 1); - PID_Init(&angle_pid); - PID_Init(&gyro_z_pid); - - PID_SetOutputLimits(&angle_pid, -500.0f, 500.0f); - PID_SetOutputLimits(&gyro_z_pid, -400.0f, 400.0f); - - PID_SetMode(&gyro_z_pid, 1); - PID_SetMode(&angle_pid, 1); -} diff --git a/app/jj_motion.h b/app/jj_motion.h deleted file mode 100644 index 2b4b1c2..0000000 --- a/app/jj_motion.h +++ /dev/null @@ -1,18 +0,0 @@ -#ifndef _JJ_MOTION_H_ -#define _JJ_MOTION_H_ -#include "ch32v30x.h" -#include "../3rd-lib/PID-Library/pid.h" -extern PID_TypeDef angle_pid; -extern PID_TypeDef gyro_z_pid; -extern float an_Kp; -extern float an_Ki; -extern float an_Kd; -extern float im_Kp; -extern float im_Ki; -extern float im_Kd; -extern float out_M; -extern float out_yaw; -extern float yaw0; -void sport_pid_init(); -void sport_motion2(uint32_t fy); -#endif \ No newline at end of file diff --git a/app/jj_param.c b/app/jj_param.c index a2a9b94..ced4ada 100644 --- a/app/jj_param.c +++ b/app/jj_param.c @@ -2,20 +2,19 @@ #include "./page/page_ui_widget.h" #include "./page/page.h" #include "zf_common_headfile.h" -#include "jj_motion.h" PARAM_INFO Param_Data[DATA_NUM]; soft_iic_info_struct eeprom_param; TYPE_UNION iic_buffer[DATA_IN_FLASH_NUM]; void jj_param_eeprom_init() { - soft_iic_init(&eeprom_param, K24C02_DEV_ADDR, K24C02_SOFT_IIC_DELAY, K24C02_SCL_PIN, K24C02_SDA_PIN); // eeprom初始化 - PARAM_REG(angle_Kp, &an_Kp, EFLOAT, 1, "an_P"); // 注冊 - PARAM_REG(angle_Ki, &an_Ki, EFLOAT, 1, "an_I"); // 注冊 - PARAM_REG(angle_Kd, &an_Kd, EFLOAT, 1, "an_D"); // 注冊 - PARAM_REG(imgax_Kp, &im_Kp, EFLOAT, 1, "im_P"); // 注冊 - PARAM_REG(imgax_Ki, &im_Ki, EFLOAT, 1, "im_I"); // 注冊 - PARAM_REG(imgax_Kd, &im_Kd, EFLOAT, 1, "im_D"); // 注冊 + soft_iic_init(&eeprom_param, K24C02_DEV_ADDR, K24C02_SOFT_IIC_DELAY, K24C02_SCL_PIN, K24C02_SDA_PIN); // eeprom 初始化 + // PARAM_REG(angle_Kp, &an_Kp, EFLOAT, 1, "an_P"); // 注冊 + // PARAM_REG(angle_Ki, &an_Ki, EFLOAT, 1, "an_I"); // 注冊 + // PARAM_REG(angle_Kd, &an_Kd, EFLOAT, 1, "an_D"); // 注冊 + // PARAM_REG(imgax_Kp, &im_Kp, EFLOAT, 1, "im_P"); // 注冊 + // PARAM_REG(imgax_Ki, &im_Ki, EFLOAT, 1, "im_I"); // 注冊 + // PARAM_REG(imgax_Kd, &im_Kd, EFLOAT, 1, "im_D"); // 注冊 for (uint8 i = 0; i < DATA_IN_FLASH_NUM; i++) { diff --git a/app/main.c b/app/main.c index d68f3d6..f08a31a 100644 --- a/app/main.c +++ b/app/main.c @@ -22,46 +22,34 @@ * 欢迎各位使用并传播本程序 但修改内容时必须保留逐飞科技的版权声明(即本声明) ********************************************************************************************************************/ #include "gl_headfile.h" -#include "by_rt_button.h" -#include "by_fan_control.h" #include "./page/page.h" -#include "jj_blueteeth.h" #include "jj_param.h" -#include "./page/page_ui_widget.h" #include "by_buzzer.h" -#include "jj_motion.h" -#include "by_imu.h" int main(void) { - clock_init(SYSTEM_CLOCK_120M); + clock_init(SYSTEM_CLOCK_144M); system_delay_init(); debug_init(); - mt9v03x_init(); + // mt9v03x_init(); ips200_init(IPS200_TYPE_SPI); - by_gpio_init(); - by_exit_init(); - by_pwm_init(); - jj_bt_init(); + usb_cdc_init(); by_buzzer_init(); - while (imu660ra_init()) - ; - jj_param_eeprom_init(); + by_button_init(); + // while (imu660ra_init()) + // ; + // jj_param_eeprom_init(); Page_Init(); - sport_pid_init(); pit_ms_init(TIM6_PIT, 2); pit_ms_init(TIM1_PIT, 2); - // gyroOffset_init(); while (1) { Page_Run(); - jj_bt_run(); queue_pop_read(); - bt_printf("hello:%f,%f\n",out_M,out_yaw); if (mt9v03x_finish_flag) { // 该操作消耗大概 1970 个 tick,折合约 110us memcpy(mt9v03x_image_copy[0], mt9v03x_image[0], (sizeof(mt9v03x_image_copy) / sizeof(uint8_t))); - //adaptiveThreshold((uint8_t*)mt9v03x_image_copy, (uint8_t*)mt9v03x_image_copy, 188, 120, 7, 17); - //ips200_show_gray_image(0, 0, mt9v03x_image_copy[0], MT9V03X_W, MT9V03X_H, MT9V03X_W, MT9V03X_H, 0); + // adaptiveThreshold((uint8_t*)mt9v03x_image_copy, (uint8_t*)mt9v03x_image_copy, 188, 120, 7, 17); + // ips200_show_gray_image(0, 0, mt9v03x_image_copy[0], MT9V03X_W, MT9V03X_H, MT9V03X_W, MT9V03X_H, 0); mt9v03x_finish_flag = 0; state_type = COMMON_STATE; @@ -72,27 +60,25 @@ int main(void) ElementJudge(); ElementRun(); MidLineTrack(); - } } } - - -void adaptiveThreshold(uint8_t* img_data, uint8_t* output_data, int width, int height, int block, uint8_t clip_value){ - int half_block = block / 2; - for(int y=half_block; y thres ? 255 : 0; } - } - thres = thres / (block * block) - clip_value; - // 进行二值化 - output_data[x+y*width] = img_data[x+y*width]>thres ? 255 : 0; } - } } diff --git a/app/page/page.c b/app/page/page.c index 794ddaa..942940c 100644 --- a/app/page/page.c +++ b/app/page/page.c @@ -1,6 +1,6 @@ #include "page.h" -#include "by_rt_button.h" +#include "by_button.h" PAGE_LIST pagelist[page_max]; static uint8_t page_busy = 0; @@ -89,8 +89,8 @@ uint8_t Page_GetStatus(void) */ void Page_Run(void) { - uint8_t temp_status = by_get_rb_status(); // 轮询旋钮状态 - if(temp_status){ + uint8_t temp_status = by_button_get_status(); // 轮询旋钮状态 + if (temp_status) { pagelist[now_page].EventCallback(temp_status); } @@ -118,7 +118,7 @@ void Page_Run(void) } /** - * @brief 页面初始化(注册,构建) ATTENTION 在此处添加新加入的页面 + * @brief 页面初始化(注册,构建)ATTENTION 在此处添加新加入的页面 * */ void Page_Init(void) diff --git a/app/page/page.h b/app/page/page.h index f65d8bf..3d51e41 100644 --- a/app/page/page.h +++ b/app/page/page.h @@ -13,7 +13,7 @@ #include "zf_common_headfile.h" -#include "by_rt_button.h" +#include "by_button.h" enum PageID { PAGE_NULL = -1, @@ -28,11 +28,11 @@ enum PageID { page_max, }; -typedef enum page_event{ - page_event_forward = rotate_button_forward, - page_event_backward = rotate_button_backward, - page_event_press_short = rotate_button_press_short, - page_event_press_long = rotate_button_press_long, +typedef enum page_event { + page_event_forward = button_event_up, + page_event_backward = button_event_down, + page_event_press_short = button_event_center_sp, + page_event_press_long = button_event_center_lp, } page_event; typedef void (*CallbackFunction_t)(void); @@ -45,16 +45,16 @@ typedef struct { EventFunction_t EventCallback; } PAGE_LIST; -//页面注册函数 -#define PAGE_REG(name)\ -do{\ - extern void PageRegister_##name(unsigned char pageID);\ - PageRegister_##name(name);\ -}while(0) +// 页面注册函数 +#define PAGE_REG(name) \ + do { \ + extern void PageRegister_##name(unsigned char pageID); \ + PageRegister_##name(name); \ + } while (0) void Page_Register(uint8_t pageID, char *pageText, - CallbackFunction_t setupCallback, CallbackFunction_t loopCallback, - CallbackFunction_t exitCallback, EventFunction_t eventCallback); + CallbackFunction_t setupCallback, CallbackFunction_t loopCallback, + CallbackFunction_t exitCallback, EventFunction_t eventCallback); void Page_EventTransmit(unsigned char event); void Page_Shift(unsigned char pageID); diff --git a/app/page/page_param.c b/app/page/page_param.c index 40dc086..ef57df5 100644 --- a/app/page/page_param.c +++ b/app/page/page_param.c @@ -1,11 +1,10 @@ #include "jj_param.h" #include "page_ui_widget.h" -#include "jj_motion.h" #include "page.h" #define LINE_HEAD 0 #define LINE_END DATA_NUM - 2 -static char Text[] = "RealTime Param"; +static char Text[] = "Param"; int event_flag = 0; int32_t index_power = 0; static int8_t Curser = LINE_HEAD; // 定义光标位置 @@ -75,7 +74,6 @@ static void Event(page_event event) return; } else if (page_event_press_long == event) { jj_param_update(); - sport_pid_init(); Page_Shift(page_menu); return; } diff --git a/libraries/sdk/Ld/Link.ld b/libraries/sdk/Ld/Link.ld index aa73cb2..e6f4187 100644 --- a/libraries/sdk/Ld/Link.ld +++ b/libraries/sdk/Ld/Link.ld @@ -1 +1,185 @@ -ENTRY( _start ) __stack_size = 2048; PROVIDE( _stack_size = __stack_size ); MEMORY { /* CH32V30x_D8C - CH32V305RB-CH32V305FB CH32V30x_D8 - CH32V303CB-CH32V303RB */ /* FLASH (rx) : ORIGIN = 0x00000000, LENGTH = 128K RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 32K */ /* CH32V30x_D8C - CH32V307VC-CH32V307WC-CH32V307RC CH32V30x_D8 - CH32V303VC-CH32V303RC FLASH + RAM supports the following configuration FLASH-192K + RAM-128K FLASH-224K + RAM-96K FLASH-256K + RAM-64K FLASH-288K + RAM-32K */ RAM (xrw) : ORIGIN = 0x20000040, LENGTH = 63K FLASH (rx) : ORIGIN = 0x00000000, LENGTH = 256K } SECTIONS { .init : { _sinit = .; . = ALIGN(4); KEEP(*(SORT_NONE(.init))) . = ALIGN(4); _einit = .; } >FLASH AT>FLASH .vector : { *(.vector); . = ALIGN(64); } >FLASH AT>FLASH .text : { . = ALIGN(4); *(.text) *(.text.*) *(.rodata) *(.rodata*) *(.glue_7) *(.glue_7t) *(.gnu.linkonce.t.*) . = ALIGN(4); } >FLASH AT>FLASH .fini : { KEEP(*(SORT_NONE(.fini))) . = ALIGN(4); } >FLASH AT>FLASH PROVIDE( _etext = . ); PROVIDE( _eitcm = . ); .preinit_array : { PROVIDE_HIDDEN (__preinit_array_start = .); KEEP (*(.preinit_array)) PROVIDE_HIDDEN (__preinit_array_end = .); } >FLASH AT>FLASH .init_array : { PROVIDE_HIDDEN (__init_array_start = .); KEEP (*(SORT_BY_INIT_PRIORITY(.init_array.*) SORT_BY_INIT_PRIORITY(.ctors.*))) KEEP (*(.init_array EXCLUDE_FILE (*crtbegin.o *crtbegin?.o *crtend.o *crtend?.o ) .ctors)) PROVIDE_HIDDEN (__init_array_end = .); } >FLASH AT>FLASH .fini_array : { PROVIDE_HIDDEN (__fini_array_start = .); KEEP (*(SORT_BY_INIT_PRIORITY(.fini_array.*) SORT_BY_INIT_PRIORITY(.dtors.*))) KEEP (*(.fini_array EXCLUDE_FILE (*crtbegin.o *crtbegin?.o *crtend.o *crtend?.o ) .dtors)) PROVIDE_HIDDEN (__fini_array_end = .); } >FLASH AT>FLASH .ctors : { /* gcc uses crtbegin.o to find the start of the constructors, so we make sure it is first. Because this is a wildcard, it doesn't matter if the user does not actually link against crtbegin.o; the linker won't look for a file to match a wildcard. The wildcard also means that it doesn't matter which directory crtbegin.o is in. */ KEEP (*crtbegin.o(.ctors)) KEEP (*crtbegin?.o(.ctors)) /* We don't want to include the .ctor section from the crtend.o file until after the sorted ctors. The .ctor section from the crtend file contains the end of ctors marker and it must be last */ KEEP (*(EXCLUDE_FILE (*crtend.o *crtend?.o ) .ctors)) KEEP (*(SORT(.ctors.*))) KEEP (*(.ctors)) } >FLASH AT>FLASH .dtors : { KEEP (*crtbegin.o(.dtors)) KEEP (*crtbegin?.o(.dtors)) KEEP (*(EXCLUDE_FILE (*crtend.o *crtend?.o ) .dtors)) KEEP (*(SORT(.dtors.*))) KEEP (*(.dtors)) } >FLASH AT>FLASH .dalign : { . = ALIGN(4); PROVIDE(_data_vma = .); } >RAM AT>FLASH .dlalign : { . = ALIGN(4); PROVIDE(_data_lma = .); } >FLASH AT>FLASH .data : { *(.gnu.linkonce.r.*) *(.data .data.*) *(.gnu.linkonce.d.*) . = ALIGN(8); PROVIDE( __global_pointer$ = . + 0x800 ); *(.sdata .sdata.*) *(.sdata2.*) *(.gnu.linkonce.s.*) . = ALIGN(8); *(.srodata.cst16) *(.srodata.cst8) *(.srodata.cst4) *(.srodata.cst2) *(.srodata .srodata.*) . = ALIGN(4); PROVIDE( _edata = .); } >RAM AT>FLASH .bss : { . = ALIGN(4); PROVIDE( _sbss = .); *(.sbss*) *(.gnu.linkonce.sb.*) *(.bss*) *(.gnu.linkonce.b.*) *(COMMON*) . = ALIGN(4); PROVIDE( _ebss = .); } >RAM AT>FLASH PROVIDE( _end = _ebss); PROVIDE( end = . ); .stack ORIGIN(RAM) + LENGTH(RAM) - __stack_size : { PROVIDE( _heap_end = . ); . = ALIGN(4); PROVIDE(_susrstack = . ); . = . + __stack_size; PROVIDE( _eusrstack = .); } >RAM } \ No newline at end of file +ENTRY( _start ) + +__stack_size = 2048; + +PROVIDE( _stack_size = __stack_size ); + + +MEMORY +{ +/* CH32V30x_D8C - CH32V305RB-CH32V305FB + CH32V30x_D8 - CH32V303CB-CH32V303RB +*/ +/* + FLASH (rx) : ORIGIN = 0x00000000, LENGTH = 128K + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 32K +*/ + +/* CH32V30x_D8C - CH32V307VC-CH32V307WC-CH32V307RC + CH32V30x_D8 - CH32V303VC-CH32V303RC + FLASH + RAM supports the following configuration + FLASH-192K + RAM-128K + FLASH-224K + RAM-96K + FLASH-256K + RAM-64K + FLASH-288K + RAM-32K +*/ + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 96K + FLASH (rx) : ORIGIN = 0x00000000, LENGTH = 224K +} + + +SECTIONS +{ + + .init : + { + _sinit = .; + . = ALIGN(4); + KEEP(*(SORT_NONE(.init))) + . = ALIGN(4); + _einit = .; + } >FLASH AT>FLASH + + .vector : + { + *(.vector); + . = ALIGN(64); + } >FLASH AT>FLASH + + .text : + { + . = ALIGN(4); + *(.text) + *(.text.*) + *(.rodata) + *(.rodata*) + *(.glue_7) + *(.glue_7t) + *(.gnu.linkonce.t.*) + . = ALIGN(4); + } >FLASH AT>FLASH + + .fini : + { + KEEP(*(SORT_NONE(.fini))) + . = ALIGN(4); + } >FLASH AT>FLASH + + PROVIDE( _etext = . ); + PROVIDE( _eitcm = . ); + + .preinit_array : + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } >FLASH AT>FLASH + + .init_array : + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT_BY_INIT_PRIORITY(.init_array.*) SORT_BY_INIT_PRIORITY(.ctors.*))) + KEEP (*(.init_array EXCLUDE_FILE (*crtbegin.o *crtbegin?.o *crtend.o *crtend?.o ) .ctors)) + PROVIDE_HIDDEN (__init_array_end = .); + } >FLASH AT>FLASH + + .fini_array : + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(SORT_BY_INIT_PRIORITY(.fini_array.*) SORT_BY_INIT_PRIORITY(.dtors.*))) + KEEP (*(.fini_array EXCLUDE_FILE (*crtbegin.o *crtbegin?.o *crtend.o *crtend?.o ) .dtors)) + PROVIDE_HIDDEN (__fini_array_end = .); + } >FLASH AT>FLASH + + .ctors : + { + /* gcc uses crtbegin.o to find the start of + the constructors, so we make sure it is + first. Because this is a wildcard, it + doesn't matter if the user does not + actually link against crtbegin.o; the + linker won't look for a file to match a + wildcard. The wildcard also means that it + doesn't matter which directory crtbegin.o + is in. */ + KEEP (*crtbegin.o(.ctors)) + KEEP (*crtbegin?.o(.ctors)) + /* We don't want to include the .ctor section from + the crtend.o file until after the sorted ctors. + The .ctor section from the crtend file contains the + end of ctors marker and it must be last */ + KEEP (*(EXCLUDE_FILE (*crtend.o *crtend?.o ) .ctors)) + KEEP (*(SORT(.ctors.*))) + KEEP (*(.ctors)) + } >FLASH AT>FLASH + + .dtors : + { + KEEP (*crtbegin.o(.dtors)) + KEEP (*crtbegin?.o(.dtors)) + KEEP (*(EXCLUDE_FILE (*crtend.o *crtend?.o ) .dtors)) + KEEP (*(SORT(.dtors.*))) + KEEP (*(.dtors)) + } >FLASH AT>FLASH + + .dalign : + { + . = ALIGN(4); + PROVIDE(_data_vma = .); + } >RAM AT>FLASH + + .dlalign : + { + . = ALIGN(4); + PROVIDE(_data_lma = .); + } >FLASH AT>FLASH + + .data : + { + *(.gnu.linkonce.r.*) + *(.data .data.*) + *(.gnu.linkonce.d.*) + . = ALIGN(8); + PROVIDE( __global_pointer$ = . + 0x800 ); + *(.sdata .sdata.*) + *(.sdata2.*) + *(.gnu.linkonce.s.*) + . = ALIGN(8); + *(.srodata.cst16) + *(.srodata.cst8) + *(.srodata.cst4) + *(.srodata.cst2) + *(.srodata .srodata.*) + . = ALIGN(4); + PROVIDE( _edata = .); + } >RAM AT>FLASH + + .bss : + { + . = ALIGN(4); + PROVIDE( _sbss = .); + *(.sbss*) + *(.gnu.linkonce.sb.*) + *(.bss*) + *(.gnu.linkonce.b.*) + *(COMMON*) + . = ALIGN(4); + PROVIDE( _ebss = .); + } >RAM AT>FLASH + + PROVIDE( _end = _ebss); + PROVIDE( end = . ); + + .stack ORIGIN(RAM) + LENGTH(RAM) - __stack_size : + { + PROVIDE( _heap_end = . ); + . = ALIGN(4); + PROVIDE(_susrstack = . ); + . = . + __stack_size; + PROVIDE( _eusrstack = .); + } >RAM + +} + + + diff --git a/libraries/zf_device/zf_device_ips200.c b/libraries/zf_device/zf_device_ips200.c index fcfd78e..201c737 100644 --- a/libraries/zf_device/zf_device_ips200.c +++ b/libraries/zf_device/zf_device_ips200.c @@ -322,8 +322,8 @@ static void ips200_set_region(uint16 x1, uint16 y1, uint16 x2, uint16 y2) // zf_assert(y2 < ips200_y_max); ips200_write_command(0x2a); - ips200_write_16bit_data(x1); - ips200_write_16bit_data(x2); + ips200_write_16bit_data(x1+80); + ips200_write_16bit_data(x2+80); ips200_write_command(0x2b); ips200_write_16bit_data(y1); diff --git a/libraries/zf_device/zf_device_ips200.h b/libraries/zf_device/zf_device_ips200.h index 6169e6b..38a6c07 100644 --- a/libraries/zf_device/zf_device_ips200.h +++ b/libraries/zf_device/zf_device_ips200.h @@ -110,7 +110,7 @@ // 例:C5-C12 IPS200_DATAPORT 设置为 GPIOC DATA_START_NUM 设置为 5 // --------------------双排 SPI 接口两寸屏幕引脚定义--------------------// -#define IPS200_DEFAULT_DISPLAY_DIR (IPS200_PORTAIT) // 默认的显示方向 +#define IPS200_DEFAULT_DISPLAY_DIR (IPS200_CROSSWISE_180) // 默认的显示方向 #define IPS200_DEFAULT_PENCOLOR (RGB565_YELLOW) // 默认的画笔颜色 #define IPS200_DEFAULT_BGCOLOR (RGB565_BLACK) // 默认的背景颜色 #define IPS200_DEFAULT_DISPLAY_FONT (IPS200_8X16_FONT) // 默认的字体模式 diff --git a/libraries/zf_device/zf_device_k24c02.h b/libraries/zf_device/zf_device_k24c02.h index 6d4a614..b8f479c 100644 --- a/libraries/zf_device/zf_device_k24c02.h +++ b/libraries/zf_device/zf_device_k24c02.h @@ -54,8 +54,8 @@ #if K24C02_USE_SOFT_IIC // ɫIJȷ ɫҵľûõ //==================================================== IIC ==================================================== #define K24C02_SOFT_IIC_DELAY (500) // IIC ʱʱ ֵԽС IIC ͨԽ -#define K24C02_SCL_PIN (E3) // IIC SCL K24C02 SCL -#define K24C02_SDA_PIN (E2 ) // IIC SDA K24C02 SDA +#define K24C02_SCL_PIN (D13) // IIC SCL K24C02 SCL +#define K24C02_SDA_PIN (D14) // IIC SDA K24C02 SDA //==================================================== IIC ==================================================== #else //====================================================Ӳ IIC ==================================================== @@ -69,7 +69,7 @@ #define K24C02_TIMEOUT_COUNT (0x00FF) // K24C02 ʱ //================================================ K24C02 ڲַ================================================ -#define K24C02_DEV_ADDR (0xA0 >> 1) // IICдʱĵַֽ +1Ϊȡ +#define K24C02_DEV_ADDR (0xA0 >> 1) // IIC дʱĵַֽ +1 Ϊȡ //================================================ K24C02 ڲַ================================================ #define K24C02_SIZE (256) // 256 byte diff --git a/libraries/zf_device/zf_device_mt9v03x_dvp.h b/libraries/zf_device/zf_device_mt9v03x_dvp.h index 8792a05..c1b8d56 100644 --- a/libraries/zf_device/zf_device_mt9v03x_dvp.h +++ b/libraries/zf_device/zf_device_mt9v03x_dvp.h @@ -95,18 +95,18 @@ #define MT9V03X_IMAGE_SIZE ( MT9V03X_W * MT9V03X_H ) // ͼСܳ 65535 #define MT9V03X_COF_BUFFER_SIZE ( 64 ) // ôڻС 64 -#define MT9V03X_AUTO_EXP_DEF (0 ) // Զع ĬϲԶع Χ [0-63] 0Ϊر - // Զع⿪ EXP_TIMEԶعʱ +#define MT9V03X_AUTO_EXP_DEF (0 ) // Զع ĬϲԶع Χ [0-63] 0 Ϊر + // Զع⿪ EXP_TIME Զعʱ // һDzҪԶع ߷dzȵԳԶع⣬ͼȶ #define MT9V03X_EXP_TIME_DEF (512) // عʱ ͷյԶعʱ䣬ùΪعֵ -#define MT9V03X_FPS_DEF (50 ) // ͼ֡ ͷյԶFPSΪFPS -#define MT9V03X_LR_OFFSET_DEF (0 ) // ͼƫ ֵ ƫ ֵ ƫ Ϊ188 376 752ʱ޷ƫ +#define MT9V03X_FPS_DEF (50 ) // ͼ֡ ͷյԶ FPSΪ FPS +#define MT9V03X_LR_OFFSET_DEF (0 ) // ͼƫ ֵ ƫ ֵ ƫ Ϊ 188 376 752 ʱ޷ƫ // ͷƫݺԶƫƣüƫ -#define MT9V03X_UD_OFFSET_DEF (0 ) // ͼƫ ֵ ƫ ֵ ƫ Ϊ120 240 480ʱ޷ƫ +#define MT9V03X_UD_OFFSET_DEF (0 ) // ͼƫ ֵ ƫ ֵ ƫ Ϊ 120 240 480 ʱ޷ƫ // ͷƫݺԶƫƣüƫ #define MT9V03X_GAIN_DEF (32 ) // ͼ Χ [16-64] عʱ̶¸ıͼ̶ -#define MT9V03X_PCLK_MODE_DEF (1 ) // ʱģʽ Χ [0-1] Ĭϣ0 ѡΪ[0ź,1ź] - // ͨΪ0ʹCH32V307DVPӿڻSTM32DCMIӿڲɼҪΪ1 +#define MT9V03X_PCLK_MODE_DEF (1 ) // ʱģʽ Χ [0-1] Ĭϣ0 ѡΪ[0źţ1ź] + // ͨΪ 0ʹ CH32V307 DVP ӿڻ STM32 DCMI ӿڲɼҪΪ 1 // MT9V034 V1.5 Լϰ汾ָ֧ // ͷö @@ -121,7 +121,7 @@ typedef enum MT9V03X_LR_OFFSET, // ͼƫ MT9V03X_UD_OFFSET, // ͼƫ MT9V03X_GAIN, // ͼƫ - MT9V03X_PCLK_MODE, // ʱģʽ(MT9V034 V1.5Լϰ汾ָ֧) + MT9V03X_PCLK_MODE, // ʱģʽ ( MT9V034 V1.5 Լϰ汾ָ֧) MT9V03X_CONFIG_FINISH, // λҪռλ MT9V03X_COLOR_GET_WHO_AM_I = 0xEF, From bd9ea4b09ee29aadefeaee2e9accfffcb9141b8c Mon Sep 17 00:00:00 2001 From: CaoWangrenbo Date: Wed, 31 Jan 2024 17:43:48 +0800 Subject: [PATCH 03/19] =?UTF-8?q?feat:=20=E5=A2=9E=E5=8A=A0LED=E7=8A=B6?= =?UTF-8?q?=E6=80=81=E6=8C=87=E7=A4=BA?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- app/by_led.c | 29 +++++++++++++++++++++++++++++ app/by_led.h | 8 ++++++++ app/by_rt_button.c | 26 -------------------------- app/by_rt_button.h | 21 --------------------- app/isr.c | 1 - app/main.c | 6 +++++- 6 files changed, 42 insertions(+), 49 deletions(-) create mode 100644 app/by_led.c create mode 100644 app/by_led.h delete mode 100644 app/by_rt_button.c delete mode 100644 app/by_rt_button.h diff --git a/app/by_led.c b/app/by_led.c new file mode 100644 index 0000000..852349f --- /dev/null +++ b/app/by_led.c @@ -0,0 +1,29 @@ +#include "by_led.h" + +#include "zf_common_headfile.h" + +#define LED_WARN_PIN E9 +#define LED_INFO_PIN E8 + +uint8_t led_warn_status = 1; +uint8_t led_info_status = 1; + +// TODO 将队列抽象出去,具有 blink 属性的设备均可使用 + +void by_led_init(void) +{ + gpio_init(LED_WARN_PIN, GPO, 0, GPO_PUSH_PULL); + gpio_init(LED_INFO_PIN, GPO, 0, GPO_PUSH_PULL); +} + +void by_led_warn_blink(void) +{ + led_warn_status = !led_warn_status; + gpio_set_level(LED_WARN_PIN, led_warn_status); +} + +void by_led_info_blink(void) +{ + led_info_status = !led_info_status; + gpio_set_level(LED_INFO_PIN, led_info_status); +} diff --git a/app/by_led.h b/app/by_led.h new file mode 100644 index 0000000..e1b6703 --- /dev/null +++ b/app/by_led.h @@ -0,0 +1,8 @@ +#ifndef _BY_LED_H__ +#define _BY_LED_H__ + +extern void by_led_init(void); +extern void by_led_warn_blink(void); +extern void by_led_info_blink(void); + +#endif \ No newline at end of file diff --git a/app/by_rt_button.c b/app/by_rt_button.c deleted file mode 100644 index d14c013..0000000 --- a/app/by_rt_button.c +++ /dev/null @@ -1,26 +0,0 @@ -#include "by_rt_button.h" -#include "zf_common_headfile.h" -uint8_t rotate_button; - -void by_gpio_init(void) -{ - gpio_init(E10, GPI, GPIO_HIGH, GPI_PULL_UP); -} - -void by_exit_init(void) -{ - exti_init(E9, EXTI_TRIGGER_FALLING); - exti_init(E11, EXTI_TRIGGER_BOTH); -} - -/** - * @brief 查询旋钮状态 - 查询后状态归零 - * - * @return uint8_t 当前旋钮状态 - */ -uint8_t by_get_rb_status(void) -{ - uint8_t temp_s = rotate_button; - rotate_button = 0; - return temp_s; -} \ No newline at end of file diff --git a/app/by_rt_button.h b/app/by_rt_button.h deleted file mode 100644 index 714e02f..0000000 --- a/app/by_rt_button.h +++ /dev/null @@ -1,21 +0,0 @@ -#ifndef _BY_RT_BUTTON_H__ -#define _BY_RT_BUTTON_H__ - -#include "stdio.h" -#include "ch32v30x.h" - -typedef enum rotate_button_event { - rotate_button_press_short = 1, - rotate_button_press_long = 2, - rotate_button_forward = 3, - rotate_button_backward = 4, -} rotate_button_event; - -extern uint8_t rotate_button; - -extern void by_exit_init(void); -extern void by_gpio_init(void); -extern uint8_t by_get_rb_status(void); -extern void by_ips_show(void); - -#endif \ No newline at end of file diff --git a/app/isr.c b/app/isr.c index 137e5f6..4c57fb0 100644 --- a/app/isr.c +++ b/app/isr.c @@ -34,7 +34,6 @@ ********************************************************************************************************************/ #include "zf_common_headfile.h" -#include "by_rt_button.h" #include "by_button.h" #include "by_buzzer.h" diff --git a/app/main.c b/app/main.c index f08a31a..557eba4 100644 --- a/app/main.c +++ b/app/main.c @@ -25,6 +25,7 @@ #include "./page/page.h" #include "jj_param.h" #include "by_buzzer.h" +#include "by_led.h" int main(void) { @@ -34,8 +35,11 @@ int main(void) // mt9v03x_init(); ips200_init(IPS200_TYPE_SPI); usb_cdc_init(); + + by_led_init(); by_buzzer_init(); by_button_init(); + // while (imu660ra_init()) // ; // jj_param_eeprom_init(); @@ -51,7 +55,7 @@ int main(void) // adaptiveThreshold((uint8_t*)mt9v03x_image_copy, (uint8_t*)mt9v03x_image_copy, 188, 120, 7, 17); // ips200_show_gray_image(0, 0, mt9v03x_image_copy[0], MT9V03X_W, MT9V03X_H, MT9V03X_W, MT9V03X_H, 0); mt9v03x_finish_flag = 0; - + by_led_info_blink(); state_type = COMMON_STATE; img_processing(); get_corners(); From 27c50ceea8c3212c35bdf66eacc5a28778282712 Mon Sep 17 00:00:00 2001 From: CaoWangrenbo Date: Wed, 31 Jan 2024 17:55:16 +0800 Subject: [PATCH 04/19] =?UTF-8?q?feat:=20=E9=80=82=E9=85=8D=E6=96=B0?= =?UTF-8?q?=E6=9D=BF=E5=8D=A1=E8=93=9D=E7=89=99?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- app/jj_blueteeth.c | 42 ++++++++++++++++++++++++++++++++++++++++++ app/jj_blueteeth.h | 9 +++++++++ app/main.c | 10 +++++++--- 3 files changed, 58 insertions(+), 3 deletions(-) create mode 100644 app/jj_blueteeth.c create mode 100644 app/jj_blueteeth.h diff --git a/app/jj_blueteeth.c b/app/jj_blueteeth.c new file mode 100644 index 0000000..a5a2828 --- /dev/null +++ b/app/jj_blueteeth.c @@ -0,0 +1,42 @@ +#include "jj_blueteeth.h" + +#include "zf_common_headfile.h" + +#define BT_UART_BAUDRATE (115200) +#define BT_UART_INDEX UART_8 +#define BT_UART_TX_PIN UART8_MAP0_TX_C4 +#define BT_UART_RX_PIN UART8_MAP0_RX_C5 + +bool bt_rx_flag = false; +uint8_t bt_buffer; // 接收字符存入 + +/** + * @brief 蓝牙初始化 + * @retval 无 + */ +void jj_bt_init() +{ + uart_init(BT_UART_INDEX, BT_UART_BAUDRATE, BT_UART_TX_PIN, UART8_MAP0_RX_C5); + uart_rx_interrupt(BT_UART_INDEX, ENABLE); +} +/** + *@brief 蓝牙中断回调函数 + */ +void jj_bt_run() +{ +} + +void jj_bt_printf(const char *format, ...) +{ + char sbuf[40]; + va_list args; + va_start(args, format); + vsnprintf(sbuf, 40, format, args); + va_end(args); + + for (uint16_t i = 0; i < strlen(sbuf); i++) { + while (USART_GetFlagStatus((USART_TypeDef *)uart_index[BT_UART_INDEX], USART_FLAG_TC) == RESET) + ; + USART_SendData((USART_TypeDef *)uart_index[BT_UART_INDEX], sbuf[i]); + } +} \ No newline at end of file diff --git a/app/jj_blueteeth.h b/app/jj_blueteeth.h new file mode 100644 index 0000000..aa12631 --- /dev/null +++ b/app/jj_blueteeth.h @@ -0,0 +1,9 @@ +#ifndef _JJ_BLUETEETH_H_ +#define _JJ_BLUETEETH_H_ + +#include "stdio.h" + +void jj_bt_init(); +void jj_bt_run(); +void jj_bt_printf(const char *format, ...); +#endif \ No newline at end of file diff --git a/app/main.c b/app/main.c index 557eba4..8e69e41 100644 --- a/app/main.c +++ b/app/main.c @@ -23,9 +23,11 @@ ********************************************************************************************************************/ #include "gl_headfile.h" #include "./page/page.h" -#include "jj_param.h" #include "by_buzzer.h" #include "by_led.h" +#include "jj_param.h" +#include "jj_blueteeth.h" + int main(void) { @@ -40,12 +42,14 @@ int main(void) by_buzzer_init(); by_button_init(); - // while (imu660ra_init()) - // ; + jj_bt_init(); // jj_param_eeprom_init(); + Page_Init(); + pit_ms_init(TIM6_PIT, 2); pit_ms_init(TIM1_PIT, 2); + while (1) { Page_Run(); queue_pop_read(); From 85fe5a27df25e24da14a60ffcbd355e7930330da Mon Sep 17 00:00:00 2001 From: bmy <2583236812@qq.com> Date: Sat, 10 Feb 2024 16:19:51 +0800 Subject: [PATCH 05/19] =?UTF-8?q?pref:=20=E6=94=B9=E8=BF=9B=E6=8C=89?= =?UTF-8?q?=E9=94=AE=E4=BD=93=E9=AA=8C?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- app/by_buzzer.c | 10 +++++++ app/by_buzzer.h | 1 + app/isr.c | 80 ++++++++++++++++++++++++++++--------------------- app/main.c | 9 +++--- 4 files changed, 61 insertions(+), 39 deletions(-) diff --git a/app/by_buzzer.c b/app/by_buzzer.c index 6af01c9..b4df4d0 100644 --- a/app/by_buzzer.c +++ b/app/by_buzzer.c @@ -51,3 +51,13 @@ void by_buzzer_add(uint16_t tone) { queue_add_element(tone); } + +void by_buzzer_run(void) +{ + if (queue_long != 0) { + pwm_init(BUZZER_PIN, a[0], 5000); + queue_pop_element(); + system_delay_ms(100); + pwm_set_duty(BUZZER_PIN, 0); + } +} \ No newline at end of file diff --git a/app/by_buzzer.h b/app/by_buzzer.h index 060c1b8..b58c9a6 100644 --- a/app/by_buzzer.h +++ b/app/by_buzzer.h @@ -20,4 +20,5 @@ extern void queue_pop_element(void); extern void queue_pop_read(void); extern void by_buzzer_init(void); extern void by_buzzer_add(uint16_t tone); +extern void by_buzzer_run(void); #endif \ No newline at end of file diff --git a/app/isr.c b/app/isr.c index 4c57fb0..e0f81ac 100644 --- a/app/isr.c +++ b/app/isr.c @@ -202,61 +202,73 @@ void EXTI9_5_IRQHandler(void) void EXTI15_10_IRQHandler(void) { if (SET == EXTI_GetITStatus(EXTI_Line10)) { - system_delay_ms(10); - if (RESET == gpio_get_level(BUTTON_LEFT_PIN)) { - button_event = button_event_left; + if (button_event == button_event_none) { + system_delay_ms(10); + if (RESET == gpio_get_level(BUTTON_LEFT_PIN)) { + button_event = button_event_left; + } + by_buzzer_add(1250); } - by_buzzer_add(1250); EXTI_ClearITPendingBit(EXTI_Line10); } if (SET == EXTI_GetITStatus(EXTI_Line11)) { - system_delay_ms(10); - if (RESET == gpio_get_level(BUTTON_DOWN_PIN)) { - button_event = button_event_down; + if (button_event == button_event_none) { + system_delay_ms(10); + if (RESET == gpio_get_level(BUTTON_DOWN_PIN)) { + button_event = button_event_down; + } + by_buzzer_add(1250); } - by_buzzer_add(1250); EXTI_ClearITPendingBit(EXTI_Line11); } if (SET == EXTI_GetITStatus(EXTI_Line12)) { - system_delay_ms(10); - if (RESET == gpio_get_level(BUTTON_UP_PIN)) { - button_event = button_event_up; + if (button_event == button_event_none) { + system_delay_ms(10); + if (RESET == gpio_get_level(BUTTON_UP_PIN)) { + button_event = button_event_up; + } + by_buzzer_add(1250); } - by_buzzer_add(1250); EXTI_ClearITPendingBit(EXTI_Line12); } if (SET == EXTI_GetITStatus(EXTI_Line13)) { - static uint64_t time_via = 0; - system_delay_ms(10); - if (RESET == gpio_get_level(BUTTON_CENTER_PIN)) { - time_via = system_get_tick(); - } else if (SET == gpio_get_level(BUTTON_CENTER_PIN)) { - time_via = system_get_tick() - time_via; - if (time_via > LONG_PRESS_THRESHOLD_TICK) { - button_event = button_event_center_lp; - by_buzzer_add(2000); - } else { - button_event = button_event_center_sp; - by_buzzer_add(1800); + if (button_event == button_event_none) { + static uint64_t time_via = 0; + system_delay_ms(10); + if (RESET == gpio_get_level(BUTTON_CENTER_PIN)) { + time_via = system_get_tick(); + } else if (SET == gpio_get_level(BUTTON_CENTER_PIN)) { + time_via = system_get_tick() - time_via; + if (time_via > LONG_PRESS_THRESHOLD_TICK) { + button_event = button_event_center_lp; + by_buzzer_add(2000); + } else { + button_event = button_event_center_sp; + by_buzzer_add(1800); + } + time_via = 0; } - time_via = 0; } EXTI_ClearITPendingBit(EXTI_Line13); } if (SET == EXTI_GetITStatus(EXTI_Line14)) { - system_delay_ms(10); - if (RESET == gpio_get_level(BUTTON_RIGHT_PIN)) { - button_event = button_event_right; - by_buzzer_add(1250); + if (button_event == button_event_none) { + system_delay_ms(10); + if (RESET == gpio_get_level(BUTTON_RIGHT_PIN)) { + button_event = button_event_right; + by_buzzer_add(1250); + } } EXTI_ClearITPendingBit(EXTI_Line14); } if (SET == EXTI_GetITStatus(EXTI_Line15)) { - system_delay_ms(10); - if (RESET == gpio_get_level(BUTTON_SIDE_PIN)) { - button_event = button_event_side; - by_buzzer_add(2000); - by_buzzer_add(1500); + if (button_event == button_event_none) { + system_delay_ms(10); + if (RESET == gpio_get_level(BUTTON_SIDE_PIN)) { + button_event = button_event_side; + by_buzzer_add(2000); + by_buzzer_add(1500); + } } EXTI_ClearITPendingBit(EXTI_Line15); } diff --git a/app/main.c b/app/main.c index 8e69e41..8b712e3 100644 --- a/app/main.c +++ b/app/main.c @@ -36,23 +36,22 @@ int main(void) debug_init(); // mt9v03x_init(); ips200_init(IPS200_TYPE_SPI); - usb_cdc_init(); by_led_init(); by_buzzer_init(); by_button_init(); - jj_bt_init(); + // jj_bt_init(); // jj_param_eeprom_init(); Page_Init(); - pit_ms_init(TIM6_PIT, 2); - pit_ms_init(TIM1_PIT, 2); + // pit_ms_init(TIM6_PIT, 2); + // pit_ms_init(TIM1_PIT, 2); while (1) { Page_Run(); - queue_pop_read(); + by_buzzer_run(); if (mt9v03x_finish_flag) { // 该操作消耗大概 1970 个 tick,折合约 110us memcpy(mt9v03x_image_copy[0], mt9v03x_image[0], (sizeof(mt9v03x_image_copy) / sizeof(uint8_t))); From 1e982b4954e05cd3a001a01e31b20004be2a988d Mon Sep 17 00:00:00 2001 From: bmy <2583236812@qq.com> Date: Thu, 15 Feb 2024 22:50:20 +0800 Subject: [PATCH 06/19] =?UTF-8?q?feat:=20=E5=A2=9E=E5=8A=A0=E9=80=9A?= =?UTF-8?q?=E4=BF=A1=E5=B8=A7=E6=8F=90=E5=8F=96=E5=8A=9F=E8=83=BD?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .eide/eide.json | 10 +- 3rd-lib/crc16/crc16.c | 137 ++++++ 3rd-lib/crc16/crc16.h | 9 + 3rd-lib/lwrb/inc/lwrb.h | 149 ++++++ 3rd-lib/lwrb/src/lwrb.c | 645 ++++++++++++++++++++++++++ app/gl_headfile.h | 1 - app/isr.c | 12 +- app/main.c | 43 +- app/main.h | 6 - app/tiny_frame/by_tiny_frame.c | 16 + app/tiny_frame/by_tiny_frame.h | 8 + app/tiny_frame/by_tiny_frame_config.h | 11 + app/tiny_frame/by_tiny_frame_parse.c | 97 ++++ app/tiny_frame/by_tiny_frame_parse.h | 25 + app/tiny_frame/by_tiny_frame_read.c | 0 app/tiny_frame/by_tiny_frame_read.h | 6 + app/tiny_frame/by_tiny_frame_write.c | 2 + app/tiny_frame/by_tiny_frame_write.h | 6 + 18 files changed, 1154 insertions(+), 29 deletions(-) create mode 100644 3rd-lib/crc16/crc16.c create mode 100644 3rd-lib/crc16/crc16.h create mode 100644 3rd-lib/lwrb/inc/lwrb.h create mode 100644 3rd-lib/lwrb/src/lwrb.c delete mode 100644 app/main.h create mode 100644 app/tiny_frame/by_tiny_frame.c create mode 100644 app/tiny_frame/by_tiny_frame.h create mode 100644 app/tiny_frame/by_tiny_frame_config.h create mode 100644 app/tiny_frame/by_tiny_frame_parse.c create mode 100644 app/tiny_frame/by_tiny_frame_parse.h create mode 100644 app/tiny_frame/by_tiny_frame_read.c create mode 100644 app/tiny_frame/by_tiny_frame_read.h create mode 100644 app/tiny_frame/by_tiny_frame_write.c create mode 100644 app/tiny_frame/by_tiny_frame_write.h diff --git a/.eide/eide.json b/.eide/eide.json index a9a788f..21b0c8d 100644 --- a/.eide/eide.json +++ b/.eide/eide.json @@ -7,7 +7,9 @@ "libraries/sdk", "libraries/zf_common", "libraries/zf_device", - "libraries/zf_driver" + "libraries/zf_driver", + "3rd-lib/crc16", + "3rd-lib/lwrb" ], "virtualFolder": { "name": "", @@ -55,7 +57,11 @@ "libraries/sdk/Core", "libraries/zf_common", "libraries/zf_device", - "libraries/zf_driver" + "libraries/zf_driver", + "3rd-lib/crc16", + "app/page", + "3rd-lib/lwrb/inc", + "app/tiny_frame" ], "libList": [ "libraries/zf_device" diff --git a/3rd-lib/crc16/crc16.c b/3rd-lib/crc16/crc16.c new file mode 100644 index 0000000..637c435 --- /dev/null +++ b/3rd-lib/crc16/crc16.c @@ -0,0 +1,137 @@ + +#include "crc16.h" + +//ModBUS CRC-16 码(modbus)校验 + +/* +1、实时计算 CRC16 +该种方式耗时比较多,但占用 FLASH、RAM 小 + +1)CRC 寄存器初始值为 FFFF;即 16 个字节全为 1; +2)CRC-16 / MODBUS 的多项式 A001H (1010 0000 0000 0001B) ‘H’表示 16 进制数,‘B’表示二进制数 + +计算步骤为: +(1).预置 16 位寄存器为十六进制 FFFF(即全为 1) ,称此寄存器为 CRC 寄存器; +(2).把第一个 8 位数据与 16 位 CRC 寄存器的低位相异或,把结果放于 CRC 寄存器; +(3).检测相异或后的 CRC 寄存器的最低位,若最低位为 1:CRC 寄存器先右移 1 位,再与多项式 A001H 进行异或;若为 0,则 CRC 寄存器右移 1 位,无需与多项式进行异或。 +(4).重复步骤 3,直到右移 8 次,这样整个 8 位数据全部进行了处理; +(5).重复步骤 2 到步骤 4,进行下一个 8 位数据的处理; +(6).最后得到的 CRC 寄存器即为 CRC 码。 + +addr:需要校验的字节数组 +num:需要校验的字节数 +返回值:16 位的 CRC 校验码 +*/ +uint16_t crc16(uint8_t *addr,uint32_t num) +{ + int i,j,temp; + uint16_t crc=0xFFFF; + for(i=0;i>1; + if(temp) + { + crc=crc^0xA001; + } + } + addr++; + } + return crc; + + //将 CRC 校验的高低位对换位置 +// uint16_t crc1; +// crc1 = crc >> 8; +// crc1 = crc1 | (crc << 8); +// return crc1; +} + +/* +2、查表计算 CRC16(耗时少) +从上面代码中,可以看出 CRC-16 的漏洞。无非是将待计算的数组,从头到尾单个字节按照同一算法反复计算。每个元素只有 0~255 的输入可能性,算法固定,所以算出来的值也是固定的。 +于是可以提前计算出校验值,按照输入为 0~255,排列为一组校验输出表。计算过程中根据输入数据进行查表,从头查到尾得到最终校验值。 +这样的计算方式省去了单片机的反复计算,极大缩短了计算耗时。而且可以将查表的数组类型定义为 const,存放在 Flash 中,运行时不占用 RAM。虽然都是空间换时间的策略,但这种方式只占用 Flash 不占用珍贵的 RAM。 + +addr:需要校验的字节数组 +num:需要校验的字节数 +返回值:16 位的 CRC 校验码 +说 明:计算结果是高位在前,需要转换才能发送 +*/ +uint16_t crc16_check(uint8_t* addr, uint32_t num) +{ + // CRC 高位字节值表 + static const uint8_t auchCRCHi[] = + { + 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, + 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, + 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, + 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, + 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, + 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, + 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, + 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, + 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, + 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, + 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, + 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, + 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, + 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, + 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, + 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, + 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, + 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, + 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, + 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, + 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, + 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, + 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, + 0x81, 0x40, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, + 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, + 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40 + } ; + // CRC 低位字节值表 + static const uint8_t auchCRCLo[] = + { + 0x00, 0xC0, 0xC1, 0x01, 0xC3, 0x03, 0x02, 0xC2, 0xC6, 0x06, + 0x07, 0xC7, 0x05, 0xC5, 0xC4, 0x04, 0xCC, 0x0C, 0x0D, 0xCD, + 0x0F, 0xCF, 0xCE, 0x0E, 0x0A, 0xCA, 0xCB, 0x0B, 0xC9, 0x09, + 0x08, 0xC8, 0xD8, 0x18, 0x19, 0xD9, 0x1B, 0xDB, 0xDA, 0x1A, + 0x1E, 0xDE, 0xDF, 0x1F, 0xDD, 0x1D, 0x1C, 0xDC, 0x14, 0xD4, + 0xD5, 0x15, 0xD7, 0x17, 0x16, 0xD6, 0xD2, 0x12, 0x13, 0xD3, + 0x11, 0xD1, 0xD0, 0x10, 0xF0, 0x30, 0x31, 0xF1, 0x33, 0xF3, + 0xF2, 0x32, 0x36, 0xF6, 0xF7, 0x37, 0xF5, 0x35, 0x34, 0xF4, + 0x3C, 0xFC, 0xFD, 0x3D, 0xFF, 0x3F, 0x3E, 0xFE, 0xFA, 0x3A, + 0x3B, 0xFB, 0x39, 0xF9, 0xF8, 0x38, 0x28, 0xE8, 0xE9, 0x29, + 0xEB, 0x2B, 0x2A, 0xEA, 0xEE, 0x2E, 0x2F, 0xEF, 0x2D, 0xED, + 0xEC, 0x2C, 0xE4, 0x24, 0x25, 0xE5, 0x27, 0xE7, 0xE6, 0x26, + 0x22, 0xE2, 0xE3, 0x23, 0xE1, 0x21, 0x20, 0xE0, 0xA0, 0x60, + 0x61, 0xA1, 0x63, 0xA3, 0xA2, 0x62, 0x66, 0xA6, 0xA7, 0x67, + 0xA5, 0x65, 0x64, 0xA4, 0x6C, 0xAC, 0xAD, 0x6D, 0xAF, 0x6F, + 0x6E, 0xAE, 0xAA, 0x6A, 0x6B, 0xAB, 0x69, 0xA9, 0xA8, 0x68, + 0x78, 0xB8, 0xB9, 0x79, 0xBB, 0x7B, 0x7A, 0xBA, 0xBE, 0x7E, + 0x7F, 0xBF, 0x7D, 0xBD, 0xBC, 0x7C, 0xB4, 0x74, 0x75, 0xB5, + 0x77, 0xB7, 0xB6, 0x76, 0x72, 0xB2, 0xB3, 0x73, 0xB1, 0x71, + 0x70, 0xB0, 0x50, 0x90, 0x91, 0x51, 0x93, 0x53, 0x52, 0x92, + 0x96, 0x56, 0x57, 0x97, 0x55, 0x95, 0x94, 0x54, 0x9C, 0x5C, + 0x5D, 0x9D, 0x5F, 0x9F, 0x9E, 0x5E, 0x5A, 0x9A, 0x9B, 0x5B, + 0x99, 0x59, 0x58, 0x98, 0x88, 0x48, 0x49, 0x89, 0x4B, 0x8B, + 0x8A, 0x4A, 0x4E, 0x8E, 0x8F, 0x4F, 0x8D, 0x4D, 0x4C, 0x8C, + 0x44, 0x84, 0x85, 0x45, 0x87, 0x47, 0x46, 0x86, 0x82, 0x42, + 0x43, 0x83, 0x41, 0x81, 0x80, 0x40 + }; + + uint8_t uchCRCHi = 0xFF; + uint8_t uchCRCLo = 0xFF; + uint16_t uIndex; + while(num--) + { + uIndex = uchCRCLo ^ *addr++; + uchCRCLo = uchCRCHi^auchCRCHi[uIndex]; + uchCRCHi = auchCRCLo[uIndex]; + } + return (uchCRCHi<<8|uchCRCLo); + +} diff --git a/3rd-lib/crc16/crc16.h b/3rd-lib/crc16/crc16.h new file mode 100644 index 0000000..9ce89ed --- /dev/null +++ b/3rd-lib/crc16/crc16.h @@ -0,0 +1,9 @@ +#ifndef __CRC_16_H +#define __CRC_16_H + +#include + +extern uint16_t crc16(uint8_t *addr,uint32_t num); // 实时计算方式 +extern uint16_t crc16_check(uint8_t* addr, uint32_t num); // 查表计算方式 + +#endif diff --git a/3rd-lib/lwrb/inc/lwrb.h b/3rd-lib/lwrb/inc/lwrb.h new file mode 100644 index 0000000..0339e03 --- /dev/null +++ b/3rd-lib/lwrb/inc/lwrb.h @@ -0,0 +1,149 @@ +/** + * \file lwrb.h + * \brief LwRB - Lightweight ring buffer + */ + +/* + * Copyright (c) 2023 Tilen MAJERLE + * + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without restriction, + * including without limitation the rights to use, copy, modify, merge, + * publish, distribute, sublicense, and/or sell copies of the Software, + * and to permit persons to whom the Software is furnished to do so, + * subject to the following conditions: + * + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES + * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE + * AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT + * HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, + * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING + * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR + * OTHER DEALINGS IN THE SOFTWARE. + * + * This file is part of LwRB - Lightweight ring buffer library. + * + * Author: Tilen MAJERLE + * Version: v3.0.0-rc1 + */ +#ifndef LWRB_HDR_H +#define LWRB_HDR_H + +#include +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif /* __cplusplus */ + +/** + * \defgroup LWRB Lightweight ring buffer manager + * \brief Lightweight ring buffer manager + * \{ + */ + +#if !defined(LWRB_DISABLE_ATOMIC) || __DOXYGEN__ +#include + +/** + * \brief Atomic type for size variable. + * Default value is set to be `unsigned 32-bits` type + */ +typedef atomic_ulong lwrb_sz_atomic_t; + +/** + * \brief Size variable for all library operations. + * Default value is set to be `unsigned 32-bits` type + */ +typedef unsigned long lwrb_sz_t; +#else +typedef unsigned long lwrb_sz_atomic_t; +typedef unsigned long lwrb_sz_t; +#endif + +/** + * \brief Event type for buffer operations + */ +typedef enum { + LWRB_EVT_READ, /*!< Read event */ + LWRB_EVT_WRITE, /*!< Write event */ + LWRB_EVT_RESET, /*!< Reset event */ +} lwrb_evt_type_t; + +/** + * \brief Buffer structure forward declaration + */ +struct lwrb; + +/** + * \brief Event callback function type + * \param[in] buff: Buffer handle for event + * \param[in] evt: Event type + * \param[in] bp: Number of bytes written or read (when used), depends on event type + */ +typedef void (*lwrb_evt_fn)(struct lwrb* buff, lwrb_evt_type_t evt, lwrb_sz_t bp); + +/* List of flags */ +#define LWRB_FLAG_READ_ALL ((uint16_t)0x0001) +#define LWRB_FLAG_WRITE_ALL ((uint16_t)0x0001) + +/** + * \brief Buffer structure + */ +typedef struct lwrb { + uint8_t* buff; /*!< Pointer to buffer data. Buffer is considered initialized when `buff != NULL` and `size > 0` */ + lwrb_sz_t size; /*!< Size of buffer data. Size of actual buffer is `1` byte less than value holds */ + lwrb_sz_atomic_t r; /*!< Next read pointer. Buffer is considered empty when `r == w` and full when `w == r - 1` */ + lwrb_sz_atomic_t w; /*!< Next write pointer. Buffer is considered empty when `r == w` and full when `w == r - 1` */ + lwrb_evt_fn evt_fn; /*!< Pointer to event callback function */ +} lwrb_t; + +uint8_t lwrb_init(lwrb_t* buff, void* buffdata, lwrb_sz_t size); +uint8_t lwrb_is_ready(lwrb_t* buff); +void lwrb_free(lwrb_t* buff); +void lwrb_reset(lwrb_t* buff); +void lwrb_set_evt_fn(lwrb_t* buff, lwrb_evt_fn fn); + +/* Read/Write functions */ +lwrb_sz_t lwrb_write(lwrb_t* buff, const void* data, lwrb_sz_t btw); +lwrb_sz_t lwrb_read(lwrb_t* buff, void* data, lwrb_sz_t btr); +lwrb_sz_t lwrb_peek(const lwrb_t* buff, lwrb_sz_t skip_count, void* data, lwrb_sz_t btp); + +/* Extended read/write functions */ +uint8_t lwrb_write_ex(lwrb_t* buff, const void* data, lwrb_sz_t btw, lwrb_sz_t* bw, uint16_t flags); +uint8_t lwrb_read_ex(lwrb_t* buff, void* data, lwrb_sz_t btr, lwrb_sz_t* br, uint16_t flags); + +/* Buffer size information */ +lwrb_sz_t lwrb_get_free(const lwrb_t* buff); +lwrb_sz_t lwrb_get_full(const lwrb_t* buff); + +/* Read data block management */ +void* lwrb_get_linear_block_read_address(const lwrb_t* buff); +lwrb_sz_t lwrb_get_linear_block_read_length(const lwrb_t* buff); +lwrb_sz_t lwrb_skip(lwrb_t* buff, lwrb_sz_t len); + +/* Write data block management */ +void* lwrb_get_linear_block_write_address(const lwrb_t* buff); +lwrb_sz_t lwrb_get_linear_block_write_length(const lwrb_t* buff); +lwrb_sz_t lwrb_advance(lwrb_t* buff, lwrb_sz_t len); + +/* Search in buffer */ +uint8_t lwrb_find(const lwrb_t* buff, const void* bts, lwrb_sz_t len, lwrb_sz_t start_offset, lwrb_sz_t* found_idx); +lwrb_sz_t lwrb_overwrite(lwrb_t* buff, const void* data, lwrb_sz_t btw); +lwrb_sz_t lwrb_move(lwrb_t* dest, lwrb_t* src); + +/** + * \} + */ + +#ifdef __cplusplus +} +#endif /* __cplusplus */ + +#endif /* LWRB_HDR_H */ diff --git a/3rd-lib/lwrb/src/lwrb.c b/3rd-lib/lwrb/src/lwrb.c new file mode 100644 index 0000000..348432c --- /dev/null +++ b/3rd-lib/lwrb/src/lwrb.c @@ -0,0 +1,645 @@ +/** + * \file lwrb.c + * \brief Lightweight ring buffer + */ + +/* + * Copyright (c) 2023 Tilen MAJERLE + * + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without restriction, + * including without limitation the rights to use, copy, modify, merge, + * publish, distribute, sublicense, and/or sell copies of the Software, + * and to permit persons to whom the Software is furnished to do so, + * subject to the following conditions: + * + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES + * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE + * AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT + * HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, + * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING + * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR + * OTHER DEALINGS IN THE SOFTWARE. + * + * This file is part of LwRB - Lightweight ring buffer library. + * + * Author: Tilen MAJERLE + * Version: v3.0.0 + */ +#include "lwrb.h" + +/* Memory set and copy functions */ +#define BUF_MEMSET memset +#define BUF_MEMCPY memcpy + +#define BUF_IS_VALID(b) ((b) != NULL && (b)->buff != NULL && (b)->size > 0) +#define BUF_MIN(x, y) ((x) < (y) ? (x) : (y)) +#define BUF_MAX(x, y) ((x) > (y) ? (x) : (y)) +#define BUF_SEND_EVT(b, type, bp) \ + do { \ + if ((b)->evt_fn != NULL) { \ + (b)->evt_fn((void*)(b), (type), (bp)); \ + } \ + } while (0) + +/* Optional atomic opeartions */ +#ifdef LWRB_DISABLE_ATOMIC +#define LWRB_INIT(var, val) (var) = (val) +#define LWRB_LOAD(var, type) (var) +#define LWRB_STORE(var, val, type) (var) = (val) +#else +#define LWRB_INIT(var, val) atomic_init(&(var), (val)) +#define LWRB_LOAD(var, type) atomic_load_explicit(&(var), (type)) +#define LWRB_STORE(var, val, type) atomic_store_explicit(&(var), (val), (type)) +#endif + +/** + * \brief Initialize buffer handle to default values with size and buffer data array + * \param[in] buff: Ring buffer instance + * \param[in] buffdata: Pointer to memory to use as buffer data + * \param[in] size: Size of `buffdata` in units of bytes + * Maximum number of bytes buffer can hold is `size - 1` + * \return `1` on success, `0` otherwise + */ +uint8_t +lwrb_init(lwrb_t* buff, void* buffdata, lwrb_sz_t size) { + if (buff == NULL || buffdata == NULL || size == 0) { + return 0; + } + + buff->evt_fn = NULL; + buff->size = size; + buff->buff = buffdata; + LWRB_INIT(buff->w, 0); + LWRB_INIT(buff->r, 0); + return 1; +} + +/** + * \brief Check if buff is initialized and ready to use + * \param[in] buff: Ring buffer instance + * \return `1` if ready, `0` otherwise + */ +uint8_t +lwrb_is_ready(lwrb_t* buff) { + return BUF_IS_VALID(buff); +} + +/** + * \brief Free buffer memory + * \note Since implementation does not use dynamic allocation, + * it just sets buffer handle to `NULL` + * \param[in] buff: Ring buffer instance + */ +void +lwrb_free(lwrb_t* buff) { + if (BUF_IS_VALID(buff)) { + buff->buff = NULL; + } +} + +/** + * \brief Set event function callback for different buffer operations + * \param[in] buff: Ring buffer instance + * \param[in] evt_fn: Callback function + */ +void +lwrb_set_evt_fn(lwrb_t* buff, lwrb_evt_fn evt_fn) { + if (BUF_IS_VALID(buff)) { + buff->evt_fn = evt_fn; + } +} + +/** + * \brief Write data to buffer. + * Copies data from `data` array to buffer and marks buffer as full for maximum `btw` number of bytes + * + * \param[in] buff: Ring buffer instance + * \param[in] data: Pointer to data to write into buffer + * \param[in] btw: Number of bytes to write + * \return Number of bytes written to buffer. + * When returned value is less than `btw`, there was no enough memory available + * to copy full data array. + */ +lwrb_sz_t +lwrb_write(lwrb_t* buff, const void* data, lwrb_sz_t btw) { + lwrb_sz_t written = 0; + + if (lwrb_write_ex(buff, data, btw, &written, 0)) { + return written; + } + return 0; +} + +/** + * \brief Write extended functionality + * + * \param buff: Ring buffer instance + * \param data: Pointer to data to write into buffer + * \param btw: Number of bytes to write + * \param bw: Output pointer to write number of bytes written + * \param flags: Optional flags. + * \ref LWRB_FLAG_WRITE_ALL: Request to write all data (up to btw). + * Will early return if no memory available + * \return `1` if write operation OK, `0` otherwise + */ +uint8_t +lwrb_write_ex(lwrb_t* buff, const void* data, lwrb_sz_t btw, lwrb_sz_t* bw, uint16_t flags) { + lwrb_sz_t tocopy, free, buff_w_ptr; + const uint8_t* d = data; + + if (!BUF_IS_VALID(buff) || data == NULL || btw == 0) { + return 0; + } + + /* Calculate maximum number of bytes available to write */ + free = lwrb_get_free(buff); + /* If no memory, or if user wants to write ALL data but no enough space, exit early */ + if (free == 0 || (free < btw && flags & LWRB_FLAG_WRITE_ALL)) { + return 0; + } + btw = BUF_MIN(free, btw); + buff_w_ptr = LWRB_LOAD(buff->w, memory_order_acquire); + + /* Step 1: Write data to linear part of buffer */ + tocopy = BUF_MIN(buff->size - buff_w_ptr, btw); + BUF_MEMCPY(&buff->buff[buff_w_ptr], d, tocopy); + buff_w_ptr += tocopy; + btw -= tocopy; + + /* Step 2: Write data to beginning of buffer (overflow part) */ + if (btw > 0) { + BUF_MEMCPY(buff->buff, &d[tocopy], btw); + buff_w_ptr = btw; + } + + /* Step 3: Check end of buffer */ + if (buff_w_ptr >= buff->size) { + buff_w_ptr = 0; + } + + /* + * Write final value to the actual running variable. + * This is to ensure no read operation can access intermediate data + */ + LWRB_STORE(buff->w, buff_w_ptr, memory_order_release); + + BUF_SEND_EVT(buff, LWRB_EVT_WRITE, tocopy + btw); + if (bw != NULL) { + *bw = tocopy + btw; + } + return 1; +} + +/** + * \brief Read data from buffer. + * Copies data from buffer to `data` array and marks buffer as free for maximum `btr` number of bytes + * + * \param[in] buff: Ring buffer instance + * \param[out] data: Pointer to output memory to copy buffer data to + * \param[in] btr: Number of bytes to read + * \return Number of bytes read and copied to data array + */ +lwrb_sz_t +lwrb_read(lwrb_t* buff, void* data, lwrb_sz_t btr) { + lwrb_sz_t read = 0; + + if (lwrb_read_ex(buff, data, btr, &read, 0)) { + return read; + } + return 0; +} + +/** + * \brief Write extended functionality + * + * \param buff: Ring buffer instance + * \param data: Pointer to memory to write read data from buffer + * \param btr: Number of bytes to read + * \param br: Output pointer to write number of bytes read + * \param flags: Optional flags + * \ref LWRB_FLAG_READ_ALL: Request to read all data (up to btr). + * Will early return if no enough bytes in the buffer + * \return `1` if read operation OK, `0` otherwise + */ +uint8_t +lwrb_read_ex(lwrb_t* buff, void* data, lwrb_sz_t btr, lwrb_sz_t* br, uint16_t flags) { + lwrb_sz_t tocopy, full, buff_r_ptr; + uint8_t* d = data; + + if (!BUF_IS_VALID(buff) || data == NULL || btr == 0) { + return 0; + } + + /* Calculate maximum number of bytes available to read */ + full = lwrb_get_full(buff); + if (full == 0 || (full < btr && (flags & LWRB_FLAG_READ_ALL))) { + return 0; + } + btr = BUF_MIN(full, btr); + buff_r_ptr = LWRB_LOAD(buff->r, memory_order_acquire); + + /* Step 1: Read data from linear part of buffer */ + tocopy = BUF_MIN(buff->size - buff_r_ptr, btr); + BUF_MEMCPY(d, &buff->buff[buff_r_ptr], tocopy); + buff_r_ptr += tocopy; + btr -= tocopy; + + /* Step 2: Read data from beginning of buffer (overflow part) */ + if (btr > 0) { + BUF_MEMCPY(&d[tocopy], buff->buff, btr); + buff_r_ptr = btr; + } + + /* Step 3: Check end of buffer */ + if (buff_r_ptr >= buff->size) { + buff_r_ptr = 0; + } + + /* + * Write final value to the actual running variable. + * This is to ensure no write operation can access intermediate data + */ + LWRB_STORE(buff->r, buff_r_ptr, memory_order_release); + + BUF_SEND_EVT(buff, LWRB_EVT_READ, tocopy + btr); + if (br != NULL) { + *br = tocopy + btr; + } + return 1; +} + +/** + * \brief Read from buffer without changing read pointer (peek only) + * \param[in] buff: Ring buffer instance + * \param[in] skip_count: Number of bytes to skip before reading data + * \param[out] data: Pointer to output memory to copy buffer data to + * \param[in] btp: Number of bytes to peek + * \return Number of bytes peeked and written to output array + */ +lwrb_sz_t +lwrb_peek(const lwrb_t* buff, lwrb_sz_t skip_count, void* data, lwrb_sz_t btp) { + lwrb_sz_t full, tocopy, r; + uint8_t* d = data; + + if (!BUF_IS_VALID(buff) || data == NULL || btp == 0) { + return 0; + } + + /* + * Calculate maximum number of bytes available to read + * and check if we can even fit to it + */ + full = lwrb_get_full(buff); + if (skip_count >= full) { + return 0; + } + r = LWRB_LOAD(buff->r, memory_order_relaxed); + r += skip_count; + full -= skip_count; + if (r >= buff->size) { + r -= buff->size; + } + + /* Check maximum number of bytes available to read after skip */ + btp = BUF_MIN(full, btp); + if (btp == 0) { + return 0; + } + + /* Step 1: Read data from linear part of buffer */ + tocopy = BUF_MIN(buff->size - r, btp); + BUF_MEMCPY(d, &buff->buff[r], tocopy); + btp -= tocopy; + + /* Step 2: Read data from beginning of buffer (overflow part) */ + if (btp > 0) { + BUF_MEMCPY(&d[tocopy], buff->buff, btp); + } + return tocopy + btp; +} + +/** + * \brief Get available size in buffer for write operation + * \param[in] buff: Ring buffer instance + * \return Number of free bytes in memory + */ +lwrb_sz_t +lwrb_get_free(const lwrb_t* buff) { + lwrb_sz_t size, w, r; + + if (!BUF_IS_VALID(buff)) { + return 0; + } + + /* + * Copy buffer pointers to local variables with atomic access. + * + * To ensure thread safety (only when in single-entry, single-exit FIFO mode use case), + * it is important to write buffer r and w values to local w and r variables. + * + * Local variables will ensure below if statements will always use the same value, + * even if buff->w or buff->r get changed during interrupt processing. + * + * They may change during load operation, important is that + * they do not change during if-elseif-else operations following these assignments. + * + * lwrb_get_free is only called for write purpose, and when in FIFO mode, then: + * - buff->w pointer will not change by another process/interrupt because we are in write mode just now + * - buff->r pointer may change by another process. If it gets changed after buff->r has been loaded to local variable, + * buffer will see "free size" less than it actually is. This is not a problem, application can + * always try again to write more data to remaining free memory that was read just during copy operation + */ + w = LWRB_LOAD(buff->w, memory_order_relaxed); + r = LWRB_LOAD(buff->r, memory_order_relaxed); + + if (w == r) { + size = buff->size; + } else if (r > w) { + size = r - w; + } else { + size = buff->size - (w - r); + } + + /* Buffer free size is always 1 less than actual size */ + return size - 1; +} + +/** + * \brief Get number of bytes currently available in buffer + * \param[in] buff: Ring buffer instance + * \return Number of bytes ready to be read + */ +lwrb_sz_t +lwrb_get_full(const lwrb_t* buff) { + lwrb_sz_t size, w, r; + + if (!BUF_IS_VALID(buff)) { + return 0; + } + + /* + * Copy buffer pointers to local variables. + * + * To ensure thread safety (only when in single-entry, single-exit FIFO mode use case), + * it is important to write buffer r and w values to local w and r variables. + * + * Local variables will ensure below if statements will always use the same value, + * even if buff->w or buff->r get changed during interrupt processing. + * + * They may change during load operation, important is that + * they do not change during if-elseif-else operations following these assignments. + * + * lwrb_get_full is only called for read purpose, and when in FIFO mode, then: + * - buff->r pointer will not change by another process/interrupt because we are in read mode just now + * - buff->w pointer may change by another process. If it gets changed after buff->w has been loaded to local variable, + * buffer will see "full size" less than it really is. This is not a problem, application can + * always try again to read more data from remaining full memory that was written just during copy operation + */ + w = LWRB_LOAD(buff->w, memory_order_relaxed); + r = LWRB_LOAD(buff->r, memory_order_relaxed); + + if (w == r) { + size = 0; + } else if (w > r) { + size = w - r; + } else { + size = buff->size - (r - w); + } + return size; +} + +/** + * \brief Resets buffer to default values. Buffer size is not modified + * \note This function is not thread safe. + * When used, application must ensure there is no active read/write operation + * \param[in] buff: Ring buffer instance + */ +void +lwrb_reset(lwrb_t* buff) { + if (BUF_IS_VALID(buff)) { + LWRB_STORE(buff->w, 0, memory_order_release); + LWRB_STORE(buff->r, 0, memory_order_release); + BUF_SEND_EVT(buff, LWRB_EVT_RESET, 0); + } +} + +/** + * \brief Get linear address for buffer for fast read + * \param[in] buff: Ring buffer instance + * \return Linear buffer start address + */ +void* +lwrb_get_linear_block_read_address(const lwrb_t* buff) { + if (!BUF_IS_VALID(buff)) { + return NULL; + } + return &buff->buff[buff->r]; +} + +/** + * \brief Get length of linear block address before it overflows for read operation + * \param[in] buff: Ring buffer instance + * \return Linear buffer size in units of bytes for read operation + */ +lwrb_sz_t +lwrb_get_linear_block_read_length(const lwrb_t* buff) { + lwrb_sz_t len, w, r; + + if (!BUF_IS_VALID(buff)) { + return 0; + } + + /* + * Use temporary values in case they are changed during operations. + * See lwrb_buff_free or lwrb_buff_full functions for more information why this is OK. + */ + w = LWRB_LOAD(buff->w, memory_order_relaxed); + r = LWRB_LOAD(buff->r, memory_order_relaxed); + + if (w > r) { + len = w - r; + } else if (r > w) { + len = buff->size - r; + } else { + len = 0; + } + return len; +} + +/** + * \brief Skip (ignore; advance read pointer) buffer data + * Marks data as read in the buffer and increases free memory for up to `len` bytes + * + * \note Useful at the end of streaming transfer such as DMA + * \param[in] buff: Ring buffer instance + * \param[in] len: Number of bytes to skip and mark as read + * \return Number of bytes skipped + */ +lwrb_sz_t +lwrb_skip(lwrb_t* buff, lwrb_sz_t len) { + lwrb_sz_t full, r; + + if (!BUF_IS_VALID(buff) || len == 0) { + return 0; + } + + full = lwrb_get_full(buff); + len = BUF_MIN(len, full); + r = LWRB_LOAD(buff->r, memory_order_acquire); + r += len; + if (r >= buff->size) { + r -= buff->size; + } + LWRB_STORE(buff->r, r, memory_order_release); + BUF_SEND_EVT(buff, LWRB_EVT_READ, len); + return len; +} + +/** + * \brief Get linear address for buffer for fast read + * \param[in] buff: Ring buffer instance + * \return Linear buffer start address + */ +void* +lwrb_get_linear_block_write_address(const lwrb_t* buff) { + if (!BUF_IS_VALID(buff)) { + return NULL; + } + return &buff->buff[buff->w]; +} + +/** + * \brief Get length of linear block address before it overflows for write operation + * \param[in] buff: Ring buffer instance + * \return Linear buffer size in units of bytes for write operation + */ +lwrb_sz_t +lwrb_get_linear_block_write_length(const lwrb_t* buff) { + lwrb_sz_t len, w, r; + + if (!BUF_IS_VALID(buff)) { + return 0; + } + + /* + * Use temporary values in case they are changed during operations. + * See lwrb_buff_free or lwrb_buff_full functions for more information why this is OK. + */ + w = LWRB_LOAD(buff->w, memory_order_relaxed); + r = LWRB_LOAD(buff->r, memory_order_relaxed); + + if (w >= r) { + len = buff->size - w; + /* + * When read pointer is 0, + * maximal length is one less as if too many bytes + * are written, buffer would be considered empty again (r == w) + */ + if (r == 0) { + /* + * Cannot overflow: + * - If r is not 0, statement does not get called + * - buff->size cannot be 0 and if r is 0, len is greater 0 + */ + --len; + } + } else { + len = r - w - 1; + } + return len; +} + +/** + * \brief Advance write pointer in the buffer. + * Similar to skip function but modifies write pointer instead of read + * + * \note Useful when hardware is writing to buffer and application needs to increase number + * of bytes written to buffer by hardware + * \param[in] buff: Ring buffer instance + * \param[in] len: Number of bytes to advance + * \return Number of bytes advanced for write operation + */ +lwrb_sz_t +lwrb_advance(lwrb_t* buff, lwrb_sz_t len) { + lwrb_sz_t free, w; + + if (!BUF_IS_VALID(buff) || len == 0) { + return 0; + } + + /* Use local variables before writing back to main structure */ + free = lwrb_get_free(buff); + len = BUF_MIN(len, free); + w = LWRB_LOAD(buff->w, memory_order_acquire); + w += len; + if (w >= buff->size) { + w -= buff->size; + } + LWRB_STORE(buff->w, w, memory_order_release); + BUF_SEND_EVT(buff, LWRB_EVT_WRITE, len); + return len; +} + +/** + * \brief Searches for a *needle* in an array, starting from given offset. + * + * \note This function is not thread-safe. + * + * \param buff: Ring buffer to search for needle in + * \param bts: Constant byte array sequence to search for in a buffer + * \param len: Length of the \arg bts array + * \param start_offset: Start offset in the buffer + * \param found_idx: Pointer to variable to write index in array where bts has been found + * Must not be set to `NULL` + * \return `1` if \arg bts found, `0` otherwise + */ +uint8_t +lwrb_find(const lwrb_t* buff, const void* bts, lwrb_sz_t len, lwrb_sz_t start_offset, lwrb_sz_t* found_idx) { + lwrb_sz_t full, r, max_x; + uint8_t found = 0; + const uint8_t* needle = bts; + + if (!BUF_IS_VALID(buff) || needle == NULL || len == 0 || found_idx == NULL) { + return 0; + } + *found_idx = 0; + + full = lwrb_get_full(buff); + /* Verify initial conditions */ + if (full < (len + start_offset)) { + return 0; + } + + /* Max number of for loops is buff_full - input_len - start_offset of buffer length */ + max_x = full - len; + for (lwrb_sz_t skip_x = start_offset; !found && skip_x <= max_x; ++skip_x) { + found = 1; /* Found by default */ + + /* Prepare the starting point for reading */ + r = buff->r + skip_x; + if (r >= buff->size) { + r -= buff->size; + } + + /* Search in the buffer */ + for (lwrb_sz_t i = 0; i < len; ++i) { + if (buff->buff[r] != needle[i]) { + found = 0; + break; + } + if (++r >= buff->size) { + r = 0; + } + } + if (found) { + *found_idx = skip_x; + } + } + return found; +} diff --git a/app/gl_headfile.h b/app/gl_headfile.h index 1482de7..08c361b 100644 --- a/app/gl_headfile.h +++ b/app/gl_headfile.h @@ -4,7 +4,6 @@ #include "gl_state.h" #include "gl_img_process.h" #include "gl_common.h" -#include "main.h" #include "gl_handle_img.h" #include "gl_transform_table.h" #include "gl_get_corners.h" diff --git a/app/isr.c b/app/isr.c index e0f81ac..cf9dd1c 100644 --- a/app/isr.c +++ b/app/isr.c @@ -34,9 +34,12 @@ ********************************************************************************************************************/ #include "zf_common_headfile.h" +#include "by_tiny_frame.h" #include "by_button.h" #include "by_buzzer.h" +#include "by_tiny_frame_parse.h" + void NMI_Handler(void) __attribute__((interrupt())); void HardFault_Handler(void) __attribute__((interrupt())); @@ -96,9 +99,12 @@ void USART2_IRQHandler(void) void USART3_IRQHandler(void) { if (USART_GetITStatus(USART3, USART_IT_RXNE) != RESET) { -#if DEBUG_UART_USE_INTERRUPT // debug ж - debug_interrupr_handler(); // debug ڽմ ݻᱻ debug λȡ -#endif // ޸ DEBUG_UART_INDEX δҪŵӦĴжȥ +#if DEBUG_UART_USE_INTERRUPT // debug ж + // debug_interrupr_handler(); // debug ڽմ ݻᱻ debug λȡ +#endif // ޸ DEBUG_UART_INDEX δҪŵӦĴжȥ + uint8_t data_s = 0; + uart_query_byte(UART_3, &data_s); + by_tiny_frame_parse_uart_handle(data_s); USART_ClearITPendingBit(USART3, USART_IT_RXNE); } } diff --git a/app/main.c b/app/main.c index 8b712e3..eb72219 100644 --- a/app/main.c +++ b/app/main.c @@ -21,13 +21,17 @@ * 许可证副本在 libraries 文件夹下 即该文件夹下的 LICENSE 文件 * 欢迎各位使用并传播本程序 但修改内容时必须保留逐飞科技的版权声明(即本声明) ********************************************************************************************************************/ +#include "zf_common_headfile.h" #include "gl_headfile.h" -#include "./page/page.h" +#include "page.h" +#include "by_tiny_frame.h" #include "by_buzzer.h" #include "by_led.h" #include "jj_param.h" #include "jj_blueteeth.h" +#include "by_tiny_frame_parse.h" + int main(void) { @@ -49,25 +53,30 @@ int main(void) // pit_ms_init(TIM6_PIT, 2); // pit_ms_init(TIM1_PIT, 2); + by_tiny_frame_init(); + printf("start running\r\n"); + while (1) { Page_Run(); by_buzzer_run(); - if (mt9v03x_finish_flag) { - // 该操作消耗大概 1970 个 tick,折合约 110us - memcpy(mt9v03x_image_copy[0], mt9v03x_image[0], (sizeof(mt9v03x_image_copy) / sizeof(uint8_t))); - // adaptiveThreshold((uint8_t*)mt9v03x_image_copy, (uint8_t*)mt9v03x_image_copy, 188, 120, 7, 17); - // ips200_show_gray_image(0, 0, mt9v03x_image_copy[0], MT9V03X_W, MT9V03X_H, MT9V03X_W, MT9V03X_H, 0); - mt9v03x_finish_flag = 0; - by_led_info_blink(); - state_type = COMMON_STATE; - img_processing(); - get_corners(); - aim_distance = COMMON_AIM; - tracking(); - ElementJudge(); - ElementRun(); - MidLineTrack(); - } + by_tiny_frame_parse_run(); + system_delay_ms(100); + // if (mt9v03x_finish_flag) { + // // 该操作消耗大概 1970 个 tick,折合约 110us + // memcpy(mt9v03x_image_copy[0], mt9v03x_image[0], (sizeof(mt9v03x_image_copy) / sizeof(uint8_t))); + // // adaptiveThreshold((uint8_t*)mt9v03x_image_copy, (uint8_t*)mt9v03x_image_copy, 188, 120, 7, 17); + // // ips200_show_gray_image(0, 0, mt9v03x_image_copy[0], MT9V03X_W, MT9V03X_H, MT9V03X_W, MT9V03X_H, 0); + // mt9v03x_finish_flag = 0; + // by_led_info_blink(); + // state_type = COMMON_STATE; + // img_processing(); + // get_corners(); + // aim_distance = COMMON_AIM; + // tracking(); + // ElementJudge(); + // ElementRun(); + // MidLineTrack(); + // } } } diff --git a/app/main.h b/app/main.h deleted file mode 100644 index 1741eaa..0000000 --- a/app/main.h +++ /dev/null @@ -1,6 +0,0 @@ -#ifndef MAIN_H -#define MAIN_H - -#include "zf_common_headfile.h" - -#endif // MAIN_H \ No newline at end of file diff --git a/app/tiny_frame/by_tiny_frame.c b/app/tiny_frame/by_tiny_frame.c new file mode 100644 index 0000000..6b2ccc5 --- /dev/null +++ b/app/tiny_frame/by_tiny_frame.c @@ -0,0 +1,16 @@ +#include "by_tiny_frame.h" + +#include +#include + +#include "by_tiny_frame_parse.h" +#include "crc16.h" +#include "zf_common_headfile.h" + +void by_tiny_frame_init(void) +{ + uart_init(BY_TF_UART_INDEX, BY_TF_UART_BAUDRATE, BY_TF_UART_TX_PIN, BY_TF_UART_RX_PIN); + uart_rx_interrupt(BY_TF_UART_INDEX, ENABLE); + + by_tiny_frame_parse_init(); +} diff --git a/app/tiny_frame/by_tiny_frame.h b/app/tiny_frame/by_tiny_frame.h new file mode 100644 index 0000000..630f0cf --- /dev/null +++ b/app/tiny_frame/by_tiny_frame.h @@ -0,0 +1,8 @@ +#ifndef _BY_TINY_FRAME_H__ +#define _BY_TINY_FRAME_H__ + +#include "by_tiny_frame_config.h" + +extern void by_tiny_frame_init(void); + +#endif diff --git a/app/tiny_frame/by_tiny_frame_config.h b/app/tiny_frame/by_tiny_frame_config.h new file mode 100644 index 0000000..2d14a89 --- /dev/null +++ b/app/tiny_frame/by_tiny_frame_config.h @@ -0,0 +1,11 @@ +#ifndef _BY_TINY_FRAME_CONFIG_H__ +#define _BY_TINY_FRAME_CONFIG_H__ + +#define BY_TF_UART_TX_PIN (UART3_MAP0_TX_B10) +#define BY_TF_UART_RX_PIN (UART3_MAP0_RX_B11) +#define BY_TF_UART_INDEX (UART_3) +#define BY_TF_UART_BAUDRATE (115200) + +#define BY_TF_PARSE_BUFFER_SIZE (50) + +#endif diff --git a/app/tiny_frame/by_tiny_frame_parse.c b/app/tiny_frame/by_tiny_frame_parse.c new file mode 100644 index 0000000..9a67111 --- /dev/null +++ b/app/tiny_frame/by_tiny_frame_parse.c @@ -0,0 +1,97 @@ +#include "by_tiny_frame_parse.h" + +#include "crc16.h" +#include "lwrb.h" + +lwrb_t lwrb_struct; +uint8_t buffer_rb[BY_TF_PARSE_BUFFER_SIZE]; +uint8_t buffer_out; +by_tf_parse_frame_t frame_now; + +void by_tiny_frame_parse_init(void) +{ + lwrb_init(&lwrb_struct, buffer_rb, 40); +} + +uint8_t by_tiny_frame_parse_listening(by_tf_parse_frame_t *frame_s, const uint8_t slave_id, const uint8_t buff) +{ + + static uint8_t cnt_s = 0; + static uint8_t cnt_rest_s = 0; + + printf("%0.2X\r\n", buff); + + do { + if ((0 == cnt_s) && (((slave_id << 1) + 1) == buff)) { + memset(frame_s, 0, sizeof(*frame_s)); + cnt_s = 1; + cnt_rest_s = 9; + frame_s->frame[0] = buff; + break; + } + + if (1 <= cnt_s) { + frame_s->frame[cnt_s] = buff; + cnt_s++; + } + + if (0 == --cnt_rest_s) { + cnt_s = 0; + + frame_s->cmd = frame_s->frame[1]; + frame_s->reg_addr |= ((uint16_t)frame_s->frame[2] << 8); + frame_s->reg_addr |= (uint16_t)frame_s->frame[3]; + frame_s->data |= ((uint32_t)frame_s->frame[4] << 24); + frame_s->data |= ((uint32_t)frame_s->frame[5] << 16); + frame_s->data |= ((uint32_t)frame_s->frame[6] << 8); + frame_s->data |= (uint32_t)frame_s->frame[7]; + return 0; + } + } while (0); + + return 1; +} + +void by_tiny_frame_parse_uart_handle(uint8_t buff) +{ + lwrb_write(&lwrb_struct, &buff, 1); +} + +void by_tiny_frame_parse_run(void) +{ + for (uint8_t i = 0; i < lwrb_get_full(&lwrb_struct); i++) { + + if (!lwrb_read(&lwrb_struct, &buffer_out, 1)) { + break; + } + + if (!by_tiny_frame_parse_listening(&frame_now, 127, buffer_out)) { + if (!by_tiny_frame_parse_crc(&frame_now)) { + printf("frame parsed!\r\n"); + } + // 解析帧 + } + // if (!mp_cmd_parse_modbus_handle(data)) { + // mp_cmd_mb_parse(&mp_cmd_mb_now, &mp_cmd_parsed_now); + // } + } +} + +uint8_t by_tiny_frame_parse_crc(by_tf_parse_frame_t *frame_s) +{ + uint16_t calc_crc_val = 0; + + calc_crc_val = crc16_check(frame_s->frame, (sizeof(frame_s->frame) - 2)); + + printf("get: %0.2X", frame_s->crc_val); + printf("\r\n"); + + printf("cal: %0.2X", calc_crc_val); + printf("\r\n"); + + if ((frame_s->crc_val == calc_crc_val) || (frame_s->crc_val == 0xFFFF)) { + return 0; + } + + return 1; +} \ No newline at end of file diff --git a/app/tiny_frame/by_tiny_frame_parse.h b/app/tiny_frame/by_tiny_frame_parse.h new file mode 100644 index 0000000..ed1801c --- /dev/null +++ b/app/tiny_frame/by_tiny_frame_parse.h @@ -0,0 +1,25 @@ +#ifndef _BY_TINY_FRAME_PARSE_H__ +#define _BY_TINY_FRAME_PARSE_H__ + +#include +#include + +#include "by_tiny_frame_config.h" + +// 从机地址 (1b) - 功能码 (1b) - 寄存器地址 (2b) - 数据 (4b) - CRC(2b) +// 从机地址 (1b) 0-127, 最低位表示发送方,主机请求低位为 0,从机应答低位为 1 + +typedef struct by_tf_parse_frame_t { + uint8_t frame[10]; + uint8_t cmd; + uint16_t reg_addr; + uint16_t crc_val; + uint32_t data; +} by_tf_parse_frame_t; + +extern void by_tiny_frame_parse_init(void); +extern void by_tiny_frame_parse_uart_handle(uint8_t buff); +extern void by_tiny_frame_parse_run(void); +extern uint8_t by_tiny_frame_parse_crc(by_tf_parse_frame_t *frame_s); + +#endif diff --git a/app/tiny_frame/by_tiny_frame_read.c b/app/tiny_frame/by_tiny_frame_read.c new file mode 100644 index 0000000..e69de29 diff --git a/app/tiny_frame/by_tiny_frame_read.h b/app/tiny_frame/by_tiny_frame_read.h new file mode 100644 index 0000000..ca4081f --- /dev/null +++ b/app/tiny_frame/by_tiny_frame_read.h @@ -0,0 +1,6 @@ +#ifndef _BY_TINY_FRAME_READ_H__ +#define _BY_TINY_FRAME_READ_H__ + +#define BY_TINY_FRAME_WRITE_CMD_CODE (0x03) + +#endif diff --git a/app/tiny_frame/by_tiny_frame_write.c b/app/tiny_frame/by_tiny_frame_write.c new file mode 100644 index 0000000..acca88c --- /dev/null +++ b/app/tiny_frame/by_tiny_frame_write.c @@ -0,0 +1,2 @@ +#include "by_tiny_frame_write.h" + diff --git a/app/tiny_frame/by_tiny_frame_write.h b/app/tiny_frame/by_tiny_frame_write.h new file mode 100644 index 0000000..20093c5 --- /dev/null +++ b/app/tiny_frame/by_tiny_frame_write.h @@ -0,0 +1,6 @@ +#ifndef _BY_TINY_FRAME_WRITE_H__ +#define _BY_TINY_FRAME_WRITE_H__ + +#define BY_TINY_FRAME_WRITE_CMD_CODE (0x06) + +#endif From 3a68f98635796322a0c0e08c7e86286d097f14f9 Mon Sep 17 00:00:00 2001 From: bmy <2583236812@qq.com> Date: Fri, 23 Feb 2024 18:56:53 +0800 Subject: [PATCH 07/19] =?UTF-8?q?feat:=20=E5=AE=8C=E6=88=90=E9=80=9A?= =?UTF-8?q?=E4=BF=A1=E5=B8=A7=E7=BB=84=E5=8C=85=E5=8A=9F=E8=83=BD?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- app/main.c | 17 ++++++++++++ app/tiny_frame/by_tiny_frame.c | 1 + app/tiny_frame/by_tiny_frame_config.h | 12 +++++++++ app/tiny_frame/by_tiny_frame_pack.c | 39 +++++++++++++++++++++++++++ app/tiny_frame/by_tiny_frame_pack.h | 24 +++++++++++++++++ app/tiny_frame/by_tiny_frame_parse.c | 20 ++++++++++++-- app/tiny_frame/by_tiny_frame_parse.h | 1 + 7 files changed, 112 insertions(+), 2 deletions(-) create mode 100644 app/tiny_frame/by_tiny_frame_pack.c create mode 100644 app/tiny_frame/by_tiny_frame_pack.h diff --git a/app/main.c b/app/main.c index eb72219..645cb7a 100644 --- a/app/main.c +++ b/app/main.c @@ -30,7 +30,10 @@ #include "jj_param.h" #include "jj_blueteeth.h" +/** 测试完成后移除 **/ #include "by_tiny_frame_parse.h" +#include "by_tiny_frame_pack.h" +/** 测试完成后移除 **/ int main(void) { @@ -56,11 +59,25 @@ int main(void) by_tiny_frame_init(); printf("start running\r\n"); + /** 测试完成后移除 **/ + by_tf_pack_frame_t frame_now; + + frame_now.cmd = 0x06; + frame_now.data = 0x19260817; + frame_now.reg_addr = 0x4059; + frame_now.slave_id = 0x0D; + /** 测试完成后移除 **/ + while (1) { Page_Run(); by_buzzer_run(); + + /** 测试完成后移除 **/ by_tiny_frame_parse_run(); + // by_tiny_frame_pack_send(&frame_now); system_delay_ms(100); + /** 测试完成后移除 **/ + // if (mt9v03x_finish_flag) { // // 该操作消耗大概 1970 个 tick,折合约 110us // memcpy(mt9v03x_image_copy[0], mt9v03x_image[0], (sizeof(mt9v03x_image_copy) / sizeof(uint8_t))); diff --git a/app/tiny_frame/by_tiny_frame.c b/app/tiny_frame/by_tiny_frame.c index 6b2ccc5..f59e6c1 100644 --- a/app/tiny_frame/by_tiny_frame.c +++ b/app/tiny_frame/by_tiny_frame.c @@ -9,6 +9,7 @@ void by_tiny_frame_init(void) { + /*** 初始化相关外设 ***/ uart_init(BY_TF_UART_INDEX, BY_TF_UART_BAUDRATE, BY_TF_UART_TX_PIN, BY_TF_UART_RX_PIN); uart_rx_interrupt(BY_TF_UART_INDEX, ENABLE); diff --git a/app/tiny_frame/by_tiny_frame_config.h b/app/tiny_frame/by_tiny_frame_config.h index 2d14a89..295678f 100644 --- a/app/tiny_frame/by_tiny_frame_config.h +++ b/app/tiny_frame/by_tiny_frame_config.h @@ -1,6 +1,8 @@ #ifndef _BY_TINY_FRAME_CONFIG_H__ #define _BY_TINY_FRAME_CONFIG_H__ +#define BY_TF_DEBUG (1) + #define BY_TF_UART_TX_PIN (UART3_MAP0_TX_B10) #define BY_TF_UART_RX_PIN (UART3_MAP0_RX_B11) #define BY_TF_UART_INDEX (UART_3) @@ -8,4 +10,14 @@ #define BY_TF_PARSE_BUFFER_SIZE (50) +/** 注释此项则为主机,否则为从机 **/ +// #define BY_TF_DEVICE_SLAVE + +#if defined(BY_TF_DEVICE_SLAVE) +/** 多从机通信时注意修改地址,避免冲突 **/ +#define BY_TF_DEVICE_SLAVE_ADDRESS (0x0D) +#else +#define BY_TF_DEVICE_MASTER +#endif + #endif diff --git a/app/tiny_frame/by_tiny_frame_pack.c b/app/tiny_frame/by_tiny_frame_pack.c new file mode 100644 index 0000000..78107f0 --- /dev/null +++ b/app/tiny_frame/by_tiny_frame_pack.c @@ -0,0 +1,39 @@ +#include "by_tiny_frame_pack.h" + +#include +#include "zf_common_headfile.h" +#include "crc16.h" + +void by_tiny_frame_pack_init(void) +{ + /** nothing to init **/ +} + +void by_tiny_frame_pack_send(by_tf_pack_frame_t *frame_s) +{ + uint16_t calc_crc_val = 0; + +#if defined(BY_TF_DEVICE_SLAVE) + frame_s->frame[0] = ((frame_s->slave_id << 1) + 1); +#else + frame_s->frame[0] = (frame_s->slave_id << 1); +#endif + + // 填充指令段 + frame_s->frame[1] = frame_s->cmd; + // 填充寄存器地址段 + frame_s->frame[2] = (uint8_t)((frame_s->reg_addr >> 8) & 0xFF); + frame_s->frame[3] = (uint8_t)(frame_s->reg_addr & 0xFF); + // 填充数据段 + frame_s->frame[4] = (uint8_t)((frame_s->data >> 24) & 0xFF); + frame_s->frame[5] = (uint8_t)((frame_s->data >> 16) & 0xFF); + frame_s->frame[6] = (uint8_t)((frame_s->data >> 8) & 0xFF); + frame_s->frame[7] = (uint8_t)(frame_s->data & 0xFF); + // 填充 CRC 段 + calc_crc_val = crc16_check(frame_s->frame, (sizeof(frame_s->frame) - 2)); + frame_s->frame[8] = (uint8_t)((calc_crc_val >> 8) & 0xFF); + frame_s->frame[9] = (uint8_t)(calc_crc_val & 0xFF); + + /** 从串口发送 **/ + uart_write_buffer(BY_TF_UART_INDEX, frame_s->frame, sizeof(frame_s->frame)); +} diff --git a/app/tiny_frame/by_tiny_frame_pack.h b/app/tiny_frame/by_tiny_frame_pack.h new file mode 100644 index 0000000..70fbb9d --- /dev/null +++ b/app/tiny_frame/by_tiny_frame_pack.h @@ -0,0 +1,24 @@ +#ifndef _BY_TINY_FRAME_PACK_H__ +#define _BY_TINY_FRAME_PACK_H__ + +#include +#include + +#include "by_tiny_frame_config.h" + +// 从机地址 (1b) - 功能码 (1b) - 寄存器地址 (2b) - 数据 (4b) - CRC(2b) +// 从机地址 (1b) 0-127, 最低位表示发送方,主机请求低位为 0,从机应答低位为 1 +// 高字节在前 + +typedef struct by_tf_pack_frame_t { + uint8_t frame[10]; + uint8_t slave_id; + uint8_t cmd; + uint16_t reg_addr; + uint32_t data; +} by_tf_pack_frame_t; + +extern void by_tiny_frame_pack_init(void); +extern void by_tiny_frame_pack_send(by_tf_pack_frame_t *frame_s); + +#endif diff --git a/app/tiny_frame/by_tiny_frame_parse.c b/app/tiny_frame/by_tiny_frame_parse.c index 9a67111..1c44b6d 100644 --- a/app/tiny_frame/by_tiny_frame_parse.c +++ b/app/tiny_frame/by_tiny_frame_parse.c @@ -10,6 +10,7 @@ by_tf_parse_frame_t frame_now; void by_tiny_frame_parse_init(void) { + /** 初始化环形缓冲区 **/ lwrb_init(&lwrb_struct, buffer_rb, 40); } @@ -19,10 +20,17 @@ uint8_t by_tiny_frame_parse_listening(by_tf_parse_frame_t *frame_s, const uint8_ static uint8_t cnt_s = 0; static uint8_t cnt_rest_s = 0; +#if (BY_TF_DEBUG) printf("%0.2X\r\n", buff); +#endif do { + +#if defined(BY_TF_DEVICE_SLAVE) + if ((0 == cnt_s) && ((slave_id << 1) == buff)) { +#else if ((0 == cnt_s) && (((slave_id << 1) + 1) == buff)) { +#endif memset(frame_s, 0, sizeof(*frame_s)); cnt_s = 1; cnt_rest_s = 9; @@ -45,6 +53,8 @@ uint8_t by_tiny_frame_parse_listening(by_tf_parse_frame_t *frame_s, const uint8_ frame_s->data |= ((uint32_t)frame_s->frame[5] << 16); frame_s->data |= ((uint32_t)frame_s->frame[6] << 8); frame_s->data |= (uint32_t)frame_s->frame[7]; + frame_s->crc_val |= ((uint16_t)frame_s->frame[8] << 8); + frame_s->crc_val |= (uint16_t)frame_s->frame[9]; return 0; } } while (0); @@ -65,11 +75,15 @@ void by_tiny_frame_parse_run(void) break; } - if (!by_tiny_frame_parse_listening(&frame_now, 127, buffer_out)) { + // TODO 待结合 read&wirte 部分修改监听的从机地址 + if (!by_tiny_frame_parse_listening(&frame_now, 0x0D, buffer_out)) { if (!by_tiny_frame_parse_crc(&frame_now)) { + +#if (BY_TF_DEBUG) printf("frame parsed!\r\n"); +#endif + // 解析帧 } - // 解析帧 } // if (!mp_cmd_parse_modbus_handle(data)) { // mp_cmd_mb_parse(&mp_cmd_mb_now, &mp_cmd_parsed_now); @@ -83,11 +97,13 @@ uint8_t by_tiny_frame_parse_crc(by_tf_parse_frame_t *frame_s) calc_crc_val = crc16_check(frame_s->frame, (sizeof(frame_s->frame) - 2)); +#if (BY_TF_DEBUG) printf("get: %0.2X", frame_s->crc_val); printf("\r\n"); printf("cal: %0.2X", calc_crc_val); printf("\r\n"); +#endif if ((frame_s->crc_val == calc_crc_val) || (frame_s->crc_val == 0xFFFF)) { return 0; diff --git a/app/tiny_frame/by_tiny_frame_parse.h b/app/tiny_frame/by_tiny_frame_parse.h index ed1801c..6047fdd 100644 --- a/app/tiny_frame/by_tiny_frame_parse.h +++ b/app/tiny_frame/by_tiny_frame_parse.h @@ -8,6 +8,7 @@ // 从机地址 (1b) - 功能码 (1b) - 寄存器地址 (2b) - 数据 (4b) - CRC(2b) // 从机地址 (1b) 0-127, 最低位表示发送方,主机请求低位为 0,从机应答低位为 1 +// 高字节在前 typedef struct by_tf_parse_frame_t { uint8_t frame[10]; From a1c047f15a78983bd6bba6a044f09c27dd966b28 Mon Sep 17 00:00:00 2001 From: bmy <2583236812@qq.com> Date: Fri, 23 Feb 2024 20:13:34 +0800 Subject: [PATCH 08/19] =?UTF-8?q?feat:=20=E6=B7=BB=E5=8A=A0=E9=80=9A?= =?UTF-8?q?=E4=BF=A1=E5=B8=A7=E8=A7=A3=E6=9E=90=E8=B6=85=E6=97=B6=E6=9C=BA?= =?UTF-8?q?=E5=88=B6?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- app/main.c | 11 ++++- app/tiny_frame/by_tiny_frame_config.h | 8 +++- app/tiny_frame/by_tiny_frame_parse.c | 65 ++++++++++++++++++++++++++- app/tiny_frame/by_tiny_frame_parse.h | 5 +++ 4 files changed, 85 insertions(+), 4 deletions(-) diff --git a/app/main.c b/app/main.c index 645cb7a..af00836 100644 --- a/app/main.c +++ b/app/main.c @@ -35,6 +35,11 @@ #include "by_tiny_frame_pack.h" /** 测试完成后移除 **/ +void test(void) +{ + printf("hhhhhhok\r\n"); +} + int main(void) { @@ -60,6 +65,9 @@ int main(void) printf("start running\r\n"); /** 测试完成后移除 **/ + by_tiny_frame_parse_handle_register(test); + by_tiny_frame_parse_start_listern(); + by_tf_pack_frame_t frame_now; frame_now.cmd = 0x06; @@ -75,7 +83,8 @@ int main(void) /** 测试完成后移除 **/ by_tiny_frame_parse_run(); // by_tiny_frame_pack_send(&frame_now); - system_delay_ms(100); + system_delay_ms(10); + by_tiny_frame_parse_timer_handle(); /** 测试完成后移除 **/ // if (mt9v03x_finish_flag) { diff --git a/app/tiny_frame/by_tiny_frame_config.h b/app/tiny_frame/by_tiny_frame_config.h index 295678f..a302e29 100644 --- a/app/tiny_frame/by_tiny_frame_config.h +++ b/app/tiny_frame/by_tiny_frame_config.h @@ -10,14 +10,18 @@ #define BY_TF_PARSE_BUFFER_SIZE (50) -/** 注释此项则为主机,否则为从机 **/ +// 注释此项则为主机,否则为从机 // #define BY_TF_DEVICE_SLAVE +/********** 从机模式配置选项 **********/ #if defined(BY_TF_DEVICE_SLAVE) -/** 多从机通信时注意修改地址,避免冲突 **/ +// 从机地址 (多从机通信时注意修改地址,避免冲突) #define BY_TF_DEVICE_SLAVE_ADDRESS (0x0D) +/********** 主机模式配置选项 **********/ #else #define BY_TF_DEVICE_MASTER +// 监听/解析 超时时间 单位毫秒 +#define BY_TF_PARSE_TIMEOUT (200) #endif #endif diff --git a/app/tiny_frame/by_tiny_frame_parse.c b/app/tiny_frame/by_tiny_frame_parse.c index 1c44b6d..d5f627f 100644 --- a/app/tiny_frame/by_tiny_frame_parse.c +++ b/app/tiny_frame/by_tiny_frame_parse.c @@ -6,10 +6,18 @@ lwrb_t lwrb_struct; uint8_t buffer_rb[BY_TF_PARSE_BUFFER_SIZE]; uint8_t buffer_out; +uint8_t listern_flag; +uint16_t listern_timeout; +uint16_t listern_timevia; by_tf_parse_frame_t frame_now; +by_tf_parse_success_handle_func parse_success_handle; void by_tiny_frame_parse_init(void) { +#if defined(BY_TF_DEVICE_MASTER) + listern_timeout = BY_TF_PARSE_TIMEOUT; +#endif + /** 初始化环形缓冲区 **/ lwrb_init(&lwrb_struct, buffer_rb, 40); } @@ -62,23 +70,63 @@ uint8_t by_tiny_frame_parse_listening(by_tf_parse_frame_t *frame_s, const uint8_ return 1; } +/** + * @brief by_tf_parse 串口回调函数,在对应串口中断函数中调用 + * + * @param buff + */ void by_tiny_frame_parse_uart_handle(uint8_t buff) { lwrb_write(&lwrb_struct, &buff, 1); } +/** + * @brief by_tf_parse 定时回调函数,要求触发周期为 1ms + * + */ +void by_tiny_frame_parse_timer_handle(void) +{ +#if defined(BY_TF_DEVICE_MASTER) + if (listern_flag) { + listern_timevia++; + } else { + listern_timevia = 0; + } +#endif +} + void by_tiny_frame_parse_run(void) { + +#if defined(BY_TF_DEVICE_MASTER) + if (0 == listern_flag) { + return; + } else { + if (listern_timeout <= listern_timevia) { + // 接收超时,停止监听 + by_tiny_frame_parse_end_listern(); +#if (BY_TF_DEBUG) + printf("by_tf_listern timeout\r\n"); +#endif + } + } +#endif + for (uint8_t i = 0; i < lwrb_get_full(&lwrb_struct); i++) { if (!lwrb_read(&lwrb_struct, &buffer_out, 1)) { break; } + // TODO 目前接收校验错误也会等待直至超时 // TODO 待结合 read&wirte 部分修改监听的从机地址 if (!by_tiny_frame_parse_listening(&frame_now, 0x0D, buffer_out)) { if (!by_tiny_frame_parse_crc(&frame_now)) { + // 接收成功后停止监听 + by_tiny_frame_parse_end_listern(); + // 解析成功回调 + parse_success_handle(); #if (BY_TF_DEBUG) printf("frame parsed!\r\n"); #endif @@ -110,4 +158,19 @@ uint8_t by_tiny_frame_parse_crc(by_tf_parse_frame_t *frame_s) } return 1; -} \ No newline at end of file +} + +void by_tiny_frame_parse_handle_register(by_tf_parse_success_handle_func func) +{ + parse_success_handle = func; +} + +void by_tiny_frame_parse_start_listern(void) +{ + listern_flag = 1; +} + +void by_tiny_frame_parse_end_listern(void) +{ + listern_flag = 0; +} diff --git a/app/tiny_frame/by_tiny_frame_parse.h b/app/tiny_frame/by_tiny_frame_parse.h index 6047fdd..eeb41a0 100644 --- a/app/tiny_frame/by_tiny_frame_parse.h +++ b/app/tiny_frame/by_tiny_frame_parse.h @@ -18,9 +18,14 @@ typedef struct by_tf_parse_frame_t { uint32_t data; } by_tf_parse_frame_t; +typedef void (*by_tf_parse_success_handle_func)(void); + extern void by_tiny_frame_parse_init(void); extern void by_tiny_frame_parse_uart_handle(uint8_t buff); extern void by_tiny_frame_parse_run(void); extern uint8_t by_tiny_frame_parse_crc(by_tf_parse_frame_t *frame_s); +extern void by_tiny_frame_parse_handle_register(by_tf_parse_success_handle_func func); +extern void by_tiny_frame_parse_start_listern(void); +extern void by_tiny_frame_parse_end_listern(void); #endif From 8a573170e0513f0f90a051c80451a4897bd2ade4 Mon Sep 17 00:00:00 2001 From: bmy <2583236812@qq.com> Date: Fri, 23 Feb 2024 20:41:40 +0800 Subject: [PATCH 09/19] =?UTF-8?q?pref:=20=E6=9B=B4=E6=94=B9=E9=80=9A?= =?UTF-8?q?=E4=BF=A1=E5=B8=A7=E6=8E=A5=E6=94=B6=E5=AE=8C=E6=88=90=E5=9B=9E?= =?UTF-8?q?=E8=B0=83=E5=87=BD=E6=95=B0=E6=A0=BC=E5=BC=8F?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- app/main.c | 8 ++++++-- app/tiny_frame/by_tiny_frame_parse.c | 9 +++++---- app/tiny_frame/by_tiny_frame_parse.h | 4 ++-- 3 files changed, 13 insertions(+), 8 deletions(-) diff --git a/app/main.c b/app/main.c index af00836..028d67c 100644 --- a/app/main.c +++ b/app/main.c @@ -35,9 +35,13 @@ #include "by_tiny_frame_pack.h" /** 测试完成后移除 **/ -void test(void) +void test(uint8_t status) { - printf("hhhhhhok\r\n"); + if (status) { + printf("noooooooo!\r\n"); + } else { + printf("hhhhhhok\r\n"); + } } int main(void) diff --git a/app/tiny_frame/by_tiny_frame_parse.c b/app/tiny_frame/by_tiny_frame_parse.c index d5f627f..0432c14 100644 --- a/app/tiny_frame/by_tiny_frame_parse.c +++ b/app/tiny_frame/by_tiny_frame_parse.c @@ -10,7 +10,7 @@ uint8_t listern_flag; uint16_t listern_timeout; uint16_t listern_timevia; by_tf_parse_frame_t frame_now; -by_tf_parse_success_handle_func parse_success_handle; +by_tf_parse_done_handle_func parse_done_handle; void by_tiny_frame_parse_init(void) { @@ -104,6 +104,7 @@ void by_tiny_frame_parse_run(void) } else { if (listern_timeout <= listern_timevia) { // 接收超时,停止监听 + parse_done_handle(1); by_tiny_frame_parse_end_listern(); #if (BY_TF_DEBUG) printf("by_tf_listern timeout\r\n"); @@ -126,7 +127,7 @@ void by_tiny_frame_parse_run(void) // 接收成功后停止监听 by_tiny_frame_parse_end_listern(); // 解析成功回调 - parse_success_handle(); + parse_done_handle(0); #if (BY_TF_DEBUG) printf("frame parsed!\r\n"); #endif @@ -160,9 +161,9 @@ uint8_t by_tiny_frame_parse_crc(by_tf_parse_frame_t *frame_s) return 1; } -void by_tiny_frame_parse_handle_register(by_tf_parse_success_handle_func func) +void by_tiny_frame_parse_handle_register(by_tf_parse_done_handle_func func) { - parse_success_handle = func; + parse_done_handle = func; } void by_tiny_frame_parse_start_listern(void) diff --git a/app/tiny_frame/by_tiny_frame_parse.h b/app/tiny_frame/by_tiny_frame_parse.h index eeb41a0..2d7a7ac 100644 --- a/app/tiny_frame/by_tiny_frame_parse.h +++ b/app/tiny_frame/by_tiny_frame_parse.h @@ -18,13 +18,13 @@ typedef struct by_tf_parse_frame_t { uint32_t data; } by_tf_parse_frame_t; -typedef void (*by_tf_parse_success_handle_func)(void); +typedef void (*by_tf_parse_done_handle_func)(uint8_t); extern void by_tiny_frame_parse_init(void); extern void by_tiny_frame_parse_uart_handle(uint8_t buff); extern void by_tiny_frame_parse_run(void); extern uint8_t by_tiny_frame_parse_crc(by_tf_parse_frame_t *frame_s); -extern void by_tiny_frame_parse_handle_register(by_tf_parse_success_handle_func func); +extern void by_tiny_frame_parse_handle_register(by_tf_parse_done_handle_func func); extern void by_tiny_frame_parse_start_listern(void); extern void by_tiny_frame_parse_end_listern(void); From 1c5c78976fcad094bd51bc9cd945e36e0270fa33 Mon Sep 17 00:00:00 2001 From: bmy <2583236812@qq.com> Date: Fri, 23 Feb 2024 21:13:31 +0800 Subject: [PATCH 10/19] =?UTF-8?q?feat:=20=E4=B8=BA=E9=80=9A=E4=BF=A1?= =?UTF-8?q?=E5=B8=A7=E8=A7=A3=E6=9E=90=E5=AE=8C=E6=88=90=E5=9B=9E=E8=B0=83?= =?UTF-8?q?=E5=87=BD=E6=95=B0=E6=B7=BB=E5=8A=A0=E5=B8=A7=E4=BF=A1=E6=81=AF?= =?UTF-8?q?=E5=85=A5=E5=8F=82(=E4=BB=A5=E4=BE=BF=E5=91=BD=E4=BB=A4?= =?UTF-8?q?=E5=87=BD=E6=95=B0=E6=A0=A1=E9=AA=8C=E6=88=90=E5=8A=9F=E4=B8=8E?= =?UTF-8?q?=E5=90=A6)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- app/main.c | 4 +++- app/tiny_frame/by_tiny_frame_parse.c | 25 ++++++++++++++++++++----- app/tiny_frame/by_tiny_frame_parse.h | 2 +- app/tiny_frame/by_tiny_frame_write.h | 10 ++++++++++ 4 files changed, 34 insertions(+), 7 deletions(-) diff --git a/app/main.c b/app/main.c index 028d67c..93718f8 100644 --- a/app/main.c +++ b/app/main.c @@ -35,8 +35,10 @@ #include "by_tiny_frame_pack.h" /** 测试完成后移除 **/ -void test(uint8_t status) +void test(by_tf_parse_frame_t frame_s, uint8_t status) { + printf("parse done\r\n"); + printf("--cmd: %0.2X\n--reg_addr: %0.4X\n--data: %0.8X\r\n", frame_s.cmd, frame_s.reg_addr, frame_s.data); if (status) { printf("noooooooo!\r\n"); } else { diff --git a/app/tiny_frame/by_tiny_frame_parse.c b/app/tiny_frame/by_tiny_frame_parse.c index 0432c14..bc0ce92 100644 --- a/app/tiny_frame/by_tiny_frame_parse.c +++ b/app/tiny_frame/by_tiny_frame_parse.c @@ -6,6 +6,7 @@ lwrb_t lwrb_struct; uint8_t buffer_rb[BY_TF_PARSE_BUFFER_SIZE]; uint8_t buffer_out; +uint8_t listern_slave_id; uint8_t listern_flag; uint16_t listern_timeout; uint16_t listern_timevia; @@ -95,6 +96,10 @@ void by_tiny_frame_parse_timer_handle(void) #endif } +/** + * @brief + * + */ void by_tiny_frame_parse_run(void) { @@ -104,7 +109,7 @@ void by_tiny_frame_parse_run(void) } else { if (listern_timeout <= listern_timevia) { // 接收超时,停止监听 - parse_done_handle(1); + parse_done_handle(frame_now, 1); by_tiny_frame_parse_end_listern(); #if (BY_TF_DEBUG) printf("by_tf_listern timeout\r\n"); @@ -119,15 +124,20 @@ void by_tiny_frame_parse_run(void) break; } - // TODO 目前接收校验错误也会等待直至超时 - // TODO 待结合 read&wirte 部分修改监听的从机地址 - if (!by_tiny_frame_parse_listening(&frame_now, 0x0D, buffer_out)) { +// TODO 目前接收校验错误也会等待直至超时 +// TODO 待结合 read&wirte 部分修改监听的从机地址 +#if defined(BY_TF_DEVICE_SLAVE) + if (!by_tiny_frame_parse_listening(&frame_now, BY_TF_DEVICE_SLAVE_ADDRESS, buffer_out)) +#else + if (!by_tiny_frame_parse_listening(&frame_now, listern_slave_id, buffer_out)) +#endif + { if (!by_tiny_frame_parse_crc(&frame_now)) { // 接收成功后停止监听 by_tiny_frame_parse_end_listern(); // 解析成功回调 - parse_done_handle(0); + parse_done_handle(frame_now, 0); #if (BY_TF_DEBUG) printf("frame parsed!\r\n"); #endif @@ -158,11 +168,16 @@ uint8_t by_tiny_frame_parse_crc(by_tf_parse_frame_t *frame_s) return 0; } + // 校验错误则直接结束监听 + by_tiny_frame_parse_end_listern(); + parse_done_handle(frame_now, 1); + return 1; } void by_tiny_frame_parse_handle_register(by_tf_parse_done_handle_func func) { + // FIXME 未校验是否传入非空值,另外假设未执行注册,也会产生非法访问 parse_done_handle = func; } diff --git a/app/tiny_frame/by_tiny_frame_parse.h b/app/tiny_frame/by_tiny_frame_parse.h index 2d7a7ac..800d80c 100644 --- a/app/tiny_frame/by_tiny_frame_parse.h +++ b/app/tiny_frame/by_tiny_frame_parse.h @@ -18,7 +18,7 @@ typedef struct by_tf_parse_frame_t { uint32_t data; } by_tf_parse_frame_t; -typedef void (*by_tf_parse_done_handle_func)(uint8_t); +typedef void (*by_tf_parse_done_handle_func)(by_tf_parse_frame_t, uint8_t); extern void by_tiny_frame_parse_init(void); extern void by_tiny_frame_parse_uart_handle(uint8_t buff); diff --git a/app/tiny_frame/by_tiny_frame_write.h b/app/tiny_frame/by_tiny_frame_write.h index 20093c5..5a84cae 100644 --- a/app/tiny_frame/by_tiny_frame_write.h +++ b/app/tiny_frame/by_tiny_frame_write.h @@ -1,6 +1,16 @@ #ifndef _BY_TINY_FRAME_WRITE_H__ #define _BY_TINY_FRAME_WRITE_H__ +#include "by_tiny_frame_config.h" +#include "by_tiny_frame_parse.h" +#include "by_tiny_frame_pack.h" + #define BY_TINY_FRAME_WRITE_CMD_CODE (0x06) +#if defined(BY_TF_DEVICE_MASTER) +extern void by_tiny_frame_write(uint8_t slave_id, uint16_t reg_addr, uint32_t data); +#elif + +#endif + #endif From 3a4c25dc4d49f5f1771308e46c32903640dac73e Mon Sep 17 00:00:00 2001 From: bmy <2583236812@qq.com> Date: Fri, 23 Feb 2024 21:25:55 +0800 Subject: [PATCH 11/19] =?UTF-8?q?refact:=20=E5=B0=86=E8=AF=BB=E5=86=99?= =?UTF-8?q?=E7=9A=84=E5=BA=94=E7=94=A8=E5=B1=82=E6=8E=A5=E5=8F=A3=E6=A0=B9?= =?UTF-8?q?=E6=8D=AE=E4=B8=BB=E4=BB=8E=E5=88=86=E5=BC=80?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ...tiny_frame_read.c => by_tiny_frame_master_read.c} | 0 app/tiny_frame/by_tiny_frame_master_read.h | 11 +++++++++++ ...ny_frame_write.c => by_tiny_frame_master_write.c} | 0 ...ny_frame_write.h => by_tiny_frame_master_write.h} | 12 +++++++----- app/tiny_frame/by_tiny_frame_read.h | 6 ------ app/tiny_frame/by_tiny_frame_slave_read_write.c | 2 ++ app/tiny_frame/by_tiny_frame_slave_read_write.h | 12 ++++++++++++ 7 files changed, 32 insertions(+), 11 deletions(-) rename app/tiny_frame/{by_tiny_frame_read.c => by_tiny_frame_master_read.c} (100%) create mode 100644 app/tiny_frame/by_tiny_frame_master_read.h rename app/tiny_frame/{by_tiny_frame_write.c => by_tiny_frame_master_write.c} (100%) rename app/tiny_frame/{by_tiny_frame_write.h => by_tiny_frame_master_write.h} (77%) delete mode 100644 app/tiny_frame/by_tiny_frame_read.h create mode 100644 app/tiny_frame/by_tiny_frame_slave_read_write.c create mode 100644 app/tiny_frame/by_tiny_frame_slave_read_write.h diff --git a/app/tiny_frame/by_tiny_frame_read.c b/app/tiny_frame/by_tiny_frame_master_read.c similarity index 100% rename from app/tiny_frame/by_tiny_frame_read.c rename to app/tiny_frame/by_tiny_frame_master_read.c diff --git a/app/tiny_frame/by_tiny_frame_master_read.h b/app/tiny_frame/by_tiny_frame_master_read.h new file mode 100644 index 0000000..b0453bc --- /dev/null +++ b/app/tiny_frame/by_tiny_frame_master_read.h @@ -0,0 +1,11 @@ +#ifndef _BY_TINY_FRAME_MASTER_READ_H__ +#define _BY_TINY_FRAME_MASTER_READ_H__ + +#include "by_tiny_frame_config.h" + +#if defined(BY_TF_DEVICE_MASTER) + +#define BY_TINY_FRAME_WRITE_CMD_CODE (0x03) + +#endif +#endif diff --git a/app/tiny_frame/by_tiny_frame_write.c b/app/tiny_frame/by_tiny_frame_master_write.c similarity index 100% rename from app/tiny_frame/by_tiny_frame_write.c rename to app/tiny_frame/by_tiny_frame_master_write.c diff --git a/app/tiny_frame/by_tiny_frame_write.h b/app/tiny_frame/by_tiny_frame_master_write.h similarity index 77% rename from app/tiny_frame/by_tiny_frame_write.h rename to app/tiny_frame/by_tiny_frame_master_write.h index 5a84cae..fd1499a 100644 --- a/app/tiny_frame/by_tiny_frame_write.h +++ b/app/tiny_frame/by_tiny_frame_master_write.h @@ -1,16 +1,18 @@ -#ifndef _BY_TINY_FRAME_WRITE_H__ -#define _BY_TINY_FRAME_WRITE_H__ +#ifndef _BY_TINY_FRAME_MASTER_WRITE_H__ +#define _BY_TINY_FRAME_MASTER_WRITE_H__ #include "by_tiny_frame_config.h" + +#if defined(BY_TF_DEVICE_MASTER) + #include "by_tiny_frame_parse.h" #include "by_tiny_frame_pack.h" #define BY_TINY_FRAME_WRITE_CMD_CODE (0x06) -#if defined(BY_TF_DEVICE_MASTER) + extern void by_tiny_frame_write(uint8_t slave_id, uint16_t reg_addr, uint32_t data); -#elif + #endif - #endif diff --git a/app/tiny_frame/by_tiny_frame_read.h b/app/tiny_frame/by_tiny_frame_read.h deleted file mode 100644 index ca4081f..0000000 --- a/app/tiny_frame/by_tiny_frame_read.h +++ /dev/null @@ -1,6 +0,0 @@ -#ifndef _BY_TINY_FRAME_READ_H__ -#define _BY_TINY_FRAME_READ_H__ - -#define BY_TINY_FRAME_WRITE_CMD_CODE (0x03) - -#endif diff --git a/app/tiny_frame/by_tiny_frame_slave_read_write.c b/app/tiny_frame/by_tiny_frame_slave_read_write.c new file mode 100644 index 0000000..f906eb5 --- /dev/null +++ b/app/tiny_frame/by_tiny_frame_slave_read_write.c @@ -0,0 +1,2 @@ +#include "by_tiny_frame_slave_read_write.h" + diff --git a/app/tiny_frame/by_tiny_frame_slave_read_write.h b/app/tiny_frame/by_tiny_frame_slave_read_write.h new file mode 100644 index 0000000..35f790e --- /dev/null +++ b/app/tiny_frame/by_tiny_frame_slave_read_write.h @@ -0,0 +1,12 @@ +#ifndef _BY_TINY_FRAME_SLAVE_READ_WRITE_H__ +#define _BY_TINY_FRAME_SLAVE_READ_WRITE_H__ + +#include "by_tiny_frame_config.h" + +#if defined(BY_TF_DEVICE_SLAVE) + +#define BY_TINY_FRAME_WRITE_CMD_CODE (0x03) +#define BY_TINY_FRAME_WRITE_CMD_CODE (0x06) + +#endif +#endif From 399ebeea1a3c67658c514dc5cf5163553113855a Mon Sep 17 00:00:00 2001 From: bmy <2583236812@qq.com> Date: Fri, 23 Feb 2024 22:25:47 +0800 Subject: [PATCH 12/19] =?UTF-8?q?feat:=20=E5=AE=8C=E6=88=90=E9=80=9A?= =?UTF-8?q?=E4=BF=A1=E5=B8=A7=E4=BB=8E=E6=9C=BA=E5=BA=94=E7=94=A8=E5=B1=82?= =?UTF-8?q?=E6=A8=A1=E6=9D=BF?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- app/main.c | 4 +- app/tiny_frame/by_tiny_frame.c | 24 ++++++++++- app/tiny_frame/by_tiny_frame.h | 1 + app/tiny_frame/by_tiny_frame_config.h | 2 +- app/tiny_frame/by_tiny_frame_master_read.c | 5 +++ app/tiny_frame/by_tiny_frame_master_read.h | 4 +- app/tiny_frame/by_tiny_frame_master_write.c | 5 ++- app/tiny_frame/by_tiny_frame_master_write.h | 3 +- .../by_tiny_frame_slave_read_write.c | 42 +++++++++++++++++++ .../by_tiny_frame_slave_read_write.h | 7 +++- 10 files changed, 87 insertions(+), 10 deletions(-) diff --git a/app/main.c b/app/main.c index 93718f8..b1a9fb4 100644 --- a/app/main.c +++ b/app/main.c @@ -71,7 +71,7 @@ int main(void) printf("start running\r\n"); /** 测试完成后移除 **/ - by_tiny_frame_parse_handle_register(test); + // by_tiny_frame_parse_handle_register(test); by_tiny_frame_parse_start_listern(); by_tf_pack_frame_t frame_now; @@ -87,7 +87,7 @@ int main(void) by_buzzer_run(); /** 测试完成后移除 **/ - by_tiny_frame_parse_run(); + by_tiny_frame_run(); // by_tiny_frame_pack_send(&frame_now); system_delay_ms(10); by_tiny_frame_parse_timer_handle(); diff --git a/app/tiny_frame/by_tiny_frame.c b/app/tiny_frame/by_tiny_frame.c index f59e6c1..86acd75 100644 --- a/app/tiny_frame/by_tiny_frame.c +++ b/app/tiny_frame/by_tiny_frame.c @@ -3,15 +3,35 @@ #include #include -#include "by_tiny_frame_parse.h" #include "crc16.h" #include "zf_common_headfile.h" +#include "by_tiny_frame_config.h" +#include "by_tiny_frame_parse.h" +#include "by_tiny_frame_master_read.h" +#include "by_tiny_frame_master_write.h" +#include "by_tiny_frame_slave_read_write.h" void by_tiny_frame_init(void) { /*** 初始化相关外设 ***/ uart_init(BY_TF_UART_INDEX, BY_TF_UART_BAUDRATE, BY_TF_UART_TX_PIN, BY_TF_UART_RX_PIN); uart_rx_interrupt(BY_TF_UART_INDEX, ENABLE); - + by_tiny_frame_parse_init(); + +#if defined(BY_TF_DEVICE_SLAVE) + by_tiny_frame_parse_handle_register(by_tiny_frame_read_write_handle); +#endif } + +void by_tiny_frame_run(void) +{ + by_tiny_frame_parse_run(); + +#if defined(BY_TF_DEVICE_MASTER) + by_tiny_frame_read_run(); + by_tiny_frame_write_run(); +#elif defined(BY_TF_DEVICE_SLAVE) + by_tiny_frame_read_write_run(); +#endif +} \ No newline at end of file diff --git a/app/tiny_frame/by_tiny_frame.h b/app/tiny_frame/by_tiny_frame.h index 630f0cf..2bd0e82 100644 --- a/app/tiny_frame/by_tiny_frame.h +++ b/app/tiny_frame/by_tiny_frame.h @@ -4,5 +4,6 @@ #include "by_tiny_frame_config.h" extern void by_tiny_frame_init(void); +void by_tiny_frame_run(void); #endif diff --git a/app/tiny_frame/by_tiny_frame_config.h b/app/tiny_frame/by_tiny_frame_config.h index a302e29..ebc3549 100644 --- a/app/tiny_frame/by_tiny_frame_config.h +++ b/app/tiny_frame/by_tiny_frame_config.h @@ -11,7 +11,7 @@ #define BY_TF_PARSE_BUFFER_SIZE (50) // 注释此项则为主机,否则为从机 -// #define BY_TF_DEVICE_SLAVE +#define BY_TF_DEVICE_SLAVE /********** 从机模式配置选项 **********/ #if defined(BY_TF_DEVICE_SLAVE) diff --git a/app/tiny_frame/by_tiny_frame_master_read.c b/app/tiny_frame/by_tiny_frame_master_read.c index e69de29..443a8c2 100644 --- a/app/tiny_frame/by_tiny_frame_master_read.c +++ b/app/tiny_frame/by_tiny_frame_master_read.c @@ -0,0 +1,5 @@ +#include "by_tiny_frame_master_read.h" + +void by_tiny_frame_read_run(void) +{ +} \ No newline at end of file diff --git a/app/tiny_frame/by_tiny_frame_master_read.h b/app/tiny_frame/by_tiny_frame_master_read.h index b0453bc..d1b2d71 100644 --- a/app/tiny_frame/by_tiny_frame_master_read.h +++ b/app/tiny_frame/by_tiny_frame_master_read.h @@ -5,7 +5,9 @@ #if defined(BY_TF_DEVICE_MASTER) -#define BY_TINY_FRAME_WRITE_CMD_CODE (0x03) +#define BY_TINY_FRAME_READ_CMD_CODE (0x03) + +extern void by_tiny_frame_read_run(void); #endif #endif diff --git a/app/tiny_frame/by_tiny_frame_master_write.c b/app/tiny_frame/by_tiny_frame_master_write.c index acca88c..9fc7047 100644 --- a/app/tiny_frame/by_tiny_frame_master_write.c +++ b/app/tiny_frame/by_tiny_frame_master_write.c @@ -1,2 +1,5 @@ -#include "by_tiny_frame_write.h" +#include "by_tiny_frame_master_write.h" +void by_tiny_frame_write_run(void) +{ +} \ No newline at end of file diff --git a/app/tiny_frame/by_tiny_frame_master_write.h b/app/tiny_frame/by_tiny_frame_master_write.h index fd1499a..9e4a237 100644 --- a/app/tiny_frame/by_tiny_frame_master_write.h +++ b/app/tiny_frame/by_tiny_frame_master_write.h @@ -10,9 +10,8 @@ #define BY_TINY_FRAME_WRITE_CMD_CODE (0x06) - extern void by_tiny_frame_write(uint8_t slave_id, uint16_t reg_addr, uint32_t data); - +extern void by_tiny_frame_write_run(void); #endif #endif diff --git a/app/tiny_frame/by_tiny_frame_slave_read_write.c b/app/tiny_frame/by_tiny_frame_slave_read_write.c index f906eb5..9883ce6 100644 --- a/app/tiny_frame/by_tiny_frame_slave_read_write.c +++ b/app/tiny_frame/by_tiny_frame_slave_read_write.c @@ -1,2 +1,44 @@ #include "by_tiny_frame_slave_read_write.h" +#include "by_tiny_frame_parse.h" +#include "by_tiny_frame_pack.h" + +void by_tiny_frame_read_write_run(void) +{ + // empty +} + +void by_tiny_frame_read_write_handle(by_tf_parse_frame_t frame_s, uint8_t status) +{ + by_tf_pack_frame_t frame_pack_s; + + frame_pack_s.slave_id = BY_TF_DEVICE_SLAVE_ADDRESS; + frame_pack_s.cmd = frame_s.cmd; + frame_pack_s.reg_addr = frame_s.reg_addr; + + if (status) { + // 接收出错,一般为 CRC 校验错误 + return; + } + + switch (frame_s.cmd) { + case 0x03: + // 添加查询接口,操作完成后应答 + frame_pack_s.data = 0XFFFFFFFF; // 示例 + by_tiny_frame_pack_send(&frame_pack_s); + break; + case 0x06: + // 添加写入接口,操作完成后应答 + frame_pack_s.data = frame_s.data; + by_tiny_frame_pack_send(&frame_pack_s); + break; + default: + break; + } + +#if (BY_TF_DEBUG) + printf("****** EXECUTE CMD SUCCESSFUL ******\r\n"); + printf("Device ID: 0x%0.2X\r\n", BY_TF_DEVICE_SLAVE_ADDRESS); + printf("--cmd: %0.2X\n--reg_addr: %0.4X\n--data: %0.8X\r\n", frame_s.cmd, frame_s.reg_addr, frame_s.data); +#endif +} diff --git a/app/tiny_frame/by_tiny_frame_slave_read_write.h b/app/tiny_frame/by_tiny_frame_slave_read_write.h index 35f790e..b71901c 100644 --- a/app/tiny_frame/by_tiny_frame_slave_read_write.h +++ b/app/tiny_frame/by_tiny_frame_slave_read_write.h @@ -5,8 +5,13 @@ #if defined(BY_TF_DEVICE_SLAVE) -#define BY_TINY_FRAME_WRITE_CMD_CODE (0x03) +#include "by_tiny_frame_parse.h" + +#define BY_TINY_FRAME_READ_CMD_CODE (0x03) #define BY_TINY_FRAME_WRITE_CMD_CODE (0x06) +extern void by_tiny_frame_read_write_run(void); +extern void by_tiny_frame_read_write_handle(by_tf_parse_frame_t frame_s, uint8_t status); + #endif #endif From bdd69e2e5968670a73ea2c8e83672e923f690b02 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?=E4=BA=95=E6=98=8E=E6=B1=9F?= <246462502@qq.com> Date: Sat, 24 Feb 2024 15:06:30 +0800 Subject: [PATCH 13/19] =?UTF-8?q?feat:=E5=AE=8C=E6=88=90ui=E8=AE=BE?= =?UTF-8?q?=E8=AE=A1?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .vscode/tasks.json | 28 +++++++ app/jj_param.c | 88 +++++++++++++--------- app/jj_param.h | 40 ++++++---- app/main.c | 3 +- app/page/page.c | 14 ++-- app/page/page.h | 20 +++-- app/page/page_dparam.c | 71 ++++++++++++++++++ app/page/page_menu.c | 6 +- app/page/page_param.c | 133 --------------------------------- app/page/page_rtcam.c | 4 +- app/page/page_sparam.c | 163 +++++++++++++++++++++++++++++++++++++++++ 11 files changed, 364 insertions(+), 206 deletions(-) create mode 100644 .vscode/tasks.json create mode 100644 app/page/page_dparam.c delete mode 100644 app/page/page_param.c create mode 100644 app/page/page_sparam.c diff --git a/.vscode/tasks.json b/.vscode/tasks.json new file mode 100644 index 0000000..ddfadc2 --- /dev/null +++ b/.vscode/tasks.json @@ -0,0 +1,28 @@ +{ + "tasks": [ + { + "type": "cppbuild", + "label": "C/C++: gcc.exe 生成活动文件", + "command": "D:\\MinGW\\bin\\gcc.exe", + "args": [ + "-fdiagnostics-color=always", + "-g", + "${file}", + "-o", + "${fileDirname}\\${fileBasenameNoExtension}.exe" + ], + "options": { + "cwd": "${fileDirname}" + }, + "problemMatcher": [ + "$gcc" + ], + "group": { + "kind": "build", + "isDefault": true + }, + "detail": "调试器生成的任务。" + } + ], + "version": "2.0.0" +} \ No newline at end of file diff --git a/app/jj_param.c b/app/jj_param.c index ced4ada..1142af9 100644 --- a/app/jj_param.c +++ b/app/jj_param.c @@ -5,44 +5,34 @@ PARAM_INFO Param_Data[DATA_NUM]; soft_iic_info_struct eeprom_param; TYPE_UNION iic_buffer[DATA_IN_FLASH_NUM]; - -void jj_param_eeprom_init() -{ - soft_iic_init(&eeprom_param, K24C02_DEV_ADDR, K24C02_SOFT_IIC_DELAY, K24C02_SCL_PIN, K24C02_SDA_PIN); // eeprom 初始化 - // PARAM_REG(angle_Kp, &an_Kp, EFLOAT, 1, "an_P"); // 注冊 - // PARAM_REG(angle_Ki, &an_Ki, EFLOAT, 1, "an_I"); // 注冊 - // PARAM_REG(angle_Kd, &an_Kd, EFLOAT, 1, "an_D"); // 注冊 - // PARAM_REG(imgax_Kp, &im_Kp, EFLOAT, 1, "im_P"); // 注冊 - // PARAM_REG(imgax_Ki, &im_Ki, EFLOAT, 1, "im_I"); // 注冊 - // PARAM_REG(imgax_Kd, &im_Kd, EFLOAT, 1, "im_D"); // 注冊 - - for (uint8 i = 0; i < DATA_IN_FLASH_NUM; i++) { - - soft_iic_read_8bit_registers(&eeprom_param, 4 * i, (uint8 *)&iic_buffer[i], 4); - switch (Param_Data[i].type) { - case EFLOAT: - *((float *)(Param_Data[i].p_data)) = - iic_buffer[i].f32; - break; - case EUINT32: - *((uint32 *)(Param_Data[i].p_data)) = - iic_buffer[i].u32; - break; - case EINT32: - *((int32 *)(Param_Data[i].p_data)) = - iic_buffer[i].s32; - break; - default: - break; - } - system_delay_ms(10); - } -} +float data0 = 1.0f; +float data1 = 1.05f; +float data2 = 10.0f; +float data3 = 100.0f; +float data4 = 4.0f; +float data5 = 66.0f; +float data6 = 13.130f; /** - * @brief 参数更新 + * @brief 参数初始化注册 * */ -void jj_param_update() +void jj_param_eeprom_init(void) +{ + soft_iic_init(&eeprom_param, K24C02_DEV_ADDR, K24C02_SOFT_IIC_DELAY, K24C02_SCL_PIN, K24C02_SDA_PIN); // eeprom初始化 + PARAM_REG(angle_Kp, &data0, EFLOAT, 1, "an_P:"); // 注冊 + PARAM_REG(angle_Ki, &data1, EFLOAT, 1, "an_I:"); // 注冊 + PARAM_REG(angle_Kd, &data2, EFLOAT, 1, "an_D:"); // 注冊 + PARAM_REG(imgax_Kp, &data3, EFLOAT, 1, "im_P:"); // 注冊 + PARAM_REG(imgax_Ki, &data4, EFLOAT, 1, "im_I:"); // 注冊 + PARAM_REG(imgax_Kd, &data5, EFLOAT, 1, "im_D:"); + PARAM_REG(other, &data6, EFLOAT, 1, "add:"); + jj_param_read(); // 注冊 +} +/** + * @brief 参数写入 + * + */ +void jj_param_write(void) { for (uint8 i = 0; i < DATA_IN_FLASH_NUM; i++) { switch (Param_Data[i].type) { @@ -62,3 +52,31 @@ void jj_param_update() system_delay_ms(10); } } +/** + * @brief 参数读出 + * + */ +void jj_param_read(void) +{ + for (uint8 i = 0; i < DATA_IN_FLASH_NUM; i++) { + + soft_iic_read_8bit_registers(&eeprom_param, 4 * i, (uint8 *)&iic_buffer[i], 4); + switch (Param_Data[i].type) { + case EFLOAT: + *((float *)(Param_Data[i].p_data)) = + iic_buffer[i].f32; + break; + case EUINT32: + *((uint32 *)(Param_Data[i].p_data)) = + iic_buffer[i].u32; + break; + case EINT32: + *((int32 *)(Param_Data[i].p_data)) = + iic_buffer[i].s32; + break; + default: + break; + } + system_delay_ms(10); + } +} diff --git a/app/jj_param.h b/app/jj_param.h index 3fbe8bb..6faea53 100644 --- a/app/jj_param.h +++ b/app/jj_param.h @@ -6,22 +6,30 @@ #include "zf_driver_soft_iic.h" /** * @brief 注册需调参数 - * + * */ -#define PARAM_REG(_data_tag_, _p_data_, _type_, _cmd_,_text_) \ - Param_Data[_data_tag_].p_data = (void *)_p_data_; \ - Param_Data[_data_tag_].type = _type_; \ - Param_Data[_data_tag_].cmd = _cmd_; \ +#define PARAM_REG(_data_tag_, _p_data_, _type_, _cmd_, _text_) \ + Param_Data[_data_tag_].p_data = (void *)_p_data_; \ + Param_Data[_data_tag_].type = _type_; \ + Param_Data[_data_tag_].cmd = _cmd_; \ Param_Data[_data_tag_].text = _text_; - + typedef enum { - DATA_HEAD = -1, - angle_Kp, + + Page1_head=0, + + angle_Kp=Page1_head, angle_Ki, angle_Kd, - imgax_Kp, + other, + + Page2_head, + // 第二页参数 + imgax_Kp=Page2_head, imgax_Ki, imgax_Kd, + + Page3_head, DATA_IN_FLASH_NUM, DATA_NUM, } data_tag_t; @@ -30,26 +38,26 @@ typedef enum { EUINT32, EINT32, EFLOAT, -}ENUM_TYPE; +} ENUM_TYPE; -typedef union{ +typedef union { uint32_t u32; int32_t s32; float f32; uint8_t u8; -}TYPE_UNION; +} TYPE_UNION; typedef struct { void *p_data; ENUM_TYPE type; uint8_t cmd; char *text; -}PARAM_INFO; +} PARAM_INFO; extern soft_iic_info_struct eeprom_param; extern PARAM_INFO Param_Data[DATA_NUM]; extern TYPE_UNION iic_buffer[DATA_IN_FLASH_NUM]; -void jj_param_eeprom_init(); -void jj_param_update(); -void jj_param_show(); +void jj_param_eeprom_init(void); +void jj_param_write(void); +void jj_param_read(void); #endif \ No newline at end of file diff --git a/app/main.c b/app/main.c index 8e69e41..9421a54 100644 --- a/app/main.c +++ b/app/main.c @@ -43,8 +43,7 @@ int main(void) by_button_init(); jj_bt_init(); - // jj_param_eeprom_init(); - + jj_param_eeprom_init(); Page_Init(); pit_ms_init(TIM6_PIT, 2); diff --git a/app/page/page.c b/app/page/page.c index 942940c..01ef310 100644 --- a/app/page/page.c +++ b/app/page/page.c @@ -4,8 +4,8 @@ PAGE_LIST pagelist[page_max]; static uint8_t page_busy = 0; +int8_t new_page = page_menu; static int8_t now_page = page_menu; -static int8_t new_page = page_menu; /** * @brief 注册一个基本页面,包含一个初始化函数,循环函数,退出函数,事件函数 @@ -17,11 +17,11 @@ static int8_t new_page = page_menu; * @param eventCallback: 事件函数回调 * @retval 无 */ -void Page_Register(uint8_t pageID, char *pageText, +void Page_Register(uint8_t pageID, CallbackFunction_t setupCallback, CallbackFunction_t loopCallback, CallbackFunction_t exitCallback, EventFunction_t eventCallback) { - pagelist[pageID].Text = pageText; + pagelist[pageID].SetupCallback = setupCallback; pagelist[pageID].LoopCallback = loopCallback; pagelist[pageID].ExitCallback = exitCallback; @@ -123,9 +123,11 @@ void Page_Run(void) */ void Page_Init(void) { - PAGE_REG(page_menu); - PAGE_REG(page_rtcam); - PAGE_REG(page_param); + PAGE_REG(page_menu, "main"); + PAGE_REG(page_rtcam, "rtcam"); + PAGE_REG(page_param1, "Param1"); + PAGE_REG(page_param2, "param2"); + PAGE_REG(page_dparam, "dparam"); // PAGE_REG(page_argv); // PAGE_REG(page_sys); // PAGE_REG(page_run); diff --git a/app/page/page.h b/app/page/page.h index 3d51e41..39ef9eb 100644 --- a/app/page/page.h +++ b/app/page/page.h @@ -20,7 +20,9 @@ enum PageID { //...... page_menu, page_rtcam, - page_param, + page_param1, + page_param2, + page_dparam, // page_argv, // page_sys, // page_run, @@ -46,13 +48,15 @@ typedef struct { } PAGE_LIST; // 页面注册函数 -#define PAGE_REG(name) \ - do { \ - extern void PageRegister_##name(unsigned char pageID); \ - PageRegister_##name(name); \ - } while (0) +#define PAGE_REG(_name_, _text_) \ + do { \ + extern void PageRegister_##_name_(unsigned char pageID); \ + PageRegister_##_name_(_name_); \ + } while (0); \ + pagelist[_name_].Text = _text_ ; -void Page_Register(uint8_t pageID, char *pageText, + +void Page_Register(uint8_t pageID, CallbackFunction_t setupCallback, CallbackFunction_t loopCallback, CallbackFunction_t exitCallback, EventFunction_t eventCallback); @@ -65,5 +69,5 @@ void Page_Run(void); void Page_Init(void); extern PAGE_LIST pagelist[page_max]; - +extern int8_t new_page ; #endif diff --git a/app/page/page_dparam.c b/app/page/page_dparam.c new file mode 100644 index 0000000..ebcb4be --- /dev/null +++ b/app/page/page_dparam.c @@ -0,0 +1,71 @@ +#include "zf_common_headfile.h" +#include "page_ui_widget.h" +#include "page.h" +float ddata0=0.0f; +// #define LINE_HEAD 1 +// #define LINE_END 7 +// static int8_t Curser = LINE_HEAD; // 定义光标位置 +// static int8_t Curser_Last = LINE_HEAD; // 定义光标位置 +/*************************************************************************************** + * + * 以下为页面模板函数 + * + ***************************************************************************************/ + +/** + * @brief 页面初始化事件 + * @param 无 + * @retval 无 + */ +static void Setup() +{ + ips200_clear(); + // 显示参数名称 + ips200_show_string(0, 0, "Dparam"); + ips200_show_string(20, 18 + 2, "ddata0:"); +} + +/** + * @brief 页面退出事件 + * @param 无 + * @retval 无 + */ +static void Exit() +{ + +} + +/** + * @brief 页面循环执行的内容 + * @param 无 + * @retval 无 + */ +static void Loop() +{ + // 刷新参数数值 + ips200_show_float(80, 18 + 2, ddata0, 4, 5); + ddata0+=0.01f; +} + +/** + * @brief 页面事件 + * @param btn:发出事件的按键 + * @param event:事件编号 + * @retval 无 + */ +static void Event(page_event event) +{ + if (page_event_press_long == event) { + Page_Shift(page_menu); + } +} + +/** + * @brief 页面注册函数 + * + * @param pageID + */ +void PageRegister_page_dparam(unsigned char pageID) +{ + Page_Register(pageID, Setup, Loop, Exit, Event); +} diff --git a/app/page/page_menu.c b/app/page/page_menu.c index 8605e47..be60e04 100644 --- a/app/page/page_menu.c +++ b/app/page/page_menu.c @@ -57,9 +57,9 @@ static void Event(page_event event) Curser_Last = Curser; if (page_event_forward == event) { - Curser--; // 光标上移 + Curser++; // 光标上移 } else if (page_event_backward == event) { - Curser++; // 光标下移 + Curser--; // 光标下移 } else if (page_event_press_short == event) { if (page_max > Curser && page_menu < Curser) { Page_Shift(Curser); // 切换到光标选中的页面 @@ -82,7 +82,7 @@ static void Event(page_event event) */ void PageRegister_page_menu(unsigned char pageID) { - Page_Register(pageID, Text, Setup, Loop, Exit, Event); + Page_Register(pageID, Setup, Loop, Exit, Event); } /*************************************************************************************** diff --git a/app/page/page_param.c b/app/page/page_param.c deleted file mode 100644 index ef57df5..0000000 --- a/app/page/page_param.c +++ /dev/null @@ -1,133 +0,0 @@ -#include "jj_param.h" -#include "page_ui_widget.h" -#include "page.h" - -#define LINE_HEAD 0 -#define LINE_END DATA_NUM - 2 -static char Text[] = "Param"; -int event_flag = 0; -int32_t index_power = 0; -static int8_t Curser = LINE_HEAD; // 定义光标位置 -static int8_t Curser_Last = LINE_HEAD; // 定义光标位置 -void jj_param_show(); -/*************************************************************************************** - * - * 以下为页面模板函数 - * - ***************************************************************************************/ -/** - * @brief 页面初始化事件 - * @param 无 - * @retval 无 - */ -static void Setup() -{ - ips200_clear(); - Print_Curser(Curser, Curser_Last, RGB565_PURPLE); - for (int16 i = 0; i < DATA_NUM - 1; i++) { - ips200_show_string(10, i * 18 + 2, Param_Data[i].text); - if (Param_Data[i].type == EINT32) - ips200_show_int(50, i * 18 + 2, *((int32 *)(Param_Data[i].p_data)), 5); - else if (Param_Data[i].type == EFLOAT) - ips200_show_float(50, i * 18 + 2, *((float *)(Param_Data[i].p_data)), 4, 5); - } - ips200_show_int(50, (DATA_NUM-1)* 18 + 2, index_power, 5); - -} - -/** - * @brief 页面退出事件 - * @param 无 - * @retval 无 - */ -static void Exit() -{ -} - -/** - * @brief 页面循环执行的内容 - * @param 无 - * @retval 无 - */ -static void Loop() -{ -} -/** - * @brief 页面事件 - * @param btn:发出事件的按键 - * @param event:事件编号 - * @retval 无 - */ -static void Event(page_event event) -{ - - if (0 == event_flag) { - - Curser_Last = Curser; - if (page_event_forward == event) { - Curser--; // 光标上移 - } else if (page_event_backward == event) { - Curser++; // 光标下移 - } else if (page_event_press_short == event) { - event_flag = 1; // 选中参数 - Print_Curser(Curser, Curser_Last, RGB565_RED); - return; - } else if (page_event_press_long == event) { - jj_param_update(); - Page_Shift(page_menu); - return; - } - if (Curser < LINE_HEAD) { - Curser = LINE_END; - } else if (Curser > LINE_END) { - Curser = LINE_HEAD; - } - Print_Curser(Curser, Curser_Last, RGB565_PURPLE); - } else if (1 == event_flag) { - if (page_event_forward == event) { - if (Param_Data[Curser].type == EFLOAT) { - *((float *)(Param_Data[Curser].p_data)) += powf(10.0f,(float)index_power); - } else if (Param_Data[Curser].type == EINT32) { - *((int32 *)(Param_Data[Curser].p_data)) += 1; - } else if (Param_Data[Curser].type == EUINT32) { - *((uint32 *)(Param_Data[Curser].p_data)) += 1; - } - } else if (page_event_backward == event) { - if (Param_Data[Curser].type == EFLOAT) { - *((float *)(Param_Data[Curser].p_data)) -=powf(10.0f,(float)index_power); - } else if (Param_Data[Curser].type == EINT32) { - *((int32 *)(Param_Data[Curser].p_data)) -= 1; - } else if (Param_Data[Curser].type == EUINT32) { - *((uint32 *)(Param_Data[Curser].p_data)) -= 1; - } - } else if (page_event_press_short == event) { - index_power++; - if (index_power > 2) { - index_power = -2; - } - ips200_show_int(50, (DATA_NUM-1)* 18 + 2, index_power, 5); - } else if (page_event_press_long == event) { - event_flag = 0; - Print_Curser(Curser, Curser_Last, RGB565_PURPLE); - } - jj_param_show(); - } -} -void jj_param_show() -{ - if (EINT32 == Param_Data[Curser].type) - ips200_show_int(50, Curser * 18 + 2, *((int32 *)(Param_Data[Curser].p_data)), 5); - else if (EUINT32 == Param_Data[Curser].type) - ips200_show_uint(50, Curser * 18 + 2, *((int32 *)(Param_Data[Curser].p_data)), 5); - else if (EFLOAT == Param_Data[Curser].type) - ips200_show_float(50, Curser * 18 + 2, *((float *)(Param_Data[Curser].p_data)), 4, 5); -} -/** - * @brief 页面注册函数 - * - * @param pageID - */ -void PageRegister_page_param(unsigned char pageID) -{ - Page_Register(pageID, Text, Setup, Loop, Exit, Event); -} diff --git a/app/page/page_rtcam.c b/app/page/page_rtcam.c index 7b479bd..9d520ee 100644 --- a/app/page/page_rtcam.c +++ b/app/page/page_rtcam.c @@ -5,8 +5,6 @@ #define LINE_HEAD 11 #define LINE_END 16 -static char Text[] = "RealTime Image"; - static int8_t Curser = LINE_HEAD; // 定义光标位置 static int8_t Curser_Last = LINE_HEAD; // 定义光标位置 /*************************************************************************************** @@ -81,7 +79,7 @@ static void Event(page_event event) */ void PageRegister_page_rtcam(unsigned char pageID) { - Page_Register(pageID, Text, Setup, Loop, Exit, Event); + Page_Register(pageID, Setup, Loop, Exit, Event); } /*************************************************************************************** diff --git a/app/page/page_sparam.c b/app/page/page_sparam.c new file mode 100644 index 0000000..a062093 --- /dev/null +++ b/app/page/page_sparam.c @@ -0,0 +1,163 @@ +#include "jj_param.h" +#include "page_ui_widget.h" +#include "page.h" + +#define LINE_HEAD 1 + +static int16 pafrist; +static int16 paend; +static int16 palong; +static int event_flag = 0; +static int32_t index_power = 0; +static int8_t Curser = LINE_HEAD; // 定义光标位置 +static int8_t Curser_Last = LINE_HEAD; // 定义光标位置 +/*************************************************************************************** + * + * 以下为页面模板函数 + * + ***************************************************************************************/ +/** + * @brief 页面初始化事件 + * @param 无 + * @retval 无 + */ +static void Setup() +{ + ips200_clear(); + + if (new_page == page_param1) { + pafrist = 0; + paend = Page2_head; + ips200_show_string(0, 0, "Param1"); + } else if (new_page == page_param2) { + pafrist = Page2_head; + paend = Page3_head; + ips200_show_string(0, 0, "Param2"); + } + + palong = paend - pafrist; + if (Curser < LINE_HEAD) { + Curser = palong; + } else if (Curser > palong) { + Curser = LINE_HEAD; + } + Print_Curser(Curser, Curser_Last, RGB565_PURPLE); + for (int16 i = 0; i < palong; i++) { + ips200_show_string(20, i * 18 + 20, Param_Data[i + pafrist].text); + if (Param_Data[i].type == EINT32) + ips200_show_int(60, i * 18 + 20, *((int32 *)(Param_Data[i + pafrist].p_data)), 5); + else if (Param_Data[i].type == EFLOAT) + ips200_show_float(60, i * 18 + 20, *((float *)(Param_Data[i + pafrist].p_data)), 4, 5); + } + ips200_show_int(50, palong * 18 + 20, index_power, 5); +} + +/** + * @brief 页面退出事件 + * @param 无 + * @retval 无 + */ +static void Exit() +{ +} + +/** + * @brief 页面循环执行的内容 + * @param 无 + * @retval 无 + */ +static void Loop() +{ +} +/** + * @brief 页面事件 + * @param btn:发出事件的按键 + * @param event:事件编号 + * @retval 无 + */ +static void Event(page_event event) +{ + + if (0 == event_flag) { + + Curser_Last = Curser; + if (page_event_forward == event) { + Curser++; // 光标上移 + } else if (page_event_backward == event) { + Curser--; // 光标下移 + } else if (page_event_press_short == event) { + event_flag = 1; // 选中参数 + Print_Curser(Curser, Curser_Last, RGB565_RED); + return; + } else if (page_event_press_long == event) { + jj_param_write(); + Page_Shift(page_menu); + return; + } + if (Curser < LINE_HEAD) { + Curser = palong; + } else if (Curser > palong) { + Curser = LINE_HEAD; + } + Print_Curser(Curser, Curser_Last, RGB565_PURPLE); + } else if (1 == event_flag) { + if (page_event_forward == event) { + switch (Param_Data[Curser + pafrist - 1].type) { + case EFLOAT: + *((float *)(Param_Data[Curser + pafrist - 1].p_data)) += powf(10.0f, (float)index_power); + break; + case EINT32: + *((int32 *)(Param_Data[Curser + pafrist - 1].p_data)) += 1; + break; + case EUINT32: + *((uint32 *)(Param_Data[Curser + pafrist - 1].p_data)) += 1; + break; + default: + break; + } + } else if (page_event_backward == event) { + switch (Param_Data[Curser + pafrist - 1].type) { + case EFLOAT: + *((float *)(Param_Data[Curser + pafrist - 1].p_data)) -= powf(10.0f, (float)index_power); + break; + case EINT32: + *((int32 *)(Param_Data[Curser + pafrist - 1].p_data)) -= 1; + break; + case EUINT32: + *((uint32 *)(Param_Data[Curser + pafrist - 1].p_data)) -= 1; + break; + default: + break; + } + } else if (page_event_press_short == event) { + index_power++; + if (index_power > 2) { + index_power = -2; + } + ips200_show_int(50, palong * 18 + 20, index_power, 5); + } else if (page_event_press_long == event) { + event_flag = 0; + Print_Curser(Curser, Curser_Last, RGB565_PURPLE); + } + if (EINT32 == Param_Data[Curser + pafrist - 1].type) + ips200_show_int(60, Curser * 18 + 2, *((int32 *)(Param_Data[Curser + pafrist - 1].p_data)), 5); + else if (EUINT32 == Param_Data[Curser + pafrist - 1].type) + ips200_show_uint(60, Curser * 18 + 2, *((int32 *)(Param_Data[Curser + pafrist - 1].p_data)), 5); + else if (EFLOAT == Param_Data[Curser + pafrist - 1].type) + ips200_show_float(60, Curser * 18 + 2, *((float *)(Param_Data[Curser + pafrist - 1].p_data)), 4, 5); + } +} + +/** + * @brief 页面注册函数 + * + * @param pageID + */ +void PageRegister_page_param1(unsigned char pageID) +{ + Page_Register(pageID, Setup, Loop, Exit, Event); +} +void PageRegister_page_param2(unsigned char pageID) +{ + Page_Register(pageID, Setup, Loop, Exit, Event); +} \ No newline at end of file From 85ccbea2f84a2ce82e47dcbc968c6a5c72423d5d Mon Sep 17 00:00:00 2001 From: bmy <2583236812@qq.com> Date: Sat, 24 Feb 2024 18:32:52 +0800 Subject: [PATCH 14/19] =?UTF-8?q?feat:=20=E5=9F=BA=E6=9C=AC=E5=AE=8C?= =?UTF-8?q?=E6=88=90=E9=80=9A=E4=BF=A1=E5=B8=A7=E4=B8=BB=E6=9C=BA=E5=86=99?= =?UTF-8?q?=E6=93=8D=E4=BD=9C=E6=8E=A5=E5=8F=A3?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- app/main.c | 37 +++++++------- app/tiny_frame/by_tiny_frame.h | 7 +++ app/tiny_frame/by_tiny_frame_config.h | 2 +- app/tiny_frame/by_tiny_frame_master_read.c | 6 ++- app/tiny_frame/by_tiny_frame_master_write.c | 51 ++++++++++++++++++- app/tiny_frame/by_tiny_frame_master_write.h | 3 +- app/tiny_frame/by_tiny_frame_parse.c | 44 +++++++++------- app/tiny_frame/by_tiny_frame_parse.h | 5 +- .../by_tiny_frame_slave_read_write.c | 6 ++- 9 files changed, 117 insertions(+), 44 deletions(-) diff --git a/app/main.c b/app/main.c index b1a9fb4..e093915 100644 --- a/app/main.c +++ b/app/main.c @@ -52,7 +52,7 @@ int main(void) clock_init(SYSTEM_CLOCK_144M); system_delay_init(); debug_init(); - // mt9v03x_init(); + mt9v03x_init(); ips200_init(IPS200_TYPE_SPI); by_led_init(); @@ -72,7 +72,7 @@ int main(void) /** 测试完成后移除 **/ // by_tiny_frame_parse_handle_register(test); - by_tiny_frame_parse_start_listern(); + // by_tiny_frame_parse_start_listen(); by_tf_pack_frame_t frame_now; @@ -82,6 +82,7 @@ int main(void) frame_now.slave_id = 0x0D; /** 测试完成后移除 **/ + by_tiny_frame_write(0x0D, 0x4059, 0x19260817); while (1) { Page_Run(); by_buzzer_run(); @@ -93,22 +94,22 @@ int main(void) by_tiny_frame_parse_timer_handle(); /** 测试完成后移除 **/ - // if (mt9v03x_finish_flag) { - // // 该操作消耗大概 1970 个 tick,折合约 110us - // memcpy(mt9v03x_image_copy[0], mt9v03x_image[0], (sizeof(mt9v03x_image_copy) / sizeof(uint8_t))); - // // adaptiveThreshold((uint8_t*)mt9v03x_image_copy, (uint8_t*)mt9v03x_image_copy, 188, 120, 7, 17); - // // ips200_show_gray_image(0, 0, mt9v03x_image_copy[0], MT9V03X_W, MT9V03X_H, MT9V03X_W, MT9V03X_H, 0); - // mt9v03x_finish_flag = 0; - // by_led_info_blink(); - // state_type = COMMON_STATE; - // img_processing(); - // get_corners(); - // aim_distance = COMMON_AIM; - // tracking(); - // ElementJudge(); - // ElementRun(); - // MidLineTrack(); - // } + if (mt9v03x_finish_flag) { + // 该操作消耗大概 1970 个 tick,折合约 110us + memcpy(mt9v03x_image_copy[0], mt9v03x_image[0], (sizeof(mt9v03x_image_copy) / sizeof(uint8_t))); + // adaptiveThreshold((uint8_t*)mt9v03x_image_copy, (uint8_t*)mt9v03x_image_copy, 188, 120, 7, 17); + // ips200_show_gray_image(0, 0, mt9v03x_image_copy[0], MT9V03X_W, MT9V03X_H, MT9V03X_W, MT9V03X_H, 0); + mt9v03x_finish_flag = 0; + by_led_info_blink(); + state_type = COMMON_STATE; + img_processing(); + get_corners(); + aim_distance = COMMON_AIM; + tracking(); + ElementJudge(); + ElementRun(); + MidLineTrack(); + } } } diff --git a/app/tiny_frame/by_tiny_frame.h b/app/tiny_frame/by_tiny_frame.h index 2bd0e82..6f59817 100644 --- a/app/tiny_frame/by_tiny_frame.h +++ b/app/tiny_frame/by_tiny_frame.h @@ -3,6 +3,13 @@ #include "by_tiny_frame_config.h" +#if defined(BY_TF_DEVICE_MASTER) +#include "by_tiny_frame_master_read.h" +#include "by_tiny_frame_master_write.h" +#elif defined(BY_TF_DEVICE_SLAVE) +#include "by_tiny_frame_slave_read_write.h" +#endif + extern void by_tiny_frame_init(void); void by_tiny_frame_run(void); diff --git a/app/tiny_frame/by_tiny_frame_config.h b/app/tiny_frame/by_tiny_frame_config.h index ebc3549..a302e29 100644 --- a/app/tiny_frame/by_tiny_frame_config.h +++ b/app/tiny_frame/by_tiny_frame_config.h @@ -11,7 +11,7 @@ #define BY_TF_PARSE_BUFFER_SIZE (50) // 注释此项则为主机,否则为从机 -#define BY_TF_DEVICE_SLAVE +// #define BY_TF_DEVICE_SLAVE /********** 从机模式配置选项 **********/ #if defined(BY_TF_DEVICE_SLAVE) diff --git a/app/tiny_frame/by_tiny_frame_master_read.c b/app/tiny_frame/by_tiny_frame_master_read.c index 443a8c2..ccb0041 100644 --- a/app/tiny_frame/by_tiny_frame_master_read.c +++ b/app/tiny_frame/by_tiny_frame_master_read.c @@ -1,5 +1,9 @@ #include "by_tiny_frame_master_read.h" +#if defined(BY_TF_DEVICE_MASTER) + void by_tiny_frame_read_run(void) { -} \ No newline at end of file +} + +#endif diff --git a/app/tiny_frame/by_tiny_frame_master_write.c b/app/tiny_frame/by_tiny_frame_master_write.c index 9fc7047..b2f6f6c 100644 --- a/app/tiny_frame/by_tiny_frame_master_write.c +++ b/app/tiny_frame/by_tiny_frame_master_write.c @@ -1,5 +1,54 @@ #include "by_tiny_frame_master_write.h" +#if defined(BY_TF_DEVICE_MASTER) + +#include "by_tiny_frame_pack.h" +#include "by_tiny_frame_parse.h" + +uint8_t write_processing_flag; + void by_tiny_frame_write_run(void) { -} \ No newline at end of file + // nothing +} + +void by_tiny_frame_write(uint8_t slave_id, uint16_t reg_addr, uint32_t data) +{ + // 填充数据 + by_tf_pack_frame_t frame_s; + frame_s.slave_id = slave_id; + frame_s.cmd = BY_TINY_FRAME_WRITE_CMD_CODE; + frame_s.reg_addr = reg_addr; + frame_s.data = data; + + // 发送写请求 + by_tiny_frame_pack_send(&frame_s); + // 设置响应监听 id + by_tiny_frame_parse_set_listen_slave_id(slave_id); + // 注册响应监听回调 + by_tiny_frame_parse_handle_register(by_tiny_frame_write_handle); + // 开启响应监听 + by_tiny_frame_parse_start_listen(); + + write_processing_flag = 1; +} + +void by_tiny_frame_write_handle(by_tf_parse_frame_t frame_s, uint8_t status) +{ + write_processing_flag = 0; + +#if (BY_TF_DEBUG) + printf("****** WRITE REGISTER DONE ******\r\n"); + printf("SLAVE ID: 0x%0.2X\r\n", frame_s.frame[0]); + printf("\t--cmd: %0.2X\n\t--reg_addr: 0x%0.4X\n\t--data: 0x%0.8X\r\n", frame_s.cmd, frame_s.reg_addr, frame_s.data); + if (status) { + printf("write operation failed!!!\r\n"); + + } else { + printf("write operation successful!!!\r\n"); + } + +#endif +} + +#endif diff --git a/app/tiny_frame/by_tiny_frame_master_write.h b/app/tiny_frame/by_tiny_frame_master_write.h index 9e4a237..50238d1 100644 --- a/app/tiny_frame/by_tiny_frame_master_write.h +++ b/app/tiny_frame/by_tiny_frame_master_write.h @@ -8,10 +8,11 @@ #include "by_tiny_frame_parse.h" #include "by_tiny_frame_pack.h" -#define BY_TINY_FRAME_WRITE_CMD_CODE (0x06) +#define BY_TINY_FRAME_WRITE_CMD_CODE (0x06) extern void by_tiny_frame_write(uint8_t slave_id, uint16_t reg_addr, uint32_t data); extern void by_tiny_frame_write_run(void); +extern void by_tiny_frame_write_handle(by_tf_parse_frame_t frame_s, uint8_t status); #endif #endif diff --git a/app/tiny_frame/by_tiny_frame_parse.c b/app/tiny_frame/by_tiny_frame_parse.c index bc0ce92..783c42e 100644 --- a/app/tiny_frame/by_tiny_frame_parse.c +++ b/app/tiny_frame/by_tiny_frame_parse.c @@ -6,17 +6,17 @@ lwrb_t lwrb_struct; uint8_t buffer_rb[BY_TF_PARSE_BUFFER_SIZE]; uint8_t buffer_out; -uint8_t listern_slave_id; -uint8_t listern_flag; -uint16_t listern_timeout; -uint16_t listern_timevia; +uint8_t listen_slave_id; +uint8_t listen_flag; +uint16_t listen_timeout; +uint16_t listen_timevia; by_tf_parse_frame_t frame_now; by_tf_parse_done_handle_func parse_done_handle; void by_tiny_frame_parse_init(void) { #if defined(BY_TF_DEVICE_MASTER) - listern_timeout = BY_TF_PARSE_TIMEOUT; + listen_timeout = BY_TF_PARSE_TIMEOUT; #endif /** 初始化环形缓冲区 **/ @@ -88,10 +88,10 @@ void by_tiny_frame_parse_uart_handle(uint8_t buff) void by_tiny_frame_parse_timer_handle(void) { #if defined(BY_TF_DEVICE_MASTER) - if (listern_flag) { - listern_timevia++; + if (listen_flag) { + listen_timevia++; } else { - listern_timevia = 0; + listen_timevia = 0; } #endif } @@ -104,15 +104,15 @@ void by_tiny_frame_parse_run(void) { #if defined(BY_TF_DEVICE_MASTER) - if (0 == listern_flag) { + if (0 == listen_flag) { return; } else { - if (listern_timeout <= listern_timevia) { + if (listen_timeout <= listen_timevia) { // 接收超时,停止监听 parse_done_handle(frame_now, 1); - by_tiny_frame_parse_end_listern(); + by_tiny_frame_parse_end_listen(); #if (BY_TF_DEBUG) - printf("by_tf_listern timeout\r\n"); + printf("by_tf_listen timeout\r\n"); #endif } } @@ -129,13 +129,13 @@ void by_tiny_frame_parse_run(void) #if defined(BY_TF_DEVICE_SLAVE) if (!by_tiny_frame_parse_listening(&frame_now, BY_TF_DEVICE_SLAVE_ADDRESS, buffer_out)) #else - if (!by_tiny_frame_parse_listening(&frame_now, listern_slave_id, buffer_out)) + if (!by_tiny_frame_parse_listening(&frame_now, listen_slave_id, buffer_out)) #endif { if (!by_tiny_frame_parse_crc(&frame_now)) { // 接收成功后停止监听 - by_tiny_frame_parse_end_listern(); + by_tiny_frame_parse_end_listen(); // 解析成功回调 parse_done_handle(frame_now, 0); #if (BY_TF_DEBUG) @@ -169,7 +169,7 @@ uint8_t by_tiny_frame_parse_crc(by_tf_parse_frame_t *frame_s) } // 校验错误则直接结束监听 - by_tiny_frame_parse_end_listern(); + by_tiny_frame_parse_end_listen(); parse_done_handle(frame_now, 1); return 1; @@ -177,16 +177,22 @@ uint8_t by_tiny_frame_parse_crc(by_tf_parse_frame_t *frame_s) void by_tiny_frame_parse_handle_register(by_tf_parse_done_handle_func func) { + // FIXME 监听过程中应不允许更改 // FIXME 未校验是否传入非空值,另外假设未执行注册,也会产生非法访问 parse_done_handle = func; } -void by_tiny_frame_parse_start_listern(void) +void by_tiny_frame_parse_start_listen(void) { - listern_flag = 1; + listen_flag = 1; } -void by_tiny_frame_parse_end_listern(void) +void by_tiny_frame_parse_end_listen(void) { - listern_flag = 0; + listen_flag = 0; } + +void by_tiny_frame_parse_set_listen_slave_id(uint8_t slave_id) +{ + listen_slave_id = slave_id; +} \ No newline at end of file diff --git a/app/tiny_frame/by_tiny_frame_parse.h b/app/tiny_frame/by_tiny_frame_parse.h index 800d80c..4ac6c0e 100644 --- a/app/tiny_frame/by_tiny_frame_parse.h +++ b/app/tiny_frame/by_tiny_frame_parse.h @@ -25,7 +25,8 @@ extern void by_tiny_frame_parse_uart_handle(uint8_t buff); extern void by_tiny_frame_parse_run(void); extern uint8_t by_tiny_frame_parse_crc(by_tf_parse_frame_t *frame_s); extern void by_tiny_frame_parse_handle_register(by_tf_parse_done_handle_func func); -extern void by_tiny_frame_parse_start_listern(void); -extern void by_tiny_frame_parse_end_listern(void); +extern void by_tiny_frame_parse_start_listen(void); +extern void by_tiny_frame_parse_end_listen(void); +extern void by_tiny_frame_parse_set_listen_slave_id(uint8_t slave_id); #endif diff --git a/app/tiny_frame/by_tiny_frame_slave_read_write.c b/app/tiny_frame/by_tiny_frame_slave_read_write.c index 9883ce6..c0fd7c4 100644 --- a/app/tiny_frame/by_tiny_frame_slave_read_write.c +++ b/app/tiny_frame/by_tiny_frame_slave_read_write.c @@ -1,5 +1,8 @@ #include "by_tiny_frame_slave_read_write.h" +#if defined(BY_TF_DEVICE_SLAVE) + +#include "by_tiny_frame_config.h" #include "by_tiny_frame_parse.h" #include "by_tiny_frame_pack.h" @@ -39,6 +42,7 @@ void by_tiny_frame_read_write_handle(by_tf_parse_frame_t frame_s, uint8_t status #if (BY_TF_DEBUG) printf("****** EXECUTE CMD SUCCESSFUL ******\r\n"); printf("Device ID: 0x%0.2X\r\n", BY_TF_DEVICE_SLAVE_ADDRESS); - printf("--cmd: %0.2X\n--reg_addr: %0.4X\n--data: %0.8X\r\n", frame_s.cmd, frame_s.reg_addr, frame_s.data); + printf("\t--cmd: %0.2X\n\t--reg_addr: 0x%0.4X\n\t--data: 0x%0.8X\r\n", frame_s.cmd, frame_s.reg_addr, frame_s.data); #endif } +#endif From 785f674adabb5f41665eed0f194d32b8e82cd4ff Mon Sep 17 00:00:00 2001 From: bmy <2583236812@qq.com> Date: Sat, 24 Feb 2024 18:53:02 +0800 Subject: [PATCH 15/19] =?UTF-8?q?feat:=20=E5=9F=BA=E6=9C=AC=E5=AE=8C?= =?UTF-8?q?=E6=88=90=E9=80=9A=E4=BF=A1=E5=B8=A7=E4=B8=BB=E6=9C=BA=E8=AF=BB?= =?UTF-8?q?=E6=93=8D=E4=BD=9C=E6=8E=A5=E5=8F=A3?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- app/main.c | 4 +- app/tiny_frame/by_tiny_frame_master_read.c | 44 ++++++++++++++++++++++ app/tiny_frame/by_tiny_frame_master_read.h | 7 +++- 3 files changed, 53 insertions(+), 2 deletions(-) diff --git a/app/main.c b/app/main.c index e093915..c1c1e31 100644 --- a/app/main.c +++ b/app/main.c @@ -33,6 +33,7 @@ /** 测试完成后移除 **/ #include "by_tiny_frame_parse.h" #include "by_tiny_frame_pack.h" +uint32_t data_test; /** 测试完成后移除 **/ void test(by_tf_parse_frame_t frame_s, uint8_t status) @@ -82,7 +83,8 @@ int main(void) frame_now.slave_id = 0x0D; /** 测试完成后移除 **/ - by_tiny_frame_write(0x0D, 0x4059, 0x19260817); + // by_tiny_frame_write(0x0D, 0x4059, 0x19260817); + by_tiny_frame_read(0x0D, 0x4059, &data_test); while (1) { Page_Run(); by_buzzer_run(); diff --git a/app/tiny_frame/by_tiny_frame_master_read.c b/app/tiny_frame/by_tiny_frame_master_read.c index ccb0041..de3f551 100644 --- a/app/tiny_frame/by_tiny_frame_master_read.c +++ b/app/tiny_frame/by_tiny_frame_master_read.c @@ -2,8 +2,52 @@ #if defined(BY_TF_DEVICE_MASTER) +uint8_t read_processing_flag; +uint32_t *data_p; + void by_tiny_frame_read_run(void) { } +void by_tiny_frame_read(uint8_t slave_id, uint16_t reg_addr, uint32_t *data) +{ + // 填充数据 + by_tf_pack_frame_t frame_s; + frame_s.slave_id = slave_id; + frame_s.cmd = BY_TINY_FRAME_READ_CMD_CODE; + frame_s.reg_addr = reg_addr; + frame_s.data = 0; + + // 发送写请求 + by_tiny_frame_pack_send(&frame_s); + // 设置响应监听 id + by_tiny_frame_parse_set_listen_slave_id(slave_id); + // 注册响应监听回调 + by_tiny_frame_parse_handle_register(by_tiny_frame_read_handle); + // 开启响应监听 + by_tiny_frame_parse_start_listen(); + + read_processing_flag = 1; +} + +void by_tiny_frame_read_handle(by_tf_parse_frame_t frame_s, uint8_t status) +{ + + read_processing_flag = 0; + if (!status) { + *data_p = frame_s.data; + } + +#if (BY_TF_DEBUG) + printf("****** READ REGISTER DONE ******\r\n"); + printf("SLAVE ID: 0x%0.2X\r\n", frame_s.frame[0]); + printf("\t--cmd: %0.2X\n\t--reg_addr: 0x%0.4X\n\t--data: 0x%0.8X\r\n", frame_s.cmd, frame_s.reg_addr, frame_s.data); + if (status) { + printf("read operation failed!!!\r\n"); + } else { + printf("read operation successful!!!\r\n"); + } +#endif +} + #endif diff --git a/app/tiny_frame/by_tiny_frame_master_read.h b/app/tiny_frame/by_tiny_frame_master_read.h index d1b2d71..b4256ef 100644 --- a/app/tiny_frame/by_tiny_frame_master_read.h +++ b/app/tiny_frame/by_tiny_frame_master_read.h @@ -5,9 +5,14 @@ #if defined(BY_TF_DEVICE_MASTER) -#define BY_TINY_FRAME_READ_CMD_CODE (0x03) +#include "by_tiny_frame_parse.h" +#include "by_tiny_frame_pack.h" +#define BY_TINY_FRAME_READ_CMD_CODE (0x03) + +extern void by_tiny_frame_read(uint8_t slave_id, uint16_t reg_addr, uint32_t *data); extern void by_tiny_frame_read_run(void); +extern void by_tiny_frame_read_handle(by_tf_parse_frame_t frame_s, uint8_t status); #endif #endif From a758d0f94fe58501c45ee9add024560eef406f5c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?=E4=BA=95=E6=98=8E=E6=B1=9F?= <246462502@qq.com> Date: Sat, 2 Mar 2024 16:00:05 +0800 Subject: [PATCH 16/19] =?UTF-8?q?feat:=20=E5=AE=8C=E6=88=90eeprom=E5=8F=8A?= =?UTF-8?q?=E9=A1=B5=E9=9D=A2ui=E6=9B=B4=E6=96=B0?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- app/isr.c | 1 + app/jj_param.c | 13 +- app/jj_param.h | 8 +- app/main.c | 53 +++--- app/page/page.c | 8 +- app/page/page.h | 2 +- app/page/page_dparam.c | 15 +- app/page/page_menu.c | 4 +- app/page/{page_sparam.c => page_sparam1.c} | 11 +- app/page/page_sparam2.c | 160 ++++++++++++++++++ app/tiny_frame/by_tiny_frame_config.h | 8 +- .../by_tiny_frame_slave_read_write.c | 56 +++--- libraries/zf_device/zf_device_k24c02.h | 2 +- libraries/zf_device/zf_device_mt9v03x_dvp.h | 4 +- libraries/zf_driver/zf_driver_soft_iic.c | 30 ++++ libraries/zf_driver/zf_driver_soft_iic.h | 122 ++++++------- 16 files changed, 348 insertions(+), 149 deletions(-) rename app/page/{page_sparam.c => page_sparam1.c} (92%) create mode 100644 app/page/page_sparam2.c diff --git a/app/isr.c b/app/isr.c index cf9dd1c..ee7debe 100644 --- a/app/isr.c +++ b/app/isr.c @@ -284,6 +284,7 @@ void TIM1_UP_IRQHandler(void) { if (TIM_GetITStatus(TIM1, TIM_IT_Update) != RESET) { TIM_ClearITPendingBit(TIM1, TIM_IT_Update); + by_tiny_frame_parse_timer_handle(); } } diff --git a/app/jj_param.c b/app/jj_param.c index 1142af9..27befa7 100644 --- a/app/jj_param.c +++ b/app/jj_param.c @@ -5,6 +5,7 @@ PARAM_INFO Param_Data[DATA_NUM]; soft_iic_info_struct eeprom_param; TYPE_UNION iic_buffer[DATA_IN_FLASH_NUM]; +uint32_t *addre[2]; float data0 = 1.0f; float data1 = 1.05f; float data2 = 10.0f; @@ -12,6 +13,8 @@ float data3 = 100.0f; float data4 = 4.0f; float data5 = 66.0f; float data6 = 13.130f; +float data7 = 10.0f; +float data8 = 0.0f; /** * @brief 参数初始化注册 * @@ -25,7 +28,9 @@ void jj_param_eeprom_init(void) PARAM_REG(imgax_Kp, &data3, EFLOAT, 1, "im_P:"); // 注冊 PARAM_REG(imgax_Ki, &data4, EFLOAT, 1, "im_I:"); // 注冊 PARAM_REG(imgax_Kd, &data5, EFLOAT, 1, "im_D:"); - PARAM_REG(other, &data6, EFLOAT, 1, "add:"); + PARAM_REG(other , &data6, EFLOAT, 1, "add:"); + PARAM_REG(delta_x , &data7, EFLOAT, 2, "delta_x:"); + PARAM_REG(delta_y , &data8, EFLOAT, 0, "delta_y:"); jj_param_read(); // 注冊 } /** @@ -48,7 +53,7 @@ void jj_param_write(void) default: break; } - soft_iic_write_8bit_registers(&eeprom_param, 4 * i, (uint8 *)&iic_buffer[i], 4); + eep_soft_iic_write_8bit_registers(&eeprom_param, (4 * i) >> 8, (4 * i), (uint8 *)&iic_buffer[i], 4); system_delay_ms(10); } } @@ -60,7 +65,7 @@ void jj_param_read(void) { for (uint8 i = 0; i < DATA_IN_FLASH_NUM; i++) { - soft_iic_read_8bit_registers(&eeprom_param, 4 * i, (uint8 *)&iic_buffer[i], 4); + eep_soft_iic_read_8bit_registers(&eeprom_param, (4 * i) >> 8, (4 * i), (uint8 *)&iic_buffer[i], 4); switch (Param_Data[i].type) { case EFLOAT: *((float *)(Param_Data[i].p_data)) = @@ -77,6 +82,6 @@ void jj_param_read(void) default: break; } - system_delay_ms(10); + system_delay_ms(10); } } diff --git a/app/jj_param.h b/app/jj_param.h index 6faea53..2e78fdc 100644 --- a/app/jj_param.h +++ b/app/jj_param.h @@ -31,6 +31,9 @@ typedef enum { Page3_head, DATA_IN_FLASH_NUM, + + delta_x, + delta_y, DATA_NUM, } data_tag_t; @@ -50,14 +53,15 @@ typedef union { typedef struct { void *p_data; ENUM_TYPE type; - uint8_t cmd; + uint8_t cmd;//01:仅存储 00:仅显示 02:传输并显示 char *text; } PARAM_INFO; - +extern uint32_t * addre[2]; extern soft_iic_info_struct eeprom_param; extern PARAM_INFO Param_Data[DATA_NUM]; extern TYPE_UNION iic_buffer[DATA_IN_FLASH_NUM]; void jj_param_eeprom_init(void); void jj_param_write(void); void jj_param_read(void); +extern float data7; #endif \ No newline at end of file diff --git a/app/main.c b/app/main.c index 889d833..b0acd5a 100644 --- a/app/main.c +++ b/app/main.c @@ -52,65 +52,60 @@ int main(void) clock_init(SYSTEM_CLOCK_144M); system_delay_init(); debug_init(); - // mt9v03x_init(); + mt9v03x_init(); ips200_init(IPS200_TYPE_SPI); by_led_init(); - by_buzzer_init(); + // by_buzzer_init(); by_button_init(); jj_bt_init(); jj_param_eeprom_init(); - // jj_bt_init(); - // jj_param_eeprom_init(); Page_Init(); - - // pit_ms_init(TIM6_PIT, 2); - // pit_ms_init(TIM1_PIT, 2); + + pit_ms_init(TIM1_PIT, 1); by_tiny_frame_init(); printf("start running\r\n"); /** 测试完成后移除 **/ - // by_tiny_frame_parse_handle_register(test); by_tiny_frame_parse_start_listern(); by_tf_pack_frame_t frame_now; frame_now.cmd = 0x06; frame_now.data = 0x19260817; - frame_now.reg_addr = 0x4059; + frame_now.reg_addr = 0x00; frame_now.slave_id = 0x0D; /** 测试完成后移除 **/ while (1) { Page_Run(); - by_buzzer_run(); + // by_buzzer_run(); /** 测试完成后移除 **/ - by_tiny_frame_run(); - // by_tiny_frame_pack_send(&frame_now); + by_tiny_frame_pack_send(&frame_now); system_delay_ms(10); - by_tiny_frame_parse_timer_handle(); /** 测试完成后移除 **/ - // if (mt9v03x_finish_flag) { - // // 该操作消耗大概 1970 个 tick,折合约 110us - // memcpy(mt9v03x_image_copy[0], mt9v03x_image[0], (sizeof(mt9v03x_image_copy) / sizeof(uint8_t))); - // // adaptiveThreshold((uint8_t*)mt9v03x_image_copy, (uint8_t*)mt9v03x_image_copy, 188, 120, 7, 17); - // // ips200_show_gray_image(0, 0, mt9v03x_image_copy[0], MT9V03X_W, MT9V03X_H, MT9V03X_W, MT9V03X_H, 0); - // mt9v03x_finish_flag = 0; - // by_led_info_blink(); - // state_type = COMMON_STATE; - // img_processing(); - // get_corners(); - // aim_distance = COMMON_AIM; - // tracking(); - // ElementJudge(); - // ElementRun(); - // MidLineTrack(); - // } + if (mt9v03x_finish_flag) { + // 该操作消耗大概 1970 个 tick,折合约 110us + memcpy(mt9v03x_image_copy[0], mt9v03x_image[0], (sizeof(mt9v03x_image_copy) / sizeof(uint8_t))); + // adaptiveThreshold((uint8_t*)mt9v03x_image_copy, (uint8_t*)mt9v03x_image_copy, 188, 120, 7, 17); + // ips200_show_gray_image(0, 0, mt9v03x_image_copy[0], MT9V03X_W, MT9V03X_H, MT9V03X_W, MT9V03X_H, 0); + mt9v03x_finish_flag = 0; + by_led_info_blink(); + // state_type = COMMON_STATE; + // img_processing(); + // get_corners(); + // aim_distance = COMMON_AIM; + // tracking(); + // ElementJudge(); + // ElementRun(); + // MidLineTrack(); + + } } } diff --git a/app/page/page.c b/app/page/page.c index 01ef310..877b879 100644 --- a/app/page/page.c +++ b/app/page/page.c @@ -4,9 +4,13 @@ PAGE_LIST pagelist[page_max]; static uint8_t page_busy = 0; -int8_t new_page = page_menu; +static int8_t new_page = page_menu; static int8_t now_page = page_menu; +int8_t Get_new_page(void) +{ + return new_page; +} /** * @brief 注册一个基本页面,包含一个初始化函数,循环函数,退出函数,事件函数 * @param pageID: 页面编号 @@ -127,7 +131,7 @@ void Page_Init(void) PAGE_REG(page_rtcam, "rtcam"); PAGE_REG(page_param1, "Param1"); PAGE_REG(page_param2, "param2"); - PAGE_REG(page_dparam, "dparam"); + PAGE_REG(page_dparam, "dparam"); // PAGE_REG(page_argv); // PAGE_REG(page_sys); // PAGE_REG(page_run); diff --git a/app/page/page.h b/app/page/page.h index 39ef9eb..7e18f75 100644 --- a/app/page/page.h +++ b/app/page/page.h @@ -67,7 +67,7 @@ void Page_OpenCurrentPage(void); uint8_t Page_GetStatus(void); void Page_Run(void); void Page_Init(void); +int8_t Get_new_page(void); extern PAGE_LIST pagelist[page_max]; -extern int8_t new_page ; #endif diff --git a/app/page/page_dparam.c b/app/page/page_dparam.c index ebcb4be..3407df5 100644 --- a/app/page/page_dparam.c +++ b/app/page/page_dparam.c @@ -1,7 +1,7 @@ #include "zf_common_headfile.h" #include "page_ui_widget.h" #include "page.h" -float ddata0=0.0f; +#include "jj_param.h" // #define LINE_HEAD 1 // #define LINE_END 7 // static int8_t Curser = LINE_HEAD; // 定义光标位置 @@ -21,8 +21,10 @@ static void Setup() { ips200_clear(); // 显示参数名称 - ips200_show_string(0, 0, "Dparam"); - ips200_show_string(20, 18 + 2, "ddata0:"); + ips200_show_string(0, 0, "Dparam"); + + ips200_show_string(20, 18 + 2, (Param_Data[delta_x].text)); + ips200_show_string(20, 18 + 20, (Param_Data[delta_y].text)); } /** @@ -32,7 +34,6 @@ static void Setup() */ static void Exit() { - } /** @@ -43,8 +44,8 @@ static void Exit() static void Loop() { // 刷新参数数值 - ips200_show_float(80, 18 + 2, ddata0, 4, 5); - ddata0+=0.01f; + ips200_show_float(90, 18 + 2, *((float *)(Param_Data[delta_x].p_data)), 4, 5); + ips200_show_float(90, 18 + 20, *((float *)(Param_Data[delta_x].p_data)), 4, 5); } /** @@ -55,7 +56,7 @@ static void Loop() */ static void Event(page_event event) { - if (page_event_press_long == event) { + if (page_event_press_long == event) { Page_Shift(page_menu); } } diff --git a/app/page/page_menu.c b/app/page/page_menu.c index be60e04..687499b 100644 --- a/app/page/page_menu.c +++ b/app/page/page_menu.c @@ -25,7 +25,7 @@ static void Setup() { ips200_clear(); Print_Menu_p(); - Print_Curser(Curser, Curser_Last,RGB565_PURPLE); + Print_Curser(Curser, Curser_Last, RGB565_PURPLE); } /** @@ -72,7 +72,7 @@ static void Event(page_event event) Curser = LINE_HEAD; } - Print_Curser(Curser, Curser_Last,RGB565_PURPLE); + Print_Curser(Curser, Curser_Last, RGB565_PURPLE); } /** diff --git a/app/page/page_sparam.c b/app/page/page_sparam1.c similarity index 92% rename from app/page/page_sparam.c rename to app/page/page_sparam1.c index a062093..fe425ab 100644 --- a/app/page/page_sparam.c +++ b/app/page/page_sparam1.c @@ -1,6 +1,7 @@ #include "jj_param.h" #include "page_ui_widget.h" #include "page.h" +#include #define LINE_HEAD 1 @@ -25,11 +26,11 @@ static void Setup() { ips200_clear(); - if (new_page == page_param1) { + if (Get_new_page() == page_param1) { pafrist = 0; paend = Page2_head; ips200_show_string(0, 0, "Param1"); - } else if (new_page == page_param2) { + } else if (Get_new_page() == page_param2) { pafrist = Page2_head; paend = Page3_head; ips200_show_string(0, 0, "Param2"); @@ -104,7 +105,7 @@ static void Event(page_event event) if (page_event_forward == event) { switch (Param_Data[Curser + pafrist - 1].type) { case EFLOAT: - *((float *)(Param_Data[Curser + pafrist - 1].p_data)) += powf(10.0f, (float)index_power); + *((float *)(Param_Data[Curser + pafrist - 1].p_data)) += powf(10, index_power); break; case EINT32: *((int32 *)(Param_Data[Curser + pafrist - 1].p_data)) += 1; @@ -157,7 +158,3 @@ void PageRegister_page_param1(unsigned char pageID) { Page_Register(pageID, Setup, Loop, Exit, Event); } -void PageRegister_page_param2(unsigned char pageID) -{ - Page_Register(pageID, Setup, Loop, Exit, Event); -} \ No newline at end of file diff --git a/app/page/page_sparam2.c b/app/page/page_sparam2.c new file mode 100644 index 0000000..2335b13 --- /dev/null +++ b/app/page/page_sparam2.c @@ -0,0 +1,160 @@ +#include "jj_param.h" +#include "page_ui_widget.h" +#include "page.h" +#include + +#define LINE_HEAD 1 + +static int16 pafrist; +static int16 paend; +static int16 palong; +static int event_flag = 0; +static int32_t index_power = 0; +static int8_t Curser = LINE_HEAD; // 定义光标位置 +static int8_t Curser_Last = LINE_HEAD; // 定义光标位置 +/*************************************************************************************** + * + * 以下为页面模板函数 + * + ***************************************************************************************/ +/** + * @brief 页面初始化事件 + * @param 无 + * @retval 无 + */ +static void Setup() +{ + ips200_clear(); + + if (Get_new_page() == page_param1) { + pafrist = 0; + paend = Page2_head; + ips200_show_string(0, 0, "Param1"); + } else if (Get_new_page() == page_param2) { + pafrist = Page2_head; + paend = Page3_head; + ips200_show_string(0, 0, "Param2"); + } + + palong = paend - pafrist; + if (Curser < LINE_HEAD) { + Curser = palong; + } else if (Curser > palong) { + Curser = LINE_HEAD; + } + Print_Curser(Curser, Curser_Last, RGB565_PURPLE); + for (int16 i = 0; i < palong; i++) { + ips200_show_string(20, i * 18 + 20, Param_Data[i + pafrist].text); + if (Param_Data[i].type == EINT32) + ips200_show_int(60, i * 18 + 20, *((int32 *)(Param_Data[i + pafrist].p_data)), 5); + else if (Param_Data[i].type == EFLOAT) + ips200_show_float(60, i * 18 + 20, *((float *)(Param_Data[i + pafrist].p_data)), 4, 5); + } + ips200_show_int(50, palong * 18 + 20, index_power, 5); +} + +/** + * @brief 页面退出事件 + * @param 无 + * @retval 无 + */ +static void Exit() +{ +} + +/** + * @brief 页面循环执行的内容 + * @param 无 + * @retval 无 + */ +static void Loop() +{ +} +/** + * @brief 页面事件 + * @param btn:发出事件的按键 + * @param event:事件编号 + * @retval 无 + */ +static void Event(page_event event) +{ + + if (0 == event_flag) { + + Curser_Last = Curser; + if (page_event_forward == event) { + Curser++; // 光标上移 + } else if (page_event_backward == event) { + Curser--; // 光标下移 + } else if (page_event_press_short == event) { + event_flag = 1; // 选中参数 + Print_Curser(Curser, Curser_Last, RGB565_RED); + return; + } else if (page_event_press_long == event) { + jj_param_write(); + Page_Shift(page_menu); + return; + } + if (Curser < LINE_HEAD) { + Curser = palong; + } else if (Curser > palong) { + Curser = LINE_HEAD; + } + Print_Curser(Curser, Curser_Last, RGB565_PURPLE); + } else if (1 == event_flag) { + if (page_event_forward == event) { + switch (Param_Data[Curser + pafrist - 1].type) { + case EFLOAT: + *((float *)(Param_Data[Curser + pafrist - 1].p_data)) += powf(10, index_power); + break; + case EINT32: + *((int32 *)(Param_Data[Curser + pafrist - 1].p_data)) += 1; + break; + case EUINT32: + *((uint32 *)(Param_Data[Curser + pafrist - 1].p_data)) += 1; + break; + default: + break; + } + } else if (page_event_backward == event) { + switch (Param_Data[Curser + pafrist - 1].type) { + case EFLOAT: + *((float *)(Param_Data[Curser + pafrist - 1].p_data)) -= powf(10.0f, (float)index_power); + break; + case EINT32: + *((int32 *)(Param_Data[Curser + pafrist - 1].p_data)) -= 1; + break; + case EUINT32: + *((uint32 *)(Param_Data[Curser + pafrist - 1].p_data)) -= 1; + break; + default: + break; + } + } else if (page_event_press_short == event) { + index_power++; + if (index_power > 2) { + index_power = -2; + } + ips200_show_int(50, palong * 18 + 20, index_power, 5); + } else if (page_event_press_long == event) { + event_flag = 0; + Print_Curser(Curser, Curser_Last, RGB565_PURPLE); + } + if (EINT32 == Param_Data[Curser + pafrist - 1].type) + ips200_show_int(60, Curser * 18 + 2, *((int32 *)(Param_Data[Curser + pafrist - 1].p_data)), 5); + else if (EUINT32 == Param_Data[Curser + pafrist - 1].type) + ips200_show_uint(60, Curser * 18 + 2, *((int32 *)(Param_Data[Curser + pafrist - 1].p_data)), 5); + else if (EFLOAT == Param_Data[Curser + pafrist - 1].type) + ips200_show_float(60, Curser * 18 + 2, *((float *)(Param_Data[Curser + pafrist - 1].p_data)), 4, 5); + } +} + +/** + * @brief 页面注册函数 + * + * @param pageID + */ +void PageRegister_page_param2(unsigned char pageID) +{ + Page_Register(pageID, Setup, Loop, Exit, Event); +} \ No newline at end of file diff --git a/app/tiny_frame/by_tiny_frame_config.h b/app/tiny_frame/by_tiny_frame_config.h index ebc3549..0cb1a78 100644 --- a/app/tiny_frame/by_tiny_frame_config.h +++ b/app/tiny_frame/by_tiny_frame_config.h @@ -3,15 +3,15 @@ #define BY_TF_DEBUG (1) -#define BY_TF_UART_TX_PIN (UART3_MAP0_TX_B10) -#define BY_TF_UART_RX_PIN (UART3_MAP0_RX_B11) -#define BY_TF_UART_INDEX (UART_3) +#define BY_TF_UART_TX_PIN (UART2_MAP0_TX_A2) +#define BY_TF_UART_RX_PIN (UART2_MAP0_RX_A3) +#define BY_TF_UART_INDEX (UART_2) #define BY_TF_UART_BAUDRATE (115200) #define BY_TF_PARSE_BUFFER_SIZE (50) // 注释此项则为主机,否则为从机 -#define BY_TF_DEVICE_SLAVE +//#define BY_TF_DEVICE_SLAVE /********** 从机模式配置选项 **********/ #if defined(BY_TF_DEVICE_SLAVE) diff --git a/app/tiny_frame/by_tiny_frame_slave_read_write.c b/app/tiny_frame/by_tiny_frame_slave_read_write.c index 9883ce6..a49649f 100644 --- a/app/tiny_frame/by_tiny_frame_slave_read_write.c +++ b/app/tiny_frame/by_tiny_frame_slave_read_write.c @@ -3,6 +3,8 @@ #include "by_tiny_frame_parse.h" #include "by_tiny_frame_pack.h" +#include "jj_param.h" + void by_tiny_frame_read_write_run(void) { // empty @@ -10,35 +12,35 @@ void by_tiny_frame_read_write_run(void) void by_tiny_frame_read_write_handle(by_tf_parse_frame_t frame_s, uint8_t status) { - by_tf_pack_frame_t frame_pack_s; +// by_tf_pack_frame_t frame_pack_s; - frame_pack_s.slave_id = BY_TF_DEVICE_SLAVE_ADDRESS; - frame_pack_s.cmd = frame_s.cmd; - frame_pack_s.reg_addr = frame_s.reg_addr; +// frame_pack_s.slave_id = BY_TF_DEVICE_SLAVE_ADDRESS; +// frame_pack_s.cmd = frame_s.cmd; +// frame_pack_s.reg_addr = frame_s.reg_addr; - if (status) { - // 接收出错,一般为 CRC 校验错误 - return; - } +// if (status) { +// // 接收出错,一般为 CRC 校验错误 +// return; +// } - switch (frame_s.cmd) { - case 0x03: - // 添加查询接口,操作完成后应答 - frame_pack_s.data = 0XFFFFFFFF; // 示例 - by_tiny_frame_pack_send(&frame_pack_s); - break; - case 0x06: - // 添加写入接口,操作完成后应答 - frame_pack_s.data = frame_s.data; - by_tiny_frame_pack_send(&frame_pack_s); - break; - default: - break; - } +// switch (frame_s.cmd) { +// case 0x03: +// // 添加查询接口,操作完成后应答,主机接收,即读取 +// frame_pack_s.data =(uint32_t)(addre[frame_pack_s.reg_addr]); +// by_tiny_frame_pack_send(&frame_pack_s); +// break; +// case 0x06: +// // 添加写入接口,操作完成后应答,主机发送,即写入 +// *addre[frame_pack_s.reg_addr] = frame_pack_s.data; +// by_tiny_frame_pack_send(&frame_pack_s); +// break; +// default: +// break; +// } -#if (BY_TF_DEBUG) - printf("****** EXECUTE CMD SUCCESSFUL ******\r\n"); - printf("Device ID: 0x%0.2X\r\n", BY_TF_DEVICE_SLAVE_ADDRESS); - printf("--cmd: %0.2X\n--reg_addr: %0.4X\n--data: %0.8X\r\n", frame_s.cmd, frame_s.reg_addr, frame_s.data); -#endif +// #if (BY_TF_DEBUG) +// printf("****** EXECUTE CMD SUCCESSFUL ******\r\n"); +// printf("Device ID: 0x%0.2X\r\n", BY_TF_DEVICE_SLAVE_ADDRESS); +// printf("--cmd: %0.2X\n--reg_addr: %0.4X\n--data: %0.8X\r\n", frame_s.cmd, frame_s.reg_addr, frame_s.data); +// #endif } diff --git a/libraries/zf_device/zf_device_k24c02.h b/libraries/zf_device/zf_device_k24c02.h index b8f479c..f4ca366 100644 --- a/libraries/zf_device/zf_device_k24c02.h +++ b/libraries/zf_device/zf_device_k24c02.h @@ -55,7 +55,7 @@ //==================================================== IIC ==================================================== #define K24C02_SOFT_IIC_DELAY (500) // IIC ʱʱ ֵԽС IIC ͨԽ #define K24C02_SCL_PIN (D13) // IIC SCL K24C02 SCL -#define K24C02_SDA_PIN (D14) // IIC SDA K24C02 SDA +#define K24C02_SDA_PIN (D12) // IIC SDA K24C02 SDA //==================================================== IIC ==================================================== #else //====================================================Ӳ IIC ==================================================== diff --git a/libraries/zf_device/zf_device_mt9v03x_dvp.h b/libraries/zf_device/zf_device_mt9v03x_dvp.h index c1b8d56..14890a2 100644 --- a/libraries/zf_device/zf_device_mt9v03x_dvp.h +++ b/libraries/zf_device/zf_device_mt9v03x_dvp.h @@ -95,7 +95,7 @@ #define MT9V03X_IMAGE_SIZE ( MT9V03X_W * MT9V03X_H ) // ͼСܳ 65535 #define MT9V03X_COF_BUFFER_SIZE ( 64 ) // ôڻС 64 -#define MT9V03X_AUTO_EXP_DEF (0 ) // Զع ĬϲԶع Χ [0-63] 0 Ϊر +#define MT9V03X_AUTO_EXP_DEF (0 ) // Զع ĬϲԶع Χ [0-63] 0 Ϊر // Զع⿪ EXP_TIME Զعʱ // һDzҪԶع ߷dzȵԳԶع⣬ͼȶ #define MT9V03X_EXP_TIME_DEF (512) // عʱ ͷյԶعʱ䣬ùΪعֵ @@ -104,7 +104,7 @@ // ͷƫݺԶƫƣüƫ #define MT9V03X_UD_OFFSET_DEF (0 ) // ͼƫ ֵ ƫ ֵ ƫ Ϊ 120 240 480 ʱ޷ƫ // ͷƫݺԶƫƣüƫ -#define MT9V03X_GAIN_DEF (32 ) // ͼ Χ [16-64] عʱ̶¸ıͼ̶ +#define MT9V03X_GAIN_DEF (64 ) // ͼ Χ [16-64] عʱ̶¸ıͼ̶ #define MT9V03X_PCLK_MODE_DEF (1 ) // ʱģʽ Χ [0-1] Ĭϣ0 ѡΪ[0źţ1ź] // ͨΪ 0ʹ CH32V307 DVP ӿڻ STM32 DCMI ӿڲɼҪΪ 1 // MT9V034 V1.5 Լϰ汾ָ֧ diff --git a/libraries/zf_driver/zf_driver_soft_iic.c b/libraries/zf_driver/zf_driver_soft_iic.c index 61094df..7f322e2 100644 --- a/libraries/zf_driver/zf_driver_soft_iic.c +++ b/libraries/zf_driver/zf_driver_soft_iic.c @@ -709,3 +709,33 @@ void soft_iic_init (soft_iic_info_struct *soft_iic_obj, uint8 addr, uint32 delay gpio_init(scl_pin, GPO, GPIO_HIGH, GPO_PUSH_PULL); // ȡӦIO AFܱ gpio_init(sda_pin, GPO, GPIO_HIGH, GPO_OPEN_DTAIN); // ȡӦIO AFܱ } +void eep_soft_iic_read_8bit_registers (soft_iic_info_struct *soft_iic_obj, const uint8 register_name_h, const uint8 register_name_l, uint8 *data, uint32 len) +{ + zf_assert(soft_iic_obj != NULL); + zf_assert(data != NULL); + soft_iic_start(soft_iic_obj); + soft_iic_send_data(soft_iic_obj, soft_iic_obj->addr << 1); + soft_iic_send_data(soft_iic_obj, register_name_h); + soft_iic_send_data(soft_iic_obj, register_name_l); + soft_iic_start(soft_iic_obj); + soft_iic_send_data(soft_iic_obj, soft_iic_obj->addr << 1 | 0x01); + while(len --) + { + *data ++ = soft_iic_read_data(soft_iic_obj, len == 0); + } + soft_iic_stop(soft_iic_obj); +} +void eep_soft_iic_write_8bit_registers (soft_iic_info_struct *soft_iic_obj, const uint8 register_name_h,const uint8 register_name_l, const uint8 *data, uint32 len) +{ + zf_assert(soft_iic_obj != NULL); + zf_assert(data != NULL); + soft_iic_start(soft_iic_obj); + soft_iic_send_data(soft_iic_obj, soft_iic_obj->addr << 1); + soft_iic_send_data(soft_iic_obj, register_name_h); + soft_iic_send_data(soft_iic_obj, register_name_l); + while(len --) + { + soft_iic_send_data(soft_iic_obj, *data ++); + } + soft_iic_stop(soft_iic_obj); +} \ No newline at end of file diff --git a/libraries/zf_driver/zf_driver_soft_iic.h b/libraries/zf_driver/zf_driver_soft_iic.h index 1323324..5a9be20 100644 --- a/libraries/zf_driver/zf_driver_soft_iic.h +++ b/libraries/zf_driver/zf_driver_soft_iic.h @@ -1,83 +1,83 @@ /********************************************************************************************************************* -* CH32V307VCT6 Opensourec Library CH32V307VCT6 Դ⣩һڹٷ SDK ӿڵĵԴ -* Copyright (c) 2022 SEEKFREE ɿƼ -* -* ļCH32V307VCT6 Դһ -* -* CH32V307VCT6 Դ -* Ըᷢ GPLGNU General Public License GNUͨù֤ -* GPL ĵ3棨 GPL3.0ѡģκκİ汾·/޸ -* -* Դķϣܷãδκεı֤ -* ûԻʺض;ı֤ -* ϸμ GPL -* -* ӦյԴͬʱյһ GPL ĸ -* ûУ -* -* ע -* Դʹ GPL3.0 Դ֤Э Ϊİ汾 -* Ӣİ libraries/doc ļµ GPL3_permission_statement.txt ļ -* ֤ libraries ļ ļµ LICENSE ļ -* ӭλʹò ޸ʱ뱣ɿƼİȨ -* -* ļ zf_driver_soft_iic -* ˾ ɶɿƼ޹˾ -* 汾Ϣ 鿴 libraries/doc ļ version ļ 汾˵ -* MounRiver Studio V1.8.1 -* ƽ̨ CH32V307VCT6 -* https://seekfree.taobao.com/ -* -* ޸ļ¼ -* ע -* 2022-09-15 W first version -********************************************************************************************************************/ + * CH32V307VCT6 Opensourec Library CH32V307VCT6 Դ⣩һڹٷ SDK ӿڵĵԴ + * Copyright (c) 2022 SEEKFREE ɿƼ + * + * ļCH32V307VCT6 Դһ + * + * CH32V307VCT6 Դ + * Ըᷢ GPLGNU General Public License GNUͨù֤ + * GPL ĵ3棨 GPL3.0ѡģκκİ汾·/޸ + * + * Դķϣܷãδκεı֤ + * ûԻʺض;ı֤ + * ϸμ GPL + * + * ӦյԴͬʱյһ GPL ĸ + * ûУ + * + * ע + * Դʹ GPL3.0 Դ֤Э Ϊİ汾 + * Ӣİ libraries/doc ļµ GPL3_permission_statement.txt ļ + * ֤ libraries ļ ļµ LICENSE ļ + * ӭλʹò ޸ʱ뱣ɿƼİȨ + * + * ļ zf_driver_soft_iic + * ˾ ɶɿƼ޹˾ + * 汾Ϣ 鿴 libraries/doc ļ version ļ 汾˵ + * MounRiver Studio V1.8.1 + * ƽ̨ CH32V307VCT6 + * https://seekfree.taobao.com/ + * + * ޸ļ¼ + * ע + * 2022-09-15 W first version + ********************************************************************************************************************/ #ifndef _zf_driver_soft_iic_h_ #define _zf_driver_soft_iic_h_ - #include "zf_driver_gpio.h" typedef struct { - gpio_pin_enum scl_pin; // ڼ¼Ӧű - gpio_pin_enum sda_pin; // ڼ¼Ӧű - uint8 addr; // ַ λַģʽ - uint32 delay; // ģ IIC ʱʱ -}soft_iic_info_struct; + gpio_pin_enum scl_pin; // ڼ¼Ӧű + gpio_pin_enum sda_pin; // ڼ¼Ӧű + uint8 addr; // ַ λַģʽ + uint32 delay; // ģ IIC ʱʱ +} soft_iic_info_struct; -void soft_iic_write_8bit (soft_iic_info_struct *soft_iic_obj, const uint8 data); -void soft_iic_write_8bit_array (soft_iic_info_struct *soft_iic_obj, const uint8 *data, uint32 len); +void soft_iic_write_8bit(soft_iic_info_struct *soft_iic_obj, const uint8 data); +void soft_iic_write_8bit_array(soft_iic_info_struct *soft_iic_obj, const uint8 *data, uint32 len); -void soft_iic_write_16bit (soft_iic_info_struct *soft_iic_obj, const uint16 data); -void soft_iic_write_16bit_array (soft_iic_info_struct *soft_iic_obj, const uint16 *data, uint32 len); +void soft_iic_write_16bit(soft_iic_info_struct *soft_iic_obj, const uint16 data); +void soft_iic_write_16bit_array(soft_iic_info_struct *soft_iic_obj, const uint16 *data, uint32 len); -void soft_iic_write_8bit_register (soft_iic_info_struct *soft_iic_obj, const uint8 register_name, const uint8 data); -void soft_iic_write_8bit_registers (soft_iic_info_struct *soft_iic_obj, const uint8 register_name, const uint8 *data, uint32 len); +void soft_iic_write_8bit_register(soft_iic_info_struct *soft_iic_obj, const uint8 register_name, const uint8 data); +void soft_iic_write_8bit_registers(soft_iic_info_struct *soft_iic_obj, const uint8 register_name, const uint8 *data, uint32 len); -void soft_iic_write_16bit_register (soft_iic_info_struct *soft_iic_obj, const uint16 register_name, const uint16 data); -void soft_iic_write_16bit_registers (soft_iic_info_struct *soft_iic_obj, const uint16 register_name, const uint16 *data, uint32 len); +void soft_iic_write_16bit_register(soft_iic_info_struct *soft_iic_obj, const uint16 register_name, const uint16 data); +void soft_iic_write_16bit_registers(soft_iic_info_struct *soft_iic_obj, const uint16 register_name, const uint16 *data, uint32 len); -uint8 soft_iic_read_8bit (soft_iic_info_struct *soft_iic_obj); -void soft_iic_read_8bit_array (soft_iic_info_struct *soft_iic_obj, uint8 *data, uint32 len); +uint8 soft_iic_read_8bit(soft_iic_info_struct *soft_iic_obj); +void soft_iic_read_8bit_array(soft_iic_info_struct *soft_iic_obj, uint8 *data, uint32 len); -uint16 soft_iic_read_16bit (soft_iic_info_struct *soft_iic_obj); -void soft_iic_read_16bit_array (soft_iic_info_struct *soft_iic_obj, uint16 *data, uint32 len); +uint16 soft_iic_read_16bit(soft_iic_info_struct *soft_iic_obj); +void soft_iic_read_16bit_array(soft_iic_info_struct *soft_iic_obj, uint16 *data, uint32 len); -uint8 soft_iic_read_8bit_register (soft_iic_info_struct *soft_iic_obj, const uint8 register_name); -void soft_iic_read_8bit_registers (soft_iic_info_struct *soft_iic_obj, const uint8 register_name, uint8 *data, uint32 len); +uint8 soft_iic_read_8bit_register(soft_iic_info_struct *soft_iic_obj, const uint8 register_name); +void soft_iic_read_8bit_registers(soft_iic_info_struct *soft_iic_obj, const uint8 register_name, uint8 *data, uint32 len); -uint16 soft_iic_read_16bit_register (soft_iic_info_struct *soft_iic_obj, const uint16 register_name); -void soft_iic_read_16bit_registers (soft_iic_info_struct *soft_iic_obj, const uint16 register_name, uint16 *data, uint32 len); +uint16 soft_iic_read_16bit_register(soft_iic_info_struct *soft_iic_obj, const uint16 register_name); +void soft_iic_read_16bit_registers(soft_iic_info_struct *soft_iic_obj, const uint16 register_name, uint16 *data, uint32 len); -void soft_iic_transfer_8bit_array (soft_iic_info_struct *soft_iic_obj, const uint8 *write_data, uint32 write_len, uint8 *read_data, uint32 read_len); -void soft_iic_transfer_16bit_array (soft_iic_info_struct *soft_iic_obj, const uint16 *write_data, uint32 write_len, uint16 *read_data, uint32 read_len); +void soft_iic_transfer_8bit_array(soft_iic_info_struct *soft_iic_obj, const uint8 *write_data, uint32 write_len, uint8 *read_data, uint32 read_len); +void soft_iic_transfer_16bit_array(soft_iic_info_struct *soft_iic_obj, const uint16 *write_data, uint32 write_len, uint16 *read_data, uint32 read_len); -void soft_iic_sccb_write_register (soft_iic_info_struct *soft_iic_obj, const uint8 register_name, uint8 data); -uint8 soft_iic_sccb_read_register (soft_iic_info_struct *soft_iic_obj, const uint8 register_name); +void soft_iic_sccb_write_register(soft_iic_info_struct *soft_iic_obj, const uint8 register_name, uint8 data); +uint8 soft_iic_sccb_read_register(soft_iic_info_struct *soft_iic_obj, const uint8 register_name); -void soft_iic_init (soft_iic_info_struct *soft_iic_obj, uint8 addr, uint32 delay, gpio_pin_enum scl_pin, gpio_pin_enum sda_pin); +void soft_iic_init(soft_iic_info_struct *soft_iic_obj, uint8 addr, uint32 delay, gpio_pin_enum scl_pin, gpio_pin_enum sda_pin); +void eep_soft_iic_write_8bit_registers(soft_iic_info_struct *soft_iic_obj, const uint8 register_name_h, const uint8 register_name_l, const uint8 *data, uint32 len); +void eep_soft_iic_read_8bit_registers(soft_iic_info_struct *soft_iic_obj, const uint8 register_name_h, const uint8 register_name_l, uint8 *data, uint32 len); #endif - From ee1ef4267661534f1978c378c2463ee4d0520eb0 Mon Sep 17 00:00:00 2001 From: bmy <2583236812@qq.com> Date: Sat, 2 Mar 2024 16:02:22 +0800 Subject: [PATCH 17/19] =?UTF-8?q?feat:=20=E5=AE=8C=E6=88=90=E9=80=9A?= =?UTF-8?q?=E4=BF=A1=E9=85=8D=E7=BD=AE?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- app/isr.c | 6 +++--- app/tiny_frame/by_tiny_frame_config.h | 6 +++--- app/tiny_frame/by_tiny_frame_master_read.c | 10 +++++++--- app/tiny_frame/by_tiny_frame_master_write.c | 11 +++++++---- app/tiny_frame/by_tiny_frame_pack.c | 3 +++ app/tiny_frame/by_tiny_frame_pack.h | 2 ++ 6 files changed, 25 insertions(+), 13 deletions(-) diff --git a/app/isr.c b/app/isr.c index cf9dd1c..80284e2 100644 --- a/app/isr.c +++ b/app/isr.c @@ -93,6 +93,9 @@ void USART1_IRQHandler(void) void USART2_IRQHandler(void) { if (USART_GetITStatus(USART2, USART_IT_RXNE) != RESET) { + uint8_t data_s = 0; + uart_query_byte(UART_2, &data_s); + by_tiny_frame_parse_uart_handle(data_s); USART_ClearITPendingBit(USART2, USART_IT_RXNE); } } @@ -102,9 +105,6 @@ void USART3_IRQHandler(void) #if DEBUG_UART_USE_INTERRUPT // debug ж // debug_interrupr_handler(); // debug ڽմ ݻᱻ debug λȡ #endif // ޸ DEBUG_UART_INDEX δҪŵӦĴжȥ - uint8_t data_s = 0; - uart_query_byte(UART_3, &data_s); - by_tiny_frame_parse_uart_handle(data_s); USART_ClearITPendingBit(USART3, USART_IT_RXNE); } } diff --git a/app/tiny_frame/by_tiny_frame_config.h b/app/tiny_frame/by_tiny_frame_config.h index a302e29..c830efa 100644 --- a/app/tiny_frame/by_tiny_frame_config.h +++ b/app/tiny_frame/by_tiny_frame_config.h @@ -3,9 +3,9 @@ #define BY_TF_DEBUG (1) -#define BY_TF_UART_TX_PIN (UART3_MAP0_TX_B10) -#define BY_TF_UART_RX_PIN (UART3_MAP0_RX_B11) -#define BY_TF_UART_INDEX (UART_3) +#define BY_TF_UART_TX_PIN (UART2_MAP0_TX_A2) +#define BY_TF_UART_RX_PIN (UART2_MAP0_RX_A3) +#define BY_TF_UART_INDEX (UART_2) #define BY_TF_UART_BAUDRATE (115200) #define BY_TF_PARSE_BUFFER_SIZE (50) diff --git a/app/tiny_frame/by_tiny_frame_master_read.c b/app/tiny_frame/by_tiny_frame_master_read.c index de3f551..d165a35 100644 --- a/app/tiny_frame/by_tiny_frame_master_read.c +++ b/app/tiny_frame/by_tiny_frame_master_read.c @@ -2,7 +2,6 @@ #if defined(BY_TF_DEVICE_MASTER) -uint8_t read_processing_flag; uint32_t *data_p; void by_tiny_frame_read_run(void) @@ -11,6 +10,11 @@ void by_tiny_frame_read_run(void) void by_tiny_frame_read(uint8_t slave_id, uint16_t reg_addr, uint32_t *data) { + if (by_tiny_frame_pack_lock) { + // 写入忙处理 + return; + } + // 填充数据 by_tf_pack_frame_t frame_s; frame_s.slave_id = slave_id; @@ -27,13 +31,13 @@ void by_tiny_frame_read(uint8_t slave_id, uint16_t reg_addr, uint32_t *data) // 开启响应监听 by_tiny_frame_parse_start_listen(); - read_processing_flag = 1; + by_tiny_frame_pack_lock = 0; } void by_tiny_frame_read_handle(by_tf_parse_frame_t frame_s, uint8_t status) { - read_processing_flag = 0; + by_tiny_frame_pack_lock = 0; if (!status) { *data_p = frame_s.data; } diff --git a/app/tiny_frame/by_tiny_frame_master_write.c b/app/tiny_frame/by_tiny_frame_master_write.c index b2f6f6c..f5adb6a 100644 --- a/app/tiny_frame/by_tiny_frame_master_write.c +++ b/app/tiny_frame/by_tiny_frame_master_write.c @@ -5,8 +5,6 @@ #include "by_tiny_frame_pack.h" #include "by_tiny_frame_parse.h" -uint8_t write_processing_flag; - void by_tiny_frame_write_run(void) { // nothing @@ -14,6 +12,11 @@ void by_tiny_frame_write_run(void) void by_tiny_frame_write(uint8_t slave_id, uint16_t reg_addr, uint32_t data) { + if(by_tiny_frame_pack_lock){ + //写入忙处理 + return; + } + // 填充数据 by_tf_pack_frame_t frame_s; frame_s.slave_id = slave_id; @@ -30,12 +33,12 @@ void by_tiny_frame_write(uint8_t slave_id, uint16_t reg_addr, uint32_t data) // 开启响应监听 by_tiny_frame_parse_start_listen(); - write_processing_flag = 1; + by_tiny_frame_pack_lock = 1; } void by_tiny_frame_write_handle(by_tf_parse_frame_t frame_s, uint8_t status) { - write_processing_flag = 0; + by_tiny_frame_pack_lock = 0; #if (BY_TF_DEBUG) printf("****** WRITE REGISTER DONE ******\r\n"); diff --git a/app/tiny_frame/by_tiny_frame_pack.c b/app/tiny_frame/by_tiny_frame_pack.c index 78107f0..fb6dfbf 100644 --- a/app/tiny_frame/by_tiny_frame_pack.c +++ b/app/tiny_frame/by_tiny_frame_pack.c @@ -4,9 +4,12 @@ #include "zf_common_headfile.h" #include "crc16.h" +uint8_t by_tiny_frame_pack_lock; + void by_tiny_frame_pack_init(void) { /** nothing to init **/ + by_tiny_frame_pack_lock = 0; } void by_tiny_frame_pack_send(by_tf_pack_frame_t *frame_s) diff --git a/app/tiny_frame/by_tiny_frame_pack.h b/app/tiny_frame/by_tiny_frame_pack.h index 70fbb9d..4d44d87 100644 --- a/app/tiny_frame/by_tiny_frame_pack.h +++ b/app/tiny_frame/by_tiny_frame_pack.h @@ -21,4 +21,6 @@ typedef struct by_tf_pack_frame_t { extern void by_tiny_frame_pack_init(void); extern void by_tiny_frame_pack_send(by_tf_pack_frame_t *frame_s); +extern uint8_t by_tiny_frame_pack_lock; + #endif From 00be00f85fff480e2fb4a84d6e2227e01bd21bf2 Mon Sep 17 00:00:00 2001 From: bmy <2583236812@qq.com> Date: Sat, 2 Mar 2024 16:17:34 +0800 Subject: [PATCH 18/19] Merge branch 'master' of http://git.brisky.space:441/btl143/firmware_clover --- app/isr.c | 1 + app/jj_param.c | 93 ++++++---- app/jj_param.h | 48 ++++-- app/main.c | 36 ++-- app/page/page.c | 18 +- app/page/page.h | 20 ++- app/page/page_dparam.c | 72 ++++++++ app/page/page_menu.c | 10 +- app/page/page_param.c | 133 --------------- app/page/page_rtcam.c | 4 +- app/page/page_sparam1.c | 160 ++++++++++++++++++ app/page/page_sparam2.c | 160 ++++++++++++++++++ .../by_tiny_frame_slave_read_write.c | 46 ++--- libraries/zf_device/zf_device_k24c02.h | 2 +- libraries/zf_device/zf_device_mt9v03x_dvp.h | 4 +- libraries/zf_driver/zf_driver_soft_iic.c | 30 ++++ libraries/zf_driver/zf_driver_soft_iic.h | 122 ++++++------- 17 files changed, 646 insertions(+), 313 deletions(-) create mode 100644 app/page/page_dparam.c delete mode 100644 app/page/page_param.c create mode 100644 app/page/page_sparam1.c create mode 100644 app/page/page_sparam2.c diff --git a/app/isr.c b/app/isr.c index 80284e2..127ceb5 100644 --- a/app/isr.c +++ b/app/isr.c @@ -284,6 +284,7 @@ void TIM1_UP_IRQHandler(void) { if (TIM_GetITStatus(TIM1, TIM_IT_Update) != RESET) { TIM_ClearITPendingBit(TIM1, TIM_IT_Update); + by_tiny_frame_parse_timer_handle(); } } diff --git a/app/jj_param.c b/app/jj_param.c index ced4ada..27befa7 100644 --- a/app/jj_param.c +++ b/app/jj_param.c @@ -5,20 +5,67 @@ PARAM_INFO Param_Data[DATA_NUM]; soft_iic_info_struct eeprom_param; TYPE_UNION iic_buffer[DATA_IN_FLASH_NUM]; - -void jj_param_eeprom_init() +uint32_t *addre[2]; +float data0 = 1.0f; +float data1 = 1.05f; +float data2 = 10.0f; +float data3 = 100.0f; +float data4 = 4.0f; +float data5 = 66.0f; +float data6 = 13.130f; +float data7 = 10.0f; +float data8 = 0.0f; +/** + * @brief 参数初始化注册 + * + */ +void jj_param_eeprom_init(void) +{ + soft_iic_init(&eeprom_param, K24C02_DEV_ADDR, K24C02_SOFT_IIC_DELAY, K24C02_SCL_PIN, K24C02_SDA_PIN); // eeprom初始化 + PARAM_REG(angle_Kp, &data0, EFLOAT, 1, "an_P:"); // 注冊 + PARAM_REG(angle_Ki, &data1, EFLOAT, 1, "an_I:"); // 注冊 + PARAM_REG(angle_Kd, &data2, EFLOAT, 1, "an_D:"); // 注冊 + PARAM_REG(imgax_Kp, &data3, EFLOAT, 1, "im_P:"); // 注冊 + PARAM_REG(imgax_Ki, &data4, EFLOAT, 1, "im_I:"); // 注冊 + PARAM_REG(imgax_Kd, &data5, EFLOAT, 1, "im_D:"); + PARAM_REG(other , &data6, EFLOAT, 1, "add:"); + PARAM_REG(delta_x , &data7, EFLOAT, 2, "delta_x:"); + PARAM_REG(delta_y , &data8, EFLOAT, 0, "delta_y:"); + jj_param_read(); // 注冊 +} +/** + * @brief 参数写入 + * + */ +void jj_param_write(void) +{ + for (uint8 i = 0; i < DATA_IN_FLASH_NUM; i++) { + switch (Param_Data[i].type) { + case EFLOAT: + iic_buffer[i].f32 = *((float *)(Param_Data[i].p_data)); + break; + case EUINT32: + iic_buffer[i].u32 = *((uint32 *)(Param_Data[i].p_data)); + break; + case EINT32: + iic_buffer[i].s32 = *((int32 *)(Param_Data[i].p_data)); + break; + default: + break; + } + eep_soft_iic_write_8bit_registers(&eeprom_param, (4 * i) >> 8, (4 * i), (uint8 *)&iic_buffer[i], 4); + system_delay_ms(10); + } +} +/** + * @brief 参数读出 + * + */ +void jj_param_read(void) { - soft_iic_init(&eeprom_param, K24C02_DEV_ADDR, K24C02_SOFT_IIC_DELAY, K24C02_SCL_PIN, K24C02_SDA_PIN); // eeprom 初始化 - // PARAM_REG(angle_Kp, &an_Kp, EFLOAT, 1, "an_P"); // 注冊 - // PARAM_REG(angle_Ki, &an_Ki, EFLOAT, 1, "an_I"); // 注冊 - // PARAM_REG(angle_Kd, &an_Kd, EFLOAT, 1, "an_D"); // 注冊 - // PARAM_REG(imgax_Kp, &im_Kp, EFLOAT, 1, "im_P"); // 注冊 - // PARAM_REG(imgax_Ki, &im_Ki, EFLOAT, 1, "im_I"); // 注冊 - // PARAM_REG(imgax_Kd, &im_Kd, EFLOAT, 1, "im_D"); // 注冊 - for (uint8 i = 0; i < DATA_IN_FLASH_NUM; i++) { - soft_iic_read_8bit_registers(&eeprom_param, 4 * i, (uint8 *)&iic_buffer[i], 4); + eep_soft_iic_read_8bit_registers(&eeprom_param, (4 * i) >> 8, (4 * i), (uint8 *)&iic_buffer[i], 4); switch (Param_Data[i].type) { case EFLOAT: *((float *)(Param_Data[i].p_data)) = @@ -38,27 +85,3 @@ void jj_param_eeprom_init() system_delay_ms(10); } } -/** - * @brief 参数更新 - * - */ -void jj_param_update() -{ - for (uint8 i = 0; i < DATA_IN_FLASH_NUM; i++) { - switch (Param_Data[i].type) { - case EFLOAT: - iic_buffer[i].f32 = *((float *)(Param_Data[i].p_data)); - break; - case EUINT32: - iic_buffer[i].u32 = *((uint32 *)(Param_Data[i].p_data)); - break; - case EINT32: - iic_buffer[i].s32 = *((int32 *)(Param_Data[i].p_data)); - break; - default: - break; - } - soft_iic_write_8bit_registers(&eeprom_param, 4 * i, (uint8 *)&iic_buffer[i], 4); - system_delay_ms(10); - } -} diff --git a/app/jj_param.h b/app/jj_param.h index 3fbe8bb..2e78fdc 100644 --- a/app/jj_param.h +++ b/app/jj_param.h @@ -6,23 +6,34 @@ #include "zf_driver_soft_iic.h" /** * @brief 注册需调参数 - * + * */ -#define PARAM_REG(_data_tag_, _p_data_, _type_, _cmd_,_text_) \ - Param_Data[_data_tag_].p_data = (void *)_p_data_; \ - Param_Data[_data_tag_].type = _type_; \ - Param_Data[_data_tag_].cmd = _cmd_; \ +#define PARAM_REG(_data_tag_, _p_data_, _type_, _cmd_, _text_) \ + Param_Data[_data_tag_].p_data = (void *)_p_data_; \ + Param_Data[_data_tag_].type = _type_; \ + Param_Data[_data_tag_].cmd = _cmd_; \ Param_Data[_data_tag_].text = _text_; - + typedef enum { - DATA_HEAD = -1, - angle_Kp, + + Page1_head=0, + + angle_Kp=Page1_head, angle_Ki, angle_Kd, - imgax_Kp, + other, + + Page2_head, + // 第二页参数 + imgax_Kp=Page2_head, imgax_Ki, imgax_Kd, + + Page3_head, DATA_IN_FLASH_NUM, + + delta_x, + delta_y, DATA_NUM, } data_tag_t; @@ -30,26 +41,27 @@ typedef enum { EUINT32, EINT32, EFLOAT, -}ENUM_TYPE; +} ENUM_TYPE; -typedef union{ +typedef union { uint32_t u32; int32_t s32; float f32; uint8_t u8; -}TYPE_UNION; +} TYPE_UNION; typedef struct { void *p_data; ENUM_TYPE type; - uint8_t cmd; + uint8_t cmd;//01:仅存储 00:仅显示 02:传输并显示 char *text; -}PARAM_INFO; - +} PARAM_INFO; +extern uint32_t * addre[2]; extern soft_iic_info_struct eeprom_param; extern PARAM_INFO Param_Data[DATA_NUM]; extern TYPE_UNION iic_buffer[DATA_IN_FLASH_NUM]; -void jj_param_eeprom_init(); -void jj_param_update(); -void jj_param_show(); +void jj_param_eeprom_init(void); +void jj_param_write(void); +void jj_param_read(void); +extern float data7; #endif \ No newline at end of file diff --git a/app/main.c b/app/main.c index c1c1e31..1d65726 100644 --- a/app/main.c +++ b/app/main.c @@ -57,16 +57,15 @@ int main(void) ips200_init(IPS200_TYPE_SPI); by_led_init(); - by_buzzer_init(); + // by_buzzer_init(); by_button_init(); - // jj_bt_init(); - // jj_param_eeprom_init(); + jj_bt_init(); + jj_param_eeprom_init(); Page_Init(); - - // pit_ms_init(TIM6_PIT, 2); - // pit_ms_init(TIM1_PIT, 2); + + pit_ms_init(TIM1_PIT, 1); by_tiny_frame_init(); printf("start running\r\n"); @@ -79,7 +78,7 @@ int main(void) frame_now.cmd = 0x06; frame_now.data = 0x19260817; - frame_now.reg_addr = 0x4059; + frame_now.reg_addr = 0x00; frame_now.slave_id = 0x0D; /** 测试完成后移除 **/ @@ -87,13 +86,11 @@ int main(void) by_tiny_frame_read(0x0D, 0x4059, &data_test); while (1) { Page_Run(); - by_buzzer_run(); + // by_buzzer_run(); /** 测试完成后移除 **/ - by_tiny_frame_run(); - // by_tiny_frame_pack_send(&frame_now); + by_tiny_frame_pack_send(&frame_now); system_delay_ms(10); - by_tiny_frame_parse_timer_handle(); /** 测试完成后移除 **/ if (mt9v03x_finish_flag) { @@ -103,14 +100,15 @@ int main(void) // ips200_show_gray_image(0, 0, mt9v03x_image_copy[0], MT9V03X_W, MT9V03X_H, MT9V03X_W, MT9V03X_H, 0); mt9v03x_finish_flag = 0; by_led_info_blink(); - state_type = COMMON_STATE; - img_processing(); - get_corners(); - aim_distance = COMMON_AIM; - tracking(); - ElementJudge(); - ElementRun(); - MidLineTrack(); + // state_type = COMMON_STATE; + // img_processing(); + // get_corners(); + // aim_distance = COMMON_AIM; + // tracking(); + // ElementJudge(); + // ElementRun(); + // MidLineTrack(); + } } } diff --git a/app/page/page.c b/app/page/page.c index 942940c..877b879 100644 --- a/app/page/page.c +++ b/app/page/page.c @@ -4,9 +4,13 @@ PAGE_LIST pagelist[page_max]; static uint8_t page_busy = 0; -static int8_t now_page = page_menu; static int8_t new_page = page_menu; +static int8_t now_page = page_menu; +int8_t Get_new_page(void) +{ + return new_page; +} /** * @brief 注册一个基本页面,包含一个初始化函数,循环函数,退出函数,事件函数 * @param pageID: 页面编号 @@ -17,11 +21,11 @@ static int8_t new_page = page_menu; * @param eventCallback: 事件函数回调 * @retval 无 */ -void Page_Register(uint8_t pageID, char *pageText, +void Page_Register(uint8_t pageID, CallbackFunction_t setupCallback, CallbackFunction_t loopCallback, CallbackFunction_t exitCallback, EventFunction_t eventCallback) { - pagelist[pageID].Text = pageText; + pagelist[pageID].SetupCallback = setupCallback; pagelist[pageID].LoopCallback = loopCallback; pagelist[pageID].ExitCallback = exitCallback; @@ -123,9 +127,11 @@ void Page_Run(void) */ void Page_Init(void) { - PAGE_REG(page_menu); - PAGE_REG(page_rtcam); - PAGE_REG(page_param); + PAGE_REG(page_menu, "main"); + PAGE_REG(page_rtcam, "rtcam"); + PAGE_REG(page_param1, "Param1"); + PAGE_REG(page_param2, "param2"); + PAGE_REG(page_dparam, "dparam"); // PAGE_REG(page_argv); // PAGE_REG(page_sys); // PAGE_REG(page_run); diff --git a/app/page/page.h b/app/page/page.h index 3d51e41..7e18f75 100644 --- a/app/page/page.h +++ b/app/page/page.h @@ -20,7 +20,9 @@ enum PageID { //...... page_menu, page_rtcam, - page_param, + page_param1, + page_param2, + page_dparam, // page_argv, // page_sys, // page_run, @@ -46,13 +48,15 @@ typedef struct { } PAGE_LIST; // 页面注册函数 -#define PAGE_REG(name) \ - do { \ - extern void PageRegister_##name(unsigned char pageID); \ - PageRegister_##name(name); \ - } while (0) +#define PAGE_REG(_name_, _text_) \ + do { \ + extern void PageRegister_##_name_(unsigned char pageID); \ + PageRegister_##_name_(_name_); \ + } while (0); \ + pagelist[_name_].Text = _text_ ; -void Page_Register(uint8_t pageID, char *pageText, + +void Page_Register(uint8_t pageID, CallbackFunction_t setupCallback, CallbackFunction_t loopCallback, CallbackFunction_t exitCallback, EventFunction_t eventCallback); @@ -63,7 +67,7 @@ void Page_OpenCurrentPage(void); uint8_t Page_GetStatus(void); void Page_Run(void); void Page_Init(void); +int8_t Get_new_page(void); extern PAGE_LIST pagelist[page_max]; - #endif diff --git a/app/page/page_dparam.c b/app/page/page_dparam.c new file mode 100644 index 0000000..3407df5 --- /dev/null +++ b/app/page/page_dparam.c @@ -0,0 +1,72 @@ +#include "zf_common_headfile.h" +#include "page_ui_widget.h" +#include "page.h" +#include "jj_param.h" +// #define LINE_HEAD 1 +// #define LINE_END 7 +// static int8_t Curser = LINE_HEAD; // 定义光标位置 +// static int8_t Curser_Last = LINE_HEAD; // 定义光标位置 +/*************************************************************************************** + * + * 以下为页面模板函数 + * + ***************************************************************************************/ + +/** + * @brief 页面初始化事件 + * @param 无 + * @retval 无 + */ +static void Setup() +{ + ips200_clear(); + // 显示参数名称 + ips200_show_string(0, 0, "Dparam"); + + ips200_show_string(20, 18 + 2, (Param_Data[delta_x].text)); + ips200_show_string(20, 18 + 20, (Param_Data[delta_y].text)); +} + +/** + * @brief 页面退出事件 + * @param 无 + * @retval 无 + */ +static void Exit() +{ +} + +/** + * @brief 页面循环执行的内容 + * @param 无 + * @retval 无 + */ +static void Loop() +{ + // 刷新参数数值 + ips200_show_float(90, 18 + 2, *((float *)(Param_Data[delta_x].p_data)), 4, 5); + ips200_show_float(90, 18 + 20, *((float *)(Param_Data[delta_x].p_data)), 4, 5); +} + +/** + * @brief 页面事件 + * @param btn:发出事件的按键 + * @param event:事件编号 + * @retval 无 + */ +static void Event(page_event event) +{ + if (page_event_press_long == event) { + Page_Shift(page_menu); + } +} + +/** + * @brief 页面注册函数 + * + * @param pageID + */ +void PageRegister_page_dparam(unsigned char pageID) +{ + Page_Register(pageID, Setup, Loop, Exit, Event); +} diff --git a/app/page/page_menu.c b/app/page/page_menu.c index 8605e47..687499b 100644 --- a/app/page/page_menu.c +++ b/app/page/page_menu.c @@ -25,7 +25,7 @@ static void Setup() { ips200_clear(); Print_Menu_p(); - Print_Curser(Curser, Curser_Last,RGB565_PURPLE); + Print_Curser(Curser, Curser_Last, RGB565_PURPLE); } /** @@ -57,9 +57,9 @@ static void Event(page_event event) Curser_Last = Curser; if (page_event_forward == event) { - Curser--; // 光标上移 + Curser++; // 光标上移 } else if (page_event_backward == event) { - Curser++; // 光标下移 + Curser--; // 光标下移 } else if (page_event_press_short == event) { if (page_max > Curser && page_menu < Curser) { Page_Shift(Curser); // 切换到光标选中的页面 @@ -72,7 +72,7 @@ static void Event(page_event event) Curser = LINE_HEAD; } - Print_Curser(Curser, Curser_Last,RGB565_PURPLE); + Print_Curser(Curser, Curser_Last, RGB565_PURPLE); } /** @@ -82,7 +82,7 @@ static void Event(page_event event) */ void PageRegister_page_menu(unsigned char pageID) { - Page_Register(pageID, Text, Setup, Loop, Exit, Event); + Page_Register(pageID, Setup, Loop, Exit, Event); } /*************************************************************************************** diff --git a/app/page/page_param.c b/app/page/page_param.c deleted file mode 100644 index ef57df5..0000000 --- a/app/page/page_param.c +++ /dev/null @@ -1,133 +0,0 @@ -#include "jj_param.h" -#include "page_ui_widget.h" -#include "page.h" - -#define LINE_HEAD 0 -#define LINE_END DATA_NUM - 2 -static char Text[] = "Param"; -int event_flag = 0; -int32_t index_power = 0; -static int8_t Curser = LINE_HEAD; // 定义光标位置 -static int8_t Curser_Last = LINE_HEAD; // 定义光标位置 -void jj_param_show(); -/*************************************************************************************** - * - * 以下为页面模板函数 - * - ***************************************************************************************/ -/** - * @brief 页面初始化事件 - * @param 无 - * @retval 无 - */ -static void Setup() -{ - ips200_clear(); - Print_Curser(Curser, Curser_Last, RGB565_PURPLE); - for (int16 i = 0; i < DATA_NUM - 1; i++) { - ips200_show_string(10, i * 18 + 2, Param_Data[i].text); - if (Param_Data[i].type == EINT32) - ips200_show_int(50, i * 18 + 2, *((int32 *)(Param_Data[i].p_data)), 5); - else if (Param_Data[i].type == EFLOAT) - ips200_show_float(50, i * 18 + 2, *((float *)(Param_Data[i].p_data)), 4, 5); - } - ips200_show_int(50, (DATA_NUM-1)* 18 + 2, index_power, 5); - -} - -/** - * @brief 页面退出事件 - * @param 无 - * @retval 无 - */ -static void Exit() -{ -} - -/** - * @brief 页面循环执行的内容 - * @param 无 - * @retval 无 - */ -static void Loop() -{ -} -/** - * @brief 页面事件 - * @param btn:发出事件的按键 - * @param event:事件编号 - * @retval 无 - */ -static void Event(page_event event) -{ - - if (0 == event_flag) { - - Curser_Last = Curser; - if (page_event_forward == event) { - Curser--; // 光标上移 - } else if (page_event_backward == event) { - Curser++; // 光标下移 - } else if (page_event_press_short == event) { - event_flag = 1; // 选中参数 - Print_Curser(Curser, Curser_Last, RGB565_RED); - return; - } else if (page_event_press_long == event) { - jj_param_update(); - Page_Shift(page_menu); - return; - } - if (Curser < LINE_HEAD) { - Curser = LINE_END; - } else if (Curser > LINE_END) { - Curser = LINE_HEAD; - } - Print_Curser(Curser, Curser_Last, RGB565_PURPLE); - } else if (1 == event_flag) { - if (page_event_forward == event) { - if (Param_Data[Curser].type == EFLOAT) { - *((float *)(Param_Data[Curser].p_data)) += powf(10.0f,(float)index_power); - } else if (Param_Data[Curser].type == EINT32) { - *((int32 *)(Param_Data[Curser].p_data)) += 1; - } else if (Param_Data[Curser].type == EUINT32) { - *((uint32 *)(Param_Data[Curser].p_data)) += 1; - } - } else if (page_event_backward == event) { - if (Param_Data[Curser].type == EFLOAT) { - *((float *)(Param_Data[Curser].p_data)) -=powf(10.0f,(float)index_power); - } else if (Param_Data[Curser].type == EINT32) { - *((int32 *)(Param_Data[Curser].p_data)) -= 1; - } else if (Param_Data[Curser].type == EUINT32) { - *((uint32 *)(Param_Data[Curser].p_data)) -= 1; - } - } else if (page_event_press_short == event) { - index_power++; - if (index_power > 2) { - index_power = -2; - } - ips200_show_int(50, (DATA_NUM-1)* 18 + 2, index_power, 5); - } else if (page_event_press_long == event) { - event_flag = 0; - Print_Curser(Curser, Curser_Last, RGB565_PURPLE); - } - jj_param_show(); - } -} -void jj_param_show() -{ - if (EINT32 == Param_Data[Curser].type) - ips200_show_int(50, Curser * 18 + 2, *((int32 *)(Param_Data[Curser].p_data)), 5); - else if (EUINT32 == Param_Data[Curser].type) - ips200_show_uint(50, Curser * 18 + 2, *((int32 *)(Param_Data[Curser].p_data)), 5); - else if (EFLOAT == Param_Data[Curser].type) - ips200_show_float(50, Curser * 18 + 2, *((float *)(Param_Data[Curser].p_data)), 4, 5); -} -/** - * @brief 页面注册函数 - * - * @param pageID - */ -void PageRegister_page_param(unsigned char pageID) -{ - Page_Register(pageID, Text, Setup, Loop, Exit, Event); -} diff --git a/app/page/page_rtcam.c b/app/page/page_rtcam.c index 7b479bd..9d520ee 100644 --- a/app/page/page_rtcam.c +++ b/app/page/page_rtcam.c @@ -5,8 +5,6 @@ #define LINE_HEAD 11 #define LINE_END 16 -static char Text[] = "RealTime Image"; - static int8_t Curser = LINE_HEAD; // 定义光标位置 static int8_t Curser_Last = LINE_HEAD; // 定义光标位置 /*************************************************************************************** @@ -81,7 +79,7 @@ static void Event(page_event event) */ void PageRegister_page_rtcam(unsigned char pageID) { - Page_Register(pageID, Text, Setup, Loop, Exit, Event); + Page_Register(pageID, Setup, Loop, Exit, Event); } /*************************************************************************************** diff --git a/app/page/page_sparam1.c b/app/page/page_sparam1.c new file mode 100644 index 0000000..fe425ab --- /dev/null +++ b/app/page/page_sparam1.c @@ -0,0 +1,160 @@ +#include "jj_param.h" +#include "page_ui_widget.h" +#include "page.h" +#include + +#define LINE_HEAD 1 + +static int16 pafrist; +static int16 paend; +static int16 palong; +static int event_flag = 0; +static int32_t index_power = 0; +static int8_t Curser = LINE_HEAD; // 定义光标位置 +static int8_t Curser_Last = LINE_HEAD; // 定义光标位置 +/*************************************************************************************** + * + * 以下为页面模板函数 + * + ***************************************************************************************/ +/** + * @brief 页面初始化事件 + * @param 无 + * @retval 无 + */ +static void Setup() +{ + ips200_clear(); + + if (Get_new_page() == page_param1) { + pafrist = 0; + paend = Page2_head; + ips200_show_string(0, 0, "Param1"); + } else if (Get_new_page() == page_param2) { + pafrist = Page2_head; + paend = Page3_head; + ips200_show_string(0, 0, "Param2"); + } + + palong = paend - pafrist; + if (Curser < LINE_HEAD) { + Curser = palong; + } else if (Curser > palong) { + Curser = LINE_HEAD; + } + Print_Curser(Curser, Curser_Last, RGB565_PURPLE); + for (int16 i = 0; i < palong; i++) { + ips200_show_string(20, i * 18 + 20, Param_Data[i + pafrist].text); + if (Param_Data[i].type == EINT32) + ips200_show_int(60, i * 18 + 20, *((int32 *)(Param_Data[i + pafrist].p_data)), 5); + else if (Param_Data[i].type == EFLOAT) + ips200_show_float(60, i * 18 + 20, *((float *)(Param_Data[i + pafrist].p_data)), 4, 5); + } + ips200_show_int(50, palong * 18 + 20, index_power, 5); +} + +/** + * @brief 页面退出事件 + * @param 无 + * @retval 无 + */ +static void Exit() +{ +} + +/** + * @brief 页面循环执行的内容 + * @param 无 + * @retval 无 + */ +static void Loop() +{ +} +/** + * @brief 页面事件 + * @param btn:发出事件的按键 + * @param event:事件编号 + * @retval 无 + */ +static void Event(page_event event) +{ + + if (0 == event_flag) { + + Curser_Last = Curser; + if (page_event_forward == event) { + Curser++; // 光标上移 + } else if (page_event_backward == event) { + Curser--; // 光标下移 + } else if (page_event_press_short == event) { + event_flag = 1; // 选中参数 + Print_Curser(Curser, Curser_Last, RGB565_RED); + return; + } else if (page_event_press_long == event) { + jj_param_write(); + Page_Shift(page_menu); + return; + } + if (Curser < LINE_HEAD) { + Curser = palong; + } else if (Curser > palong) { + Curser = LINE_HEAD; + } + Print_Curser(Curser, Curser_Last, RGB565_PURPLE); + } else if (1 == event_flag) { + if (page_event_forward == event) { + switch (Param_Data[Curser + pafrist - 1].type) { + case EFLOAT: + *((float *)(Param_Data[Curser + pafrist - 1].p_data)) += powf(10, index_power); + break; + case EINT32: + *((int32 *)(Param_Data[Curser + pafrist - 1].p_data)) += 1; + break; + case EUINT32: + *((uint32 *)(Param_Data[Curser + pafrist - 1].p_data)) += 1; + break; + default: + break; + } + } else if (page_event_backward == event) { + switch (Param_Data[Curser + pafrist - 1].type) { + case EFLOAT: + *((float *)(Param_Data[Curser + pafrist - 1].p_data)) -= powf(10.0f, (float)index_power); + break; + case EINT32: + *((int32 *)(Param_Data[Curser + pafrist - 1].p_data)) -= 1; + break; + case EUINT32: + *((uint32 *)(Param_Data[Curser + pafrist - 1].p_data)) -= 1; + break; + default: + break; + } + } else if (page_event_press_short == event) { + index_power++; + if (index_power > 2) { + index_power = -2; + } + ips200_show_int(50, palong * 18 + 20, index_power, 5); + } else if (page_event_press_long == event) { + event_flag = 0; + Print_Curser(Curser, Curser_Last, RGB565_PURPLE); + } + if (EINT32 == Param_Data[Curser + pafrist - 1].type) + ips200_show_int(60, Curser * 18 + 2, *((int32 *)(Param_Data[Curser + pafrist - 1].p_data)), 5); + else if (EUINT32 == Param_Data[Curser + pafrist - 1].type) + ips200_show_uint(60, Curser * 18 + 2, *((int32 *)(Param_Data[Curser + pafrist - 1].p_data)), 5); + else if (EFLOAT == Param_Data[Curser + pafrist - 1].type) + ips200_show_float(60, Curser * 18 + 2, *((float *)(Param_Data[Curser + pafrist - 1].p_data)), 4, 5); + } +} + +/** + * @brief 页面注册函数 + * + * @param pageID + */ +void PageRegister_page_param1(unsigned char pageID) +{ + Page_Register(pageID, Setup, Loop, Exit, Event); +} diff --git a/app/page/page_sparam2.c b/app/page/page_sparam2.c new file mode 100644 index 0000000..2335b13 --- /dev/null +++ b/app/page/page_sparam2.c @@ -0,0 +1,160 @@ +#include "jj_param.h" +#include "page_ui_widget.h" +#include "page.h" +#include + +#define LINE_HEAD 1 + +static int16 pafrist; +static int16 paend; +static int16 palong; +static int event_flag = 0; +static int32_t index_power = 0; +static int8_t Curser = LINE_HEAD; // 定义光标位置 +static int8_t Curser_Last = LINE_HEAD; // 定义光标位置 +/*************************************************************************************** + * + * 以下为页面模板函数 + * + ***************************************************************************************/ +/** + * @brief 页面初始化事件 + * @param 无 + * @retval 无 + */ +static void Setup() +{ + ips200_clear(); + + if (Get_new_page() == page_param1) { + pafrist = 0; + paend = Page2_head; + ips200_show_string(0, 0, "Param1"); + } else if (Get_new_page() == page_param2) { + pafrist = Page2_head; + paend = Page3_head; + ips200_show_string(0, 0, "Param2"); + } + + palong = paend - pafrist; + if (Curser < LINE_HEAD) { + Curser = palong; + } else if (Curser > palong) { + Curser = LINE_HEAD; + } + Print_Curser(Curser, Curser_Last, RGB565_PURPLE); + for (int16 i = 0; i < palong; i++) { + ips200_show_string(20, i * 18 + 20, Param_Data[i + pafrist].text); + if (Param_Data[i].type == EINT32) + ips200_show_int(60, i * 18 + 20, *((int32 *)(Param_Data[i + pafrist].p_data)), 5); + else if (Param_Data[i].type == EFLOAT) + ips200_show_float(60, i * 18 + 20, *((float *)(Param_Data[i + pafrist].p_data)), 4, 5); + } + ips200_show_int(50, palong * 18 + 20, index_power, 5); +} + +/** + * @brief 页面退出事件 + * @param 无 + * @retval 无 + */ +static void Exit() +{ +} + +/** + * @brief 页面循环执行的内容 + * @param 无 + * @retval 无 + */ +static void Loop() +{ +} +/** + * @brief 页面事件 + * @param btn:发出事件的按键 + * @param event:事件编号 + * @retval 无 + */ +static void Event(page_event event) +{ + + if (0 == event_flag) { + + Curser_Last = Curser; + if (page_event_forward == event) { + Curser++; // 光标上移 + } else if (page_event_backward == event) { + Curser--; // 光标下移 + } else if (page_event_press_short == event) { + event_flag = 1; // 选中参数 + Print_Curser(Curser, Curser_Last, RGB565_RED); + return; + } else if (page_event_press_long == event) { + jj_param_write(); + Page_Shift(page_menu); + return; + } + if (Curser < LINE_HEAD) { + Curser = palong; + } else if (Curser > palong) { + Curser = LINE_HEAD; + } + Print_Curser(Curser, Curser_Last, RGB565_PURPLE); + } else if (1 == event_flag) { + if (page_event_forward == event) { + switch (Param_Data[Curser + pafrist - 1].type) { + case EFLOAT: + *((float *)(Param_Data[Curser + pafrist - 1].p_data)) += powf(10, index_power); + break; + case EINT32: + *((int32 *)(Param_Data[Curser + pafrist - 1].p_data)) += 1; + break; + case EUINT32: + *((uint32 *)(Param_Data[Curser + pafrist - 1].p_data)) += 1; + break; + default: + break; + } + } else if (page_event_backward == event) { + switch (Param_Data[Curser + pafrist - 1].type) { + case EFLOAT: + *((float *)(Param_Data[Curser + pafrist - 1].p_data)) -= powf(10.0f, (float)index_power); + break; + case EINT32: + *((int32 *)(Param_Data[Curser + pafrist - 1].p_data)) -= 1; + break; + case EUINT32: + *((uint32 *)(Param_Data[Curser + pafrist - 1].p_data)) -= 1; + break; + default: + break; + } + } else if (page_event_press_short == event) { + index_power++; + if (index_power > 2) { + index_power = -2; + } + ips200_show_int(50, palong * 18 + 20, index_power, 5); + } else if (page_event_press_long == event) { + event_flag = 0; + Print_Curser(Curser, Curser_Last, RGB565_PURPLE); + } + if (EINT32 == Param_Data[Curser + pafrist - 1].type) + ips200_show_int(60, Curser * 18 + 2, *((int32 *)(Param_Data[Curser + pafrist - 1].p_data)), 5); + else if (EUINT32 == Param_Data[Curser + pafrist - 1].type) + ips200_show_uint(60, Curser * 18 + 2, *((int32 *)(Param_Data[Curser + pafrist - 1].p_data)), 5); + else if (EFLOAT == Param_Data[Curser + pafrist - 1].type) + ips200_show_float(60, Curser * 18 + 2, *((float *)(Param_Data[Curser + pafrist - 1].p_data)), 4, 5); + } +} + +/** + * @brief 页面注册函数 + * + * @param pageID + */ +void PageRegister_page_param2(unsigned char pageID) +{ + Page_Register(pageID, Setup, Loop, Exit, Event); +} \ No newline at end of file diff --git a/app/tiny_frame/by_tiny_frame_slave_read_write.c b/app/tiny_frame/by_tiny_frame_slave_read_write.c index c0fd7c4..df356c0 100644 --- a/app/tiny_frame/by_tiny_frame_slave_read_write.c +++ b/app/tiny_frame/by_tiny_frame_slave_read_write.c @@ -6,6 +6,8 @@ #include "by_tiny_frame_parse.h" #include "by_tiny_frame_pack.h" +#include "jj_param.h" + void by_tiny_frame_read_write_run(void) { // empty @@ -13,31 +15,31 @@ void by_tiny_frame_read_write_run(void) void by_tiny_frame_read_write_handle(by_tf_parse_frame_t frame_s, uint8_t status) { - by_tf_pack_frame_t frame_pack_s; +// by_tf_pack_frame_t frame_pack_s; - frame_pack_s.slave_id = BY_TF_DEVICE_SLAVE_ADDRESS; - frame_pack_s.cmd = frame_s.cmd; - frame_pack_s.reg_addr = frame_s.reg_addr; +// frame_pack_s.slave_id = BY_TF_DEVICE_SLAVE_ADDRESS; +// frame_pack_s.cmd = frame_s.cmd; +// frame_pack_s.reg_addr = frame_s.reg_addr; - if (status) { - // 接收出错,一般为 CRC 校验错误 - return; - } +// if (status) { +// // 接收出错,一般为 CRC 校验错误 +// return; +// } - switch (frame_s.cmd) { - case 0x03: - // 添加查询接口,操作完成后应答 - frame_pack_s.data = 0XFFFFFFFF; // 示例 - by_tiny_frame_pack_send(&frame_pack_s); - break; - case 0x06: - // 添加写入接口,操作完成后应答 - frame_pack_s.data = frame_s.data; - by_tiny_frame_pack_send(&frame_pack_s); - break; - default: - break; - } +// switch (frame_s.cmd) { +// case 0x03: +// // 添加查询接口,操作完成后应答,主机接收,即读取 +// frame_pack_s.data =(uint32_t)(addre[frame_pack_s.reg_addr]); +// by_tiny_frame_pack_send(&frame_pack_s); +// break; +// case 0x06: +// // 添加写入接口,操作完成后应答,主机发送,即写入 +// *addre[frame_pack_s.reg_addr] = frame_pack_s.data; +// by_tiny_frame_pack_send(&frame_pack_s); +// break; +// default: +// break; +// } #if (BY_TF_DEBUG) printf("****** EXECUTE CMD SUCCESSFUL ******\r\n"); diff --git a/libraries/zf_device/zf_device_k24c02.h b/libraries/zf_device/zf_device_k24c02.h index b8f479c..f4ca366 100644 --- a/libraries/zf_device/zf_device_k24c02.h +++ b/libraries/zf_device/zf_device_k24c02.h @@ -55,7 +55,7 @@ //==================================================== IIC ==================================================== #define K24C02_SOFT_IIC_DELAY (500) // IIC ʱʱ ֵԽС IIC ͨԽ #define K24C02_SCL_PIN (D13) // IIC SCL K24C02 SCL -#define K24C02_SDA_PIN (D14) // IIC SDA K24C02 SDA +#define K24C02_SDA_PIN (D12) // IIC SDA K24C02 SDA //==================================================== IIC ==================================================== #else //====================================================Ӳ IIC ==================================================== diff --git a/libraries/zf_device/zf_device_mt9v03x_dvp.h b/libraries/zf_device/zf_device_mt9v03x_dvp.h index c1b8d56..14890a2 100644 --- a/libraries/zf_device/zf_device_mt9v03x_dvp.h +++ b/libraries/zf_device/zf_device_mt9v03x_dvp.h @@ -95,7 +95,7 @@ #define MT9V03X_IMAGE_SIZE ( MT9V03X_W * MT9V03X_H ) // ͼСܳ 65535 #define MT9V03X_COF_BUFFER_SIZE ( 64 ) // ôڻС 64 -#define MT9V03X_AUTO_EXP_DEF (0 ) // Զع ĬϲԶع Χ [0-63] 0 Ϊر +#define MT9V03X_AUTO_EXP_DEF (0 ) // Զع ĬϲԶع Χ [0-63] 0 Ϊر // Զع⿪ EXP_TIME Զعʱ // һDzҪԶع ߷dzȵԳԶع⣬ͼȶ #define MT9V03X_EXP_TIME_DEF (512) // عʱ ͷյԶعʱ䣬ùΪعֵ @@ -104,7 +104,7 @@ // ͷƫݺԶƫƣüƫ #define MT9V03X_UD_OFFSET_DEF (0 ) // ͼƫ ֵ ƫ ֵ ƫ Ϊ 120 240 480 ʱ޷ƫ // ͷƫݺԶƫƣüƫ -#define MT9V03X_GAIN_DEF (32 ) // ͼ Χ [16-64] عʱ̶¸ıͼ̶ +#define MT9V03X_GAIN_DEF (64 ) // ͼ Χ [16-64] عʱ̶¸ıͼ̶ #define MT9V03X_PCLK_MODE_DEF (1 ) // ʱģʽ Χ [0-1] Ĭϣ0 ѡΪ[0źţ1ź] // ͨΪ 0ʹ CH32V307 DVP ӿڻ STM32 DCMI ӿڲɼҪΪ 1 // MT9V034 V1.5 Լϰ汾ָ֧ diff --git a/libraries/zf_driver/zf_driver_soft_iic.c b/libraries/zf_driver/zf_driver_soft_iic.c index 61094df..7f322e2 100644 --- a/libraries/zf_driver/zf_driver_soft_iic.c +++ b/libraries/zf_driver/zf_driver_soft_iic.c @@ -709,3 +709,33 @@ void soft_iic_init (soft_iic_info_struct *soft_iic_obj, uint8 addr, uint32 delay gpio_init(scl_pin, GPO, GPIO_HIGH, GPO_PUSH_PULL); // ȡӦIO AFܱ gpio_init(sda_pin, GPO, GPIO_HIGH, GPO_OPEN_DTAIN); // ȡӦIO AFܱ } +void eep_soft_iic_read_8bit_registers (soft_iic_info_struct *soft_iic_obj, const uint8 register_name_h, const uint8 register_name_l, uint8 *data, uint32 len) +{ + zf_assert(soft_iic_obj != NULL); + zf_assert(data != NULL); + soft_iic_start(soft_iic_obj); + soft_iic_send_data(soft_iic_obj, soft_iic_obj->addr << 1); + soft_iic_send_data(soft_iic_obj, register_name_h); + soft_iic_send_data(soft_iic_obj, register_name_l); + soft_iic_start(soft_iic_obj); + soft_iic_send_data(soft_iic_obj, soft_iic_obj->addr << 1 | 0x01); + while(len --) + { + *data ++ = soft_iic_read_data(soft_iic_obj, len == 0); + } + soft_iic_stop(soft_iic_obj); +} +void eep_soft_iic_write_8bit_registers (soft_iic_info_struct *soft_iic_obj, const uint8 register_name_h,const uint8 register_name_l, const uint8 *data, uint32 len) +{ + zf_assert(soft_iic_obj != NULL); + zf_assert(data != NULL); + soft_iic_start(soft_iic_obj); + soft_iic_send_data(soft_iic_obj, soft_iic_obj->addr << 1); + soft_iic_send_data(soft_iic_obj, register_name_h); + soft_iic_send_data(soft_iic_obj, register_name_l); + while(len --) + { + soft_iic_send_data(soft_iic_obj, *data ++); + } + soft_iic_stop(soft_iic_obj); +} \ No newline at end of file diff --git a/libraries/zf_driver/zf_driver_soft_iic.h b/libraries/zf_driver/zf_driver_soft_iic.h index 1323324..5a9be20 100644 --- a/libraries/zf_driver/zf_driver_soft_iic.h +++ b/libraries/zf_driver/zf_driver_soft_iic.h @@ -1,83 +1,83 @@ /********************************************************************************************************************* -* CH32V307VCT6 Opensourec Library CH32V307VCT6 Դ⣩һڹٷ SDK ӿڵĵԴ -* Copyright (c) 2022 SEEKFREE ɿƼ -* -* ļCH32V307VCT6 Դһ -* -* CH32V307VCT6 Դ -* Ըᷢ GPLGNU General Public License GNUͨù֤ -* GPL ĵ3棨 GPL3.0ѡģκκİ汾·/޸ -* -* Դķϣܷãδκεı֤ -* ûԻʺض;ı֤ -* ϸμ GPL -* -* ӦյԴͬʱյһ GPL ĸ -* ûУ -* -* ע -* Դʹ GPL3.0 Դ֤Э Ϊİ汾 -* Ӣİ libraries/doc ļµ GPL3_permission_statement.txt ļ -* ֤ libraries ļ ļµ LICENSE ļ -* ӭλʹò ޸ʱ뱣ɿƼİȨ -* -* ļ zf_driver_soft_iic -* ˾ ɶɿƼ޹˾ -* 汾Ϣ 鿴 libraries/doc ļ version ļ 汾˵ -* MounRiver Studio V1.8.1 -* ƽ̨ CH32V307VCT6 -* https://seekfree.taobao.com/ -* -* ޸ļ¼ -* ע -* 2022-09-15 W first version -********************************************************************************************************************/ + * CH32V307VCT6 Opensourec Library CH32V307VCT6 Դ⣩һڹٷ SDK ӿڵĵԴ + * Copyright (c) 2022 SEEKFREE ɿƼ + * + * ļCH32V307VCT6 Դһ + * + * CH32V307VCT6 Դ + * Ըᷢ GPLGNU General Public License GNUͨù֤ + * GPL ĵ3棨 GPL3.0ѡģκκİ汾·/޸ + * + * Դķϣܷãδκεı֤ + * ûԻʺض;ı֤ + * ϸμ GPL + * + * ӦյԴͬʱյһ GPL ĸ + * ûУ + * + * ע + * Դʹ GPL3.0 Դ֤Э Ϊİ汾 + * Ӣİ libraries/doc ļµ GPL3_permission_statement.txt ļ + * ֤ libraries ļ ļµ LICENSE ļ + * ӭλʹò ޸ʱ뱣ɿƼİȨ + * + * ļ zf_driver_soft_iic + * ˾ ɶɿƼ޹˾ + * 汾Ϣ 鿴 libraries/doc ļ version ļ 汾˵ + * MounRiver Studio V1.8.1 + * ƽ̨ CH32V307VCT6 + * https://seekfree.taobao.com/ + * + * ޸ļ¼ + * ע + * 2022-09-15 W first version + ********************************************************************************************************************/ #ifndef _zf_driver_soft_iic_h_ #define _zf_driver_soft_iic_h_ - #include "zf_driver_gpio.h" typedef struct { - gpio_pin_enum scl_pin; // ڼ¼Ӧű - gpio_pin_enum sda_pin; // ڼ¼Ӧű - uint8 addr; // ַ λַģʽ - uint32 delay; // ģ IIC ʱʱ -}soft_iic_info_struct; + gpio_pin_enum scl_pin; // ڼ¼Ӧű + gpio_pin_enum sda_pin; // ڼ¼Ӧű + uint8 addr; // ַ λַģʽ + uint32 delay; // ģ IIC ʱʱ +} soft_iic_info_struct; -void soft_iic_write_8bit (soft_iic_info_struct *soft_iic_obj, const uint8 data); -void soft_iic_write_8bit_array (soft_iic_info_struct *soft_iic_obj, const uint8 *data, uint32 len); +void soft_iic_write_8bit(soft_iic_info_struct *soft_iic_obj, const uint8 data); +void soft_iic_write_8bit_array(soft_iic_info_struct *soft_iic_obj, const uint8 *data, uint32 len); -void soft_iic_write_16bit (soft_iic_info_struct *soft_iic_obj, const uint16 data); -void soft_iic_write_16bit_array (soft_iic_info_struct *soft_iic_obj, const uint16 *data, uint32 len); +void soft_iic_write_16bit(soft_iic_info_struct *soft_iic_obj, const uint16 data); +void soft_iic_write_16bit_array(soft_iic_info_struct *soft_iic_obj, const uint16 *data, uint32 len); -void soft_iic_write_8bit_register (soft_iic_info_struct *soft_iic_obj, const uint8 register_name, const uint8 data); -void soft_iic_write_8bit_registers (soft_iic_info_struct *soft_iic_obj, const uint8 register_name, const uint8 *data, uint32 len); +void soft_iic_write_8bit_register(soft_iic_info_struct *soft_iic_obj, const uint8 register_name, const uint8 data); +void soft_iic_write_8bit_registers(soft_iic_info_struct *soft_iic_obj, const uint8 register_name, const uint8 *data, uint32 len); -void soft_iic_write_16bit_register (soft_iic_info_struct *soft_iic_obj, const uint16 register_name, const uint16 data); -void soft_iic_write_16bit_registers (soft_iic_info_struct *soft_iic_obj, const uint16 register_name, const uint16 *data, uint32 len); +void soft_iic_write_16bit_register(soft_iic_info_struct *soft_iic_obj, const uint16 register_name, const uint16 data); +void soft_iic_write_16bit_registers(soft_iic_info_struct *soft_iic_obj, const uint16 register_name, const uint16 *data, uint32 len); -uint8 soft_iic_read_8bit (soft_iic_info_struct *soft_iic_obj); -void soft_iic_read_8bit_array (soft_iic_info_struct *soft_iic_obj, uint8 *data, uint32 len); +uint8 soft_iic_read_8bit(soft_iic_info_struct *soft_iic_obj); +void soft_iic_read_8bit_array(soft_iic_info_struct *soft_iic_obj, uint8 *data, uint32 len); -uint16 soft_iic_read_16bit (soft_iic_info_struct *soft_iic_obj); -void soft_iic_read_16bit_array (soft_iic_info_struct *soft_iic_obj, uint16 *data, uint32 len); +uint16 soft_iic_read_16bit(soft_iic_info_struct *soft_iic_obj); +void soft_iic_read_16bit_array(soft_iic_info_struct *soft_iic_obj, uint16 *data, uint32 len); -uint8 soft_iic_read_8bit_register (soft_iic_info_struct *soft_iic_obj, const uint8 register_name); -void soft_iic_read_8bit_registers (soft_iic_info_struct *soft_iic_obj, const uint8 register_name, uint8 *data, uint32 len); +uint8 soft_iic_read_8bit_register(soft_iic_info_struct *soft_iic_obj, const uint8 register_name); +void soft_iic_read_8bit_registers(soft_iic_info_struct *soft_iic_obj, const uint8 register_name, uint8 *data, uint32 len); -uint16 soft_iic_read_16bit_register (soft_iic_info_struct *soft_iic_obj, const uint16 register_name); -void soft_iic_read_16bit_registers (soft_iic_info_struct *soft_iic_obj, const uint16 register_name, uint16 *data, uint32 len); +uint16 soft_iic_read_16bit_register(soft_iic_info_struct *soft_iic_obj, const uint16 register_name); +void soft_iic_read_16bit_registers(soft_iic_info_struct *soft_iic_obj, const uint16 register_name, uint16 *data, uint32 len); -void soft_iic_transfer_8bit_array (soft_iic_info_struct *soft_iic_obj, const uint8 *write_data, uint32 write_len, uint8 *read_data, uint32 read_len); -void soft_iic_transfer_16bit_array (soft_iic_info_struct *soft_iic_obj, const uint16 *write_data, uint32 write_len, uint16 *read_data, uint32 read_len); +void soft_iic_transfer_8bit_array(soft_iic_info_struct *soft_iic_obj, const uint8 *write_data, uint32 write_len, uint8 *read_data, uint32 read_len); +void soft_iic_transfer_16bit_array(soft_iic_info_struct *soft_iic_obj, const uint16 *write_data, uint32 write_len, uint16 *read_data, uint32 read_len); -void soft_iic_sccb_write_register (soft_iic_info_struct *soft_iic_obj, const uint8 register_name, uint8 data); -uint8 soft_iic_sccb_read_register (soft_iic_info_struct *soft_iic_obj, const uint8 register_name); +void soft_iic_sccb_write_register(soft_iic_info_struct *soft_iic_obj, const uint8 register_name, uint8 data); +uint8 soft_iic_sccb_read_register(soft_iic_info_struct *soft_iic_obj, const uint8 register_name); -void soft_iic_init (soft_iic_info_struct *soft_iic_obj, uint8 addr, uint32 delay, gpio_pin_enum scl_pin, gpio_pin_enum sda_pin); +void soft_iic_init(soft_iic_info_struct *soft_iic_obj, uint8 addr, uint32 delay, gpio_pin_enum scl_pin, gpio_pin_enum sda_pin); +void eep_soft_iic_write_8bit_registers(soft_iic_info_struct *soft_iic_obj, const uint8 register_name_h, const uint8 register_name_l, const uint8 *data, uint32 len); +void eep_soft_iic_read_8bit_registers(soft_iic_info_struct *soft_iic_obj, const uint8 register_name_h, const uint8 register_name_l, uint8 *data, uint32 len); #endif - From 79f03ae6b47d76a92d972c1a275e82f1b7241b33 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?=E4=BA=95=E6=98=8E=E6=B1=9F?= <246462502@qq.com> Date: Sat, 2 Mar 2024 18:17:30 +0800 Subject: [PATCH 19/19] =?UTF-8?q?fix:=20=E9=80=9A=E4=BF=A1bug=E4=BF=AE?= =?UTF-8?q?=E5=A4=8D=E5=8F=8A=E6=B5=8B=E8=AF=95?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- app/jj_param.c | 1 + app/jj_param.h | 2 +- app/main.c | 34 +++++++--------------------- app/tiny_frame/by_tiny_frame.c | 1 + app/tiny_frame/by_tiny_frame_parse.h | 1 + 5 files changed, 12 insertions(+), 27 deletions(-) diff --git a/app/jj_param.c b/app/jj_param.c index 27befa7..05dbe4b 100644 --- a/app/jj_param.c +++ b/app/jj_param.c @@ -5,6 +5,7 @@ PARAM_INFO Param_Data[DATA_NUM]; soft_iic_info_struct eeprom_param; TYPE_UNION iic_buffer[DATA_IN_FLASH_NUM]; +TYPE_UNION tiny_frame_param[20]; uint32_t *addre[2]; float data0 = 1.0f; float data1 = 1.05f; diff --git a/app/jj_param.h b/app/jj_param.h index 2e78fdc..9abf6ff 100644 --- a/app/jj_param.h +++ b/app/jj_param.h @@ -56,10 +56,10 @@ typedef struct { uint8_t cmd;//01:仅存储 00:仅显示 02:传输并显示 char *text; } PARAM_INFO; -extern uint32_t * addre[2]; extern soft_iic_info_struct eeprom_param; extern PARAM_INFO Param_Data[DATA_NUM]; extern TYPE_UNION iic_buffer[DATA_IN_FLASH_NUM]; +extern TYPE_UNION tiny_frame_param[20]; void jj_param_eeprom_init(void); void jj_param_write(void); void jj_param_read(void); diff --git a/app/main.c b/app/main.c index 1d65726..4d96157 100644 --- a/app/main.c +++ b/app/main.c @@ -46,7 +46,6 @@ void test(by_tf_parse_frame_t frame_s, uint8_t status) printf("hhhhhhok\r\n"); } } - int main(void) { @@ -57,42 +56,26 @@ int main(void) ips200_init(IPS200_TYPE_SPI); by_led_init(); - // by_buzzer_init(); + // by_buzzer_init(); by_button_init(); jj_bt_init(); jj_param_eeprom_init(); Page_Init(); - - pit_ms_init(TIM1_PIT, 1); + + pit_ms_init(TIM1_PIT, 1); by_tiny_frame_init(); printf("start running\r\n"); - - /** 测试完成后移除 **/ - // by_tiny_frame_parse_handle_register(test); - // by_tiny_frame_parse_start_listen(); - - by_tf_pack_frame_t frame_now; - - frame_now.cmd = 0x06; - frame_now.data = 0x19260817; - frame_now.reg_addr = 0x00; - frame_now.slave_id = 0x0D; - /** 测试完成后移除 **/ - - // by_tiny_frame_write(0x0D, 0x4059, 0x19260817); - by_tiny_frame_read(0x0D, 0x4059, &data_test); + tiny_frame_param[0].f32 = 100.5f; + // by_tiny_frame_read(0x0D, 0x4059, &data_test); while (1) { Page_Run(); - // by_buzzer_run(); - - /** 测试完成后移除 **/ - by_tiny_frame_pack_send(&frame_now); + // by_buzzer_run(); + by_tiny_frame_write(0x0D, 0x0000, tiny_frame_param[0].u32); + by_tiny_frame_run(); system_delay_ms(10); - /** 测试完成后移除 **/ - if (mt9v03x_finish_flag) { // 该操作消耗大概 1970 个 tick,折合约 110us memcpy(mt9v03x_image_copy[0], mt9v03x_image[0], (sizeof(mt9v03x_image_copy) / sizeof(uint8_t))); @@ -108,7 +91,6 @@ int main(void) // ElementJudge(); // ElementRun(); // MidLineTrack(); - } } } diff --git a/app/tiny_frame/by_tiny_frame.c b/app/tiny_frame/by_tiny_frame.c index 86acd75..e682f71 100644 --- a/app/tiny_frame/by_tiny_frame.c +++ b/app/tiny_frame/by_tiny_frame.c @@ -18,6 +18,7 @@ void by_tiny_frame_init(void) uart_rx_interrupt(BY_TF_UART_INDEX, ENABLE); by_tiny_frame_parse_init(); + by_tiny_frame_pack_init(); #if defined(BY_TF_DEVICE_SLAVE) by_tiny_frame_parse_handle_register(by_tiny_frame_read_write_handle); diff --git a/app/tiny_frame/by_tiny_frame_parse.h b/app/tiny_frame/by_tiny_frame_parse.h index 4ac6c0e..1dcb0a5 100644 --- a/app/tiny_frame/by_tiny_frame_parse.h +++ b/app/tiny_frame/by_tiny_frame_parse.h @@ -22,6 +22,7 @@ typedef void (*by_tf_parse_done_handle_func)(by_tf_parse_frame_t, uint8_t); extern void by_tiny_frame_parse_init(void); extern void by_tiny_frame_parse_uart_handle(uint8_t buff); +extern void by_tiny_frame_parse_timer_handle(void); extern void by_tiny_frame_parse_run(void); extern uint8_t by_tiny_frame_parse_crc(by_tf_parse_frame_t *frame_s); extern void by_tiny_frame_parse_handle_register(by_tf_parse_done_handle_func func);