Compare commits
36 Commits
42c8f0bc1b
...
feature/ct
| Author | SHA1 | Date | |
|---|---|---|---|
| 3e7c5c5089 | |||
| 76ba24e527 | |||
| dd8c727f0b | |||
| 843e74ded0 | |||
| 527585217c | |||
| d3d896a419 | |||
| a690f3a209 | |||
| d7e25af8bf | |||
| 40e0ca1d0c | |||
| 26f5cfe3ce | |||
| 6d313aaa54 | |||
| 2bc91de389 | |||
| 99d4347938 | |||
| 8c0137a59c | |||
| f0f71f3252 | |||
| f729829cb2 | |||
| b4dd5c789c | |||
| 0f8a5ca047 | |||
| ec33dab706 | |||
| 45ef68b74d | |||
| 07dd185e7c | |||
| 32daa4bce9 | |||
| fc4687428b | |||
| 7b4fdb73e9 | |||
| 43d30bb283 | |||
| 317e3bbd25 | |||
| 83e4959c09 | |||
| 408d99783a | |||
| aed378588d | |||
| a54a54286e | |||
| ea5e75d8fc | |||
| 79e27902ec | |||
| 762a4da61e | |||
| 66935e66ce | |||
| d387c26596 | |||
| 7d30ec0355 |
@@ -1 +1 @@
|
|||||||
[]
|
[{"node":"ADC1","expanded":true,"format":0,"pinned":false}]
|
||||||
17
firmware/.vscode/c_cpp_properties.json
vendored
17
firmware/.vscode/c_cpp_properties.json
vendored
@@ -3,16 +3,25 @@
|
|||||||
{
|
{
|
||||||
"name": "Win32",
|
"name": "Win32",
|
||||||
"includePath": [
|
"includePath": [
|
||||||
"${workspaceFolder}/func_gen_stm32f303re_nucleo/Core/**",
|
"${workspaceFolder}/func_gen_stm32f303re_nucleo/Core/Inc",
|
||||||
"${workspaceFolder}/func_gen_stm32f303re_nucleo/Drivers/**",
|
"${workspaceFolder}/func_gen_stm32f303re_nucleo/Drivers/CMSIS/Core/Include",
|
||||||
"${workspaceFolder}/shared_libs/**"
|
"${workspaceFolder}/func_gen_stm32f303re_nucleo/Drivers/CMSIS/Device/ST/STM32F3xx/Include",
|
||||||
|
"${workspaceFolder}/func_gen_stm32f303re_nucleo/Drivers/STM32F3xx_HAL_Driver/Inc",
|
||||||
|
"${workspaceFolder}/shared_libs",
|
||||||
|
"${workspaceFolder}/shared_libs/bitmaps",
|
||||||
|
"${workspaceFolder}/shared_libs/controllers",
|
||||||
|
"${workspaceFolder}/shared_libs/disp_layout",
|
||||||
|
"${workspaceFolder}/shared_libs/display",
|
||||||
|
"${workspaceFolder}/shared_libs/drivers/**",
|
||||||
|
"${workspaceFolder}/shared_libs/utils/**"
|
||||||
],
|
],
|
||||||
"defines": [
|
"defines": [
|
||||||
"_DEBUG",
|
"_DEBUG",
|
||||||
"UNICODE",
|
"UNICODE",
|
||||||
"_UNICODE",
|
"_UNICODE",
|
||||||
"STM32F303xE",
|
"STM32F303xE",
|
||||||
"USE_HAL_DRIVER"
|
"USE_HAL_DRIVER",
|
||||||
|
"ULOG_ENABLED"
|
||||||
],
|
],
|
||||||
"compilerPath": "C:/MyApps/arm-gcc/gcc-arm-none-eabi-10.3-2021.10/bin/arm-none-eabi-gcc.exe",
|
"compilerPath": "C:/MyApps/arm-gcc/gcc-arm-none-eabi-10.3-2021.10/bin/arm-none-eabi-gcc.exe",
|
||||||
"cStandard": "c11",
|
"cStandard": "c11",
|
||||||
|
|||||||
52
firmware/.vscode/launch.json
vendored
52
firmware/.vscode/launch.json
vendored
@@ -14,20 +14,48 @@
|
|||||||
"servertype": "jlink",
|
"servertype": "jlink",
|
||||||
"device": "STM32F303RE",
|
"device": "STM32F303RE",
|
||||||
"interface": "swd",
|
"interface": "swd",
|
||||||
"runToMain": true,
|
|
||||||
"svdFile": "STM32F303xE.svd",
|
"svdFile": "STM32F303xE.svd",
|
||||||
// "swoConfig": {
|
"preLaunchTask": "${defaultBuildTask}",
|
||||||
// "enabled": false,
|
"rttConfig": {
|
||||||
// "cpuFrequency": 8000000,
|
"enabled": true,
|
||||||
// "swoFrequency": 2000000,
|
"address": "auto",
|
||||||
// "source": "probe",
|
"decoders": [
|
||||||
// "decoders": [{
|
{
|
||||||
// "type": "console",
|
"label": "RTT stdout",
|
||||||
// "label": "ITM",
|
"port": 0,
|
||||||
// "port": 0
|
"type": "console",
|
||||||
|
"timestamp": true
|
||||||
|
},
|
||||||
|
// {
|
||||||
|
// "label": "RTT graph",
|
||||||
|
// "port": 0,
|
||||||
|
// "encoding": "unsigned",
|
||||||
|
// "graphId": "1",
|
||||||
|
// "scale": 1
|
||||||
|
// }
|
||||||
|
]
|
||||||
|
},
|
||||||
|
// "graphConfig": [
|
||||||
|
// {
|
||||||
|
// "label": "Graph 1",
|
||||||
|
// "type": "realtime",
|
||||||
|
// "minimum": 0,
|
||||||
|
// "maximum": 65535,
|
||||||
|
// "timespan": 30,
|
||||||
|
// "plots": [
|
||||||
|
// {
|
||||||
|
// "graphId": "1",
|
||||||
|
// "label": "data 1",
|
||||||
|
// "color": "#53753c",
|
||||||
|
// },
|
||||||
|
// {
|
||||||
|
// "graphId": "2",
|
||||||
|
// "label": "data 2",
|
||||||
|
// "color": "#955f20"
|
||||||
|
// }
|
||||||
|
// ]
|
||||||
// }
|
// }
|
||||||
// ]
|
// ]
|
||||||
// }]
|
|
||||||
}
|
}
|
||||||
]
|
]
|
||||||
}
|
}
|
||||||
30
firmware/.vscode/settings.json
vendored
Normal file
30
firmware/.vscode/settings.json
vendored
Normal file
@@ -0,0 +1,30 @@
|
|||||||
|
{
|
||||||
|
"files.associations": {
|
||||||
|
"ad9833_def.h": "c",
|
||||||
|
"ad9833.h": "c",
|
||||||
|
"disp_layout.h": "c",
|
||||||
|
"bitmap_disp_buttons.h": "c",
|
||||||
|
"bitmap_fonts.h": "c",
|
||||||
|
"font_gfx.h": "c",
|
||||||
|
"display_gfx.h": "c",
|
||||||
|
"main.h": "c",
|
||||||
|
"ctrl_button.h": "c",
|
||||||
|
"ctrl_bottom_button.h": "c",
|
||||||
|
"printf.h": "c",
|
||||||
|
"disp_layout_template.h": "c",
|
||||||
|
"disp_layout_types.h": "c",
|
||||||
|
"ctrl_app_types.h": "c",
|
||||||
|
"tim.h": "c",
|
||||||
|
"ulog.h": "c",
|
||||||
|
"ctrl_generator.h": "c",
|
||||||
|
"type_traits": "c",
|
||||||
|
"ctrl_gen_types.h": "c",
|
||||||
|
"mcp41x.h": "c",
|
||||||
|
"ctrl_channel_button.h": "c",
|
||||||
|
"ctrl_encoder.h": "c",
|
||||||
|
"ctrl_disp_button.h": "c",
|
||||||
|
"ctrl_app.h": "c",
|
||||||
|
"ctrl_app_defs.h": "c"
|
||||||
|
},
|
||||||
|
"cortex-debug.variableUseNaturalFormat": true
|
||||||
|
}
|
||||||
File diff suppressed because one or more lines are too long
52
firmware/func_gen_stm32f303re_nucleo/Core/Inc/i2c.h
Normal file
52
firmware/func_gen_stm32f303re_nucleo/Core/Inc/i2c.h
Normal file
@@ -0,0 +1,52 @@
|
|||||||
|
/* USER CODE BEGIN Header */
|
||||||
|
/**
|
||||||
|
******************************************************************************
|
||||||
|
* @file i2c.h
|
||||||
|
* @brief This file contains all the function prototypes for
|
||||||
|
* the i2c.c file
|
||||||
|
******************************************************************************
|
||||||
|
* @attention
|
||||||
|
*
|
||||||
|
* Copyright (c) 2023 STMicroelectronics.
|
||||||
|
* All rights reserved.
|
||||||
|
*
|
||||||
|
* This software is licensed under terms that can be found in the LICENSE file
|
||||||
|
* in the root directory of this software component.
|
||||||
|
* If no LICENSE file comes with this software, it is provided AS-IS.
|
||||||
|
*
|
||||||
|
******************************************************************************
|
||||||
|
*/
|
||||||
|
/* USER CODE END Header */
|
||||||
|
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||||
|
#ifndef __I2C_H__
|
||||||
|
#define __I2C_H__
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* Includes ------------------------------------------------------------------*/
|
||||||
|
#include "main.h"
|
||||||
|
|
||||||
|
/* USER CODE BEGIN Includes */
|
||||||
|
|
||||||
|
/* USER CODE END Includes */
|
||||||
|
|
||||||
|
extern I2C_HandleTypeDef hi2c1;
|
||||||
|
|
||||||
|
/* USER CODE BEGIN Private defines */
|
||||||
|
|
||||||
|
/* USER CODE END Private defines */
|
||||||
|
|
||||||
|
void MX_I2C1_Init(void);
|
||||||
|
|
||||||
|
/* USER CODE BEGIN Prototypes */
|
||||||
|
|
||||||
|
/* USER CODE END Prototypes */
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif /* __I2C_H__ */
|
||||||
|
|
||||||
@@ -1,21 +1,21 @@
|
|||||||
/* USER CODE BEGIN Header */
|
/* USER CODE BEGIN Header */
|
||||||
/**
|
/**
|
||||||
******************************************************************************
|
******************************************************************************
|
||||||
* @file : main.h
|
* @file : main.h
|
||||||
* @brief : Header for main.c file.
|
* @brief : Header for main.c file.
|
||||||
* This file contains the common defines of the application.
|
* This file contains the common defines of the application.
|
||||||
******************************************************************************
|
******************************************************************************
|
||||||
* @attention
|
* @attention
|
||||||
*
|
*
|
||||||
* Copyright (c) 2023 STMicroelectronics.
|
* Copyright (c) 2023 STMicroelectronics.
|
||||||
* All rights reserved.
|
* All rights reserved.
|
||||||
*
|
*
|
||||||
* This software is licensed under terms that can be found in the LICENSE file
|
* This software is licensed under terms that can be found in the LICENSE file
|
||||||
* in the root directory of this software component.
|
* in the root directory of this software component.
|
||||||
* If no LICENSE file comes with this software, it is provided AS-IS.
|
* If no LICENSE file comes with this software, it is provided AS-IS.
|
||||||
*
|
*
|
||||||
******************************************************************************
|
******************************************************************************
|
||||||
*/
|
*/
|
||||||
/* USER CODE END Header */
|
/* USER CODE END Header */
|
||||||
|
|
||||||
/* Define to prevent recursive inclusion -------------------------------------*/
|
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||||
@@ -31,7 +31,8 @@ extern "C" {
|
|||||||
|
|
||||||
/* Private includes ----------------------------------------------------------*/
|
/* Private includes ----------------------------------------------------------*/
|
||||||
/* USER CODE BEGIN Includes */
|
/* USER CODE BEGIN Includes */
|
||||||
|
// #include "SEGGER_RTT.h"
|
||||||
|
#include "ulog.h"
|
||||||
/* USER CODE END Includes */
|
/* USER CODE END Includes */
|
||||||
|
|
||||||
/* Exported types ------------------------------------------------------------*/
|
/* Exported types ------------------------------------------------------------*/
|
||||||
@@ -59,18 +60,52 @@ void Error_Handler(void);
|
|||||||
/* Private defines -----------------------------------------------------------*/
|
/* Private defines -----------------------------------------------------------*/
|
||||||
#define B1_Pin GPIO_PIN_13
|
#define B1_Pin GPIO_PIN_13
|
||||||
#define B1_GPIO_Port GPIOC
|
#define B1_GPIO_Port GPIOC
|
||||||
|
#define BTN1_Pin GPIO_PIN_0
|
||||||
|
#define BTN1_GPIO_Port GPIOA
|
||||||
|
#define BTN2_Pin GPIO_PIN_1
|
||||||
|
#define BTN2_GPIO_Port GPIOA
|
||||||
#define USART_TX_Pin GPIO_PIN_2
|
#define USART_TX_Pin GPIO_PIN_2
|
||||||
#define USART_TX_GPIO_Port GPIOA
|
#define USART_TX_GPIO_Port GPIOA
|
||||||
#define USART_RX_Pin GPIO_PIN_3
|
#define USART_RX_Pin GPIO_PIN_3
|
||||||
#define USART_RX_GPIO_Port GPIOA
|
#define USART_RX_GPIO_Port GPIOA
|
||||||
#define LD2_Pin GPIO_PIN_5
|
#define BTN3_Pin GPIO_PIN_4
|
||||||
#define LD2_GPIO_Port GPIOA
|
#define BTN3_GPIO_Port GPIOA
|
||||||
|
#define BTN4_Pin GPIO_PIN_5
|
||||||
|
#define BTN4_GPIO_Port GPIOA
|
||||||
|
#define DDS2_CS_Pin GPIO_PIN_10
|
||||||
|
#define DDS2_CS_GPIO_Port GPIOB
|
||||||
|
#define AMP1_CS_Pin GPIO_PIN_11
|
||||||
|
#define AMP1_CS_GPIO_Port GPIOB
|
||||||
|
#define DDS1_CS_Pin GPIO_PIN_12
|
||||||
|
#define DDS1_CS_GPIO_Port GPIOB
|
||||||
|
#define ST7565_RST_Pin GPIO_PIN_8
|
||||||
|
#define ST7565_RST_GPIO_Port GPIOC
|
||||||
|
#define ST7565_A0_Pin GPIO_PIN_9
|
||||||
|
#define ST7565_A0_GPIO_Port GPIOC
|
||||||
|
#define BTN5_Pin GPIO_PIN_8
|
||||||
|
#define BTN5_GPIO_Port GPIOA
|
||||||
|
#define BTN_CH1_Pin GPIO_PIN_9
|
||||||
|
#define BTN_CH1_GPIO_Port GPIOA
|
||||||
|
#define LED_CH1_Pin GPIO_PIN_10
|
||||||
|
#define LED_CH1_GPIO_Port GPIOA
|
||||||
|
#define BTN_CH2_Pin GPIO_PIN_11
|
||||||
|
#define BTN_CH2_GPIO_Port GPIOA
|
||||||
|
#define LED_CH2_Pin GPIO_PIN_12
|
||||||
|
#define LED_CH2_GPIO_Port GPIOA
|
||||||
#define TMS_Pin GPIO_PIN_13
|
#define TMS_Pin GPIO_PIN_13
|
||||||
#define TMS_GPIO_Port GPIOA
|
#define TMS_GPIO_Port GPIOA
|
||||||
#define TCK_Pin GPIO_PIN_14
|
#define TCK_Pin GPIO_PIN_14
|
||||||
#define TCK_GPIO_Port GPIOA
|
#define TCK_GPIO_Port GPIOA
|
||||||
|
#define ST7565_SCK_Pin GPIO_PIN_10
|
||||||
|
#define ST7565_SCK_GPIO_Port GPIOC
|
||||||
|
#define ST7565_CS_Pin GPIO_PIN_11
|
||||||
|
#define ST7565_CS_GPIO_Port GPIOC
|
||||||
|
#define ST7565_MOSI_Pin GPIO_PIN_12
|
||||||
|
#define ST7565_MOSI_GPIO_Port GPIOC
|
||||||
#define SWO_Pin GPIO_PIN_3
|
#define SWO_Pin GPIO_PIN_3
|
||||||
#define SWO_GPIO_Port GPIOB
|
#define SWO_GPIO_Port GPIOB
|
||||||
|
#define AMP2_CS_Pin GPIO_PIN_9
|
||||||
|
#define AMP2_CS_GPIO_Port GPIOB
|
||||||
/* USER CODE BEGIN Private defines */
|
/* USER CODE BEGIN Private defines */
|
||||||
|
|
||||||
/* USER CODE END Private defines */
|
/* USER CODE END Private defines */
|
||||||
|
|||||||
55
firmware/func_gen_stm32f303re_nucleo/Core/Inc/spi.h
Normal file
55
firmware/func_gen_stm32f303re_nucleo/Core/Inc/spi.h
Normal file
@@ -0,0 +1,55 @@
|
|||||||
|
/* USER CODE BEGIN Header */
|
||||||
|
/**
|
||||||
|
******************************************************************************
|
||||||
|
* @file spi.h
|
||||||
|
* @brief This file contains all the function prototypes for
|
||||||
|
* the spi.c file
|
||||||
|
******************************************************************************
|
||||||
|
* @attention
|
||||||
|
*
|
||||||
|
* Copyright (c) 2023 STMicroelectronics.
|
||||||
|
* All rights reserved.
|
||||||
|
*
|
||||||
|
* This software is licensed under terms that can be found in the LICENSE file
|
||||||
|
* in the root directory of this software component.
|
||||||
|
* If no LICENSE file comes with this software, it is provided AS-IS.
|
||||||
|
*
|
||||||
|
******************************************************************************
|
||||||
|
*/
|
||||||
|
/* USER CODE END Header */
|
||||||
|
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||||
|
#ifndef __SPI_H__
|
||||||
|
#define __SPI_H__
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* Includes ------------------------------------------------------------------*/
|
||||||
|
#include "main.h"
|
||||||
|
|
||||||
|
/* USER CODE BEGIN Includes */
|
||||||
|
|
||||||
|
/* USER CODE END Includes */
|
||||||
|
|
||||||
|
extern SPI_HandleTypeDef hspi2;
|
||||||
|
|
||||||
|
extern SPI_HandleTypeDef hspi3;
|
||||||
|
|
||||||
|
/* USER CODE BEGIN Private defines */
|
||||||
|
|
||||||
|
/* USER CODE END Private defines */
|
||||||
|
|
||||||
|
void MX_SPI2_Init(void);
|
||||||
|
void MX_SPI3_Init(void);
|
||||||
|
|
||||||
|
/* USER CODE BEGIN Prototypes */
|
||||||
|
|
||||||
|
/* USER CODE END Prototypes */
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif /* __SPI_H__ */
|
||||||
|
|
||||||
@@ -56,8 +56,8 @@
|
|||||||
/*#define HAL_LPTIM_MODULE_ENABLED */
|
/*#define HAL_LPTIM_MODULE_ENABLED */
|
||||||
/*#define HAL_RNG_MODULE_ENABLED */
|
/*#define HAL_RNG_MODULE_ENABLED */
|
||||||
/*#define HAL_RTC_MODULE_ENABLED */
|
/*#define HAL_RTC_MODULE_ENABLED */
|
||||||
/*#define HAL_SPI_MODULE_ENABLED */
|
#define HAL_SPI_MODULE_ENABLED
|
||||||
/*#define HAL_TIM_MODULE_ENABLED */
|
#define HAL_TIM_MODULE_ENABLED
|
||||||
#define HAL_UART_MODULE_ENABLED
|
#define HAL_UART_MODULE_ENABLED
|
||||||
/*#define HAL_USART_MODULE_ENABLED */
|
/*#define HAL_USART_MODULE_ENABLED */
|
||||||
/*#define HAL_IRDA_MODULE_ENABLED */
|
/*#define HAL_IRDA_MODULE_ENABLED */
|
||||||
|
|||||||
60
firmware/func_gen_stm32f303re_nucleo/Core/Inc/tim.h
Normal file
60
firmware/func_gen_stm32f303re_nucleo/Core/Inc/tim.h
Normal file
@@ -0,0 +1,60 @@
|
|||||||
|
/* USER CODE BEGIN Header */
|
||||||
|
/**
|
||||||
|
******************************************************************************
|
||||||
|
* @file tim.h
|
||||||
|
* @brief This file contains all the function prototypes for
|
||||||
|
* the tim.c file
|
||||||
|
******************************************************************************
|
||||||
|
* @attention
|
||||||
|
*
|
||||||
|
* Copyright (c) 2023 STMicroelectronics.
|
||||||
|
* All rights reserved.
|
||||||
|
*
|
||||||
|
* This software is licensed under terms that can be found in the LICENSE file
|
||||||
|
* in the root directory of this software component.
|
||||||
|
* If no LICENSE file comes with this software, it is provided AS-IS.
|
||||||
|
*
|
||||||
|
******************************************************************************
|
||||||
|
*/
|
||||||
|
/* USER CODE END Header */
|
||||||
|
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||||
|
#ifndef __TIM_H__
|
||||||
|
#define __TIM_H__
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* Includes ------------------------------------------------------------------*/
|
||||||
|
#include "main.h"
|
||||||
|
|
||||||
|
/* USER CODE BEGIN Includes */
|
||||||
|
|
||||||
|
/* USER CODE END Includes */
|
||||||
|
|
||||||
|
extern TIM_HandleTypeDef htim1;
|
||||||
|
|
||||||
|
extern TIM_HandleTypeDef htim2;
|
||||||
|
|
||||||
|
extern TIM_HandleTypeDef htim3;
|
||||||
|
|
||||||
|
/* USER CODE BEGIN Private defines */
|
||||||
|
|
||||||
|
/* USER CODE END Private defines */
|
||||||
|
|
||||||
|
void MX_TIM1_Init(void);
|
||||||
|
void MX_TIM2_Init(void);
|
||||||
|
void MX_TIM3_Init(void);
|
||||||
|
|
||||||
|
void HAL_TIM_MspPostInit(TIM_HandleTypeDef *htim);
|
||||||
|
|
||||||
|
/* USER CODE BEGIN Prototypes */
|
||||||
|
|
||||||
|
/* USER CODE END Prototypes */
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif /* __TIM_H__ */
|
||||||
|
|
||||||
@@ -1,21 +1,21 @@
|
|||||||
/* USER CODE BEGIN Header */
|
/* USER CODE BEGIN Header */
|
||||||
/**
|
/**
|
||||||
******************************************************************************
|
******************************************************************************
|
||||||
* @file gpio.c
|
* @file gpio.c
|
||||||
* @brief This file provides code for the configuration
|
* @brief This file provides code for the configuration
|
||||||
* of all used GPIO pins.
|
* of all used GPIO pins.
|
||||||
******************************************************************************
|
******************************************************************************
|
||||||
* @attention
|
* @attention
|
||||||
*
|
*
|
||||||
* Copyright (c) 2023 STMicroelectronics.
|
* Copyright (c) 2023 STMicroelectronics.
|
||||||
* All rights reserved.
|
* All rights reserved.
|
||||||
*
|
*
|
||||||
* This software is licensed under terms that can be found in the LICENSE file
|
* This software is licensed under terms that can be found in the LICENSE file
|
||||||
* in the root directory of this software component.
|
* in the root directory of this software component.
|
||||||
* If no LICENSE file comes with this software, it is provided AS-IS.
|
* If no LICENSE file comes with this software, it is provided AS-IS.
|
||||||
*
|
*
|
||||||
******************************************************************************
|
******************************************************************************
|
||||||
*/
|
*/
|
||||||
/* USER CODE END Header */
|
/* USER CODE END Header */
|
||||||
|
|
||||||
/* Includes ------------------------------------------------------------------*/
|
/* Includes ------------------------------------------------------------------*/
|
||||||
@@ -51,7 +51,13 @@ void MX_GPIO_Init(void)
|
|||||||
__HAL_RCC_GPIOB_CLK_ENABLE();
|
__HAL_RCC_GPIOB_CLK_ENABLE();
|
||||||
|
|
||||||
/*Configure GPIO pin Output Level */
|
/*Configure GPIO pin Output Level */
|
||||||
HAL_GPIO_WritePin(LD2_GPIO_Port, LD2_Pin, GPIO_PIN_RESET);
|
HAL_GPIO_WritePin(GPIOB, DDS2_CS_Pin|AMP1_CS_Pin|DDS1_CS_Pin|AMP2_CS_Pin, GPIO_PIN_RESET);
|
||||||
|
|
||||||
|
/*Configure GPIO pin Output Level */
|
||||||
|
HAL_GPIO_WritePin(GPIOC, ST7565_RST_Pin|ST7565_A0_Pin|ST7565_CS_Pin, GPIO_PIN_RESET);
|
||||||
|
|
||||||
|
/*Configure GPIO pin Output Level */
|
||||||
|
HAL_GPIO_WritePin(GPIOA, LED_CH1_Pin|LED_CH2_Pin, GPIO_PIN_RESET);
|
||||||
|
|
||||||
/*Configure GPIO pin : PtPin */
|
/*Configure GPIO pin : PtPin */
|
||||||
GPIO_InitStruct.Pin = B1_Pin;
|
GPIO_InitStruct.Pin = B1_Pin;
|
||||||
@@ -59,12 +65,34 @@ void MX_GPIO_Init(void)
|
|||||||
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
||||||
HAL_GPIO_Init(B1_GPIO_Port, &GPIO_InitStruct);
|
HAL_GPIO_Init(B1_GPIO_Port, &GPIO_InitStruct);
|
||||||
|
|
||||||
/*Configure GPIO pin : PtPin */
|
/*Configure GPIO pins : PAPin PAPin PAPin PAPin
|
||||||
GPIO_InitStruct.Pin = LD2_Pin;
|
PAPin PAPin PAPin */
|
||||||
|
GPIO_InitStruct.Pin = BTN1_Pin|BTN2_Pin|BTN3_Pin|BTN4_Pin
|
||||||
|
|BTN5_Pin|BTN_CH1_Pin|BTN_CH2_Pin;
|
||||||
|
GPIO_InitStruct.Mode = GPIO_MODE_INPUT;
|
||||||
|
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
||||||
|
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
|
||||||
|
|
||||||
|
/*Configure GPIO pins : PBPin PBPin PBPin PBPin */
|
||||||
|
GPIO_InitStruct.Pin = DDS2_CS_Pin|AMP1_CS_Pin|DDS1_CS_Pin|AMP2_CS_Pin;
|
||||||
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
|
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
|
||||||
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
||||||
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
|
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
|
||||||
HAL_GPIO_Init(LD2_GPIO_Port, &GPIO_InitStruct);
|
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
|
||||||
|
|
||||||
|
/*Configure GPIO pins : PCPin PCPin PCPin */
|
||||||
|
GPIO_InitStruct.Pin = ST7565_RST_Pin|ST7565_A0_Pin|ST7565_CS_Pin;
|
||||||
|
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
|
||||||
|
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
||||||
|
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
|
||||||
|
HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
|
||||||
|
|
||||||
|
/*Configure GPIO pins : PAPin PAPin */
|
||||||
|
GPIO_InitStruct.Pin = LED_CH1_Pin|LED_CH2_Pin;
|
||||||
|
GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP;
|
||||||
|
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
||||||
|
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
|
||||||
|
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
130
firmware/func_gen_stm32f303re_nucleo/Core/Src/i2c.c
Normal file
130
firmware/func_gen_stm32f303re_nucleo/Core/Src/i2c.c
Normal file
@@ -0,0 +1,130 @@
|
|||||||
|
/* USER CODE BEGIN Header */
|
||||||
|
/**
|
||||||
|
******************************************************************************
|
||||||
|
* @file i2c.c
|
||||||
|
* @brief This file provides code for the configuration
|
||||||
|
* of the I2C instances.
|
||||||
|
******************************************************************************
|
||||||
|
* @attention
|
||||||
|
*
|
||||||
|
* Copyright (c) 2023 STMicroelectronics.
|
||||||
|
* All rights reserved.
|
||||||
|
*
|
||||||
|
* This software is licensed under terms that can be found in the LICENSE file
|
||||||
|
* in the root directory of this software component.
|
||||||
|
* If no LICENSE file comes with this software, it is provided AS-IS.
|
||||||
|
*
|
||||||
|
******************************************************************************
|
||||||
|
*/
|
||||||
|
/* USER CODE END Header */
|
||||||
|
/* Includes ------------------------------------------------------------------*/
|
||||||
|
#include "i2c.h"
|
||||||
|
|
||||||
|
/* USER CODE BEGIN 0 */
|
||||||
|
|
||||||
|
/* USER CODE END 0 */
|
||||||
|
|
||||||
|
I2C_HandleTypeDef hi2c1;
|
||||||
|
|
||||||
|
/* I2C1 init function */
|
||||||
|
void MX_I2C1_Init(void)
|
||||||
|
{
|
||||||
|
|
||||||
|
/* USER CODE BEGIN I2C1_Init 0 */
|
||||||
|
|
||||||
|
/* USER CODE END I2C1_Init 0 */
|
||||||
|
|
||||||
|
/* USER CODE BEGIN I2C1_Init 1 */
|
||||||
|
|
||||||
|
/* USER CODE END I2C1_Init 1 */
|
||||||
|
hi2c1.Instance = I2C1;
|
||||||
|
hi2c1.Init.Timing = 0x0000020B;
|
||||||
|
hi2c1.Init.OwnAddress1 = 0;
|
||||||
|
hi2c1.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT;
|
||||||
|
hi2c1.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE;
|
||||||
|
hi2c1.Init.OwnAddress2 = 0;
|
||||||
|
hi2c1.Init.OwnAddress2Masks = I2C_OA2_NOMASK;
|
||||||
|
hi2c1.Init.GeneralCallMode = I2C_GENERALCALL_DISABLE;
|
||||||
|
hi2c1.Init.NoStretchMode = I2C_NOSTRETCH_DISABLE;
|
||||||
|
if (HAL_I2C_Init(&hi2c1) != HAL_OK)
|
||||||
|
{
|
||||||
|
Error_Handler();
|
||||||
|
}
|
||||||
|
|
||||||
|
/** Configure Analogue filter
|
||||||
|
*/
|
||||||
|
if (HAL_I2CEx_ConfigAnalogFilter(&hi2c1, I2C_ANALOGFILTER_ENABLE) != HAL_OK)
|
||||||
|
{
|
||||||
|
Error_Handler();
|
||||||
|
}
|
||||||
|
|
||||||
|
/** Configure Digital filter
|
||||||
|
*/
|
||||||
|
if (HAL_I2CEx_ConfigDigitalFilter(&hi2c1, 0) != HAL_OK)
|
||||||
|
{
|
||||||
|
Error_Handler();
|
||||||
|
}
|
||||||
|
/* USER CODE BEGIN I2C1_Init 2 */
|
||||||
|
|
||||||
|
/* USER CODE END I2C1_Init 2 */
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
void HAL_I2C_MspInit(I2C_HandleTypeDef* i2cHandle)
|
||||||
|
{
|
||||||
|
|
||||||
|
GPIO_InitTypeDef GPIO_InitStruct = {0};
|
||||||
|
if(i2cHandle->Instance==I2C1)
|
||||||
|
{
|
||||||
|
/* USER CODE BEGIN I2C1_MspInit 0 */
|
||||||
|
|
||||||
|
/* USER CODE END I2C1_MspInit 0 */
|
||||||
|
|
||||||
|
__HAL_RCC_GPIOB_CLK_ENABLE();
|
||||||
|
/**I2C1 GPIO Configuration
|
||||||
|
PB6 ------> I2C1_SCL
|
||||||
|
PB7 ------> I2C1_SDA
|
||||||
|
*/
|
||||||
|
GPIO_InitStruct.Pin = GPIO_PIN_6|GPIO_PIN_7;
|
||||||
|
GPIO_InitStruct.Mode = GPIO_MODE_AF_OD;
|
||||||
|
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
||||||
|
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
|
||||||
|
GPIO_InitStruct.Alternate = GPIO_AF4_I2C1;
|
||||||
|
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
|
||||||
|
|
||||||
|
/* I2C1 clock enable */
|
||||||
|
__HAL_RCC_I2C1_CLK_ENABLE();
|
||||||
|
/* USER CODE BEGIN I2C1_MspInit 1 */
|
||||||
|
|
||||||
|
/* USER CODE END I2C1_MspInit 1 */
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void HAL_I2C_MspDeInit(I2C_HandleTypeDef* i2cHandle)
|
||||||
|
{
|
||||||
|
|
||||||
|
if(i2cHandle->Instance==I2C1)
|
||||||
|
{
|
||||||
|
/* USER CODE BEGIN I2C1_MspDeInit 0 */
|
||||||
|
|
||||||
|
/* USER CODE END I2C1_MspDeInit 0 */
|
||||||
|
/* Peripheral clock disable */
|
||||||
|
__HAL_RCC_I2C1_CLK_DISABLE();
|
||||||
|
|
||||||
|
/**I2C1 GPIO Configuration
|
||||||
|
PB6 ------> I2C1_SCL
|
||||||
|
PB7 ------> I2C1_SDA
|
||||||
|
*/
|
||||||
|
HAL_GPIO_DeInit(GPIOB, GPIO_PIN_6);
|
||||||
|
|
||||||
|
HAL_GPIO_DeInit(GPIOB, GPIO_PIN_7);
|
||||||
|
|
||||||
|
/* USER CODE BEGIN I2C1_MspDeInit 1 */
|
||||||
|
|
||||||
|
/* USER CODE END I2C1_MspDeInit 1 */
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/* USER CODE BEGIN 1 */
|
||||||
|
|
||||||
|
/* USER CODE END 1 */
|
||||||
@@ -18,12 +18,19 @@
|
|||||||
/* USER CODE END Header */
|
/* USER CODE END Header */
|
||||||
/* Includes ------------------------------------------------------------------*/
|
/* Includes ------------------------------------------------------------------*/
|
||||||
#include "main.h"
|
#include "main.h"
|
||||||
|
#include "i2c.h"
|
||||||
|
#include "spi.h"
|
||||||
|
#include "tim.h"
|
||||||
#include "usart.h"
|
#include "usart.h"
|
||||||
#include "gpio.h"
|
#include "gpio.h"
|
||||||
|
|
||||||
/* Private includes ----------------------------------------------------------*/
|
/* Private includes ----------------------------------------------------------*/
|
||||||
/* USER CODE BEGIN Includes */
|
/* USER CODE BEGIN Includes */
|
||||||
|
#include "ctrl_app.h"
|
||||||
|
#include "display_gfx.h"
|
||||||
|
#include "disp_layout.h"
|
||||||
|
#include "st7565.h"
|
||||||
|
#include "SEGGER_RTT.h"
|
||||||
/* USER CODE END Includes */
|
/* USER CODE END Includes */
|
||||||
|
|
||||||
/* Private typedef -----------------------------------------------------------*/
|
/* Private typedef -----------------------------------------------------------*/
|
||||||
@@ -43,13 +50,15 @@
|
|||||||
/* Private variables ---------------------------------------------------------*/
|
/* Private variables ---------------------------------------------------------*/
|
||||||
|
|
||||||
/* USER CODE BEGIN PV */
|
/* USER CODE BEGIN PV */
|
||||||
|
st7565_handle_t hst7565;
|
||||||
|
GFX_display_t disp;
|
||||||
|
APP_data_t app_data;
|
||||||
/* USER CODE END PV */
|
/* USER CODE END PV */
|
||||||
|
|
||||||
/* Private function prototypes -----------------------------------------------*/
|
/* Private function prototypes -----------------------------------------------*/
|
||||||
void SystemClock_Config(void);
|
void SystemClock_Config(void);
|
||||||
/* USER CODE BEGIN PFP */
|
/* USER CODE BEGIN PFP */
|
||||||
|
void RTT_console_logger(ulog_level_t severity, char *msg);
|
||||||
/* USER CODE END PFP */
|
/* USER CODE END PFP */
|
||||||
|
|
||||||
/* Private user code ---------------------------------------------------------*/
|
/* Private user code ---------------------------------------------------------*/
|
||||||
@@ -58,126 +67,175 @@ void SystemClock_Config(void);
|
|||||||
/* USER CODE END 0 */
|
/* USER CODE END 0 */
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief The application entry point.
|
* @brief The application entry point.
|
||||||
* @retval int
|
* @retval int
|
||||||
*/
|
*/
|
||||||
int main(void)
|
int main(void)
|
||||||
{
|
{
|
||||||
/* USER CODE BEGIN 1 */
|
/* USER CODE BEGIN 1 */
|
||||||
|
|
||||||
/* USER CODE END 1 */
|
/* USER CODE END 1 */
|
||||||
|
|
||||||
/* MCU Configuration--------------------------------------------------------*/
|
/* MCU Configuration--------------------------------------------------------*/
|
||||||
|
|
||||||
/* Reset of all peripherals, Initializes the Flash interface and the Systick. */
|
/* Reset of all peripherals, Initializes the Flash interface and the Systick. */
|
||||||
HAL_Init();
|
HAL_Init();
|
||||||
|
|
||||||
/* USER CODE BEGIN Init */
|
/* USER CODE BEGIN Init */
|
||||||
|
|
||||||
/* USER CODE END Init */
|
/* USER CODE END Init */
|
||||||
|
|
||||||
/* Configure the system clock */
|
/* Configure the system clock */
|
||||||
SystemClock_Config();
|
SystemClock_Config();
|
||||||
|
|
||||||
/* USER CODE BEGIN SysInit */
|
/* USER CODE BEGIN SysInit */
|
||||||
|
|
||||||
/* USER CODE END SysInit */
|
/* USER CODE END SysInit */
|
||||||
|
|
||||||
/* Initialize all configured peripherals */
|
/* Initialize all configured peripherals */
|
||||||
MX_GPIO_Init();
|
MX_GPIO_Init();
|
||||||
MX_USART2_UART_Init();
|
MX_USART2_UART_Init();
|
||||||
/* USER CODE BEGIN 2 */
|
MX_SPI2_Init();
|
||||||
|
MX_I2C1_Init();
|
||||||
|
MX_SPI3_Init();
|
||||||
|
MX_TIM2_Init();
|
||||||
|
MX_TIM3_Init();
|
||||||
|
MX_TIM1_Init();
|
||||||
|
/* USER CODE BEGIN 2 */
|
||||||
|
ulog_init();
|
||||||
|
ulog_subscribe(RTT_console_logger, ULOG_TRACE_LEVEL);
|
||||||
|
|
||||||
/* USER CODE END 2 */
|
HAL_TIM_Encoder_Start(&htim3, TIM_CHANNEL_ALL);
|
||||||
|
HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_2);
|
||||||
|
HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_3);
|
||||||
|
HAL_TIM_PWM_Start(&htim1, TIM_CHANNEL_4);
|
||||||
|
// SEGGER_RTT_WriteString(0, "App start...\n");
|
||||||
|
ULOG_INFO("start app...");
|
||||||
|
|
||||||
/* Infinite loop */
|
hst7565.hspi = &hspi3;
|
||||||
/* USER CODE BEGIN WHILE */
|
hst7565.cs_port = ST7565_CS_GPIO_Port;
|
||||||
while (1)
|
hst7565.cs_pin = ST7565_CS_Pin;
|
||||||
{
|
hst7565.a0_port = ST7565_A0_GPIO_Port;
|
||||||
/* USER CODE END WHILE */
|
hst7565.a0_pin = ST7565_A0_Pin;
|
||||||
|
hst7565.rst_port = ST7565_RST_GPIO_Port;
|
||||||
|
hst7565.rst_pin = ST7565_RST_Pin;
|
||||||
|
ST7565_Init(&hst7565, &disp);
|
||||||
|
|
||||||
/* USER CODE BEGIN 3 */
|
/* USER CODE END 2 */
|
||||||
}
|
|
||||||
/* USER CODE END 3 */
|
/* Infinite loop */
|
||||||
|
/* USER CODE BEGIN WHILE */
|
||||||
|
DISP_clearScreen(&disp);
|
||||||
|
ST7565_DisplayAll(&hst7565);
|
||||||
|
HAL_Delay(1000);
|
||||||
|
uint32_t last_tick = HAL_GetTick();
|
||||||
|
APP_init(&app_data);
|
||||||
|
while (1)
|
||||||
|
{
|
||||||
|
CTRL_buttonsHandler();
|
||||||
|
if (HAL_GetTick() - last_tick > 100)
|
||||||
|
{
|
||||||
|
last_tick = HAL_GetTick();
|
||||||
|
ST7565_DisplayAll(&hst7565);
|
||||||
|
LAY_drawDisplayLayout(&disp, &app_data);
|
||||||
|
}
|
||||||
|
/* USER CODE END WHILE */
|
||||||
|
|
||||||
|
/* USER CODE BEGIN 3 */
|
||||||
|
}
|
||||||
|
/* USER CODE END 3 */
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief System Clock Configuration
|
* @brief System Clock Configuration
|
||||||
* @retval None
|
* @retval None
|
||||||
*/
|
*/
|
||||||
void SystemClock_Config(void)
|
void SystemClock_Config(void)
|
||||||
{
|
{
|
||||||
RCC_OscInitTypeDef RCC_OscInitStruct = {0};
|
RCC_OscInitTypeDef RCC_OscInitStruct = {0};
|
||||||
RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
|
RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
|
||||||
RCC_PeriphCLKInitTypeDef PeriphClkInit = {0};
|
RCC_PeriphCLKInitTypeDef PeriphClkInit = {0};
|
||||||
|
|
||||||
/** Initializes the RCC Oscillators according to the specified parameters
|
/** Initializes the RCC Oscillators according to the specified parameters
|
||||||
* in the RCC_OscInitTypeDef structure.
|
* in the RCC_OscInitTypeDef structure.
|
||||||
*/
|
*/
|
||||||
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI;
|
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI;
|
||||||
RCC_OscInitStruct.HSIState = RCC_HSI_ON;
|
RCC_OscInitStruct.HSIState = RCC_HSI_ON;
|
||||||
RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
|
RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
|
||||||
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
|
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
|
||||||
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI;
|
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI;
|
||||||
RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL9;
|
RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL9;
|
||||||
RCC_OscInitStruct.PLL.PREDIV = RCC_PREDIV_DIV1;
|
RCC_OscInitStruct.PLL.PREDIV = RCC_PREDIV_DIV1;
|
||||||
if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
|
if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
|
||||||
{
|
{
|
||||||
Error_Handler();
|
Error_Handler();
|
||||||
}
|
}
|
||||||
|
|
||||||
/** Initializes the CPU, AHB and APB buses clocks
|
/** Initializes the CPU, AHB and APB buses clocks
|
||||||
*/
|
*/
|
||||||
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK | RCC_CLOCKTYPE_SYSCLK | RCC_CLOCKTYPE_PCLK1 | RCC_CLOCKTYPE_PCLK2;
|
RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
|
||||||
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
|
|RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;
|
||||||
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
|
RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
|
||||||
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2;
|
RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
|
||||||
RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;
|
RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2;
|
||||||
|
RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;
|
||||||
|
|
||||||
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK)
|
if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK)
|
||||||
{
|
{
|
||||||
Error_Handler();
|
Error_Handler();
|
||||||
}
|
}
|
||||||
PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USART2;
|
PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USART2|RCC_PERIPHCLK_I2C1
|
||||||
PeriphClkInit.Usart2ClockSelection = RCC_USART2CLKSOURCE_PCLK1;
|
|RCC_PERIPHCLK_TIM1|RCC_PERIPHCLK_TIM2
|
||||||
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK)
|
|RCC_PERIPHCLK_TIM34;
|
||||||
{
|
PeriphClkInit.Usart2ClockSelection = RCC_USART2CLKSOURCE_PCLK1;
|
||||||
Error_Handler();
|
PeriphClkInit.I2c1ClockSelection = RCC_I2C1CLKSOURCE_HSI;
|
||||||
}
|
PeriphClkInit.Tim1ClockSelection = RCC_TIM1CLK_PLLCLK;
|
||||||
|
PeriphClkInit.Tim2ClockSelection = RCC_TIM2CLK_HCLK;
|
||||||
|
PeriphClkInit.Tim34ClockSelection = RCC_TIM34CLK_HCLK;
|
||||||
|
if (HAL_RCCEx_PeriphCLKConfig(&PeriphClkInit) != HAL_OK)
|
||||||
|
{
|
||||||
|
Error_Handler();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/* USER CODE BEGIN 4 */
|
/* USER CODE BEGIN 4 */
|
||||||
|
void RTT_console_logger(ulog_level_t severity, char *msg)
|
||||||
|
{
|
||||||
|
SEGGER_RTT_printf(0, "[%s]: %s\n",
|
||||||
|
// HAL_GetTick(), // user defined function
|
||||||
|
ulog_level_name(severity),
|
||||||
|
msg);
|
||||||
|
}
|
||||||
/* USER CODE END 4 */
|
/* USER CODE END 4 */
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief This function is executed in case of error occurrence.
|
* @brief This function is executed in case of error occurrence.
|
||||||
* @retval None
|
* @retval None
|
||||||
*/
|
*/
|
||||||
void Error_Handler(void)
|
void Error_Handler(void)
|
||||||
{
|
{
|
||||||
/* USER CODE BEGIN Error_Handler_Debug */
|
/* USER CODE BEGIN Error_Handler_Debug */
|
||||||
/* User can add his own implementation to report the HAL error return state */
|
/* User can add his own implementation to report the HAL error return state */
|
||||||
__disable_irq();
|
__disable_irq();
|
||||||
while (1)
|
while (1)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
/* USER CODE END Error_Handler_Debug */
|
/* USER CODE END Error_Handler_Debug */
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef USE_FULL_ASSERT
|
#ifdef USE_FULL_ASSERT
|
||||||
/**
|
/**
|
||||||
* @brief Reports the name of the source file and the source line number
|
* @brief Reports the name of the source file and the source line number
|
||||||
* where the assert_param error has occurred.
|
* where the assert_param error has occurred.
|
||||||
* @param file: pointer to the source file name
|
* @param file: pointer to the source file name
|
||||||
* @param line: assert_param error line source number
|
* @param line: assert_param error line source number
|
||||||
* @retval None
|
* @retval None
|
||||||
*/
|
*/
|
||||||
void assert_failed(uint8_t *file, uint32_t line)
|
void assert_failed(uint8_t *file, uint32_t line)
|
||||||
{
|
{
|
||||||
/* USER CODE BEGIN 6 */
|
/* USER CODE BEGIN 6 */
|
||||||
/* User can add his own implementation to report the file name and line number,
|
/* User can add his own implementation to report the file name and line number,
|
||||||
ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
|
ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
|
||||||
/* USER CODE END 6 */
|
/* USER CODE END 6 */
|
||||||
}
|
}
|
||||||
#endif /* USE_FULL_ASSERT */
|
#endif /* USE_FULL_ASSERT */
|
||||||
|
|||||||
198
firmware/func_gen_stm32f303re_nucleo/Core/Src/spi.c
Normal file
198
firmware/func_gen_stm32f303re_nucleo/Core/Src/spi.c
Normal file
@@ -0,0 +1,198 @@
|
|||||||
|
/* USER CODE BEGIN Header */
|
||||||
|
/**
|
||||||
|
******************************************************************************
|
||||||
|
* @file spi.c
|
||||||
|
* @brief This file provides code for the configuration
|
||||||
|
* of the SPI instances.
|
||||||
|
******************************************************************************
|
||||||
|
* @attention
|
||||||
|
*
|
||||||
|
* Copyright (c) 2023 STMicroelectronics.
|
||||||
|
* All rights reserved.
|
||||||
|
*
|
||||||
|
* This software is licensed under terms that can be found in the LICENSE file
|
||||||
|
* in the root directory of this software component.
|
||||||
|
* If no LICENSE file comes with this software, it is provided AS-IS.
|
||||||
|
*
|
||||||
|
******************************************************************************
|
||||||
|
*/
|
||||||
|
/* USER CODE END Header */
|
||||||
|
/* Includes ------------------------------------------------------------------*/
|
||||||
|
#include "spi.h"
|
||||||
|
|
||||||
|
/* USER CODE BEGIN 0 */
|
||||||
|
|
||||||
|
/* USER CODE END 0 */
|
||||||
|
|
||||||
|
SPI_HandleTypeDef hspi2;
|
||||||
|
SPI_HandleTypeDef hspi3;
|
||||||
|
|
||||||
|
/* SPI2 init function */
|
||||||
|
void MX_SPI2_Init(void)
|
||||||
|
{
|
||||||
|
|
||||||
|
/* USER CODE BEGIN SPI2_Init 0 */
|
||||||
|
|
||||||
|
/* USER CODE END SPI2_Init 0 */
|
||||||
|
|
||||||
|
/* USER CODE BEGIN SPI2_Init 1 */
|
||||||
|
|
||||||
|
/* USER CODE END SPI2_Init 1 */
|
||||||
|
hspi2.Instance = SPI2;
|
||||||
|
hspi2.Init.Mode = SPI_MODE_MASTER;
|
||||||
|
hspi2.Init.Direction = SPI_DIRECTION_2LINES;
|
||||||
|
hspi2.Init.DataSize = SPI_DATASIZE_8BIT;
|
||||||
|
hspi2.Init.CLKPolarity = SPI_POLARITY_HIGH;
|
||||||
|
hspi2.Init.CLKPhase = SPI_PHASE_1EDGE;
|
||||||
|
hspi2.Init.NSS = SPI_NSS_SOFT;
|
||||||
|
hspi2.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_32;
|
||||||
|
hspi2.Init.FirstBit = SPI_FIRSTBIT_MSB;
|
||||||
|
hspi2.Init.TIMode = SPI_TIMODE_DISABLE;
|
||||||
|
hspi2.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
|
||||||
|
hspi2.Init.CRCPolynomial = 7;
|
||||||
|
hspi2.Init.CRCLength = SPI_CRC_LENGTH_DATASIZE;
|
||||||
|
hspi2.Init.NSSPMode = SPI_NSS_PULSE_ENABLE;
|
||||||
|
if (HAL_SPI_Init(&hspi2) != HAL_OK)
|
||||||
|
{
|
||||||
|
Error_Handler();
|
||||||
|
}
|
||||||
|
/* USER CODE BEGIN SPI2_Init 2 */
|
||||||
|
|
||||||
|
/* USER CODE END SPI2_Init 2 */
|
||||||
|
|
||||||
|
}
|
||||||
|
/* SPI3 init function */
|
||||||
|
void MX_SPI3_Init(void)
|
||||||
|
{
|
||||||
|
|
||||||
|
/* USER CODE BEGIN SPI3_Init 0 */
|
||||||
|
|
||||||
|
/* USER CODE END SPI3_Init 0 */
|
||||||
|
|
||||||
|
/* USER CODE BEGIN SPI3_Init 1 */
|
||||||
|
|
||||||
|
/* USER CODE END SPI3_Init 1 */
|
||||||
|
hspi3.Instance = SPI3;
|
||||||
|
hspi3.Init.Mode = SPI_MODE_MASTER;
|
||||||
|
hspi3.Init.Direction = SPI_DIRECTION_1LINE;
|
||||||
|
hspi3.Init.DataSize = SPI_DATASIZE_8BIT;
|
||||||
|
hspi3.Init.CLKPolarity = SPI_POLARITY_LOW;
|
||||||
|
hspi3.Init.CLKPhase = SPI_PHASE_1EDGE;
|
||||||
|
hspi3.Init.NSS = SPI_NSS_SOFT;
|
||||||
|
hspi3.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_64;
|
||||||
|
hspi3.Init.FirstBit = SPI_FIRSTBIT_MSB;
|
||||||
|
hspi3.Init.TIMode = SPI_TIMODE_DISABLE;
|
||||||
|
hspi3.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
|
||||||
|
hspi3.Init.CRCPolynomial = 7;
|
||||||
|
hspi3.Init.CRCLength = SPI_CRC_LENGTH_DATASIZE;
|
||||||
|
hspi3.Init.NSSPMode = SPI_NSS_PULSE_ENABLE;
|
||||||
|
if (HAL_SPI_Init(&hspi3) != HAL_OK)
|
||||||
|
{
|
||||||
|
Error_Handler();
|
||||||
|
}
|
||||||
|
/* USER CODE BEGIN SPI3_Init 2 */
|
||||||
|
|
||||||
|
/* USER CODE END SPI3_Init 2 */
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
void HAL_SPI_MspInit(SPI_HandleTypeDef* spiHandle)
|
||||||
|
{
|
||||||
|
|
||||||
|
GPIO_InitTypeDef GPIO_InitStruct = {0};
|
||||||
|
if(spiHandle->Instance==SPI2)
|
||||||
|
{
|
||||||
|
/* USER CODE BEGIN SPI2_MspInit 0 */
|
||||||
|
|
||||||
|
/* USER CODE END SPI2_MspInit 0 */
|
||||||
|
/* SPI2 clock enable */
|
||||||
|
__HAL_RCC_SPI2_CLK_ENABLE();
|
||||||
|
|
||||||
|
__HAL_RCC_GPIOB_CLK_ENABLE();
|
||||||
|
/**SPI2 GPIO Configuration
|
||||||
|
PB13 ------> SPI2_SCK
|
||||||
|
PB14 ------> SPI2_MISO
|
||||||
|
PB15 ------> SPI2_MOSI
|
||||||
|
*/
|
||||||
|
GPIO_InitStruct.Pin = GPIO_PIN_13|GPIO_PIN_14|GPIO_PIN_15;
|
||||||
|
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
|
||||||
|
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
||||||
|
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
|
||||||
|
GPIO_InitStruct.Alternate = GPIO_AF5_SPI2;
|
||||||
|
HAL_GPIO_Init(GPIOB, &GPIO_InitStruct);
|
||||||
|
|
||||||
|
/* USER CODE BEGIN SPI2_MspInit 1 */
|
||||||
|
|
||||||
|
/* USER CODE END SPI2_MspInit 1 */
|
||||||
|
}
|
||||||
|
else if(spiHandle->Instance==SPI3)
|
||||||
|
{
|
||||||
|
/* USER CODE BEGIN SPI3_MspInit 0 */
|
||||||
|
|
||||||
|
/* USER CODE END SPI3_MspInit 0 */
|
||||||
|
/* SPI3 clock enable */
|
||||||
|
__HAL_RCC_SPI3_CLK_ENABLE();
|
||||||
|
|
||||||
|
__HAL_RCC_GPIOC_CLK_ENABLE();
|
||||||
|
/**SPI3 GPIO Configuration
|
||||||
|
PC10 ------> SPI3_SCK
|
||||||
|
PC12 ------> SPI3_MOSI
|
||||||
|
*/
|
||||||
|
GPIO_InitStruct.Pin = ST7565_SCK_Pin|ST7565_MOSI_Pin;
|
||||||
|
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
|
||||||
|
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
||||||
|
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
|
||||||
|
GPIO_InitStruct.Alternate = GPIO_AF6_SPI3;
|
||||||
|
HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
|
||||||
|
|
||||||
|
/* USER CODE BEGIN SPI3_MspInit 1 */
|
||||||
|
|
||||||
|
/* USER CODE END SPI3_MspInit 1 */
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void HAL_SPI_MspDeInit(SPI_HandleTypeDef* spiHandle)
|
||||||
|
{
|
||||||
|
|
||||||
|
if(spiHandle->Instance==SPI2)
|
||||||
|
{
|
||||||
|
/* USER CODE BEGIN SPI2_MspDeInit 0 */
|
||||||
|
|
||||||
|
/* USER CODE END SPI2_MspDeInit 0 */
|
||||||
|
/* Peripheral clock disable */
|
||||||
|
__HAL_RCC_SPI2_CLK_DISABLE();
|
||||||
|
|
||||||
|
/**SPI2 GPIO Configuration
|
||||||
|
PB13 ------> SPI2_SCK
|
||||||
|
PB14 ------> SPI2_MISO
|
||||||
|
PB15 ------> SPI2_MOSI
|
||||||
|
*/
|
||||||
|
HAL_GPIO_DeInit(GPIOB, GPIO_PIN_13|GPIO_PIN_14|GPIO_PIN_15);
|
||||||
|
|
||||||
|
/* USER CODE BEGIN SPI2_MspDeInit 1 */
|
||||||
|
|
||||||
|
/* USER CODE END SPI2_MspDeInit 1 */
|
||||||
|
}
|
||||||
|
else if(spiHandle->Instance==SPI3)
|
||||||
|
{
|
||||||
|
/* USER CODE BEGIN SPI3_MspDeInit 0 */
|
||||||
|
|
||||||
|
/* USER CODE END SPI3_MspDeInit 0 */
|
||||||
|
/* Peripheral clock disable */
|
||||||
|
__HAL_RCC_SPI3_CLK_DISABLE();
|
||||||
|
|
||||||
|
/**SPI3 GPIO Configuration
|
||||||
|
PC10 ------> SPI3_SCK
|
||||||
|
PC12 ------> SPI3_MOSI
|
||||||
|
*/
|
||||||
|
HAL_GPIO_DeInit(GPIOC, ST7565_SCK_Pin|ST7565_MOSI_Pin);
|
||||||
|
|
||||||
|
/* USER CODE BEGIN SPI3_MspDeInit 1 */
|
||||||
|
|
||||||
|
/* USER CODE END SPI3_MspDeInit 1 */
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/* USER CODE BEGIN 1 */
|
||||||
|
|
||||||
|
/* USER CODE END 1 */
|
||||||
338
firmware/func_gen_stm32f303re_nucleo/Core/Src/tim.c
Normal file
338
firmware/func_gen_stm32f303re_nucleo/Core/Src/tim.c
Normal file
@@ -0,0 +1,338 @@
|
|||||||
|
/* USER CODE BEGIN Header */
|
||||||
|
/**
|
||||||
|
******************************************************************************
|
||||||
|
* @file tim.c
|
||||||
|
* @brief This file provides code for the configuration
|
||||||
|
* of the TIM instances.
|
||||||
|
******************************************************************************
|
||||||
|
* @attention
|
||||||
|
*
|
||||||
|
* Copyright (c) 2023 STMicroelectronics.
|
||||||
|
* All rights reserved.
|
||||||
|
*
|
||||||
|
* This software is licensed under terms that can be found in the LICENSE file
|
||||||
|
* in the root directory of this software component.
|
||||||
|
* If no LICENSE file comes with this software, it is provided AS-IS.
|
||||||
|
*
|
||||||
|
******************************************************************************
|
||||||
|
*/
|
||||||
|
/* USER CODE END Header */
|
||||||
|
/* Includes ------------------------------------------------------------------*/
|
||||||
|
#include "tim.h"
|
||||||
|
|
||||||
|
/* USER CODE BEGIN 0 */
|
||||||
|
|
||||||
|
/* USER CODE END 0 */
|
||||||
|
|
||||||
|
TIM_HandleTypeDef htim1;
|
||||||
|
TIM_HandleTypeDef htim2;
|
||||||
|
TIM_HandleTypeDef htim3;
|
||||||
|
|
||||||
|
/* TIM1 init function */
|
||||||
|
void MX_TIM1_Init(void)
|
||||||
|
{
|
||||||
|
|
||||||
|
/* USER CODE BEGIN TIM1_Init 0 */
|
||||||
|
|
||||||
|
/* USER CODE END TIM1_Init 0 */
|
||||||
|
|
||||||
|
TIM_ClockConfigTypeDef sClockSourceConfig = {0};
|
||||||
|
TIM_MasterConfigTypeDef sMasterConfig = {0};
|
||||||
|
TIM_OC_InitTypeDef sConfigOC = {0};
|
||||||
|
TIM_BreakDeadTimeConfigTypeDef sBreakDeadTimeConfig = {0};
|
||||||
|
|
||||||
|
/* USER CODE BEGIN TIM1_Init 1 */
|
||||||
|
|
||||||
|
/* USER CODE END TIM1_Init 1 */
|
||||||
|
htim1.Instance = TIM1;
|
||||||
|
htim1.Init.Prescaler = 0;
|
||||||
|
htim1.Init.CounterMode = TIM_COUNTERMODE_UP;
|
||||||
|
htim1.Init.Period = 5;
|
||||||
|
htim1.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
|
||||||
|
htim1.Init.RepetitionCounter = 0;
|
||||||
|
htim1.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_ENABLE;
|
||||||
|
if (HAL_TIM_Base_Init(&htim1) != HAL_OK)
|
||||||
|
{
|
||||||
|
Error_Handler();
|
||||||
|
}
|
||||||
|
sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL;
|
||||||
|
if (HAL_TIM_ConfigClockSource(&htim1, &sClockSourceConfig) != HAL_OK)
|
||||||
|
{
|
||||||
|
Error_Handler();
|
||||||
|
}
|
||||||
|
if (HAL_TIM_PWM_Init(&htim1) != HAL_OK)
|
||||||
|
{
|
||||||
|
Error_Handler();
|
||||||
|
}
|
||||||
|
sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
|
||||||
|
sMasterConfig.MasterOutputTrigger2 = TIM_TRGO2_RESET;
|
||||||
|
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
|
||||||
|
if (HAL_TIMEx_MasterConfigSynchronization(&htim1, &sMasterConfig) != HAL_OK)
|
||||||
|
{
|
||||||
|
Error_Handler();
|
||||||
|
}
|
||||||
|
sConfigOC.OCMode = TIM_OCMODE_PWM1;
|
||||||
|
sConfigOC.Pulse = 3;
|
||||||
|
sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH;
|
||||||
|
sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH;
|
||||||
|
sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
|
||||||
|
sConfigOC.OCIdleState = TIM_OCIDLESTATE_RESET;
|
||||||
|
sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET;
|
||||||
|
if (HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_2) != HAL_OK)
|
||||||
|
{
|
||||||
|
Error_Handler();
|
||||||
|
}
|
||||||
|
if (HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_3) != HAL_OK)
|
||||||
|
{
|
||||||
|
Error_Handler();
|
||||||
|
}
|
||||||
|
sConfigOC.OCFastMode = TIM_OCFAST_ENABLE;
|
||||||
|
if (HAL_TIM_PWM_ConfigChannel(&htim1, &sConfigOC, TIM_CHANNEL_4) != HAL_OK)
|
||||||
|
{
|
||||||
|
Error_Handler();
|
||||||
|
}
|
||||||
|
sBreakDeadTimeConfig.OffStateRunMode = TIM_OSSR_DISABLE;
|
||||||
|
sBreakDeadTimeConfig.OffStateIDLEMode = TIM_OSSI_DISABLE;
|
||||||
|
sBreakDeadTimeConfig.LockLevel = TIM_LOCKLEVEL_OFF;
|
||||||
|
sBreakDeadTimeConfig.DeadTime = 0;
|
||||||
|
sBreakDeadTimeConfig.BreakState = TIM_BREAK_DISABLE;
|
||||||
|
sBreakDeadTimeConfig.BreakPolarity = TIM_BREAKPOLARITY_HIGH;
|
||||||
|
sBreakDeadTimeConfig.BreakFilter = 0;
|
||||||
|
sBreakDeadTimeConfig.Break2State = TIM_BREAK2_DISABLE;
|
||||||
|
sBreakDeadTimeConfig.Break2Polarity = TIM_BREAK2POLARITY_HIGH;
|
||||||
|
sBreakDeadTimeConfig.Break2Filter = 0;
|
||||||
|
sBreakDeadTimeConfig.AutomaticOutput = TIM_AUTOMATICOUTPUT_DISABLE;
|
||||||
|
if (HAL_TIMEx_ConfigBreakDeadTime(&htim1, &sBreakDeadTimeConfig) != HAL_OK)
|
||||||
|
{
|
||||||
|
Error_Handler();
|
||||||
|
}
|
||||||
|
/* USER CODE BEGIN TIM1_Init 2 */
|
||||||
|
|
||||||
|
/* USER CODE END TIM1_Init 2 */
|
||||||
|
HAL_TIM_MspPostInit(&htim1);
|
||||||
|
|
||||||
|
}
|
||||||
|
/* TIM2 init function */
|
||||||
|
void MX_TIM2_Init(void)
|
||||||
|
{
|
||||||
|
|
||||||
|
/* USER CODE BEGIN TIM2_Init 0 */
|
||||||
|
|
||||||
|
/* USER CODE END TIM2_Init 0 */
|
||||||
|
|
||||||
|
TIM_ClockConfigTypeDef sClockSourceConfig = {0};
|
||||||
|
TIM_MasterConfigTypeDef sMasterConfig = {0};
|
||||||
|
|
||||||
|
/* USER CODE BEGIN TIM2_Init 1 */
|
||||||
|
|
||||||
|
/* USER CODE END TIM2_Init 1 */
|
||||||
|
htim2.Instance = TIM2;
|
||||||
|
htim2.Init.Prescaler = 0;
|
||||||
|
htim2.Init.CounterMode = TIM_COUNTERMODE_UP;
|
||||||
|
htim2.Init.Period = 4294967295;
|
||||||
|
htim2.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
|
||||||
|
htim2.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
|
||||||
|
if (HAL_TIM_Base_Init(&htim2) != HAL_OK)
|
||||||
|
{
|
||||||
|
Error_Handler();
|
||||||
|
}
|
||||||
|
sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL;
|
||||||
|
if (HAL_TIM_ConfigClockSource(&htim2, &sClockSourceConfig) != HAL_OK)
|
||||||
|
{
|
||||||
|
Error_Handler();
|
||||||
|
}
|
||||||
|
sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
|
||||||
|
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
|
||||||
|
if (HAL_TIMEx_MasterConfigSynchronization(&htim2, &sMasterConfig) != HAL_OK)
|
||||||
|
{
|
||||||
|
Error_Handler();
|
||||||
|
}
|
||||||
|
/* USER CODE BEGIN TIM2_Init 2 */
|
||||||
|
|
||||||
|
/* USER CODE END TIM2_Init 2 */
|
||||||
|
|
||||||
|
}
|
||||||
|
/* TIM3 init function */
|
||||||
|
void MX_TIM3_Init(void)
|
||||||
|
{
|
||||||
|
|
||||||
|
/* USER CODE BEGIN TIM3_Init 0 */
|
||||||
|
|
||||||
|
/* USER CODE END TIM3_Init 0 */
|
||||||
|
|
||||||
|
TIM_Encoder_InitTypeDef sConfig = {0};
|
||||||
|
TIM_MasterConfigTypeDef sMasterConfig = {0};
|
||||||
|
|
||||||
|
/* USER CODE BEGIN TIM3_Init 1 */
|
||||||
|
|
||||||
|
/* USER CODE END TIM3_Init 1 */
|
||||||
|
htim3.Instance = TIM3;
|
||||||
|
htim3.Init.Prescaler = 0;
|
||||||
|
htim3.Init.CounterMode = TIM_COUNTERMODE_UP;
|
||||||
|
htim3.Init.Period = 255;
|
||||||
|
htim3.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
|
||||||
|
htim3.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
|
||||||
|
sConfig.EncoderMode = TIM_ENCODERMODE_TI1;
|
||||||
|
sConfig.IC1Polarity = TIM_ICPOLARITY_RISING;
|
||||||
|
sConfig.IC1Selection = TIM_ICSELECTION_DIRECTTI;
|
||||||
|
sConfig.IC1Prescaler = TIM_ICPSC_DIV1;
|
||||||
|
sConfig.IC1Filter = 15;
|
||||||
|
sConfig.IC2Polarity = TIM_ICPOLARITY_RISING;
|
||||||
|
sConfig.IC2Selection = TIM_ICSELECTION_DIRECTTI;
|
||||||
|
sConfig.IC2Prescaler = TIM_ICPSC_DIV1;
|
||||||
|
sConfig.IC2Filter = 15;
|
||||||
|
if (HAL_TIM_Encoder_Init(&htim3, &sConfig) != HAL_OK)
|
||||||
|
{
|
||||||
|
Error_Handler();
|
||||||
|
}
|
||||||
|
sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
|
||||||
|
sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
|
||||||
|
if (HAL_TIMEx_MasterConfigSynchronization(&htim3, &sMasterConfig) != HAL_OK)
|
||||||
|
{
|
||||||
|
Error_Handler();
|
||||||
|
}
|
||||||
|
/* USER CODE BEGIN TIM3_Init 2 */
|
||||||
|
|
||||||
|
/* USER CODE END TIM3_Init 2 */
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
void HAL_TIM_Base_MspInit(TIM_HandleTypeDef* tim_baseHandle)
|
||||||
|
{
|
||||||
|
|
||||||
|
if(tim_baseHandle->Instance==TIM1)
|
||||||
|
{
|
||||||
|
/* USER CODE BEGIN TIM1_MspInit 0 */
|
||||||
|
|
||||||
|
/* USER CODE END TIM1_MspInit 0 */
|
||||||
|
/* TIM1 clock enable */
|
||||||
|
__HAL_RCC_TIM1_CLK_ENABLE();
|
||||||
|
/* USER CODE BEGIN TIM1_MspInit 1 */
|
||||||
|
|
||||||
|
/* USER CODE END TIM1_MspInit 1 */
|
||||||
|
}
|
||||||
|
else if(tim_baseHandle->Instance==TIM2)
|
||||||
|
{
|
||||||
|
/* USER CODE BEGIN TIM2_MspInit 0 */
|
||||||
|
|
||||||
|
/* USER CODE END TIM2_MspInit 0 */
|
||||||
|
/* TIM2 clock enable */
|
||||||
|
__HAL_RCC_TIM2_CLK_ENABLE();
|
||||||
|
/* USER CODE BEGIN TIM2_MspInit 1 */
|
||||||
|
|
||||||
|
/* USER CODE END TIM2_MspInit 1 */
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void HAL_TIM_Encoder_MspInit(TIM_HandleTypeDef* tim_encoderHandle)
|
||||||
|
{
|
||||||
|
|
||||||
|
GPIO_InitTypeDef GPIO_InitStruct = {0};
|
||||||
|
if(tim_encoderHandle->Instance==TIM3)
|
||||||
|
{
|
||||||
|
/* USER CODE BEGIN TIM3_MspInit 0 */
|
||||||
|
|
||||||
|
/* USER CODE END TIM3_MspInit 0 */
|
||||||
|
/* TIM3 clock enable */
|
||||||
|
__HAL_RCC_TIM3_CLK_ENABLE();
|
||||||
|
|
||||||
|
__HAL_RCC_GPIOA_CLK_ENABLE();
|
||||||
|
/**TIM3 GPIO Configuration
|
||||||
|
PA6 ------> TIM3_CH1
|
||||||
|
PA7 ------> TIM3_CH2
|
||||||
|
*/
|
||||||
|
GPIO_InitStruct.Pin = GPIO_PIN_6|GPIO_PIN_7;
|
||||||
|
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
|
||||||
|
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
||||||
|
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW;
|
||||||
|
GPIO_InitStruct.Alternate = GPIO_AF2_TIM3;
|
||||||
|
HAL_GPIO_Init(GPIOA, &GPIO_InitStruct);
|
||||||
|
|
||||||
|
/* USER CODE BEGIN TIM3_MspInit 1 */
|
||||||
|
|
||||||
|
/* USER CODE END TIM3_MspInit 1 */
|
||||||
|
}
|
||||||
|
}
|
||||||
|
void HAL_TIM_MspPostInit(TIM_HandleTypeDef* timHandle)
|
||||||
|
{
|
||||||
|
|
||||||
|
GPIO_InitTypeDef GPIO_InitStruct = {0};
|
||||||
|
if(timHandle->Instance==TIM1)
|
||||||
|
{
|
||||||
|
/* USER CODE BEGIN TIM1_MspPostInit 0 */
|
||||||
|
|
||||||
|
/* USER CODE END TIM1_MspPostInit 0 */
|
||||||
|
|
||||||
|
__HAL_RCC_GPIOC_CLK_ENABLE();
|
||||||
|
/**TIM1 GPIO Configuration
|
||||||
|
PC1 ------> TIM1_CH2
|
||||||
|
PC2 ------> TIM1_CH3
|
||||||
|
PC3 ------> TIM1_CH4
|
||||||
|
*/
|
||||||
|
GPIO_InitStruct.Pin = GPIO_PIN_1|GPIO_PIN_2|GPIO_PIN_3;
|
||||||
|
GPIO_InitStruct.Mode = GPIO_MODE_AF_PP;
|
||||||
|
GPIO_InitStruct.Pull = GPIO_NOPULL;
|
||||||
|
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_HIGH;
|
||||||
|
GPIO_InitStruct.Alternate = GPIO_AF2_TIM1;
|
||||||
|
HAL_GPIO_Init(GPIOC, &GPIO_InitStruct);
|
||||||
|
|
||||||
|
/* USER CODE BEGIN TIM1_MspPostInit 1 */
|
||||||
|
|
||||||
|
/* USER CODE END TIM1_MspPostInit 1 */
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
void HAL_TIM_Base_MspDeInit(TIM_HandleTypeDef* tim_baseHandle)
|
||||||
|
{
|
||||||
|
|
||||||
|
if(tim_baseHandle->Instance==TIM1)
|
||||||
|
{
|
||||||
|
/* USER CODE BEGIN TIM1_MspDeInit 0 */
|
||||||
|
|
||||||
|
/* USER CODE END TIM1_MspDeInit 0 */
|
||||||
|
/* Peripheral clock disable */
|
||||||
|
__HAL_RCC_TIM1_CLK_DISABLE();
|
||||||
|
/* USER CODE BEGIN TIM1_MspDeInit 1 */
|
||||||
|
|
||||||
|
/* USER CODE END TIM1_MspDeInit 1 */
|
||||||
|
}
|
||||||
|
else if(tim_baseHandle->Instance==TIM2)
|
||||||
|
{
|
||||||
|
/* USER CODE BEGIN TIM2_MspDeInit 0 */
|
||||||
|
|
||||||
|
/* USER CODE END TIM2_MspDeInit 0 */
|
||||||
|
/* Peripheral clock disable */
|
||||||
|
__HAL_RCC_TIM2_CLK_DISABLE();
|
||||||
|
/* USER CODE BEGIN TIM2_MspDeInit 1 */
|
||||||
|
|
||||||
|
/* USER CODE END TIM2_MspDeInit 1 */
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void HAL_TIM_Encoder_MspDeInit(TIM_HandleTypeDef* tim_encoderHandle)
|
||||||
|
{
|
||||||
|
|
||||||
|
if(tim_encoderHandle->Instance==TIM3)
|
||||||
|
{
|
||||||
|
/* USER CODE BEGIN TIM3_MspDeInit 0 */
|
||||||
|
|
||||||
|
/* USER CODE END TIM3_MspDeInit 0 */
|
||||||
|
/* Peripheral clock disable */
|
||||||
|
__HAL_RCC_TIM3_CLK_DISABLE();
|
||||||
|
|
||||||
|
/**TIM3 GPIO Configuration
|
||||||
|
PA6 ------> TIM3_CH1
|
||||||
|
PA7 ------> TIM3_CH2
|
||||||
|
*/
|
||||||
|
HAL_GPIO_DeInit(GPIOA, GPIO_PIN_6|GPIO_PIN_7);
|
||||||
|
|
||||||
|
/* USER CODE BEGIN TIM3_MspDeInit 1 */
|
||||||
|
|
||||||
|
/* USER CODE END TIM3_MspDeInit 1 */
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/* USER CODE BEGIN 1 */
|
||||||
|
|
||||||
|
/* USER CODE END 1 */
|
||||||
@@ -1,5 +1,5 @@
|
|||||||
##########################################################################################################################
|
##########################################################################################################################
|
||||||
# File automatically-generated by tool: [projectgenerator] version: [3.17.1] date: [Sat Mar 25 17:33:18 CET 2023]
|
# File automatically-generated by tool: [projectgenerator] version: [3.17.1] date: [Sat Aug 12 20:39:38 CEST 2023]
|
||||||
##########################################################################################################################
|
##########################################################################################################################
|
||||||
|
|
||||||
# ------------------------------------------------
|
# ------------------------------------------------
|
||||||
@@ -58,7 +58,58 @@ Drivers/STM32F3xx_HAL_Driver/Src/stm32f3xx_hal_flash_ex.c \
|
|||||||
Drivers/STM32F3xx_HAL_Driver/Src/stm32f3xx_hal_i2c.c \
|
Drivers/STM32F3xx_HAL_Driver/Src/stm32f3xx_hal_i2c.c \
|
||||||
Drivers/STM32F3xx_HAL_Driver/Src/stm32f3xx_hal_i2c_ex.c \
|
Drivers/STM32F3xx_HAL_Driver/Src/stm32f3xx_hal_i2c_ex.c \
|
||||||
Drivers/STM32F3xx_HAL_Driver/Src/stm32f3xx_hal_exti.c \
|
Drivers/STM32F3xx_HAL_Driver/Src/stm32f3xx_hal_exti.c \
|
||||||
Core/Src/system_stm32f3xx.c
|
Core/Src/system_stm32f3xx.c \
|
||||||
|
Core/Src/spi.c \
|
||||||
|
Drivers/STM32F3xx_HAL_Driver/Src/stm32f3xx_hal_spi.c \
|
||||||
|
Drivers/STM32F3xx_HAL_Driver/Src/stm32f3xx_hal_spi_ex.c \
|
||||||
|
Core/Src/i2c.c \
|
||||||
|
Core/Src/tim.c
|
||||||
|
|
||||||
|
######################################
|
||||||
|
# shared libs source
|
||||||
|
######################################
|
||||||
|
# ad9833
|
||||||
|
C_SOURCES += ../shared_libs/drivers/ad9833/ad9833.c
|
||||||
|
# ltc2631
|
||||||
|
C_SOURCES += ../shared_libs/drivers/ltc2631/ltc2631.c
|
||||||
|
# mcp41x
|
||||||
|
C_SOURCES += ../shared_libs/drivers/mcp41x/mcp41x.c
|
||||||
|
# st7565
|
||||||
|
C_SOURCES += ../shared_libs/drivers/st7565/st7565.c
|
||||||
|
# hw_button
|
||||||
|
C_SOURCES += ../shared_libs/drivers/hw_button/hw_button.c
|
||||||
|
# led
|
||||||
|
C_SOURCES += ../shared_libs/drivers/led/led.c
|
||||||
|
# mcu_cs
|
||||||
|
C_SOURCES += ../shared_libs/drivers/mcu_cs/mcu_cs.c
|
||||||
|
|
||||||
|
# display
|
||||||
|
C_SOURCES += ../shared_libs/display/display_gfx.c
|
||||||
|
C_SOURCES += ../shared_libs/display/font_gfx.c
|
||||||
|
|
||||||
|
# bitmaps
|
||||||
|
C_SOURCES += ../shared_libs/bitmaps/bitmap_disp_buttons.c
|
||||||
|
C_SOURCES += ../shared_libs/bitmaps/bitmap_font_5x7.c
|
||||||
|
C_SOURCES += ../shared_libs/bitmaps/bitmap_wave.c
|
||||||
|
|
||||||
|
# display_layout
|
||||||
|
C_SOURCES += ../shared_libs/disp_layout/disp_layout.c
|
||||||
|
|
||||||
|
# controllers
|
||||||
|
C_SOURCES += ../shared_libs/controllers/ctrl_app.c
|
||||||
|
C_SOURCES += ../shared_libs/controllers/ctrl_bottom_button.c
|
||||||
|
C_SOURCES += ../shared_libs/controllers/ctrl_channel_button.c
|
||||||
|
C_SOURCES += ../shared_libs/controllers/ctrl_disp_button.c
|
||||||
|
C_SOURCES += ../shared_libs/controllers/ctrl_encoder.c
|
||||||
|
C_SOURCES += ../shared_libs/controllers/ctrl_signal_gen.c
|
||||||
|
|
||||||
|
# utils/printf
|
||||||
|
C_SOURCES += ../shared_libs/utils/printf/printf.c
|
||||||
|
# utils/rtt
|
||||||
|
C_SOURCES += ../shared_libs/utils/rtt/SEGGER_RTT.c
|
||||||
|
C_SOURCES += ../shared_libs/utils/rtt/SEGGER_RTT_printf.c
|
||||||
|
# utils/ulog
|
||||||
|
C_SOURCES += ../shared_libs/utils/ulog/ulog.c
|
||||||
|
|
||||||
# ASM sources
|
# ASM sources
|
||||||
ASM_SOURCES = \
|
ASM_SOURCES = \
|
||||||
@@ -107,7 +158,8 @@ AS_DEFS =
|
|||||||
# C defines
|
# C defines
|
||||||
C_DEFS = \
|
C_DEFS = \
|
||||||
-DUSE_HAL_DRIVER \
|
-DUSE_HAL_DRIVER \
|
||||||
-DSTM32F303xE
|
-DSTM32F303xE \
|
||||||
|
-DULOG_ENABLED
|
||||||
|
|
||||||
|
|
||||||
# AS includes
|
# AS includes
|
||||||
@@ -121,11 +173,40 @@ C_INCLUDES = \
|
|||||||
-IDrivers/CMSIS/Device/ST/STM32F3xx/Include \
|
-IDrivers/CMSIS/Device/ST/STM32F3xx/Include \
|
||||||
-IDrivers/CMSIS/Include
|
-IDrivers/CMSIS/Include
|
||||||
|
|
||||||
|
# ad9833 includes
|
||||||
|
C_INCLUDES += -I../shared_libs/drivers/ad9833
|
||||||
|
# ltc2631 includes
|
||||||
|
C_INCLUDES += -I../shared_libs/drivers/ltc2631
|
||||||
|
# mcp41x includes
|
||||||
|
C_INCLUDES += -I../shared_libs/drivers/mcp41x
|
||||||
|
# st7565 includes
|
||||||
|
C_INCLUDES += -I../shared_libs/drivers/st7565
|
||||||
|
# hw_button includes
|
||||||
|
C_INCLUDES += -I../shared_libs/drivers/hw_button
|
||||||
|
# led includes
|
||||||
|
C_INCLUDES += -I../shared_libs/drivers/led
|
||||||
|
# mcu_cs includes
|
||||||
|
C_INCLUDES += -I../shared_libs/drivers/mcu_cs
|
||||||
|
# display includes
|
||||||
|
C_INCLUDES += -I../shared_libs/display
|
||||||
|
# bitmaps includes
|
||||||
|
C_INCLUDES += -I../shared_libs/bitmaps
|
||||||
|
# display layout includes
|
||||||
|
C_INCLUDES += -I../shared_libs/disp_layout
|
||||||
|
# controllers includes
|
||||||
|
C_INCLUDES += -I../shared_libs/controllers
|
||||||
|
|
||||||
|
# utils includes
|
||||||
|
C_INCLUDES += -I../shared_libs/utils/printf
|
||||||
|
C_INCLUDES += -I../shared_libs/utils/rtt
|
||||||
|
C_INCLUDES += -I../shared_libs/utils/ulog
|
||||||
|
C_INCLUDES += -I../shared_libs/utils/spi_cs
|
||||||
|
|
||||||
|
|
||||||
# compile gcc flags
|
# compile gcc flags
|
||||||
ASFLAGS = $(MCU) $(AS_DEFS) $(AS_INCLUDES) $(OPT) -Wall -fdata-sections -ffunction-sections
|
ASFLAGS = $(MCU) $(AS_DEFS) $(AS_INCLUDES) $(OPT) -Wall -fdata-sections -ffunction-sections
|
||||||
|
|
||||||
CFLAGS += $(MCU) $(C_DEFS) $(C_INCLUDES) $(OPT) -Wall -fdata-sections -ffunction-sections
|
CFLAGS += $(MCU) $(C_DEFS) $(C_INCLUDES) $(OPT) -Wall -fdata-sections -ffunction-sections -Wdouble-promotion
|
||||||
|
|
||||||
ifeq ($(DEBUG), 1)
|
ifeq ($(DEBUG), 1)
|
||||||
CFLAGS += -g -gdwarf-2
|
CFLAGS += -g -gdwarf-2
|
||||||
@@ -191,4 +272,4 @@ clean:
|
|||||||
#######################################
|
#######################################
|
||||||
-include $(wildcard $(BUILD_DIR)/*.d)
|
-include $(wildcard $(BUILD_DIR)/*.d)
|
||||||
|
|
||||||
# *** EOF ***
|
# *** EOF ***
|
||||||
|
|||||||
@@ -1,28 +1,67 @@
|
|||||||
#MicroXplorer Configuration settings - do not modify
|
#MicroXplorer Configuration settings - do not modify
|
||||||
File.Version=6
|
File.Version=6
|
||||||
|
GPIO.groupedBy=Group By Peripherals
|
||||||
|
I2C1.I2C_Speed_Mode=I2C_Fast
|
||||||
|
I2C1.IPParameters=I2C_Speed_Mode,Timing
|
||||||
|
I2C1.Timing=0x0000020B
|
||||||
KeepUserPlacement=false
|
KeepUserPlacement=false
|
||||||
Mcu.CPN=STM32F303RET6
|
Mcu.CPN=STM32F303RET6
|
||||||
Mcu.Family=STM32F3
|
Mcu.Family=STM32F3
|
||||||
Mcu.IP0=NVIC
|
Mcu.IP0=I2C1
|
||||||
Mcu.IP1=RCC
|
Mcu.IP1=NVIC
|
||||||
Mcu.IP2=SYS
|
Mcu.IP2=RCC
|
||||||
Mcu.IP3=USART2
|
Mcu.IP3=SPI2
|
||||||
Mcu.IPNb=4
|
Mcu.IP4=SPI3
|
||||||
|
Mcu.IP5=SYS
|
||||||
|
Mcu.IP6=TIM1
|
||||||
|
Mcu.IP7=TIM2
|
||||||
|
Mcu.IP8=TIM3
|
||||||
|
Mcu.IP9=USART2
|
||||||
|
Mcu.IPNb=10
|
||||||
Mcu.Name=STM32F303R(D-E)Tx
|
Mcu.Name=STM32F303R(D-E)Tx
|
||||||
Mcu.Package=LQFP64
|
Mcu.Package=LQFP64
|
||||||
Mcu.Pin0=PC13
|
Mcu.Pin0=PC13
|
||||||
Mcu.Pin1=PC14-OSC32_IN
|
Mcu.Pin1=PC14-OSC32_IN
|
||||||
Mcu.Pin10=PB3
|
Mcu.Pin10=PA2
|
||||||
Mcu.Pin11=VP_SYS_VS_Systick
|
Mcu.Pin11=PA3
|
||||||
|
Mcu.Pin12=PA4
|
||||||
|
Mcu.Pin13=PA5
|
||||||
|
Mcu.Pin14=PA6
|
||||||
|
Mcu.Pin15=PA7
|
||||||
|
Mcu.Pin16=PB10
|
||||||
|
Mcu.Pin17=PB11
|
||||||
|
Mcu.Pin18=PB12
|
||||||
|
Mcu.Pin19=PB13
|
||||||
Mcu.Pin2=PC15-OSC32_OUT
|
Mcu.Pin2=PC15-OSC32_OUT
|
||||||
|
Mcu.Pin20=PB14
|
||||||
|
Mcu.Pin21=PB15
|
||||||
|
Mcu.Pin22=PC8
|
||||||
|
Mcu.Pin23=PC9
|
||||||
|
Mcu.Pin24=PA8
|
||||||
|
Mcu.Pin25=PA9
|
||||||
|
Mcu.Pin26=PA10
|
||||||
|
Mcu.Pin27=PA11
|
||||||
|
Mcu.Pin28=PA12
|
||||||
|
Mcu.Pin29=PA13
|
||||||
Mcu.Pin3=PF0-OSC_IN
|
Mcu.Pin3=PF0-OSC_IN
|
||||||
|
Mcu.Pin30=PA14
|
||||||
|
Mcu.Pin31=PC10
|
||||||
|
Mcu.Pin32=PC11
|
||||||
|
Mcu.Pin33=PC12
|
||||||
|
Mcu.Pin34=PB3
|
||||||
|
Mcu.Pin35=PB6
|
||||||
|
Mcu.Pin36=PB7
|
||||||
|
Mcu.Pin37=PB9
|
||||||
|
Mcu.Pin38=VP_SYS_VS_Systick
|
||||||
|
Mcu.Pin39=VP_TIM1_VS_ClockSourceINT
|
||||||
Mcu.Pin4=PF1-OSC_OUT
|
Mcu.Pin4=PF1-OSC_OUT
|
||||||
Mcu.Pin5=PA2
|
Mcu.Pin40=VP_TIM2_VS_ClockSourceINT
|
||||||
Mcu.Pin6=PA3
|
Mcu.Pin5=PC1
|
||||||
Mcu.Pin7=PA5
|
Mcu.Pin6=PC2
|
||||||
Mcu.Pin8=PA13
|
Mcu.Pin7=PC3
|
||||||
Mcu.Pin9=PA14
|
Mcu.Pin8=PA0
|
||||||
Mcu.PinsNb=12
|
Mcu.Pin9=PA1
|
||||||
|
Mcu.PinsNb=41
|
||||||
Mcu.ThirdPartyNb=0
|
Mcu.ThirdPartyNb=0
|
||||||
Mcu.UserConstants=
|
Mcu.UserConstants=
|
||||||
Mcu.UserName=STM32F303RETx
|
Mcu.UserName=STM32F303RETx
|
||||||
@@ -39,6 +78,26 @@ NVIC.PriorityGroup=NVIC_PRIORITYGROUP_0
|
|||||||
NVIC.SVCall_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
|
NVIC.SVCall_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
|
||||||
NVIC.SysTick_IRQn=true\:0\:0\:true\:false\:true\:true\:true\:false
|
NVIC.SysTick_IRQn=true\:0\:0\:true\:false\:true\:true\:true\:false
|
||||||
NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:true\:false\:false
|
NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:true\:false\:false
|
||||||
|
PA0.GPIOParameters=GPIO_Label
|
||||||
|
PA0.GPIO_Label=BTN1
|
||||||
|
PA0.Locked=true
|
||||||
|
PA0.Signal=GPIO_Input
|
||||||
|
PA1.GPIOParameters=GPIO_Label
|
||||||
|
PA1.GPIO_Label=BTN2
|
||||||
|
PA1.Locked=true
|
||||||
|
PA1.Signal=GPIO_Input
|
||||||
|
PA10.GPIOParameters=GPIO_Label
|
||||||
|
PA10.GPIO_Label=LED_CH1
|
||||||
|
PA10.Locked=true
|
||||||
|
PA10.Signal=GPIO_Output
|
||||||
|
PA11.GPIOParameters=GPIO_Label
|
||||||
|
PA11.GPIO_Label=BTN_CH2
|
||||||
|
PA11.Locked=true
|
||||||
|
PA11.Signal=GPIO_Input
|
||||||
|
PA12.GPIOParameters=GPIO_Label
|
||||||
|
PA12.GPIO_Label=LED_CH2
|
||||||
|
PA12.Locked=true
|
||||||
|
PA12.Signal=GPIO_Output
|
||||||
PA13.GPIOParameters=GPIO_Label
|
PA13.GPIOParameters=GPIO_Label
|
||||||
PA13.GPIO_Label=TMS
|
PA13.GPIO_Label=TMS
|
||||||
PA13.Locked=true
|
PA13.Locked=true
|
||||||
@@ -65,17 +124,72 @@ PA3.GPIO_Speed=GPIO_SPEED_FREQ_LOW
|
|||||||
PA3.Locked=true
|
PA3.Locked=true
|
||||||
PA3.Mode=Asynchronous
|
PA3.Mode=Asynchronous
|
||||||
PA3.Signal=USART2_RX
|
PA3.Signal=USART2_RX
|
||||||
PA5.GPIOParameters=GPIO_Speed,GPIO_PuPd,GPIO_Label,GPIO_Mode
|
PA4.GPIOParameters=GPIO_Label
|
||||||
PA5.GPIO_Label=LD2 [Green Led]
|
PA4.GPIO_Label=BTN3
|
||||||
PA5.GPIO_Mode=GPIO_MODE_OUTPUT_PP
|
PA4.Locked=true
|
||||||
PA5.GPIO_PuPd=GPIO_NOPULL
|
PA4.Signal=GPIO_Input
|
||||||
PA5.GPIO_Speed=GPIO_SPEED_FREQ_LOW
|
PA5.GPIOParameters=GPIO_Label
|
||||||
|
PA5.GPIO_Label=BTN4
|
||||||
PA5.Locked=true
|
PA5.Locked=true
|
||||||
PA5.Signal=GPIO_Output
|
PA5.Signal=GPIO_Input
|
||||||
|
PA6.Signal=S_TIM3_CH1
|
||||||
|
PA7.Locked=true
|
||||||
|
PA7.Signal=S_TIM3_CH2
|
||||||
|
PA8.GPIOParameters=GPIO_Label
|
||||||
|
PA8.GPIO_Label=BTN5
|
||||||
|
PA8.Locked=true
|
||||||
|
PA8.Signal=GPIO_Input
|
||||||
|
PA9.GPIOParameters=GPIO_Label
|
||||||
|
PA9.GPIO_Label=BTN_CH1
|
||||||
|
PA9.Locked=true
|
||||||
|
PA9.Signal=GPIO_Input
|
||||||
|
PB10.GPIOParameters=GPIO_Label
|
||||||
|
PB10.GPIO_Label=DDS2_CS
|
||||||
|
PB10.Locked=true
|
||||||
|
PB10.Signal=GPIO_Output
|
||||||
|
PB11.GPIOParameters=GPIO_Label
|
||||||
|
PB11.GPIO_Label=AMP1_CS
|
||||||
|
PB11.Locked=true
|
||||||
|
PB11.Signal=GPIO_Output
|
||||||
|
PB12.GPIOParameters=GPIO_Label
|
||||||
|
PB12.GPIO_Label=DDS1_CS
|
||||||
|
PB12.Locked=true
|
||||||
|
PB12.Signal=GPIO_Output
|
||||||
|
PB13.Mode=Full_Duplex_Master
|
||||||
|
PB13.Signal=SPI2_SCK
|
||||||
|
PB14.Mode=Full_Duplex_Master
|
||||||
|
PB14.Signal=SPI2_MISO
|
||||||
|
PB15.Mode=Full_Duplex_Master
|
||||||
|
PB15.Signal=SPI2_MOSI
|
||||||
PB3.GPIOParameters=GPIO_Label
|
PB3.GPIOParameters=GPIO_Label
|
||||||
PB3.GPIO_Label=SWO
|
PB3.GPIO_Label=SWO
|
||||||
PB3.Locked=true
|
PB3.Locked=true
|
||||||
PB3.Signal=SYS_JTDO-TRACESWO
|
PB3.Signal=SYS_JTDO-TRACESWO
|
||||||
|
PB6.Locked=true
|
||||||
|
PB6.Mode=I2C
|
||||||
|
PB6.Signal=I2C1_SCL
|
||||||
|
PB7.Mode=I2C
|
||||||
|
PB7.Signal=I2C1_SDA
|
||||||
|
PB9.GPIOParameters=GPIO_Label
|
||||||
|
PB9.GPIO_Label=AMP2_CS
|
||||||
|
PB9.Locked=true
|
||||||
|
PB9.Signal=GPIO_Output
|
||||||
|
PC1.GPIOParameters=GPIO_Speed
|
||||||
|
PC1.GPIO_Speed=GPIO_SPEED_FREQ_HIGH
|
||||||
|
PC1.Signal=S_TIM1_CH2
|
||||||
|
PC10.GPIOParameters=GPIO_Label
|
||||||
|
PC10.GPIO_Label=ST7565_SCK
|
||||||
|
PC10.Locked=true
|
||||||
|
PC10.Mode=Simplex_Bidirectional_Master
|
||||||
|
PC10.Signal=SPI3_SCK
|
||||||
|
PC11.GPIOParameters=GPIO_Label
|
||||||
|
PC11.GPIO_Label=ST7565_CS
|
||||||
|
PC11.Locked=true
|
||||||
|
PC11.Signal=GPIO_Output
|
||||||
|
PC12.GPIOParameters=GPIO_Label
|
||||||
|
PC12.GPIO_Label=ST7565_MOSI
|
||||||
|
PC12.Mode=Simplex_Bidirectional_Master
|
||||||
|
PC12.Signal=SPI3_MOSI
|
||||||
PC13.GPIOParameters=GPIO_Label,GPIO_ModeDefaultEXTI
|
PC13.GPIOParameters=GPIO_Label,GPIO_ModeDefaultEXTI
|
||||||
PC13.GPIO_Label=B1 [Blue PushButton]
|
PC13.GPIO_Label=B1 [Blue PushButton]
|
||||||
PC13.GPIO_ModeDefaultEXTI=GPIO_MODE_IT_FALLING
|
PC13.GPIO_ModeDefaultEXTI=GPIO_MODE_IT_FALLING
|
||||||
@@ -87,6 +201,20 @@ PC14-OSC32_IN.Signal=RCC_OSC32_IN
|
|||||||
PC15-OSC32_OUT.Locked=true
|
PC15-OSC32_OUT.Locked=true
|
||||||
PC15-OSC32_OUT.Mode=LSE-External-Oscillator
|
PC15-OSC32_OUT.Mode=LSE-External-Oscillator
|
||||||
PC15-OSC32_OUT.Signal=RCC_OSC32_OUT
|
PC15-OSC32_OUT.Signal=RCC_OSC32_OUT
|
||||||
|
PC2.GPIOParameters=GPIO_Speed
|
||||||
|
PC2.GPIO_Speed=GPIO_SPEED_FREQ_HIGH
|
||||||
|
PC2.Signal=S_TIM1_CH3
|
||||||
|
PC3.GPIOParameters=GPIO_Speed
|
||||||
|
PC3.GPIO_Speed=GPIO_SPEED_FREQ_HIGH
|
||||||
|
PC3.Signal=S_TIM1_CH4
|
||||||
|
PC8.GPIOParameters=GPIO_Label
|
||||||
|
PC8.GPIO_Label=ST7565_RST
|
||||||
|
PC8.Locked=true
|
||||||
|
PC8.Signal=GPIO_Output
|
||||||
|
PC9.GPIOParameters=GPIO_Label
|
||||||
|
PC9.GPIO_Label=ST7565_A0
|
||||||
|
PC9.Locked=true
|
||||||
|
PC9.Signal=GPIO_Output
|
||||||
PF0-OSC_IN.Locked=true
|
PF0-OSC_IN.Locked=true
|
||||||
PF0-OSC_IN.Mode=HSE-External-Clock-Source
|
PF0-OSC_IN.Mode=HSE-External-Clock-Source
|
||||||
PF0-OSC_IN.Signal=RCC_OSC_IN
|
PF0-OSC_IN.Signal=RCC_OSC_IN
|
||||||
@@ -120,7 +248,7 @@ ProjectManager.StackSize=0x400
|
|||||||
ProjectManager.TargetToolchain=Makefile
|
ProjectManager.TargetToolchain=Makefile
|
||||||
ProjectManager.ToolChainLocation=
|
ProjectManager.ToolChainLocation=
|
||||||
ProjectManager.UnderRoot=false
|
ProjectManager.UnderRoot=false
|
||||||
ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_USART2_UART_Init-USART2-false-HAL-true
|
ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_USART2_UART_Init-USART2-false-HAL-true,4-MX_SPI2_Init-SPI2-false-HAL-true,5-MX_I2C1_Init-I2C1-false-HAL-true,6-MX_SPI3_Init-SPI3-false-HAL-true,7-MX_TIM2_Init-TIM2-false-HAL-true,8-MX_TIM3_Init-TIM3-false-HAL-true,9-MX_TIM17_Init-TIM17-false-HAL-true,10-MX_TIM1_Init-TIM1-false-HAL-true
|
||||||
RCC.ADC12outputFreq_Value=72000000
|
RCC.ADC12outputFreq_Value=72000000
|
||||||
RCC.ADC34outputFreq_Value=72000000
|
RCC.ADC34outputFreq_Value=72000000
|
||||||
RCC.AHBFreq_Value=72000000
|
RCC.AHBFreq_Value=72000000
|
||||||
@@ -139,9 +267,9 @@ RCC.I2C1Freq_Value=8000000
|
|||||||
RCC.I2C2Freq_Value=8000000
|
RCC.I2C2Freq_Value=8000000
|
||||||
RCC.I2C3Freq_Value=8000000
|
RCC.I2C3Freq_Value=8000000
|
||||||
RCC.I2SClocksFreq_Value=72000000
|
RCC.I2SClocksFreq_Value=72000000
|
||||||
RCC.IPParameters=ADC12outputFreq_Value,ADC34outputFreq_Value,AHBFreq_Value,APB1CLKDivider,APB1Freq_Value,APB1TimFreq_Value,APB2Freq_Value,APB2TimFreq_Value,CortexFreq_Value,FCLKCortexFreq_Value,FamilyName,HCLKFreq_Value,HSE_VALUE,HSI_VALUE,I2C1Freq_Value,I2C2Freq_Value,I2C3Freq_Value,I2SClocksFreq_Value,LSI_VALUE,MCOFreq_Value,PLLCLKFreq_Value,PLLM,PLLMCOFreq_Value,PLLMUL,PLLN,PLLP,PLLQ,RCC_PLLsource_Clock_Source_FROM_HSE,RTCFreq_Value,RTCHSEDivFreq_Value,SYSCLKFreq_VALUE,SYSCLKSourceVirtual,TIM15Freq_Value,TIM16Freq_Value,TIM17Freq_Value,TIM1Freq_Value,TIM20Freq_Value,TIM2Freq_Value,TIM3Freq_Value,TIM8Freq_Value,UART4Freq_Value,UART5Freq_Value,USART1Freq_Value,USART2Freq_Value,USART3Freq_Value,USBFreq_Value,VCOOutput2Freq_Value
|
RCC.IPParameters=ADC12outputFreq_Value,ADC34outputFreq_Value,AHBFreq_Value,APB1CLKDivider,APB1Freq_Value,APB1TimFreq_Value,APB2Freq_Value,APB2TimFreq_Value,CortexFreq_Value,FCLKCortexFreq_Value,FamilyName,HCLKFreq_Value,HSE_VALUE,HSI_VALUE,I2C1Freq_Value,I2C2Freq_Value,I2C3Freq_Value,I2SClocksFreq_Value,LSI_VALUE,MCOFreq_Value,PLLCLKFreq_Value,PLLM,PLLMCOFreq_Value,PLLMUL,PLLN,PLLP,PLLQ,RCC_MCODiv,RCC_MCOSource,RCC_PLLsource_Clock_Source_FROM_HSE,RTCFreq_Value,RTCHSEDivFreq_Value,SYSCLKFreq_VALUE,SYSCLKSourceVirtual,TIM15Freq_Value,TIM16Freq_Value,TIM17Freq_Value,TIM1Freq_Value,TIM1Selection,TIM20Freq_Value,TIM2Freq_Value,TIM3Freq_Value,TIM8Freq_Value,UART4Freq_Value,UART5Freq_Value,USART1Freq_Value,USART2Freq_Value,USART3Freq_Value,USBFreq_Value,VCOOutput2Freq_Value
|
||||||
RCC.LSI_VALUE=40000
|
RCC.LSI_VALUE=40000
|
||||||
RCC.MCOFreq_Value=72000000
|
RCC.MCOFreq_Value=9000000
|
||||||
RCC.PLLCLKFreq_Value=72000000
|
RCC.PLLCLKFreq_Value=72000000
|
||||||
RCC.PLLM=8
|
RCC.PLLM=8
|
||||||
RCC.PLLMCOFreq_Value=72000000
|
RCC.PLLMCOFreq_Value=72000000
|
||||||
@@ -149,6 +277,8 @@ RCC.PLLMUL=RCC_PLL_MUL9
|
|||||||
RCC.PLLN=336
|
RCC.PLLN=336
|
||||||
RCC.PLLP=RCC_PLLP_DIV4
|
RCC.PLLP=RCC_PLLP_DIV4
|
||||||
RCC.PLLQ=7
|
RCC.PLLQ=7
|
||||||
|
RCC.RCC_MCODiv=RCC_MCODIV_8
|
||||||
|
RCC.RCC_MCOSource=RCC_MCO1SOURCE_PLLCLK
|
||||||
RCC.RCC_PLLsource_Clock_Source_FROM_HSE=RCC_HSE_PREDIV_DIV2
|
RCC.RCC_PLLsource_Clock_Source_FROM_HSE=RCC_HSE_PREDIV_DIV2
|
||||||
RCC.RTCFreq_Value=40000
|
RCC.RTCFreq_Value=40000
|
||||||
RCC.RTCHSEDivFreq_Value=250000
|
RCC.RTCHSEDivFreq_Value=250000
|
||||||
@@ -157,7 +287,8 @@ RCC.SYSCLKSourceVirtual=RCC_SYSCLKSOURCE_PLLCLK
|
|||||||
RCC.TIM15Freq_Value=72000000
|
RCC.TIM15Freq_Value=72000000
|
||||||
RCC.TIM16Freq_Value=72000000
|
RCC.TIM16Freq_Value=72000000
|
||||||
RCC.TIM17Freq_Value=72000000
|
RCC.TIM17Freq_Value=72000000
|
||||||
RCC.TIM1Freq_Value=72000000
|
RCC.TIM1Freq_Value=144000000
|
||||||
|
RCC.TIM1Selection=RCC_TIM1CLK_PLLCLK
|
||||||
RCC.TIM20Freq_Value=72000000
|
RCC.TIM20Freq_Value=72000000
|
||||||
RCC.TIM2Freq_Value=72000000
|
RCC.TIM2Freq_Value=72000000
|
||||||
RCC.TIM3Freq_Value=72000000
|
RCC.TIM3Freq_Value=72000000
|
||||||
@@ -171,9 +302,55 @@ RCC.USBFreq_Value=72000000
|
|||||||
RCC.VCOOutput2Freq_Value=8000000
|
RCC.VCOOutput2Freq_Value=8000000
|
||||||
SH.GPXTI13.0=GPIO_EXTI13
|
SH.GPXTI13.0=GPIO_EXTI13
|
||||||
SH.GPXTI13.ConfNb=1
|
SH.GPXTI13.ConfNb=1
|
||||||
|
SH.S_TIM1_CH2.0=TIM1_CH2,PWM Generation2 CH2
|
||||||
|
SH.S_TIM1_CH2.ConfNb=1
|
||||||
|
SH.S_TIM1_CH3.0=TIM1_CH3,PWM Generation3 CH3
|
||||||
|
SH.S_TIM1_CH3.ConfNb=1
|
||||||
|
SH.S_TIM1_CH4.0=TIM1_CH4,PWM Generation4 CH4
|
||||||
|
SH.S_TIM1_CH4.ConfNb=1
|
||||||
|
SH.S_TIM3_CH1.0=TIM3_CH1,Encoder_Interface
|
||||||
|
SH.S_TIM3_CH1.ConfNb=1
|
||||||
|
SH.S_TIM3_CH2.0=TIM3_CH2,Encoder_Interface
|
||||||
|
SH.S_TIM3_CH2.ConfNb=1
|
||||||
|
SPI2.BaudRatePrescaler=SPI_BAUDRATEPRESCALER_32
|
||||||
|
SPI2.CLKPolarity=SPI_POLARITY_HIGH
|
||||||
|
SPI2.CalculateBaudRate=1.125 MBits/s
|
||||||
|
SPI2.DataSize=SPI_DATASIZE_8BIT
|
||||||
|
SPI2.Direction=SPI_DIRECTION_2LINES
|
||||||
|
SPI2.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate,DataSize,NSSPMode,BaudRatePrescaler,CLKPolarity
|
||||||
|
SPI2.Mode=SPI_MODE_MASTER
|
||||||
|
SPI2.NSSPMode=SPI_NSS_PULSE_ENABLE
|
||||||
|
SPI2.VirtualType=VM_MASTER
|
||||||
|
SPI3.BaudRatePrescaler=SPI_BAUDRATEPRESCALER_64
|
||||||
|
SPI3.CalculateBaudRate=562.5 KBits/s
|
||||||
|
SPI3.DataSize=SPI_DATASIZE_8BIT
|
||||||
|
SPI3.Direction=SPI_DIRECTION_1LINE
|
||||||
|
SPI3.IPParameters=VirtualType,Mode,Direction,CalculateBaudRate,BaudRatePrescaler,DataSize
|
||||||
|
SPI3.Mode=SPI_MODE_MASTER
|
||||||
|
SPI3.VirtualType=VM_MASTER
|
||||||
|
TIM1.AutoReloadPreload=TIM_AUTORELOAD_PRELOAD_ENABLE
|
||||||
|
TIM1.Channel-PWM\ Generation2\ CH2=TIM_CHANNEL_2
|
||||||
|
TIM1.Channel-PWM\ Generation3\ CH3=TIM_CHANNEL_3
|
||||||
|
TIM1.Channel-PWM\ Generation4\ CH4=TIM_CHANNEL_4
|
||||||
|
TIM1.IPParameters=Channel-PWM Generation4 CH4,Channel-PWM Generation3 CH3,Channel-PWM Generation2 CH2,Period,Pulse-PWM Generation2 CH2,Pulse-PWM Generation3 CH3,Pulse-PWM Generation4 CH4,AutoReloadPreload,OCFastMode_PWM-PWM Generation4 CH4
|
||||||
|
TIM1.OCFastMode_PWM-PWM\ Generation4\ CH4=TIM_OCFAST_ENABLE
|
||||||
|
TIM1.Period=5
|
||||||
|
TIM1.Pulse-PWM\ Generation2\ CH2=3
|
||||||
|
TIM1.Pulse-PWM\ Generation3\ CH3=3
|
||||||
|
TIM1.Pulse-PWM\ Generation4\ CH4=3
|
||||||
|
TIM2.AutoReloadPreload=TIM_AUTORELOAD_PRELOAD_DISABLE
|
||||||
|
TIM2.IPParameters=AutoReloadPreload
|
||||||
|
TIM3.IC1Filter=15
|
||||||
|
TIM3.IC2Filter=15
|
||||||
|
TIM3.IPParameters=Period,IC1Filter,IC2Filter
|
||||||
|
TIM3.Period=255
|
||||||
USART2.IPParameters=VirtualMode-Asynchronous
|
USART2.IPParameters=VirtualMode-Asynchronous
|
||||||
USART2.VirtualMode-Asynchronous=VM_ASYNC
|
USART2.VirtualMode-Asynchronous=VM_ASYNC
|
||||||
VP_SYS_VS_Systick.Mode=SysTick
|
VP_SYS_VS_Systick.Mode=SysTick
|
||||||
VP_SYS_VS_Systick.Signal=SYS_VS_Systick
|
VP_SYS_VS_Systick.Signal=SYS_VS_Systick
|
||||||
|
VP_TIM1_VS_ClockSourceINT.Mode=Internal
|
||||||
|
VP_TIM1_VS_ClockSourceINT.Signal=TIM1_VS_ClockSourceINT
|
||||||
|
VP_TIM2_VS_ClockSourceINT.Mode=Internal
|
||||||
|
VP_TIM2_VS_ClockSourceINT.Signal=TIM2_VS_ClockSourceINT
|
||||||
board=NUCLEO-F303RE
|
board=NUCLEO-F303RE
|
||||||
boardIOC=true
|
boardIOC=true
|
||||||
|
|||||||
239
firmware/shared_libs/bitmaps/bitmap_disp_buttons.c
Normal file
239
firmware/shared_libs/bitmaps/bitmap_disp_buttons.c
Normal file
@@ -0,0 +1,239 @@
|
|||||||
|
#include "main.h"
|
||||||
|
|
||||||
|
#include "bitmap_disp_buttons.h"
|
||||||
|
|
||||||
|
// clang-format off
|
||||||
|
|
||||||
|
const uint8_t btn_fre[] = {
|
||||||
|
// res: 25x11 - 50 bytes
|
||||||
|
0xFC,0x02,0x01,0x01,0xFD,0x25,0x25,0x25,0x05,0x01,0xFD,0x25,0x65,0xA5,0x19,0x01,
|
||||||
|
0xFD,0x25,0x25,0x25,0x05,0x01,0x01,0x02,0xFC,0xF9,0xFA,0xFC,0xFC,0xFD,0xFC,0xFC,
|
||||||
|
0xFC,0xFC,0xFC,0xFD,0xFC,0xFC,0xFC,0xFD,0xFC,0xFD,0xFD,0xFD,0xFD,0xFD,0xFC,0xFC,
|
||||||
|
0xFA,0xF9,
|
||||||
|
};
|
||||||
|
|
||||||
|
const uint8_t btn_fre_inverse[] = {
|
||||||
|
// res: 25x11 - 50 bytes
|
||||||
|
0xFC,0xFE,0xFF,0xFF,0x03,0xDB,0xDB,0xDB,0xFB,0xFF,0x03,0xDB,0x9B,0x5B,0xE7,0xFF,
|
||||||
|
0x03,0xDB,0xDB,0xDB,0xFB,0xFF,0xFF,0xFE,0xFC,0xF9,0xFB,0xFF,0xFF,0xFE,0xFF,0xFF,
|
||||||
|
0xFF,0xFF,0xFF,0xFE,0xFF,0xFF,0xFF,0xFE,0xFF,0xFE,0xFE,0xFE,0xFE,0xFE,0xFF,0xFF,
|
||||||
|
0xFB,0xF9,
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
const uint8_t btn_amp[] = {
|
||||||
|
// res: 25x11 - 50 bytes
|
||||||
|
0xFC,0x02,0x01,0x01,0xF1,0x49,0x45,0x49,0xF1,0x01,0xFD,0x09,0x11,0x09,0xFD,0x01,
|
||||||
|
0xFD,0x25,0x25,0x25,0x19,0x01,0x01,0x02,0xFC,0xF9,0xFA,0xFC,0xFC,0xFD,0xFC,0xFC,
|
||||||
|
0xFC,0xFD,0xFC,0xFD,0xFC,0xFC,0xFC,0xFD,0xFC,0xFD,0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,
|
||||||
|
0xFA,0xF9,
|
||||||
|
};
|
||||||
|
|
||||||
|
const uint8_t btn_amp_inverse[] = {
|
||||||
|
// res: 25x11 - 50 bytes
|
||||||
|
0xFC,0xFE,0xFF,0xFF,0x0F,0xB7,0xBB,0xB7,0x0F,0xFF,0x03,0xF7,0xEF,0xF7,0x03,0xFF,
|
||||||
|
0x03,0xDB,0xDB,0xDB,0xE7,0xFF,0xFF,0xFE,0xFC,0xF9,0xFB,0xFF,0xFF,0xFE,0xFF,0xFF,
|
||||||
|
0xFF,0xFE,0xFF,0xFE,0xFF,0xFF,0xFF,0xFE,0xFF,0xFE,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,
|
||||||
|
0xFB,0xF9,
|
||||||
|
};
|
||||||
|
|
||||||
|
const uint8_t btn_off[] = {
|
||||||
|
// res: 25x11 - 50 bytes
|
||||||
|
0xFC,0x02,0x01,0x01,0xF9,0x05,0x05,0x05,0xF9,0x01,0xFD,0x25,0x25,0x25,0x05,0x01,
|
||||||
|
0xFD,0x25,0x25,0x25,0x05,0x01,0x01,0x02,0xFC,0xF9,0xFA,0xFC,0xFC,0xFC,0xFD,0xFD,
|
||||||
|
0xFD,0xFC,0xFC,0xFD,0xFC,0xFC,0xFC,0xFC,0xFC,0xFD,0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,
|
||||||
|
0xFA,0xF9,
|
||||||
|
};
|
||||||
|
|
||||||
|
const uint8_t btn_off_inverse[] = {
|
||||||
|
// res: 25x11 - 50 bytes
|
||||||
|
0xFC,0xFE,0xFF,0xFF,0x07,0xFB,0xFB,0xFB,0x07,0xFF,0x03,0xDB,0xDB,0xDB,0xFB,0xFF,
|
||||||
|
0x03,0xDB,0xDB,0xDB,0xFB,0xFF,0xFF,0xFE,0xFC,0xF9,0xFB,0xFF,0xFF,0xFF,0xFE,0xFE,
|
||||||
|
0xFE,0xFF,0xFF,0xFE,0xFF,0xFF,0xFF,0xFF,0xFF,0xFE,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,
|
||||||
|
0xFB,0xF9,
|
||||||
|
};
|
||||||
|
|
||||||
|
const uint8_t btn_pha[] = {
|
||||||
|
// res: 25x11 - 50 bytes
|
||||||
|
0xFC,0x02,0x01,0x01,0xFD,0x25,0x25,0x25,0x19,0x01,0xFD,0x21,0x21,0x21,0xFD,0x01,
|
||||||
|
0xF1,0x49,0x45,0x49,0xF1,0x01,0x01,0x02,0xFC,0xF9,0xFA,0xFC,0xFC,0xFD,0xFC,0xFC,
|
||||||
|
0xFC,0xFC,0xFC,0xFD,0xFC,0xFC,0xFC,0xFD,0xFC,0xFD,0xFC,0xFC,0xFC,0xFD,0xFC,0xFC,
|
||||||
|
0xFA,0xF9,
|
||||||
|
};
|
||||||
|
|
||||||
|
const uint8_t btn_pha_inverse[] = {
|
||||||
|
// res: 25x11 - 50 bytes
|
||||||
|
0xFC,0xFE,0xFF,0xFF,0x03,0xDB,0xDB,0xDB,0xE7,0xFF,0x03,0xDF,0xDF,0xDF,0x03,0xFF,
|
||||||
|
0x0F,0xB7,0xBB,0xB7,0x0F,0xFF,0xFF,0xFE,0xFC,0xF9,0xFB,0xFF,0xFF,0xFE,0xFF,0xFF,
|
||||||
|
0xFF,0xFF,0xFF,0xFE,0xFF,0xFF,0xFF,0xFE,0xFF,0xFE,0xFF,0xFF,0xFF,0xFE,0xFF,0xFF,
|
||||||
|
0xFB,0xF9,
|
||||||
|
};
|
||||||
|
|
||||||
|
const uint8_t btn_wav_noraml[] = {
|
||||||
|
// res: 25x11 - 50 bytes
|
||||||
|
0x3F,0x40,0x80,0x80,0xBF,0x80,0x87,0x80,0xBF,0x80,0x8F,0x92,0xA2,0x92,0x8F,0x80,
|
||||||
|
0xBE,0x81,0x80,0x81,0xBE,0x80,0x80,0x40,0x3F,0x9F,0x5F,0x3F,0x3F,0x3F,0xBF,0x3F,
|
||||||
|
0xBF,0x3F,0x3F,0xBF,0x3F,0x3F,0x3F,0xBF,0x3F,0x3F,0x3F,0xBF,0x3F,0x3F,0x3F,0x3F,
|
||||||
|
0x5F,0x9F,
|
||||||
|
};
|
||||||
|
|
||||||
|
const uint8_t btn_wav_inverse[] = {
|
||||||
|
// res: 25x11 - 50 bytes
|
||||||
|
0x3F,0x7F,0xFF,0xFF,0xC0,0xFF,0xF8,0xFF,0xC0,0xFF,0xF0,0xED,0xDD,0xED,0xF0,0xFF,
|
||||||
|
0xC1,0xFE,0xFF,0xFE,0xC1,0xFF,0xFF,0x7F,0x3F,0x9F,0xDF,0xFF,0xFF,0xFF,0x7F,0xFF,
|
||||||
|
0x7F,0xFF,0xFF,0x7F,0xFF,0xFF,0xFF,0x7F,0xFF,0xFF,0xFF,0x7F,0xFF,0xFF,0xFF,0xFF,
|
||||||
|
0xDF,0x9F,
|
||||||
|
};
|
||||||
|
|
||||||
|
const uint8_t btn_wav_short[] = {
|
||||||
|
// res: 24x11 - 48 bytes
|
||||||
|
0xFC,0x02,0x01,0x01,0xFD,0x01,0xE1,0x01,0xFD,0x01,0xF1,0x49,0x45,0x49,0xF1,0x01,
|
||||||
|
0x7D,0x81,0x01,0x81,0x7D,0x01,0x02,0xFC,0xF9,0xFA,0xFC,0xFC,0xFC,0xFD,0xFC,0xFD,
|
||||||
|
0xFC,0xFC,0xFD,0xFC,0xFC,0xFC,0xFD,0xFC,0xFC,0xFC,0xFD,0xFC,0xFC,0xFC,0xFA,0xF9,
|
||||||
|
};
|
||||||
|
|
||||||
|
const uint8_t btn_wav_inverse_short[] = {
|
||||||
|
// res: 24x11 - 48 bytes
|
||||||
|
0xFC,0xFE,0xFF,0xFF,0x03,0xFF,0x1F,0xFF,0x03,0xFF,0x0F,0xB7,0xBB,0xB7,0x0F,0xFF,
|
||||||
|
0x83,0x7F,0xFF,0x7F,0x83,0xFF,0xFE,0xFC,0xF9,0xFB,0xFF,0xFF,0xFF,0xFE,0xFF,0xFE,
|
||||||
|
0xFF,0xFF,0xFE,0xFF,0xFF,0xFF,0xFE,0xFF,0xFF,0xFF,0xFE,0xFF,0xFF,0xFF,0xFB,0xF9,
|
||||||
|
};
|
||||||
|
|
||||||
|
const uint8_t btn_back_short[] = {
|
||||||
|
// res: 24x11 - 48 bytes
|
||||||
|
0xFC,0x02,0x01,0x01,0x01,0x01,0x01,0x21,0x71,0xA9,0x21,0x21,0x21,0x21,0x21,0x21,
|
||||||
|
0x3D,0x01,0x01,0x01,0x01,0x01,0x02,0xFC,0xF9,0xFA,0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,
|
||||||
|
0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,0xFA,0xF9,
|
||||||
|
};
|
||||||
|
|
||||||
|
const uint8_t btn_back_inverse_short[] = {
|
||||||
|
// res: 24x11 - 48 bytes
|
||||||
|
0xFC,0xFE,0xFF,0xFF,0xFF,0xFF,0xFF,0xDF,0x8F,0x57,0xDF,0xDF,0xDF,0xDF,0xDF,0xDF,
|
||||||
|
0xC3,0xFF,0xFF,0xFF,0xFF,0xFF,0xFE,0xFC,0xF9,0xFB,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,
|
||||||
|
0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFB,0xF9,
|
||||||
|
};
|
||||||
|
|
||||||
|
const uint8_t btn_left[] = {
|
||||||
|
// res: 25x11 - 50 bytes
|
||||||
|
0xFC,0x02,0x01,0x01,0x21,0x21,0x71,0x71,0xF9,0xF9,0x21,0x21,0x21,0x21,0x21,0x21,
|
||||||
|
0x21,0x21,0x21,0x21,0x01,0x01,0x01,0x02,0xFC,0xF9,0xFA,0xFC,0xFC,0xFC,0xFC,0xFC,
|
||||||
|
0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,
|
||||||
|
0xFA,0xF9,
|
||||||
|
};
|
||||||
|
|
||||||
|
const uint8_t btn_left_inverse[] = {
|
||||||
|
// res: 25x11 - 50 bytes
|
||||||
|
0xFC,0xFE,0xFF,0xFF,0xDF,0xDF,0x8F,0x8F,0x07,0x07,0xDF,0xDF,0xDF,0xDF,0xDF,0xDF,
|
||||||
|
0xDF,0xDF,0xDF,0xDF,0xFF,0xFF,0xFF,0xFE,0xFC,0xF9,0xFB,0xFF,0xFF,0xFF,0xFF,0xFF,
|
||||||
|
0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,
|
||||||
|
0xFB,0xF9,
|
||||||
|
};
|
||||||
|
const uint8_t btn_right[] = {
|
||||||
|
// res: 25x11 - 50 bytes
|
||||||
|
0xFC,0x02,0x01,0x01,0x01,0x21,0x21,0x21,0x21,0x21,0x21,0x21,0x21,0x21,0xF9,0xF9,
|
||||||
|
0x71,0x71,0x21,0x21,0x01,0x01,0x01,0x02,0xFC,0xF9,0xFA,0xFC,0xFC,0xFC,0xFC,0xFC,
|
||||||
|
0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,
|
||||||
|
0xFA,0xF9,
|
||||||
|
};
|
||||||
|
const uint8_t btn_right_inverse[] = {
|
||||||
|
// res: 25x11 - 50 bytes
|
||||||
|
0xFC,0xFE,0xFF,0xFF,0xFF,0xDF,0xDF,0xDF,0xDF,0xDF,0xDF,0xDF,0xDF,0xDF,0x07,0x07,
|
||||||
|
0x8F,0x8F,0xDF,0xDF,0xFF,0xFF,0xFF,0xFE,0xFC,0xF9,0xFB,0xFF,0xFF,0xFF,0xFF,0xFF,
|
||||||
|
0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,
|
||||||
|
0xFB,0xF9,
|
||||||
|
};
|
||||||
|
const uint8_t btn_x0_01[] = {
|
||||||
|
// res: 25x11 - 50 bytes
|
||||||
|
0xFC,0x02,0x01,0x89,0x51,0x21,0x51,0x89,0x01,0x01,0x81,0x81,0x01,0xF9,0x45,0x25,
|
||||||
|
0x15,0xF9,0x01,0x09,0xFD,0x01,0x01,0x02,0xFC,0xF9,0xFA,0xFC,0xFC,0xFC,0xFC,0xFC,
|
||||||
|
0xFC,0xFC,0xFC,0xFD,0xFD,0xFC,0xFC,0xFD,0xFD,0xFD,0xFC,0xFC,0xFD,0xFD,0xFD,0xFC,
|
||||||
|
0xFA,0xF9,
|
||||||
|
};
|
||||||
|
const uint8_t btn_x0_01_inverse[] = {
|
||||||
|
// res: 25x11 - 50 bytes
|
||||||
|
0xFC,0xFE,0xFF,0x77,0xAF,0xDF,0xAF,0x77,0xFF,0xFF,0x7F,0x7F,0xFF,0x07,0xBB,0xDB,
|
||||||
|
0xEB,0x07,0xFF,0xF7,0x03,0xFF,0xFF,0xFE,0xFC,0xF9,0xFB,0xFF,0xFF,0xFF,0xFF,0xFF,
|
||||||
|
0xFF,0xFF,0xFF,0xFE,0xFE,0xFF,0xFF,0xFE,0xFE,0xFE,0xFF,0xFF,0xFE,0xFE,0xFE,0xFF,
|
||||||
|
0xFB,0xF9,
|
||||||
|
};
|
||||||
|
const uint8_t btn_x0_1[] = {
|
||||||
|
// res: 25x11 - 50 bytes
|
||||||
|
0xFC,0x02,0x01,0x01,0x01,0x89,0x51,0x21,0x51,0x89,0x01,0x01,0x81,0x81,0x01,0x01,
|
||||||
|
0x09,0xFD,0x01,0x01,0x01,0x01,0x01,0x02,0xFC,0xF9,0xFA,0xFC,0xFC,0xFC,0xFC,0xFC,
|
||||||
|
0xFC,0xFC,0xFC,0xFC,0xFC,0xFD,0xFD,0xFC,0xFC,0xFD,0xFD,0xFD,0xFC,0xFC,0xFC,0xFC,
|
||||||
|
0xFA,0xF9,
|
||||||
|
};
|
||||||
|
const uint8_t btn_x0_1_inverse[] = {
|
||||||
|
// res: 25x11 - 50 bytes
|
||||||
|
0xFC,0xFE,0xFF,0xFF,0xFF,0x77,0xAF,0xDF,0xAF,0x77,0xFF,0xFF,0x7F,0x7F,0xFF,0xFF,
|
||||||
|
0xF7,0x03,0xFF,0xFF,0xFF,0xFF,0xFF,0xFE,0xFC,0xF9,0xFB,0xFF,0xFF,0xFF,0xFF,0xFF,
|
||||||
|
0xFF,0xFF,0xFF,0xFF,0xFF,0xFE,0xFE,0xFF,0xFF,0xFE,0xFE,0xFE,0xFF,0xFF,0xFF,0xFF,
|
||||||
|
0xFB,0xF9,
|
||||||
|
};
|
||||||
|
const uint8_t btn_x1[] = {
|
||||||
|
// res: 25x11 - 50 bytes
|
||||||
|
0xFC,0x02,0x01,0x01,0x01,0x01,0x89,0x51,0x21,0x51,0x89,0x01,0x01,0x01,0x01,0x09,
|
||||||
|
0xFD,0x01,0x01,0x01,0x01,0x01,0x01,0x02,0xFC,0xF9,0xFA,0xFC,0xFC,0xFC,0xFC,0xFC,
|
||||||
|
0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,0xFC,0xFD,0xFD,0xFD,0xFC,0xFC,0xFC,0xFC,0xFC,
|
||||||
|
0xFA,0xF9,
|
||||||
|
};
|
||||||
|
const uint8_t btn_x1_inverse[] = {
|
||||||
|
// res: 25x11 - 50 bytes
|
||||||
|
0xFC,0xFE,0xFF,0xFF,0xFF,0xFF,0x77,0xAF,0xDF,0xAF,0x77,0xFF,0xFF,0xFF,0xFF,0xF7,
|
||||||
|
0x03,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFE,0xFC,0xF9,0xFB,0xFF,0xFF,0xFF,0xFF,0xFF,
|
||||||
|
0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFE,0xFE,0xFE,0xFF,0xFF,0xFF,0xFF,0xFF,
|
||||||
|
0xFB,0xF9,
|
||||||
|
};
|
||||||
|
const uint8_t btn_x10[] = {
|
||||||
|
// res: 25x11 - 50 bytes
|
||||||
|
0xFC,0x02,0x01,0x01,0x89,0x51,0x21,0x51,0x89,0x01,0x01,0x01,0x09,0xFD,0x01,0x01,
|
||||||
|
0xF9,0x45,0x25,0x15,0xF9,0x01,0x01,0x02,0xFC,0xF9,0xFA,0xFC,0xFC,0xFC,0xFC,0xFC,
|
||||||
|
0xFC,0xFC,0xFC,0xFC,0xFC,0xFD,0xFD,0xFD,0xFC,0xFC,0xFD,0xFD,0xFD,0xFC,0xFC,0xFC,
|
||||||
|
0xFA,0xF9,
|
||||||
|
};
|
||||||
|
const uint8_t btn_x10_inverse[] = {
|
||||||
|
// res: 25x11 - 50 bytes
|
||||||
|
0xFC,0xFE,0xFF,0xFF,0x77,0xAF,0xDF,0xAF,0x77,0xFF,0xFF,0xFF,0xF7,0x03,0xFF,0xFF,
|
||||||
|
0x07,0xBB,0xDB,0xEB,0x07,0xFF,0xFF,0xFE,0xFC,0xF9,0xFB,0xFF,0xFF,0xFF,0xFF,0xFF,
|
||||||
|
0xFF,0xFF,0xFF,0xFF,0xFF,0xFE,0xFE,0xFE,0xFF,0xFF,0xFE,0xFE,0xFE,0xFF,0xFF,0xFF,
|
||||||
|
0xFB,0xF9,
|
||||||
|
};
|
||||||
|
const uint8_t btn_empty[] = {
|
||||||
|
// res: 25x11 - 50 bytes
|
||||||
|
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||||
|
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||||
|
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||||
|
0x00,0x00,
|
||||||
|
};
|
||||||
|
|
||||||
|
// clang-format on
|
||||||
|
|
||||||
|
const GFX_bitmap_t bitmap_btnBottom[BITMAP_BTN_MAX] = {
|
||||||
|
{25, 11, btn_fre},
|
||||||
|
{25, 11, btn_fre_inverse},
|
||||||
|
{25, 11, btn_amp},
|
||||||
|
{25, 11, btn_amp_inverse},
|
||||||
|
{25, 11, btn_off},
|
||||||
|
{25, 11, btn_off_inverse},
|
||||||
|
{25, 11, btn_pha},
|
||||||
|
{25, 11, btn_pha_inverse},
|
||||||
|
{24, 11, btn_wav_short},
|
||||||
|
{24, 11, btn_wav_inverse_short},
|
||||||
|
{24, 11, btn_back_short},
|
||||||
|
{24, 11, btn_back_inverse_short},
|
||||||
|
{25, 11, btn_left},
|
||||||
|
{25, 11, btn_left_inverse},
|
||||||
|
{25, 11, btn_right},
|
||||||
|
{25, 11, btn_right_inverse},
|
||||||
|
{25, 11, btn_x0_01},
|
||||||
|
{25, 11, btn_x0_01_inverse},
|
||||||
|
{25, 11, btn_x0_1},
|
||||||
|
{25, 11, btn_x0_1_inverse},
|
||||||
|
{25, 11, btn_x1},
|
||||||
|
{25, 11, btn_x1_inverse},
|
||||||
|
{25, 11, btn_x10},
|
||||||
|
{25, 11, btn_x10_inverse},
|
||||||
|
{25, 11, btn_empty},
|
||||||
|
|
||||||
|
{0, 0, NULL},
|
||||||
|
};
|
||||||
36
firmware/shared_libs/bitmaps/bitmap_disp_buttons.h
Normal file
36
firmware/shared_libs/bitmaps/bitmap_disp_buttons.h
Normal file
@@ -0,0 +1,36 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "display_gfx.h"
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
BITMAP_BTN_FREQ,
|
||||||
|
BITMAP_BTN_FREQ_INVERSE,
|
||||||
|
BITMAP_BTN_AMPL,
|
||||||
|
BITMAP_BTN_AMPL_INVERSE,
|
||||||
|
BITMAP_BTN_OFFS,
|
||||||
|
BITMAP_BTN_OFFS_INVERSE,
|
||||||
|
BITMAP_BTN_PHAS,
|
||||||
|
BITMAP_BTN_PHAS_INVERSE,
|
||||||
|
BITMAP_BTN_WAVE,
|
||||||
|
BITMAP_BTN_WAVE_INVERSE,
|
||||||
|
BITMAP_BTN_BACK,
|
||||||
|
BITMAP_BTN_BACK_INVERSE,
|
||||||
|
BITMAP_BTN_LEFT,
|
||||||
|
BITMAP_BTN_LEFT_INVERSE,
|
||||||
|
BITMAP_BTN_RIGHT,
|
||||||
|
BITMAP_BTN_RIGHT_INVERSE,
|
||||||
|
BITMAP_BTN_X0_01,
|
||||||
|
BITMAP_BTN_X0_01_INVERSE,
|
||||||
|
BITMAP_BTN_X0_1,
|
||||||
|
BITMAP_BTN_X0_1_INVERSE,
|
||||||
|
BITMAP_BTN_X1,
|
||||||
|
BITMAP_BTN_X1_INVERSE,
|
||||||
|
BITMAP_BTN_X10,
|
||||||
|
BITMAP_BTN_X10_INVERSE,
|
||||||
|
BITMAP_BTN_EMPTY,
|
||||||
|
BITMAP_BTN_NONE,
|
||||||
|
BITMAP_BTN_MAX,
|
||||||
|
} BITMAP_buttonName_t;
|
||||||
|
|
||||||
|
extern const GFX_bitmap_t bitmap_btnBottom[BITMAP_BTN_MAX];
|
||||||
211
firmware/shared_libs/bitmaps/bitmap_font_5x7.c
Normal file
211
firmware/shared_libs/bitmaps/bitmap_font_5x7.c
Normal file
@@ -0,0 +1,211 @@
|
|||||||
|
#include "main.h"
|
||||||
|
|
||||||
|
#include "bitmap_fonts.h"
|
||||||
|
|
||||||
|
// clang-format off
|
||||||
|
const uint8_t font5x7[] = {
|
||||||
|
0x00, 0x00, 0x5F, 0x00, 0x00, // 0x21 !
|
||||||
|
0x00, 0x07, 0x00, 0x07, 0x00, // 0x22 "
|
||||||
|
0x14, 0x7F, 0x14, 0x7F, 0x14, // 0x23 #
|
||||||
|
0x24, 0x2A, 0x7F, 0x2A, 0x12, // 0x24 $
|
||||||
|
0x23, 0x13, 0x08, 0x64, 0x62, // 0x25 %
|
||||||
|
0x36, 0x49, 0x56, 0x20, 0x50, // 0x26 &
|
||||||
|
0x00, 0x08, 0x07, 0x03, 0x00, // 0x27 '
|
||||||
|
0x00, 0x1C, 0x22, 0x41, 0x00, // 0x28 (
|
||||||
|
0x00, 0x41, 0x22, 0x1C, 0x00, // 0x29 )
|
||||||
|
0x2A, 0x1C, 0x7F, 0x1C, 0x2A, // 0x2A *
|
||||||
|
0x08, 0x08, 0x3E, 0x08, 0x08, // 0x2B +
|
||||||
|
0x00, 0x80, 0x70, 0x30, 0x00, // 0x2C ,
|
||||||
|
0x08, 0x08, 0x08, 0x08, 0x08, // 0x2D -
|
||||||
|
0x00, 0x00, 0x60, 0x60, 0x00, // 0x2E .
|
||||||
|
0x20, 0x10, 0x08, 0x04, 0x02, // 0x2F /
|
||||||
|
0x3E, 0x51, 0x49, 0x45, 0x3E, // 0x30 0
|
||||||
|
0x00, 0x42, 0x7F, 0x40, 0x00, // 0x31 1
|
||||||
|
0x72, 0x49, 0x49, 0x49, 0x46, // 0x32 2
|
||||||
|
0x21, 0x41, 0x49, 0x4D, 0x33, // 0x33 3
|
||||||
|
0x18, 0x14, 0x12, 0x7F, 0x10, // 0x34 4
|
||||||
|
0x27, 0x45, 0x45, 0x45, 0x39, // 0x35 5
|
||||||
|
0x3C, 0x4A, 0x49, 0x49, 0x31, // 0x36 6
|
||||||
|
0x41, 0x21, 0x11, 0x09, 0x07, // 0x37 7
|
||||||
|
0x36, 0x49, 0x49, 0x49, 0x36, // 0x38 8
|
||||||
|
0x46, 0x49, 0x49, 0x29, 0x1E, // 0x39 9
|
||||||
|
0x00, 0x00, 0x14, 0x00, 0x00, // 0x3A :
|
||||||
|
0x00, 0x40, 0x34, 0x00, 0x00, // 0x3B ;
|
||||||
|
0x00, 0x08, 0x14, 0x22, 0x41, // 0x3C <
|
||||||
|
0x14, 0x14, 0x14, 0x14, 0x14, // 0x3D =
|
||||||
|
0x00, 0x41, 0x22, 0x14, 0x08, // 0x3E >
|
||||||
|
0x02, 0x01, 0x59, 0x09, 0x06, // 0x3F ?
|
||||||
|
0x3E, 0x41, 0x5D, 0x59, 0x4E, // 0x40 @
|
||||||
|
0x7C, 0x12, 0x11, 0x12, 0x7C, // 0x41 A
|
||||||
|
0x7F, 0x49, 0x49, 0x49, 0x36, // 0x42 B
|
||||||
|
0x3E, 0x41, 0x41, 0x41, 0x22, // 0x43 C
|
||||||
|
0x7F, 0x41, 0x41, 0x41, 0x3E, // 0x44 D
|
||||||
|
0x7F, 0x49, 0x49, 0x49, 0x41, // 0x45 E
|
||||||
|
0x7F, 0x09, 0x09, 0x09, 0x01, // 0x46 F
|
||||||
|
0x3E, 0x41, 0x41, 0x51, 0x73, // 0x47 G
|
||||||
|
0x7F, 0x08, 0x08, 0x08, 0x7F, // 0x48 H
|
||||||
|
0x00, 0x41, 0x7F, 0x41, 0x00, // 0x49 I
|
||||||
|
0x20, 0x40, 0x41, 0x3F, 0x01, // 0x4A J
|
||||||
|
0x7F, 0x08, 0x14, 0x22, 0x41, // 0x4B K
|
||||||
|
0x7F, 0x40, 0x40, 0x40, 0x40, // 0x4C L
|
||||||
|
0x7F, 0x02, 0x1C, 0x02, 0x7F, // 0x4D M
|
||||||
|
0x7F, 0x04, 0x08, 0x10, 0x7F, // 0x4E N
|
||||||
|
0x3E, 0x41, 0x41, 0x41, 0x3E, // 0x4F O
|
||||||
|
0x7F, 0x09, 0x09, 0x09, 0x06, // 0x50 P
|
||||||
|
0x3E, 0x41, 0x51, 0x21, 0x5E, // 0x51 Q
|
||||||
|
0x7F, 0x09, 0x19, 0x29, 0x46, // 0x52 R
|
||||||
|
0x26, 0x49, 0x49, 0x49, 0x32, // 0x53 S
|
||||||
|
0x03, 0x01, 0x7F, 0x01, 0x03, // 0x54 T
|
||||||
|
0x3F, 0x40, 0x40, 0x40, 0x3F, // 0x55 U
|
||||||
|
0x1F, 0x20, 0x40, 0x20, 0x1F, // 0x56 V
|
||||||
|
0x3F, 0x40, 0x38, 0x40, 0x3F, // 0x57 W
|
||||||
|
0x63, 0x14, 0x08, 0x14, 0x63, // 0x58 X
|
||||||
|
0x03, 0x04, 0x78, 0x04, 0x03, // 0x59 Y
|
||||||
|
0x61, 0x59, 0x49, 0x4D, 0x43, // 0x5A Z
|
||||||
|
0x00, 0x7F, 0x41, 0x41, 0x41, // 0x5B [
|
||||||
|
0x02, 0x04, 0x08, 0x10, 0x20, // 0x5C backslash
|
||||||
|
0x00, 0x41, 0x41, 0x41, 0x7F, // 0x5D ]
|
||||||
|
0x04, 0x02, 0x01, 0x02, 0x04, // 0x5E ^
|
||||||
|
0x40, 0x40, 0x40, 0x40, 0x40, // 0x5F _
|
||||||
|
0x00, 0x03, 0x07, 0x08, 0x00, // 0x60 `
|
||||||
|
0x20, 0x54, 0x54, 0x78, 0x40, // 0x61 a
|
||||||
|
0x7F, 0x28, 0x44, 0x44, 0x38, // 0x62 b
|
||||||
|
0x38, 0x44, 0x44, 0x44, 0x28, // 0x63 c
|
||||||
|
0x38, 0x44, 0x44, 0x28, 0x7F, // 0x64 d
|
||||||
|
0x38, 0x54, 0x54, 0x54, 0x18, // 0x65 e
|
||||||
|
0x00, 0x08, 0x7E, 0x09, 0x02, // 0x66 f
|
||||||
|
0x18, 0xA4, 0xA4, 0x9C, 0x78, // 0x67 g
|
||||||
|
0x7F, 0x08, 0x04, 0x04, 0x78, // 0x68 h
|
||||||
|
0x00, 0x44, 0x7D, 0x40, 0x00, // 0x69 i
|
||||||
|
0x20, 0x40, 0x40, 0x3D, 0x00, // 0x6A j
|
||||||
|
0x7F, 0x10, 0x28, 0x44, 0x00, // 0x6B k
|
||||||
|
0x00, 0x41, 0x7F, 0x40, 0x00, // 0x6C l
|
||||||
|
0x7C, 0x04, 0x78, 0x04, 0x78, // 0x6D m
|
||||||
|
0x7C, 0x08, 0x04, 0x04, 0x78, // 0x6E n
|
||||||
|
0x38, 0x44, 0x44, 0x44, 0x38, // 0x6F o
|
||||||
|
0xFC, 0x18, 0x24, 0x24, 0x18, // 0x70 p
|
||||||
|
0x18, 0x24, 0x24, 0x18, 0xFC, // 0x71 q
|
||||||
|
0x7C, 0x08, 0x04, 0x04, 0x08, // 0x72 r
|
||||||
|
0x48, 0x54, 0x54, 0x54, 0x24, // 0x73 s
|
||||||
|
0x04, 0x04, 0x3F, 0x44, 0x24, // 0x74 t
|
||||||
|
0x3C, 0x40, 0x40, 0x20, 0x7C, // 0x75 u
|
||||||
|
0x1C, 0x20, 0x40, 0x20, 0x1C, // 0x76 v
|
||||||
|
0x3C, 0x40, 0x30, 0x40, 0x3C, // 0x77 w
|
||||||
|
0x44, 0x28, 0x10, 0x28, 0x44, // 0x78 x
|
||||||
|
0x4C, 0x90, 0x90, 0x90, 0x7C, // 0x79 y
|
||||||
|
0x44, 0x64, 0x54, 0x4C, 0x44, // 0x7A z
|
||||||
|
0x00, 0x08, 0x36, 0x41, 0x00, // 0x7B {
|
||||||
|
0x00, 0x00, 0x77, 0x00, 0x00, // 0x7C |
|
||||||
|
0x00, 0x41, 0x36, 0x08, 0x00, // 0x7D }
|
||||||
|
0x02, 0x01, 0x02, 0x04, 0x02, // 0x7E ~
|
||||||
|
};
|
||||||
|
// clang-format on
|
||||||
|
|
||||||
|
/* { [Char width in bits], [Offset into arial_6ptCharBitmaps in bytes] } */
|
||||||
|
const GFX_fontChar_t font5x7Descriptors[] = {
|
||||||
|
{5, 00}, // 0x21 !
|
||||||
|
{5, 05}, // 0x22 "
|
||||||
|
{5, 10}, // 0x23 #
|
||||||
|
{5, 15}, // 0x24 $
|
||||||
|
{5, 20}, // 0x25 %
|
||||||
|
{5, 25}, // 0x26 &
|
||||||
|
{5, 30}, // 0x27 '
|
||||||
|
{5, 35}, // 0x28 (
|
||||||
|
{5, 40}, // 0x29 )
|
||||||
|
{5, 45}, // 0x2A *
|
||||||
|
{5, 50}, // 0x2B +
|
||||||
|
{5, 55}, // 0x2C ,
|
||||||
|
{5, 60}, // 0x2D -
|
||||||
|
{5, 65}, // 0x2E .
|
||||||
|
{5, 70}, // 0x2F /
|
||||||
|
{5, 75}, // 0x30 0
|
||||||
|
{5, 80}, // 0x31 1
|
||||||
|
{5, 85}, // 0x32 2
|
||||||
|
{5, 90}, // 0x33 3
|
||||||
|
{5, 95}, // 0x34 4
|
||||||
|
{5, 100}, // 0x35 5
|
||||||
|
{5, 105}, // 0x36 6
|
||||||
|
{5, 110}, // 0x37 7
|
||||||
|
{5, 115}, // 0x38 8
|
||||||
|
{5, 120}, // 0x39 9
|
||||||
|
{5, 125}, // 0x3A :
|
||||||
|
{5, 130}, // 0x3B ;
|
||||||
|
{5, 135}, // 0x3C <
|
||||||
|
{5, 140}, // 0x3D =
|
||||||
|
{5, 145}, // 0x3E >
|
||||||
|
{5, 150}, // 0x3F ?
|
||||||
|
{5, 155}, // 0x40 @
|
||||||
|
{5, 160}, // 0x41 A
|
||||||
|
{5, 165}, // 0x42 B
|
||||||
|
{5, 170}, // 0x43 C
|
||||||
|
{5, 175}, // 0x44 D
|
||||||
|
{5, 180}, // 0x45 E
|
||||||
|
{5, 185}, // 0x46 F
|
||||||
|
{5, 190}, // 0x47 G
|
||||||
|
{5, 195}, // 0x48 H
|
||||||
|
{5, 200}, // 0x49 I
|
||||||
|
{5, 205}, // 0x4A J
|
||||||
|
{5, 210}, // 0x4B K
|
||||||
|
{5, 215}, // 0x4C L
|
||||||
|
{5, 220}, // 0x4D M
|
||||||
|
{5, 225}, // 0x4E N
|
||||||
|
{5, 230}, // 0x4F O
|
||||||
|
{5, 235}, // 0x50 P
|
||||||
|
{5, 240}, // 0x51 Q
|
||||||
|
{5, 245}, // 0x52 R
|
||||||
|
{5, 250}, // 0x53 S
|
||||||
|
{5, 255}, // 0x54 T
|
||||||
|
{5, 260}, // 0x55 U
|
||||||
|
{5, 265}, // 0x56 V
|
||||||
|
{5, 270}, // 0x57 W
|
||||||
|
{5, 275}, // 0x58 X
|
||||||
|
{5, 280}, // 0x59 Y
|
||||||
|
{5, 285}, // 0x5A Z
|
||||||
|
{5, 290}, // 0x5B [
|
||||||
|
{5, 295}, // 0x5C back
|
||||||
|
{5, 300}, // 0x5D ]
|
||||||
|
{5, 305}, // 0x5E ^
|
||||||
|
{5, 310}, // 0x5F _
|
||||||
|
{5, 315}, // 0x60 `
|
||||||
|
{5, 320}, // 0x61 a
|
||||||
|
{5, 325}, // 0x62 b
|
||||||
|
{5, 330}, // 0x63 c
|
||||||
|
{5, 335}, // 0x64 d
|
||||||
|
{5, 340}, // 0x65 e
|
||||||
|
{5, 345}, // 0x66 f
|
||||||
|
{5, 350}, // 0x67 g
|
||||||
|
{5, 355}, // 0x68 h
|
||||||
|
{5, 360}, // 0x69 i
|
||||||
|
{5, 365}, // 0x6A j
|
||||||
|
{5, 370}, // 0x6B k
|
||||||
|
{5, 375}, // 0x6C l
|
||||||
|
{5, 380}, // 0x6D m
|
||||||
|
{5, 385}, // 0x6E n
|
||||||
|
{5, 390}, // 0x6F o
|
||||||
|
{5, 395}, // 0x70 p
|
||||||
|
{5, 400}, // 0x71 q
|
||||||
|
{5, 405}, // 0x72 r
|
||||||
|
{5, 410}, // 0x73 s
|
||||||
|
{5, 415}, // 0x74 t
|
||||||
|
{5, 420}, // 0x75 u
|
||||||
|
{5, 425}, // 0x76 v
|
||||||
|
{5, 430}, // 0x77 w
|
||||||
|
{5, 435}, // 0x78 x
|
||||||
|
{5, 440}, // 0x79 y
|
||||||
|
{5, 445}, // 0x7A z
|
||||||
|
{5, 450}, // 0x7B {
|
||||||
|
{5, 455}, // 0x7C |
|
||||||
|
{5, 460}, // 0x7D }
|
||||||
|
{5, 465}, // 0x7E ~
|
||||||
|
};
|
||||||
|
|
||||||
|
/* Font information for Arial 6pt */
|
||||||
|
const GFX_font_t font5x7Info = {
|
||||||
|
.heightPixels = 8,
|
||||||
|
.startChar = '!',
|
||||||
|
.endChar = '~',
|
||||||
|
.interspacePixels = 1,
|
||||||
|
.spacePixels = 3,
|
||||||
|
.charInfo = font5x7Descriptors,
|
||||||
|
.data = font5x7,
|
||||||
|
};
|
||||||
8
firmware/shared_libs/bitmaps/bitmap_fonts.h
Normal file
8
firmware/shared_libs/bitmaps/bitmap_fonts.h
Normal file
@@ -0,0 +1,8 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "font_gfx.h"
|
||||||
|
|
||||||
|
/* Font data for standard 5x7t */
|
||||||
|
extern const uint8_t font5x7[];
|
||||||
|
extern const GFX_font_t font5x7Info;
|
||||||
|
extern const GFX_fontChar_t font5x7Descriptors[];
|
||||||
57
firmware/shared_libs/bitmaps/bitmap_wave.c
Normal file
57
firmware/shared_libs/bitmaps/bitmap_wave.c
Normal file
@@ -0,0 +1,57 @@
|
|||||||
|
#include "main.h"
|
||||||
|
|
||||||
|
#include "bitmap_wave.h"
|
||||||
|
|
||||||
|
// clang-format off
|
||||||
|
const uint8_t wave_sin[] = {
|
||||||
|
// res: 48x25(32) - 192 bytes
|
||||||
|
0x00,0x00,0x80,0x60,0x10,0x08,0x04,0x04,0x02,0x02,0x01,0x01,0x01,0x01,0x02,0x02,
|
||||||
|
0x04,0x04,0x08,0x10,0x60,0x80,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||||
|
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||||
|
0x18,0x06,0x01,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||||
|
0x00,0x00,0x00,0x00,0x00,0x01,0x06,0x18,0x30,0xC0,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||||
|
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0xC0,0x30,
|
||||||
|
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||||
|
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x03,0x0C,0x10,0x20,0x40,0x40,
|
||||||
|
0x80,0x80,0x00,0x00,0x00,0x00,0x80,0x80,0x40,0x40,0x20,0x10,0x0C,0x03,0x00,0x00,
|
||||||
|
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||||
|
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||||
|
0x00,0x00,0x01,0x01,0x01,0x01,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||||
|
};
|
||||||
|
|
||||||
|
const uint8_t wave_tri[] = {
|
||||||
|
// res: 48x25(32) - 192 bytes
|
||||||
|
0x00,0x00,0x00,0x00,0x00,0x80,0x40,0x20,0x10,0x08,0x04,0x02,0x01,0x02,0x04,0x08,
|
||||||
|
0x10,0x20,0x40,0x80,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||||
|
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||||
|
0x10,0x08,0x04,0x02,0x01,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||||
|
0x00,0x00,0x00,0x00,0x01,0x02,0x04,0x08,0x10,0x20,0x40,0x80,0x00,0x00,0x00,0x00,
|
||||||
|
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x80,0x40,0x20,
|
||||||
|
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||||
|
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x01,0x02,0x04,0x08,
|
||||||
|
0x10,0x20,0x40,0x80,0x00,0x80,0x40,0x20,0x10,0x08,0x04,0x02,0x01,0x00,0x00,0x00,
|
||||||
|
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||||
|
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||||
|
0x00,0x00,0x00,0x00,0x01,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||||
|
};
|
||||||
|
const uint8_t wave_sqr[] = {
|
||||||
|
// res: 48x25(32) - 192 bytes
|
||||||
|
0xFF,0x01,0x01,0x01,0x01,0x01,0x01,0x01,0x01,0x01,0x01,0x01,0x01,0x01,0x01,0x01,
|
||||||
|
0x01,0x01,0x01,0x01,0x01,0x01,0x01,0x01,0xFF,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||||
|
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||||
|
0xFF,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||||
|
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0xFF,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||||
|
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||||
|
0xFF,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||||
|
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0xFF,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||||
|
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||||
|
0x01,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,
|
||||||
|
0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x01,0x01,0x01,0x01,0x01,0x01,0x01,0x01,
|
||||||
|
0x01,0x01,0x01,0x01,0x01,0x01,0x01,0x01,0x01,0x01,0x01,0x01,0x01,0x01,0x01,0x01,
|
||||||
|
};
|
||||||
|
|
||||||
|
const GFX_bitmap_t wave[WAVE_MAX] = {
|
||||||
|
{48, 25, wave_sin},
|
||||||
|
{48, 25, wave_tri},
|
||||||
|
{48, 25, wave_sqr},
|
||||||
|
};
|
||||||
13
firmware/shared_libs/bitmaps/bitmap_wave.h
Normal file
13
firmware/shared_libs/bitmaps/bitmap_wave.h
Normal file
@@ -0,0 +1,13 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "display_gfx.h"
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
WAVE_SIN,
|
||||||
|
WAVE_TRI,
|
||||||
|
WAVE_SQR,
|
||||||
|
WAVE_MAX
|
||||||
|
} BITMAP_wave_t;
|
||||||
|
|
||||||
|
extern const GFX_bitmap_t wave[WAVE_MAX];
|
||||||
449
firmware/shared_libs/controllers/ctrl_app.c
Normal file
449
firmware/shared_libs/controllers/ctrl_app.c
Normal file
@@ -0,0 +1,449 @@
|
|||||||
|
#include "main.h"
|
||||||
|
#include "tim.h"
|
||||||
|
#include "ctrl_bottom_button.h"
|
||||||
|
#include "ctrl_channel_button.h"
|
||||||
|
#include "ctrl_encoder.h"
|
||||||
|
#include "ctrl_disp_button.h"
|
||||||
|
#include "ctrl_signal_gen.h"
|
||||||
|
|
||||||
|
#include "ctrl_app.h"
|
||||||
|
|
||||||
|
typedef void (*btn_action_t)(APP_data_t *app_data);
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
btn_action_t command;
|
||||||
|
BITMAP_buttonName_t bitmap_name;
|
||||||
|
} CMD_button_t;
|
||||||
|
|
||||||
|
static const CMD_button_t btn_command[BTN_STATE_MAX][DISP_BTN_MAX];
|
||||||
|
static const LAY_dispBtn_t btn_hw_to_disp[BTN_BOT_MAX] = {DISP_BTN_1, DISP_BTN_2, DISP_BTN_3, DISP_BTN_4, DISP_BTN_5};
|
||||||
|
static const GEN_channel_t btn_ch_to_chan[CHANNEL_MAX] = {CHANNEL1, CHANNEL2, CHANNEL3, CHANNEL4, CHANNEL5, CHANNEL6};
|
||||||
|
static const uint32_t pow_of_10[7] = {1, 10, 100, 1000, 10000, 100000, 1000000};
|
||||||
|
|
||||||
|
static APP_data_t *_app_data;
|
||||||
|
|
||||||
|
static dds_gen_t dds_gen[DDS_CH_MAX] = {
|
||||||
|
{.super.type = GEN_FG_TYPE, .dds_ch = DDS_CH1},
|
||||||
|
{.super.type = GEN_FG_TYPE, .dds_ch = DDS_CH2},
|
||||||
|
{.super.type = GEN_FG_TYPE, .dds_ch = DDS_CH3},
|
||||||
|
};
|
||||||
|
static pwm_gen_t pwm_gen[PWM_CH_MAX] = {
|
||||||
|
{.super.type = GEN_PWM_TYPE, .pwm_ch = PWM_CH1},
|
||||||
|
{.super.type = GEN_PWM_TYPE, .pwm_ch = PWM_CH2},
|
||||||
|
{.super.type = GEN_PWM_TYPE, .pwm_ch = PWM_CH3},
|
||||||
|
};
|
||||||
|
|
||||||
|
static signal_gen_t *signal_gen[CHANNEL_MAX] = {
|
||||||
|
&dds_gen[DDS_CH1].super,
|
||||||
|
&dds_gen[DDS_CH2].super,
|
||||||
|
&dds_gen[DDS_CH3].super,
|
||||||
|
&pwm_gen[PWM_CH1].super,
|
||||||
|
&pwm_gen[PWM_CH2].super,
|
||||||
|
&pwm_gen[PWM_CH3].super,
|
||||||
|
};
|
||||||
|
|
||||||
|
static void _setGenInitailState(GEN_channel_t channel);
|
||||||
|
static void _signalGenDefaultValues(void);
|
||||||
|
static void _changeValueDdsGen(int8_t dir);
|
||||||
|
static void _changeValuePwmGen(int8_t dir);
|
||||||
|
|
||||||
|
//****************************
|
||||||
|
// Initialization
|
||||||
|
//****************************
|
||||||
|
|
||||||
|
void CTRL_buttonsInit(void)
|
||||||
|
{
|
||||||
|
CTRL_bottomButtonInit();
|
||||||
|
CTRL_channelButtonInit();
|
||||||
|
}
|
||||||
|
|
||||||
|
void APP_init(APP_data_t *app_data)
|
||||||
|
{
|
||||||
|
_app_data = app_data;
|
||||||
|
_app_data->freq_focus_digit = 4;
|
||||||
|
_app_data->ampl_focus_digit = 1;
|
||||||
|
_app_data->offs_focus_digit = 1;
|
||||||
|
_app_data->phas_focus_digit = 0;
|
||||||
|
_app_data->duty_focus_digit = 0;
|
||||||
|
|
||||||
|
_app_data->curr_gen = signal_gen[CHANNEL1];
|
||||||
|
|
||||||
|
_app_data->curr_state_lay = LAY_MAIN;
|
||||||
|
_app_data->curr_state_btn = BTN_MAIN_FG;
|
||||||
|
_app_data->curr_channel = CHANNEL1;
|
||||||
|
|
||||||
|
// _app_data->isChannelChange = 1;
|
||||||
|
// _app_data->isGraphChange = 1;
|
||||||
|
// _app_data->isValueChange = 1;
|
||||||
|
// _app_data->isButtonChange = 1;
|
||||||
|
// _app_data->isButtonBlink = 1;
|
||||||
|
_app_data->disp_update |= UPDATE_BUTTON | UPDATE_GRAPH | UPDATE_VALUE | UPDATE_CHANNEL;
|
||||||
|
|
||||||
|
CTRL_buttonsInit();
|
||||||
|
_signalGenDefaultValues();
|
||||||
|
GEN_init(signal_gen);
|
||||||
|
_setGenInitailState(CHANNEL1);
|
||||||
|
_setGenInitailState(CHANNEL2);
|
||||||
|
}
|
||||||
|
|
||||||
|
//****************************
|
||||||
|
// Handlers
|
||||||
|
//****************************
|
||||||
|
|
||||||
|
void CTRL_buttonsHandler(void)
|
||||||
|
{
|
||||||
|
CTRL_bottomButtonsHandler();
|
||||||
|
CTRL_channelButtonsHandler();
|
||||||
|
CTRL_encoderHandler();
|
||||||
|
}
|
||||||
|
|
||||||
|
//****************************
|
||||||
|
// Events
|
||||||
|
//****************************
|
||||||
|
|
||||||
|
void CTRL_pushedDispBtnEvent(ButtonKey_t *key)
|
||||||
|
{
|
||||||
|
ULOG_TRACE("Disp btn: %d", key->instance);
|
||||||
|
_app_data->last_key = btn_hw_to_disp[key->instance];
|
||||||
|
btn_command[_app_data->curr_state_btn][_app_data->last_key].command(_app_data);
|
||||||
|
}
|
||||||
|
|
||||||
|
void CTRL_encoderEvent(int8_t enc)
|
||||||
|
{
|
||||||
|
ULOG_TRACE("Enco event: %i", enc);
|
||||||
|
switch (_app_data->curr_gen->type)
|
||||||
|
{
|
||||||
|
case GEN_FG_TYPE:
|
||||||
|
_changeValueDdsGen(enc / 2);
|
||||||
|
break;
|
||||||
|
case GEN_PWM_TYPE:
|
||||||
|
_changeValuePwmGen(enc / 2);
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
ULOG_ERROR("%s:%d: Unknown generator type: %d", __FILE__, __LINE__, _app_data->curr_gen->type);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void CTRL_pushedChanBtnEvent(ButtonKey_t *key)
|
||||||
|
{
|
||||||
|
ULOG_TRACE("Chan btn: %d", key->instance);
|
||||||
|
GEN_channel_t channel = btn_ch_to_chan[key->instance];
|
||||||
|
|
||||||
|
_app_data->curr_gen = signal_gen[channel];
|
||||||
|
|
||||||
|
_app_data->curr_state_lay = LAY_MAIN;
|
||||||
|
_app_data->curr_state_btn = BTN_MAIN_FG;
|
||||||
|
_app_data->curr_channel = channel;
|
||||||
|
|
||||||
|
// _app_data->isChannelChange = 1;
|
||||||
|
// _app_data->isGraphChange = 1;
|
||||||
|
// _app_data->isValueChange = 1;
|
||||||
|
// _app_data->isButtonChange = 1;
|
||||||
|
// _app_data->isButtonBlink = 1;
|
||||||
|
_app_data->disp_update |= UPDATE_BUTTON | UPDATE_GRAPH | UPDATE_VALUE | UPDATE_CHANNEL;
|
||||||
|
}
|
||||||
|
|
||||||
|
void CTRL_longPushedChanBtnEvent(ButtonKey_t *key)
|
||||||
|
{
|
||||||
|
ULOG_TRACE("Chan btn(long): %d", key->instance);
|
||||||
|
GEN_channel_t channel = btn_ch_to_chan[key->instance];
|
||||||
|
|
||||||
|
switch (signal_gen[channel]->type)
|
||||||
|
{
|
||||||
|
case GEN_FG_TYPE:
|
||||||
|
{
|
||||||
|
dds_gen_t *dds_gen = (dds_gen_t *)signal_gen[channel];
|
||||||
|
dds_gen->settings.enabled = dds_gen->settings.enabled ? FALSE : TRUE;
|
||||||
|
setEnabled(signal_gen[channel]);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case GEN_PWM_TYPE:
|
||||||
|
{
|
||||||
|
pwm_gen_t *pwm_gen = (pwm_gen_t *)signal_gen[channel];
|
||||||
|
pwm_gen->settings.enabled = pwm_gen->settings.enabled ? FALSE : TRUE;
|
||||||
|
setEnabled(signal_gen[channel]);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
default:
|
||||||
|
ULOG_ERROR("%s:%d: Unknown generator type: %d", __FILE__, __LINE__, _app_data->curr_gen->type);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
//*******************************************************************
|
||||||
|
|
||||||
|
static void _changeValueDdsGen(int8_t dir)
|
||||||
|
{
|
||||||
|
dds_gen_t *dds_gen = (dds_gen_t *)_app_data->curr_gen;
|
||||||
|
|
||||||
|
switch (_app_data->curr_state_lay)
|
||||||
|
{
|
||||||
|
case LAY_FREQ:
|
||||||
|
{
|
||||||
|
uint32_t new_freq = dir * pow_of_10[_app_data->freq_focus_digit] + dds_gen->settings.frequency;
|
||||||
|
ULOG_DEBUG("<FG> New freq: %lu", new_freq);
|
||||||
|
if (new_freq > MAX_FREQ)
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
dds_gen->settings.frequency = new_freq;
|
||||||
|
setFrequency(&dds_gen->super);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case LAY_AMPL:
|
||||||
|
{
|
||||||
|
uint16_t new_ampl = dir * pow_of_10[_app_data->ampl_focus_digit] + dds_gen->settings.amplitude;
|
||||||
|
ULOG_DEBUG("<FG> New ampl: %u", new_ampl);
|
||||||
|
if (dds_gen->settings.offset + new_ampl > MAX_VOLT_POS || dds_gen->settings.offset - new_ampl < MAX_VOLT_NEG)
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
dds_gen->settings.amplitude = new_ampl;
|
||||||
|
setAmplitude(&dds_gen->super);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case LAY_OFFS:
|
||||||
|
{
|
||||||
|
int16_t new_offs = dir * pow_of_10[_app_data->offs_focus_digit] + dds_gen->settings.offset;
|
||||||
|
ULOG_DEBUG("<FG> New offs: %i", new_offs);
|
||||||
|
if (new_offs + dds_gen->settings.amplitude > MAX_VOLT_POS || new_offs - dds_gen->settings.amplitude < MAX_VOLT_NEG)
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
dds_gen->settings.offset = new_offs;
|
||||||
|
setOfsset(&dds_gen->super);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case LAY_PHAS:
|
||||||
|
{
|
||||||
|
uint16_t new_phas = dir * pow_of_10[_app_data->phas_focus_digit] + dds_gen->settings.phase;
|
||||||
|
ULOG_DEBUG("<FG> New phas: %u", new_phas);
|
||||||
|
if (new_phas > MAX_PHAS)
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
dds_gen->settings.phase = new_phas;
|
||||||
|
setPhase(&dds_gen->super);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
default:
|
||||||
|
ULOG_ERROR("%s:%d: Unknown layout: %d", __FILE__, __LINE__, _app_data->curr_state_lay);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
// _app_data->isValueChange = 1;
|
||||||
|
// _app_data->isGraphChange = 1;
|
||||||
|
_app_data->disp_update |= UPDATE_GRAPH | UPDATE_VALUE;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void _changeValuePwmGen(int8_t dir)
|
||||||
|
{
|
||||||
|
pwm_gen_t *pwm_gen = (pwm_gen_t *)_app_data->curr_gen;
|
||||||
|
|
||||||
|
switch (_app_data->curr_state_lay)
|
||||||
|
{
|
||||||
|
case LAY_FREQ:
|
||||||
|
{
|
||||||
|
uint32_t new_freq = dir * pow_of_10[_app_data->freq_focus_digit] + pwm_gen->settings.frequency;
|
||||||
|
ULOG_DEBUG("<PWM> New freq: %lu", new_freq);
|
||||||
|
if (new_freq > MAX_FREQ)
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
pwm_gen->settings.frequency = new_freq;
|
||||||
|
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case LAY_AMPL:
|
||||||
|
{
|
||||||
|
uint16_t new_ampl = dir * pow_of_10[_app_data->ampl_focus_digit] + pwm_gen->settings.amplitude;
|
||||||
|
ULOG_DEBUG("<PWM> New ampl: %u", new_ampl);
|
||||||
|
if (pwm_gen->settings.offset + new_ampl > MAX_VOLT_POS || pwm_gen->settings.offset - new_ampl < MAX_VOLT_NEG)
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
pwm_gen->settings.amplitude = new_ampl;
|
||||||
|
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case LAY_OFFS:
|
||||||
|
{
|
||||||
|
int16_t new_offs = dir * pow_of_10[_app_data->offs_focus_digit] + pwm_gen->settings.offset;
|
||||||
|
ULOG_DEBUG("<PWM> New offs: %i", new_offs);
|
||||||
|
if (new_offs + pwm_gen->settings.amplitude > MAX_VOLT_POS || new_offs - pwm_gen->settings.amplitude < MAX_VOLT_NEG)
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
pwm_gen->settings.offset = new_offs;
|
||||||
|
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case LAY_PHAS:
|
||||||
|
{
|
||||||
|
uint16_t new_phas = dir * pow_of_10[_app_data->phas_focus_digit] + pwm_gen->settings.phase;
|
||||||
|
ULOG_DEBUG("<PWM> New phas: %u", new_phas);
|
||||||
|
if (new_phas > MAX_PHAS)
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
pwm_gen->settings.phase = new_phas;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case LAY_DUTY:
|
||||||
|
{
|
||||||
|
uint8_t new_duty = dir * pow_of_10[_app_data->duty_focus_digit] + pwm_gen->settings.duty;
|
||||||
|
ULOG_DEBUG("<PWM> New duty: %u", new_duty);
|
||||||
|
if (new_duty > MAX_DUTY)
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
pwm_gen->settings.duty = new_duty;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
default:
|
||||||
|
ULOG_ERROR("%s:%d: Unknown layout: %d", __FILE__, __LINE__, _app_data->curr_state_lay);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
// _app_data->isValueChange = 1;
|
||||||
|
// _app_data->isGraphChange = 1;
|
||||||
|
_app_data->disp_update |= UPDATE_GRAPH | UPDATE_VALUE;
|
||||||
|
}
|
||||||
|
|
||||||
|
void _signalGenDefaultValues(void)
|
||||||
|
{
|
||||||
|
for (GEN_channel_t channel = CHANNEL1; channel < CHANNEL_MAX; channel++)
|
||||||
|
{
|
||||||
|
switch (signal_gen[channel]->type)
|
||||||
|
{
|
||||||
|
case GEN_FG_TYPE:
|
||||||
|
{
|
||||||
|
dds_gen_t *dds_gen = (dds_gen_t *)signal_gen[channel];
|
||||||
|
dds_gen->settings.frequency = 1000;
|
||||||
|
dds_gen->settings.amplitude = 100;
|
||||||
|
dds_gen->settings.offset = 165;
|
||||||
|
dds_gen->settings.phase = 0;
|
||||||
|
dds_gen->settings.wave = GEN_SIN;
|
||||||
|
dds_gen->settings.link = 0;
|
||||||
|
dds_gen->settings.enabled = FALSE;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case GEN_PWM_TYPE:
|
||||||
|
{
|
||||||
|
pwm_gen_t *pwm_gen = (pwm_gen_t *)signal_gen[channel];
|
||||||
|
pwm_gen->settings.frequency = 1000;
|
||||||
|
pwm_gen->settings.amplitude = 100;
|
||||||
|
pwm_gen->settings.offset = 0;
|
||||||
|
pwm_gen->settings.phase = 0;
|
||||||
|
pwm_gen->settings.duty = 50;
|
||||||
|
pwm_gen->settings.link = 0;
|
||||||
|
pwm_gen->settings.enabled = FALSE;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void _setGenInitailState(GEN_channel_t channel)
|
||||||
|
{
|
||||||
|
setFrequency(signal_gen[channel]);
|
||||||
|
setWave(signal_gen[channel]);
|
||||||
|
setPhase(signal_gen[channel]);
|
||||||
|
setAmplitude(signal_gen[channel]);
|
||||||
|
setEnabled(signal_gen[channel]);
|
||||||
|
// setOfsset(signal_gen[channel]);
|
||||||
|
}
|
||||||
|
|
||||||
|
inline BITMAP_buttonName_t CTRL_getBitmapName(LAY_dispBtn_t disp_btn)
|
||||||
|
{
|
||||||
|
return btn_command[_app_data->curr_state_btn][disp_btn].bitmap_name;
|
||||||
|
}
|
||||||
|
|
||||||
|
static const CMD_button_t btn_command[BTN_STATE_MAX][DISP_BTN_MAX] = {
|
||||||
|
{
|
||||||
|
// BTN_MAIN_FG
|
||||||
|
{enterToFreqLayout, BITMAP_BTN_FREQ},
|
||||||
|
{enterToAmplLayout, BITMAP_BTN_AMPL},
|
||||||
|
{enterToOffslLayout, BITMAP_BTN_OFFS},
|
||||||
|
{enterToPhasLayout, BITMAP_BTN_PHAS},
|
||||||
|
{enterToWavelLayout, BITMAP_BTN_WAVE},
|
||||||
|
},
|
||||||
|
{
|
||||||
|
// BTN_MAIN_PWM
|
||||||
|
{enterToFreqLayout, BITMAP_BTN_FREQ},
|
||||||
|
{enterToAmplLayout, BITMAP_BTN_AMPL},
|
||||||
|
{enterToOffslLayout, BITMAP_BTN_OFFS},
|
||||||
|
{enterToPhasLayout, BITMAP_BTN_PHAS},
|
||||||
|
{enterToDutyLayout, BITMAP_BTN_NONE},
|
||||||
|
},
|
||||||
|
{
|
||||||
|
// BTN_FREQ
|
||||||
|
{moveToLeftFocusFreqNumber, BITMAP_BTN_LEFT},
|
||||||
|
{moveToRighttFocusFreqNumber, BITMAP_BTN_RIGHT},
|
||||||
|
{doNoting, BITMAP_BTN_NONE},
|
||||||
|
{doNoting, BITMAP_BTN_NONE},
|
||||||
|
{backToMain, BITMAP_BTN_BACK},
|
||||||
|
},
|
||||||
|
{
|
||||||
|
// BTN_FREQ_MIN
|
||||||
|
{moveToLeftFocusFreqNumber, BITMAP_BTN_LEFT},
|
||||||
|
{doNoting, BITMAP_BTN_EMPTY},
|
||||||
|
{doNoting, BITMAP_BTN_NONE},
|
||||||
|
{doNoting, BITMAP_BTN_NONE},
|
||||||
|
{backToMain, BITMAP_BTN_BACK},
|
||||||
|
},
|
||||||
|
{
|
||||||
|
// BTN_FREQ_MAX
|
||||||
|
{doNoting, BITMAP_BTN_EMPTY},
|
||||||
|
{moveToRighttFocusFreqNumber, BITMAP_BTN_RIGHT},
|
||||||
|
{doNoting, BITMAP_BTN_NONE},
|
||||||
|
{doNoting, BITMAP_BTN_NONE},
|
||||||
|
{backToMain, BITMAP_BTN_BACK},
|
||||||
|
},
|
||||||
|
{
|
||||||
|
// BTN_AMPL
|
||||||
|
{setTo1xFocusNumber, BITMAP_BTN_X1},
|
||||||
|
{setTo0_1xFocusNumber, BITMAP_BTN_X0_1},
|
||||||
|
{setTo0_01xFocusNumber, BITMAP_BTN_X0_01},
|
||||||
|
{doNoting, BITMAP_BTN_NONE},
|
||||||
|
{backToMain, BITMAP_BTN_BACK},
|
||||||
|
},
|
||||||
|
{
|
||||||
|
// BTN_OFFS
|
||||||
|
{setTo1xFocusNumber, BITMAP_BTN_X1},
|
||||||
|
{setTo0_1xFocusNumber, BITMAP_BTN_X0_1},
|
||||||
|
{setTo0_01xFocusNumber, BITMAP_BTN_X0_01},
|
||||||
|
{doNoting, BITMAP_BTN_NONE},
|
||||||
|
{backToMain, BITMAP_BTN_BACK},
|
||||||
|
},
|
||||||
|
{
|
||||||
|
// BTN_PHAS
|
||||||
|
{setTo10xFocusNumber, BITMAP_BTN_X10},
|
||||||
|
{setTo1xFocusNumber, BITMAP_BTN_X1},
|
||||||
|
{doNoting, BITMAP_BTN_NONE},
|
||||||
|
{doNoting, BITMAP_BTN_NONE},
|
||||||
|
{backToMain, BITMAP_BTN_BACK},
|
||||||
|
},
|
||||||
|
{
|
||||||
|
// BTN_DUTY
|
||||||
|
{setTo10xFocusNumber, BITMAP_BTN_X10},
|
||||||
|
{setTo1xFocusNumber, BITMAP_BTN_X1},
|
||||||
|
{doNoting, BITMAP_BTN_NONE},
|
||||||
|
{doNoting, BITMAP_BTN_NONE},
|
||||||
|
{backToMain, BITMAP_BTN_BACK},
|
||||||
|
},
|
||||||
|
{
|
||||||
|
// BTN_WAVE
|
||||||
|
{doNoting, BITMAP_BTN_NONE},
|
||||||
|
{doNoting, BITMAP_BTN_NONE},
|
||||||
|
{doNoting, BITMAP_BTN_NONE},
|
||||||
|
{doNoting, BITMAP_BTN_NONE},
|
||||||
|
{backToMain, BITMAP_BTN_BACK},
|
||||||
|
},
|
||||||
|
|
||||||
|
};
|
||||||
13
firmware/shared_libs/controllers/ctrl_app.h
Normal file
13
firmware/shared_libs/controllers/ctrl_app.h
Normal file
@@ -0,0 +1,13 @@
|
|||||||
|
#pragma once
|
||||||
|
#include "hw_button.h"
|
||||||
|
#include "bitmap_disp_buttons.h"
|
||||||
|
#include "ctrl_app_types.h"
|
||||||
|
|
||||||
|
|
||||||
|
void APP_init(APP_data_t *app_data);
|
||||||
|
void CTRL_buttonsInit(void);
|
||||||
|
void CTRL_buttonsHandler(void);
|
||||||
|
void CTRL_pushedDispBtnEvent(ButtonKey_t *key);
|
||||||
|
void CTRL_pushedChanBtnEvent(ButtonKey_t *key);
|
||||||
|
void CTRL_encoderEvent(int8_t enc);
|
||||||
|
BITMAP_buttonName_t CTRL_getBitmapName(LAY_dispBtn_t disp_btn);
|
||||||
124
firmware/shared_libs/controllers/ctrl_app_defs.h
Normal file
124
firmware/shared_libs/controllers/ctrl_app_defs.h
Normal file
@@ -0,0 +1,124 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#define FUN_GEN_FOCUS_MAX 6U
|
||||||
|
#define PWM_GEN_FOCUS_MAX 4U
|
||||||
|
#define MAX_FREQ 1000000U
|
||||||
|
#define MAX_VOLT_POS 360
|
||||||
|
#define MAX_VOLT_NEG 0
|
||||||
|
#define MAX_PHAS 360
|
||||||
|
#define MAX_DUTY 100
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
FALSE,
|
||||||
|
TRUE
|
||||||
|
} bool_t;
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
GEN_FG_TYPE,
|
||||||
|
GEN_PWM_TYPE,
|
||||||
|
GEN_TYPE_MAX
|
||||||
|
} GEN_type_t;
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
DDS_CH1,
|
||||||
|
DDS_CH2,
|
||||||
|
DDS_CH3,
|
||||||
|
DDS_CH_MAX,
|
||||||
|
} DDS_channel_t;
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
PWM_CH1,
|
||||||
|
PWM_CH2,
|
||||||
|
PWM_CH3,
|
||||||
|
PWM_CH_MAX,
|
||||||
|
} PWM_channel_t;
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
CHANNEL1,
|
||||||
|
CHANNEL2,
|
||||||
|
CHANNEL3,
|
||||||
|
CHANNEL4,
|
||||||
|
CHANNEL5,
|
||||||
|
CHANNEL6,
|
||||||
|
CHANNEL_MAX
|
||||||
|
} GEN_channel_t;
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
GEN_SIN,
|
||||||
|
GEN_TRI,
|
||||||
|
GEN_SQR,
|
||||||
|
GEN_WAVE_MAX,
|
||||||
|
} GEN_wave_t;
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
LAY_MAIN,
|
||||||
|
LAY_FREQ,
|
||||||
|
LAY_AMPL,
|
||||||
|
LAY_OFFS,
|
||||||
|
LAY_PHAS,
|
||||||
|
LAY_DUTY,
|
||||||
|
LAY_WAVE,
|
||||||
|
LAY_STATE_MAX
|
||||||
|
} STATE_layout_t;
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
BTN_MAIN_FG,
|
||||||
|
BTN_MAIN_PWM,
|
||||||
|
BTN_FREQ,
|
||||||
|
BTN_FREQ_MIN,
|
||||||
|
BTN_FREQ_MAX,
|
||||||
|
BTN_AMPL,
|
||||||
|
BTN_OFFS,
|
||||||
|
BTN_PHAS,
|
||||||
|
BTN_DUTY,
|
||||||
|
BTN_WAVE,
|
||||||
|
BTN_STATE_MAX
|
||||||
|
} STATE_button_t;
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
DISP_BTN_1,
|
||||||
|
DISP_BTN_2,
|
||||||
|
DISP_BTN_3,
|
||||||
|
DISP_BTN_4,
|
||||||
|
DISP_BTN_5,
|
||||||
|
DISP_BTN_MAX,
|
||||||
|
} LAY_dispBtn_t;
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
UPDATE_CHANNEL = 1,
|
||||||
|
UPDATE_GRAPH = 2,
|
||||||
|
UPDATE_VALUE = 4,
|
||||||
|
UPDATE_BUTTON = 8,
|
||||||
|
UPDATE_ALL = 15,
|
||||||
|
} LAY_update_t;
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
FREQ_LINK1 = 1,
|
||||||
|
FREQ_LINK2 = 2,
|
||||||
|
AMPL_LINK1 = 4,
|
||||||
|
AMPL_LINK2 = 8,
|
||||||
|
OFFS_LINK1 = 16,
|
||||||
|
OFFS_LINK2 = 32,
|
||||||
|
PHAS_LINK1 = 64,
|
||||||
|
PHAS_LINK2 = 128,
|
||||||
|
} GEN_linkMask_t;
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
MCU_CS1,
|
||||||
|
MCU_CS2,
|
||||||
|
MCU_CS3,
|
||||||
|
MCU_CS4,
|
||||||
|
MCU_CS_MAX,
|
||||||
|
} MCU_cs_count_t;
|
||||||
106
firmware/shared_libs/controllers/ctrl_app_types.h
Normal file
106
firmware/shared_libs/controllers/ctrl_app_types.h
Normal file
@@ -0,0 +1,106 @@
|
|||||||
|
#pragma once
|
||||||
|
#include "main.h"
|
||||||
|
#include "ad9833.h"
|
||||||
|
#include "mcp41x.h"
|
||||||
|
#include "ltc2631.h"
|
||||||
|
#include "ctrl_app_defs.h"
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
uint32_t frequency;
|
||||||
|
uint16_t amplitude;
|
||||||
|
int16_t offset;
|
||||||
|
uint16_t phase;
|
||||||
|
uint8_t duty;
|
||||||
|
uint8_t link;
|
||||||
|
bool_t enabled;
|
||||||
|
} pwm_settings_t;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
uint32_t frequency;
|
||||||
|
uint16_t amplitude;
|
||||||
|
int16_t offset;
|
||||||
|
uint16_t phase;
|
||||||
|
uint8_t wave;
|
||||||
|
uint8_t link;
|
||||||
|
uint8_t enabled;
|
||||||
|
} dds_settings_t;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
GPIO_TypeDef *port;
|
||||||
|
uint16_t pin;
|
||||||
|
} led_handle_t;
|
||||||
|
|
||||||
|
typedef struct FG_handle_s
|
||||||
|
{
|
||||||
|
ad9833_handle_t hdds;
|
||||||
|
ltc2631_handle_t hoffs;
|
||||||
|
mcp41x_handle_t hampl;
|
||||||
|
led_handle_t hled;
|
||||||
|
} dds_handle_t;
|
||||||
|
|
||||||
|
typedef uint8_t timer_handle_t;
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
timer_handle_t hpwm;
|
||||||
|
ltc2631_handle_t hoffs;
|
||||||
|
mcp41x_handle_t hampl;
|
||||||
|
led_handle_t hled;
|
||||||
|
} pwm_handle_t;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
GEN_type_t const type;
|
||||||
|
} signal_gen_t;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
signal_gen_t *next;
|
||||||
|
signal_gen_t *prev;
|
||||||
|
} link_t;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
signal_gen_t super;
|
||||||
|
DDS_channel_t const dds_ch;
|
||||||
|
dds_settings_t settings;
|
||||||
|
dds_handle_t handle;
|
||||||
|
link_t link;
|
||||||
|
} dds_gen_t;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
signal_gen_t super;
|
||||||
|
PWM_channel_t const pwm_ch;
|
||||||
|
pwm_settings_t settings;
|
||||||
|
pwm_handle_t handle;
|
||||||
|
link_t link;
|
||||||
|
} pwm_gen_t;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
uint8_t freq_focus_digit;
|
||||||
|
uint8_t ampl_focus_digit;
|
||||||
|
uint8_t offs_focus_digit;
|
||||||
|
uint8_t phas_focus_digit;
|
||||||
|
uint8_t duty_focus_digit;
|
||||||
|
|
||||||
|
signal_gen_t *curr_gen;
|
||||||
|
|
||||||
|
GEN_channel_t curr_channel;
|
||||||
|
STATE_layout_t curr_state_lay;
|
||||||
|
STATE_button_t curr_state_btn;
|
||||||
|
|
||||||
|
// uint8_t isChannelChange;
|
||||||
|
// uint8_t isGraphChange;
|
||||||
|
// uint8_t isValueChange;
|
||||||
|
// uint8_t isButtonChange;
|
||||||
|
LAY_update_t disp_update;
|
||||||
|
uint8_t button_blink;
|
||||||
|
uint8_t timer_blink[DISP_BTN_MAX];
|
||||||
|
|
||||||
|
LAY_dispBtn_t last_key;
|
||||||
|
|
||||||
|
} APP_data_t;
|
||||||
58
firmware/shared_libs/controllers/ctrl_bottom_button.c
Normal file
58
firmware/shared_libs/controllers/ctrl_bottom_button.c
Normal file
@@ -0,0 +1,58 @@
|
|||||||
|
#include "main.h"
|
||||||
|
#include "ctrl_bottom_button.h"
|
||||||
|
|
||||||
|
static ButtonKey_t bottom_buttons[BTN_BOT_MAX];
|
||||||
|
|
||||||
|
void CTRL_bottomButtonInit(void)
|
||||||
|
{
|
||||||
|
bottom_buttons[BTN_BOT_1].instance = BTN_BOT_1;
|
||||||
|
bottom_buttons[BTN_BOT_1].buttonPressed = CTRL_pushedDispBtnEvent;
|
||||||
|
bottom_buttons[BTN_BOT_1].gpio_port = BTN1_GPIO_Port;
|
||||||
|
bottom_buttons[BTN_BOT_1].gpio_pin = BTN1_Pin;
|
||||||
|
bottom_buttons[BTN_BOT_1].pushed_state = GPIO_PIN_RESET;
|
||||||
|
|
||||||
|
bottom_buttons[BTN_BOT_2].instance = BTN_BOT_2;
|
||||||
|
bottom_buttons[BTN_BOT_2].buttonPressed = CTRL_pushedDispBtnEvent;
|
||||||
|
bottom_buttons[BTN_BOT_2].gpio_port = BTN2_GPIO_Port;
|
||||||
|
bottom_buttons[BTN_BOT_2].gpio_pin = BTN2_Pin;
|
||||||
|
bottom_buttons[BTN_BOT_2].pushed_state = GPIO_PIN_RESET;
|
||||||
|
|
||||||
|
bottom_buttons[BTN_BOT_3].instance = BTN_BOT_3;
|
||||||
|
bottom_buttons[BTN_BOT_3].buttonPressed = CTRL_pushedDispBtnEvent;
|
||||||
|
bottom_buttons[BTN_BOT_3].gpio_port = BTN3_GPIO_Port;
|
||||||
|
bottom_buttons[BTN_BOT_3].gpio_pin = BTN3_Pin;
|
||||||
|
bottom_buttons[BTN_BOT_3].pushed_state = GPIO_PIN_RESET;
|
||||||
|
|
||||||
|
bottom_buttons[BTN_BOT_4].instance = BTN_BOT_4;
|
||||||
|
bottom_buttons[BTN_BOT_4].buttonPressed = CTRL_pushedDispBtnEvent;
|
||||||
|
bottom_buttons[BTN_BOT_4].gpio_port = BTN4_GPIO_Port;
|
||||||
|
bottom_buttons[BTN_BOT_4].gpio_pin = BTN4_Pin;
|
||||||
|
bottom_buttons[BTN_BOT_4].pushed_state = GPIO_PIN_RESET;
|
||||||
|
|
||||||
|
bottom_buttons[BTN_BOT_5].instance = BTN_BOT_5;
|
||||||
|
bottom_buttons[BTN_BOT_5].buttonPressed = CTRL_pushedDispBtnEvent;
|
||||||
|
bottom_buttons[BTN_BOT_5].gpio_port = BTN5_GPIO_Port;
|
||||||
|
bottom_buttons[BTN_BOT_5].gpio_pin = BTN5_Pin;
|
||||||
|
bottom_buttons[BTN_BOT_5].pushed_state = GPIO_PIN_RESET;
|
||||||
|
|
||||||
|
for (HW_BotBtnName_t btn_key = BTN_BOT_1; btn_key < BTN_BOT_MAX; btn_key++)
|
||||||
|
{
|
||||||
|
bottom_buttons[btn_key].state = IDLE;
|
||||||
|
bottom_buttons[btn_key].timer_debounce = BTN_DEFAULT_DEBOUNCE_MS;
|
||||||
|
bottom_buttons[btn_key].timer_long_pressed = BTN_DEFAULT_LONGPRESSED_MS;
|
||||||
|
bottom_buttons[btn_key].timer_repeat_delay = BTN_DEFAULT_REPEAT_MS;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void CTRL_bottomButtonsHandler(void)
|
||||||
|
{
|
||||||
|
for (HW_BotBtnName_t btn_key = BTN_BOT_1; btn_key < BTN_BOT_MAX; btn_key++)
|
||||||
|
{
|
||||||
|
buttonHandler(&bottom_buttons[btn_key]);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
__weak void CTRL_pushedDispBtnEvent(ButtonKey_t *key)
|
||||||
|
{
|
||||||
|
UNUSED(key);
|
||||||
|
}
|
||||||
17
firmware/shared_libs/controllers/ctrl_bottom_button.h
Normal file
17
firmware/shared_libs/controllers/ctrl_bottom_button.h
Normal file
@@ -0,0 +1,17 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "hw_button.h"
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
BTN_BOT_1,
|
||||||
|
BTN_BOT_2,
|
||||||
|
BTN_BOT_3,
|
||||||
|
BTN_BOT_4,
|
||||||
|
BTN_BOT_5,
|
||||||
|
BTN_BOT_MAX,
|
||||||
|
} HW_BotBtnName_t;
|
||||||
|
|
||||||
|
void CTRL_bottomButtonInit(void);
|
||||||
|
void CTRL_bottomButtonsHandler(void);
|
||||||
|
void CTRL_pushedDispBtnEvent(ButtonKey_t *key);
|
||||||
74
firmware/shared_libs/controllers/ctrl_channel_button.c
Normal file
74
firmware/shared_libs/controllers/ctrl_channel_button.c
Normal file
@@ -0,0 +1,74 @@
|
|||||||
|
#include "main.h"
|
||||||
|
#include "ctrl_channel_button.h"
|
||||||
|
|
||||||
|
#define DUMMY_GPIO_Port B1_GPIO_Port
|
||||||
|
#define DUMMY_GPIO_Pin B1_Pin
|
||||||
|
|
||||||
|
static ButtonKey_t channel_buttons[BTN_CH_MAX];
|
||||||
|
|
||||||
|
void CTRL_channelButtonInit(void)
|
||||||
|
{
|
||||||
|
channel_buttons[BTN_CH_1].instance = BTN_CH_1;
|
||||||
|
channel_buttons[BTN_CH_1].buttonPressed = CTRL_pushedChanBtnEvent;
|
||||||
|
channel_buttons[BTN_CH_1].buttonLongPressed = CTRL_longPushedChanBtnEvent;
|
||||||
|
channel_buttons[BTN_CH_1].gpio_port = BTN_CH1_GPIO_Port;
|
||||||
|
channel_buttons[BTN_CH_1].gpio_pin = BTN_CH1_Pin;
|
||||||
|
channel_buttons[BTN_CH_1].pushed_state = GPIO_PIN_RESET;
|
||||||
|
|
||||||
|
channel_buttons[BTN_CH_2].instance = BTN_CH_2;
|
||||||
|
channel_buttons[BTN_CH_2].buttonPressed = CTRL_pushedChanBtnEvent;
|
||||||
|
channel_buttons[BTN_CH_2].buttonLongPressed = CTRL_longPushedChanBtnEvent;
|
||||||
|
channel_buttons[BTN_CH_2].gpio_port = BTN_CH2_GPIO_Port;
|
||||||
|
channel_buttons[BTN_CH_2].gpio_pin = BTN_CH2_Pin;
|
||||||
|
channel_buttons[BTN_CH_2].pushed_state = GPIO_PIN_RESET;
|
||||||
|
|
||||||
|
channel_buttons[BTN_CH_3].instance = BTN_CH_3;
|
||||||
|
channel_buttons[BTN_CH_3].buttonPressed = CTRL_pushedChanBtnEvent;
|
||||||
|
channel_buttons[BTN_CH_3].gpio_port = DUMMY_GPIO_Port;
|
||||||
|
channel_buttons[BTN_CH_3].gpio_pin = DUMMY_GPIO_Pin;
|
||||||
|
channel_buttons[BTN_CH_3].pushed_state = GPIO_PIN_RESET;
|
||||||
|
|
||||||
|
channel_buttons[BTN_CH_4].instance = BTN_CH_4;
|
||||||
|
channel_buttons[BTN_CH_4].buttonPressed = CTRL_pushedChanBtnEvent;
|
||||||
|
channel_buttons[BTN_CH_4].gpio_port = DUMMY_GPIO_Port;
|
||||||
|
channel_buttons[BTN_CH_4].gpio_pin = DUMMY_GPIO_Pin;
|
||||||
|
channel_buttons[BTN_CH_4].pushed_state = GPIO_PIN_RESET;
|
||||||
|
|
||||||
|
channel_buttons[BTN_CH_5].instance = BTN_CH_5;
|
||||||
|
channel_buttons[BTN_CH_5].buttonPressed = CTRL_pushedChanBtnEvent;
|
||||||
|
channel_buttons[BTN_CH_5].gpio_port = DUMMY_GPIO_Port;
|
||||||
|
channel_buttons[BTN_CH_5].gpio_pin = DUMMY_GPIO_Pin;
|
||||||
|
channel_buttons[BTN_CH_5].pushed_state = GPIO_PIN_RESET;
|
||||||
|
|
||||||
|
channel_buttons[BTN_CH_6].instance = BTN_CH_6;
|
||||||
|
channel_buttons[BTN_CH_6].buttonPressed = CTRL_pushedChanBtnEvent;
|
||||||
|
channel_buttons[BTN_CH_6].gpio_port = DUMMY_GPIO_Port;
|
||||||
|
channel_buttons[BTN_CH_6].gpio_pin = DUMMY_GPIO_Pin;
|
||||||
|
channel_buttons[BTN_CH_6].pushed_state = GPIO_PIN_RESET;
|
||||||
|
|
||||||
|
for (HW_chanBtnName_t btn_key = BTN_CH_1; btn_key < BTN_CH_MAX; btn_key++)
|
||||||
|
{
|
||||||
|
channel_buttons[btn_key].state = IDLE;
|
||||||
|
channel_buttons[btn_key].timer_debounce = BTN_DEFAULT_DEBOUNCE_MS;
|
||||||
|
channel_buttons[btn_key].timer_long_pressed = BTN_DEFAULT_LONGPRESSED_MS;
|
||||||
|
channel_buttons[btn_key].timer_repeat_delay = BTN_DEFAULT_REPEAT_MS;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void CTRL_channelButtonsHandler(void)
|
||||||
|
{
|
||||||
|
for (HW_chanBtnName_t btn_key = BTN_CH_1; btn_key < BTN_CH_MAX; btn_key++)
|
||||||
|
{
|
||||||
|
buttonHandler(&channel_buttons[btn_key]);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
__weak void CTRL_pushedChanBtnEvent(ButtonKey_t *key)
|
||||||
|
{
|
||||||
|
UNUSED(key);
|
||||||
|
}
|
||||||
|
|
||||||
|
__weak void CTRL_longPushedChanBtnEvent(ButtonKey_t *key)
|
||||||
|
{
|
||||||
|
UNUSED(key);
|
||||||
|
}
|
||||||
19
firmware/shared_libs/controllers/ctrl_channel_button.h
Normal file
19
firmware/shared_libs/controllers/ctrl_channel_button.h
Normal file
@@ -0,0 +1,19 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "hw_button.h"
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
BTN_CH_1,
|
||||||
|
BTN_CH_2,
|
||||||
|
BTN_CH_3,
|
||||||
|
BTN_CH_4,
|
||||||
|
BTN_CH_5,
|
||||||
|
BTN_CH_6,
|
||||||
|
BTN_CH_MAX,
|
||||||
|
} HW_chanBtnName_t;
|
||||||
|
|
||||||
|
void CTRL_channelButtonInit(void);
|
||||||
|
void CTRL_channelButtonsHandler(void);
|
||||||
|
void CTRL_pushedChanBtnEvent(ButtonKey_t *key);
|
||||||
|
void CTRL_longPushedChanBtnEvent(ButtonKey_t *key);
|
||||||
244
firmware/shared_libs/controllers/ctrl_disp_button.c
Normal file
244
firmware/shared_libs/controllers/ctrl_disp_button.c
Normal file
@@ -0,0 +1,244 @@
|
|||||||
|
#include "ctrl_disp_button.h"
|
||||||
|
|
||||||
|
void doNoting(APP_data_t *app_data)
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
void backToMain(APP_data_t *app_data)
|
||||||
|
{
|
||||||
|
app_data->curr_state_lay = LAY_MAIN;
|
||||||
|
|
||||||
|
switch (app_data->curr_gen->type)
|
||||||
|
{
|
||||||
|
case GEN_FG_TYPE:
|
||||||
|
app_data->curr_state_btn = BTN_MAIN_FG;
|
||||||
|
break;
|
||||||
|
|
||||||
|
case GEN_PWM_TYPE:
|
||||||
|
app_data->curr_state_btn = BTN_MAIN_PWM;
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
// app_data->isButtonChange = 1;
|
||||||
|
// app_data->isGraphChange = 1;
|
||||||
|
// app_data->isValueChange = 1;
|
||||||
|
// app_data->isGraphChange = 1;
|
||||||
|
app_data->disp_update = UPDATE_ALL;
|
||||||
|
}
|
||||||
|
|
||||||
|
void blockFocusAtMaxAndMin(APP_data_t *app_data)
|
||||||
|
{
|
||||||
|
switch (app_data->curr_state_btn)
|
||||||
|
{
|
||||||
|
case BTN_FREQ_MIN:
|
||||||
|
if (app_data->freq_focus_digit > 0)
|
||||||
|
{
|
||||||
|
app_data->curr_state_btn = BTN_FREQ;
|
||||||
|
app_data->disp_update |= UPDATE_BUTTON;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case BTN_FREQ_MAX:
|
||||||
|
if (app_data->freq_focus_digit < FUN_GEN_FOCUS_MAX)
|
||||||
|
{
|
||||||
|
app_data->curr_state_btn = BTN_FREQ;
|
||||||
|
app_data->disp_update |= UPDATE_BUTTON;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case BTN_FREQ:
|
||||||
|
if (app_data->freq_focus_digit == 0)
|
||||||
|
{
|
||||||
|
app_data->curr_state_btn = BTN_FREQ_MIN;
|
||||||
|
app_data->disp_update |= UPDATE_BUTTON;
|
||||||
|
}
|
||||||
|
else if (app_data->freq_focus_digit == FUN_GEN_FOCUS_MAX)
|
||||||
|
{
|
||||||
|
app_data->curr_state_btn = BTN_FREQ_MAX;
|
||||||
|
app_data->disp_update |= UPDATE_BUTTON;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void enterToFreqLayout(APP_data_t *app_data)
|
||||||
|
{
|
||||||
|
app_data->curr_state_lay = LAY_FREQ;
|
||||||
|
app_data->curr_state_btn = BTN_FREQ;
|
||||||
|
blockFocusAtMaxAndMin(app_data);
|
||||||
|
|
||||||
|
// app_data->isButtonChange = 1;
|
||||||
|
// app_data->isGraphChange = 1;
|
||||||
|
// app_data->isValueChange = 1;
|
||||||
|
app_data->disp_update |= UPDATE_BUTTON | UPDATE_GRAPH | UPDATE_VALUE;
|
||||||
|
}
|
||||||
|
|
||||||
|
void enterToAmplLayout(APP_data_t *app_data)
|
||||||
|
{
|
||||||
|
app_data->curr_state_lay = LAY_AMPL;
|
||||||
|
app_data->curr_state_btn = BTN_AMPL;
|
||||||
|
|
||||||
|
// app_data->isButtonChange = 1;
|
||||||
|
// app_data->isGraphChange = 1;
|
||||||
|
// app_data->isValueChange = 1;
|
||||||
|
app_data->disp_update |= UPDATE_BUTTON | UPDATE_GRAPH | UPDATE_VALUE;
|
||||||
|
}
|
||||||
|
|
||||||
|
void enterToOffslLayout(APP_data_t *app_data)
|
||||||
|
{
|
||||||
|
app_data->curr_state_lay = LAY_OFFS;
|
||||||
|
app_data->curr_state_btn = BTN_OFFS;
|
||||||
|
|
||||||
|
// app_data->isButtonChange = 1;
|
||||||
|
// app_data->isGraphChange = 1;
|
||||||
|
// app_data->isValueChange = 1;
|
||||||
|
app_data->disp_update |= UPDATE_BUTTON | UPDATE_GRAPH | UPDATE_VALUE;
|
||||||
|
}
|
||||||
|
|
||||||
|
void enterToPhasLayout(APP_data_t *app_data)
|
||||||
|
{
|
||||||
|
app_data->curr_state_lay = LAY_PHAS;
|
||||||
|
app_data->curr_state_btn = BTN_PHAS;
|
||||||
|
|
||||||
|
// app_data->isButtonChange = 1;
|
||||||
|
// app_data->isGraphChange = 1;
|
||||||
|
// app_data->isValueChange = 1;
|
||||||
|
app_data->disp_update |= UPDATE_BUTTON | UPDATE_GRAPH | UPDATE_VALUE;
|
||||||
|
}
|
||||||
|
|
||||||
|
void enterToDutyLayout(APP_data_t *app_data)
|
||||||
|
{
|
||||||
|
app_data->curr_state_lay = LAY_DUTY;
|
||||||
|
app_data->curr_state_btn = BTN_DUTY;
|
||||||
|
|
||||||
|
// app_data->isButtonChange = 1;
|
||||||
|
// app_data->isGraphChange = 1;
|
||||||
|
// app_data->isValueChange = 1;
|
||||||
|
app_data->disp_update |= UPDATE_BUTTON | UPDATE_GRAPH | UPDATE_VALUE;
|
||||||
|
}
|
||||||
|
|
||||||
|
void enterToWavelLayout(APP_data_t *app_data)
|
||||||
|
{
|
||||||
|
app_data->curr_state_lay = LAY_WAVE;
|
||||||
|
app_data->curr_state_btn = BTN_WAVE;
|
||||||
|
|
||||||
|
// app_data->isButtonChange = 1;
|
||||||
|
// app_data->isGraphChange = 1;
|
||||||
|
// app_data->isValueChange = 1;
|
||||||
|
app_data->disp_update |= UPDATE_BUTTON | UPDATE_GRAPH | UPDATE_VALUE;
|
||||||
|
}
|
||||||
|
|
||||||
|
void moveToLeftFocusFreqNumber(APP_data_t *app_data)
|
||||||
|
{
|
||||||
|
app_data->freq_focus_digit += 1;
|
||||||
|
// app_data->isValueChange = 1;
|
||||||
|
app_data->disp_update |= UPDATE_VALUE;
|
||||||
|
|
||||||
|
blockFocusAtMaxAndMin(app_data);
|
||||||
|
app_data->timer_blink[app_data->last_key] = 2;
|
||||||
|
app_data->button_blink |= (1 << app_data->last_key);
|
||||||
|
}
|
||||||
|
|
||||||
|
void moveToRighttFocusFreqNumber(APP_data_t *app_data)
|
||||||
|
{
|
||||||
|
app_data->freq_focus_digit -= 1;
|
||||||
|
// app_data->isValueChange = 1;
|
||||||
|
app_data->disp_update |= UPDATE_VALUE;
|
||||||
|
|
||||||
|
blockFocusAtMaxAndMin(app_data);
|
||||||
|
app_data->timer_blink[app_data->last_key] = 2;
|
||||||
|
app_data->button_blink |= (1 << app_data->last_key);
|
||||||
|
}
|
||||||
|
|
||||||
|
void setTo0_01xFocusNumber(APP_data_t *app_data)
|
||||||
|
{
|
||||||
|
switch (app_data->curr_state_lay)
|
||||||
|
{
|
||||||
|
case LAY_AMPL:
|
||||||
|
app_data->ampl_focus_digit = 0;
|
||||||
|
break;
|
||||||
|
case LAY_OFFS:
|
||||||
|
app_data->offs_focus_digit = 0;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
app_data->timer_blink[app_data->last_key] = 2;
|
||||||
|
app_data->button_blink |= (1 << app_data->last_key);
|
||||||
|
// app_data->isValueChange = 1;
|
||||||
|
app_data->disp_update |= UPDATE_VALUE;
|
||||||
|
}
|
||||||
|
void setTo0_1xFocusNumber(APP_data_t *app_data)
|
||||||
|
{
|
||||||
|
switch (app_data->curr_state_lay)
|
||||||
|
{
|
||||||
|
case LAY_AMPL:
|
||||||
|
app_data->ampl_focus_digit = 1;
|
||||||
|
break;
|
||||||
|
case LAY_OFFS:
|
||||||
|
app_data->offs_focus_digit = 1;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
app_data->timer_blink[app_data->last_key] = 2;
|
||||||
|
app_data->button_blink |= (1 << app_data->last_key);
|
||||||
|
// app_data->isValueChange = 1;
|
||||||
|
app_data->disp_update |= UPDATE_VALUE;
|
||||||
|
}
|
||||||
|
void setTo1xFocusNumber(APP_data_t *app_data)
|
||||||
|
{
|
||||||
|
switch (app_data->curr_state_lay)
|
||||||
|
{
|
||||||
|
case LAY_AMPL:
|
||||||
|
app_data->ampl_focus_digit = 2;
|
||||||
|
break;
|
||||||
|
case LAY_OFFS:
|
||||||
|
app_data->offs_focus_digit = 2;
|
||||||
|
break;
|
||||||
|
case LAY_PHAS:
|
||||||
|
app_data->phas_focus_digit = 0;
|
||||||
|
break;
|
||||||
|
case LAY_DUTY:
|
||||||
|
app_data->duty_focus_digit = 0;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
app_data->timer_blink[app_data->last_key] = 2;
|
||||||
|
app_data->button_blink |= (1 << app_data->last_key);
|
||||||
|
// app_data->isValueChange = 1;
|
||||||
|
app_data->disp_update |= UPDATE_VALUE;
|
||||||
|
}
|
||||||
|
void setTo10xFocusNumber(APP_data_t *app_data)
|
||||||
|
{
|
||||||
|
switch (app_data->curr_state_lay)
|
||||||
|
{
|
||||||
|
case LAY_AMPL:
|
||||||
|
app_data->ampl_focus_digit = 3;
|
||||||
|
break;
|
||||||
|
case LAY_OFFS:
|
||||||
|
app_data->offs_focus_digit = 3;
|
||||||
|
break;
|
||||||
|
case LAY_PHAS:
|
||||||
|
app_data->phas_focus_digit = 1;
|
||||||
|
break;
|
||||||
|
case LAY_DUTY:
|
||||||
|
app_data->duty_focus_digit = 1;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
app_data->timer_blink[app_data->last_key] = 2;
|
||||||
|
app_data->button_blink |= (1 << app_data->last_key);
|
||||||
|
// app_data->isValueChange = 1;
|
||||||
|
app_data->disp_update |= UPDATE_VALUE;
|
||||||
|
}
|
||||||
18
firmware/shared_libs/controllers/ctrl_disp_button.h
Normal file
18
firmware/shared_libs/controllers/ctrl_disp_button.h
Normal file
@@ -0,0 +1,18 @@
|
|||||||
|
#pragma once
|
||||||
|
#include "ctrl_app_types.h"
|
||||||
|
|
||||||
|
void doNoting(APP_data_t *app_data);
|
||||||
|
void backToMain(APP_data_t *app_data);
|
||||||
|
void blockFocusAtMaxAndMin(APP_data_t *app_data);
|
||||||
|
void enterToFreqLayout(APP_data_t *app_data);
|
||||||
|
void enterToAmplLayout(APP_data_t *app_data);
|
||||||
|
void enterToOffslLayout(APP_data_t *app_data);
|
||||||
|
void enterToPhasLayout(APP_data_t *app_data);
|
||||||
|
void enterToDutyLayout(APP_data_t *app_data);
|
||||||
|
void enterToWavelLayout(APP_data_t *app_data);
|
||||||
|
void moveToLeftFocusFreqNumber(APP_data_t *app_data);
|
||||||
|
void moveToRighttFocusFreqNumber(APP_data_t *app_data);
|
||||||
|
void setTo0_01xFocusNumber(APP_data_t *app_data);
|
||||||
|
void setTo0_1xFocusNumber(APP_data_t *app_data);
|
||||||
|
void setTo1xFocusNumber(APP_data_t *app_data);
|
||||||
|
void setTo10xFocusNumber(APP_data_t *app_data);
|
||||||
16
firmware/shared_libs/controllers/ctrl_encoder.c
Normal file
16
firmware/shared_libs/controllers/ctrl_encoder.c
Normal file
@@ -0,0 +1,16 @@
|
|||||||
|
#include "main.h"
|
||||||
|
#include "tim.h"
|
||||||
|
#include "ctrl_app.h"
|
||||||
|
|
||||||
|
void CTRL_encoderHandler(void)
|
||||||
|
{
|
||||||
|
static uint8_t cnt;
|
||||||
|
if (htim3.Instance->CNT == cnt || htim3.Instance->CNT % 2 == 1)
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
// SEGGER_RTT_printf(0, "TIM3.cnt: %d\n", htim3.Instance->CNT);
|
||||||
|
CTRL_encoderEvent(htim3.Instance->CNT - cnt);
|
||||||
|
cnt = (uint8_t)htim3.Instance->CNT;
|
||||||
|
}
|
||||||
3
firmware/shared_libs/controllers/ctrl_encoder.h
Normal file
3
firmware/shared_libs/controllers/ctrl_encoder.h
Normal file
@@ -0,0 +1,3 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
void CTRL_encoderHandler(void);
|
||||||
478
firmware/shared_libs/controllers/ctrl_signal_gen.c
Normal file
478
firmware/shared_libs/controllers/ctrl_signal_gen.c
Normal file
@@ -0,0 +1,478 @@
|
|||||||
|
#include "spi.h"
|
||||||
|
#include "ctrl_app_types.h"
|
||||||
|
#include "mcu_cs.h"
|
||||||
|
#include "led.h"
|
||||||
|
|
||||||
|
static MCU_cs_t mcu_cs[MCU_CS_MAX];
|
||||||
|
|
||||||
|
// ************************
|
||||||
|
// INITIALIZATION
|
||||||
|
// ************************
|
||||||
|
|
||||||
|
static void _dds_init(dds_gen_t *dds_gen)
|
||||||
|
{
|
||||||
|
dds_gen->link.next = &dds_gen->super;
|
||||||
|
dds_gen->link.prev = &dds_gen->super;
|
||||||
|
|
||||||
|
switch (dds_gen->dds_ch)
|
||||||
|
{
|
||||||
|
case DDS_CH1:
|
||||||
|
mcu_cs_init(&mcu_cs[MCU_CS1], DDS1_CS_GPIO_Port, DDS1_CS_Pin, GPIO_PIN_SET);
|
||||||
|
ad9833_init(&dds_gen->handle.hdds, &hspi2, &mcu_cs[MCU_CS1].super);
|
||||||
|
|
||||||
|
mcu_cs_init(&mcu_cs[MCU_CS2], AMP1_CS_GPIO_Port, AMP1_CS_Pin, GPIO_PIN_SET);
|
||||||
|
mcp41x_init(&dds_gen->handle.hampl, &hspi2, &mcu_cs[MCU_CS2].super, MCP41X_10K);
|
||||||
|
|
||||||
|
led_init(&dds_gen->handle.hled, LED_CH1_GPIO_Port, LED_CH1_Pin);
|
||||||
|
break;
|
||||||
|
case DDS_CH2:
|
||||||
|
mcu_cs_init(&mcu_cs[MCU_CS3], DDS2_CS_GPIO_Port, DDS2_CS_Pin, GPIO_PIN_SET);
|
||||||
|
ad9833_init(&dds_gen->handle.hdds, &hspi2, &mcu_cs[MCU_CS3].super);
|
||||||
|
|
||||||
|
mcu_cs_init(&mcu_cs[MCU_CS4], AMP2_CS_GPIO_Port, AMP2_CS_Pin, GPIO_PIN_SET);
|
||||||
|
mcp41x_init(&dds_gen->handle.hampl, &hspi2, &mcu_cs[MCU_CS4].super, MCP41X_10K);
|
||||||
|
|
||||||
|
led_init(&dds_gen->handle.hled, LED_CH2_GPIO_Port, LED_CH2_Pin);
|
||||||
|
break;
|
||||||
|
case DDS_CH3:
|
||||||
|
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static void _pwm_init(pwm_gen_t *pwm_gen)
|
||||||
|
{
|
||||||
|
switch (pwm_gen->pwm_ch)
|
||||||
|
{
|
||||||
|
case PWM_CH1:
|
||||||
|
|
||||||
|
break;
|
||||||
|
case PWM_CH2:
|
||||||
|
|
||||||
|
break;
|
||||||
|
case PWM_CH3:
|
||||||
|
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void GEN_init(signal_gen_t **signal_gen)
|
||||||
|
{
|
||||||
|
for (GEN_channel_t channel = CHANNEL1; channel < CHANNEL_MAX; channel++)
|
||||||
|
{
|
||||||
|
switch (signal_gen[channel]->type)
|
||||||
|
{
|
||||||
|
case GEN_FG_TYPE:
|
||||||
|
_dds_init((dds_gen_t *)signal_gen[channel]);
|
||||||
|
case GEN_PWM_TYPE:
|
||||||
|
_pwm_init((pwm_gen_t *)signal_gen[channel]);
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// ad9833_init(&dds_gen[FG_CHAN3].hdds, &hspi2, DDS3_CS_PORT, DDS3_CS_PIN);
|
||||||
|
|
||||||
|
// ltc2631_init(&dds_gen[FG_CHAN1].hoffs, &hi2c1, 0x00, LTC2631_8BIT, LTC_REF_2V5);
|
||||||
|
// ltc2631_init(&dds_gen[FG_CHAN2].hoffs, &hi2c1, 0x01, LTC2631_8BIT, LTC_REF_2V5);
|
||||||
|
// ltc2631_init(&dds_gen[FG_CHAN3].hoffs, &hi2c1, 0x02, LTC2631_8BIT, LTC_REF_2V5);
|
||||||
|
|
||||||
|
// mcp41x_init(&dds_gen[FG_CHAN3].hampl, &hspi2, AMP3_CS_PORT, AMP3_CS_PIN, MCP41X_10K);
|
||||||
|
}
|
||||||
|
|
||||||
|
// ************************
|
||||||
|
// AMPLITIUDE
|
||||||
|
// ************************
|
||||||
|
|
||||||
|
static void _setAmpliude(mcp41x_handle_t *hampl, uint16_t ampl_x100)
|
||||||
|
{
|
||||||
|
uint8_t value = (ampl_x100 * UINT8_MAX) / MAX_VOLT_POS;
|
||||||
|
ULOG_DEBUG("(%d:_setAmplitude) ampl_x100: %d, value: %d", __LINE__, ampl_x100, value);
|
||||||
|
|
||||||
|
mcp41x_setValue(hampl, value);
|
||||||
|
}
|
||||||
|
|
||||||
|
void setAmplitude(signal_gen_t *sig_gen)
|
||||||
|
{
|
||||||
|
static signal_gen_t *curr_sig_gen = NULL;
|
||||||
|
|
||||||
|
if (curr_sig_gen == NULL)
|
||||||
|
{
|
||||||
|
curr_sig_gen = sig_gen;
|
||||||
|
}
|
||||||
|
|
||||||
|
switch (sig_gen->type)
|
||||||
|
{
|
||||||
|
case GEN_FG_TYPE:
|
||||||
|
{
|
||||||
|
dds_gen_t *dds_gen = (dds_gen_t *)sig_gen;
|
||||||
|
signal_gen_t *next_sig_gen = dds_gen->link.next;
|
||||||
|
|
||||||
|
_setAmpliude(&dds_gen->handle.hampl, dds_gen->settings.amplitude);
|
||||||
|
|
||||||
|
if (next_sig_gen != curr_sig_gen)
|
||||||
|
{
|
||||||
|
setAmplitude(next_sig_gen);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
curr_sig_gen = NULL;
|
||||||
|
}
|
||||||
|
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case GEN_PWM_TYPE:
|
||||||
|
{
|
||||||
|
pwm_gen_t *pwm_gen = (pwm_gen_t *)sig_gen;
|
||||||
|
signal_gen_t *next_sig_gen = pwm_gen->link.next;
|
||||||
|
|
||||||
|
_setAmpliude(&pwm_gen->handle.hampl, pwm_gen->settings.amplitude);
|
||||||
|
|
||||||
|
if (next_sig_gen != curr_sig_gen)
|
||||||
|
{
|
||||||
|
setAmplitude(next_sig_gen);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
curr_sig_gen = NULL;
|
||||||
|
}
|
||||||
|
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
default:
|
||||||
|
ULOG_ERROR("%s:%d: Unknown generator type: %d", __FILE__, __LINE__, sig_gen->type);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// ************************
|
||||||
|
// OFFSET
|
||||||
|
// ************************
|
||||||
|
|
||||||
|
static void _setOffset(ltc2631_handle_t *hoffs, int16_t offs_x100)
|
||||||
|
{
|
||||||
|
uint32_t value = (offs_x100 + MAX_VOLT_POS) * LTC_REF_2V5;
|
||||||
|
ULOG_DEBUG("(%d:_setOffset) offs_x100: %d, value: %d", __LINE__, offs_x100, value);
|
||||||
|
ltc2631_setOutputVoltage_u(hoffs, value);
|
||||||
|
}
|
||||||
|
|
||||||
|
void setOfsset(signal_gen_t *sig_gen)
|
||||||
|
{
|
||||||
|
static signal_gen_t *curr_sig_gen = NULL;
|
||||||
|
|
||||||
|
if (curr_sig_gen == NULL)
|
||||||
|
{
|
||||||
|
curr_sig_gen = sig_gen;
|
||||||
|
}
|
||||||
|
|
||||||
|
switch (sig_gen->type)
|
||||||
|
{
|
||||||
|
case GEN_FG_TYPE:
|
||||||
|
{
|
||||||
|
dds_gen_t *dds_gen = (dds_gen_t *)sig_gen;
|
||||||
|
signal_gen_t *next_sig_gen = dds_gen->link.next;
|
||||||
|
|
||||||
|
_setOffset(&dds_gen->handle.hoffs, dds_gen->settings.offset);
|
||||||
|
|
||||||
|
if (next_sig_gen != curr_sig_gen)
|
||||||
|
{
|
||||||
|
setOfsset(next_sig_gen);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
curr_sig_gen = NULL;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case GEN_PWM_TYPE:
|
||||||
|
{
|
||||||
|
pwm_gen_t *pwm_gen = (pwm_gen_t *)sig_gen;
|
||||||
|
signal_gen_t *next_sig_gen = pwm_gen->link.next;
|
||||||
|
|
||||||
|
_setOffset(&pwm_gen->handle.hoffs, pwm_gen->settings.offset);
|
||||||
|
|
||||||
|
if (next_sig_gen != curr_sig_gen)
|
||||||
|
{
|
||||||
|
setOfsset(next_sig_gen);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
curr_sig_gen = NULL;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
default:
|
||||||
|
ULOG_ERROR("%s:%d: Unknown generator type: %d", __FILE__, __LINE__, sig_gen->type);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// ************************
|
||||||
|
// FREQUENCY
|
||||||
|
// ************************
|
||||||
|
|
||||||
|
static void _setFreqDdsGen(ad9833_handle_t *hdds, uint32_t freq)
|
||||||
|
{
|
||||||
|
ULOG_DEBUG("(%d:_setFreqDdsGen) freq: %d", __LINE__, freq);
|
||||||
|
ad9833_setFrequency(hdds, CHAN_0, freq);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void _setFreqPwmGen(timer_handle_t *hpwm, uint32_t freq)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
void setFrequency(signal_gen_t *sig_gen)
|
||||||
|
{
|
||||||
|
static signal_gen_t *curr_sig_gen = NULL;
|
||||||
|
|
||||||
|
if (curr_sig_gen == NULL)
|
||||||
|
{
|
||||||
|
curr_sig_gen = sig_gen;
|
||||||
|
}
|
||||||
|
|
||||||
|
switch (sig_gen->type)
|
||||||
|
{
|
||||||
|
case GEN_FG_TYPE:
|
||||||
|
{
|
||||||
|
dds_gen_t *dds_gen = (dds_gen_t *)sig_gen;
|
||||||
|
signal_gen_t *next_sig_gen = dds_gen->link.next;
|
||||||
|
|
||||||
|
ad9833_spi_activate(&dds_gen->handle.hdds);
|
||||||
|
|
||||||
|
if (next_sig_gen != curr_sig_gen)
|
||||||
|
{
|
||||||
|
setFrequency(next_sig_gen);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
_setFreqDdsGen(&dds_gen->handle.hdds, dds_gen->settings.frequency);
|
||||||
|
curr_sig_gen = NULL;
|
||||||
|
}
|
||||||
|
|
||||||
|
ad9833_spi_deactivate(&dds_gen->handle.hdds);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case GEN_PWM_TYPE:
|
||||||
|
{
|
||||||
|
pwm_gen_t *pwm_gen = (pwm_gen_t *)sig_gen;
|
||||||
|
signal_gen_t *next_sig_gen = pwm_gen->link.next;
|
||||||
|
|
||||||
|
_setFreqPwmGen(&pwm_gen->handle.hpwm, pwm_gen->settings.frequency);
|
||||||
|
|
||||||
|
if (next_sig_gen != curr_sig_gen)
|
||||||
|
{
|
||||||
|
setFrequency(next_sig_gen);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
curr_sig_gen = NULL;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
default:
|
||||||
|
ULOG_ERROR("%s:%d: Unknown generator type: %d", __FILE__, __LINE__, sig_gen->type);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// ************************
|
||||||
|
// PHASE
|
||||||
|
// ************************
|
||||||
|
|
||||||
|
static void _setPhaseDdsGen(ad9833_handle_t *hdds, uint32_t phas)
|
||||||
|
{
|
||||||
|
ULOG_DEBUG("(%d:_setPhaseDdsGen) phase: %d", __LINE__, phas);
|
||||||
|
ad9833_setPhase(hdds, CHAN_0, phas);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void _setPhasePwmGen(timer_handle_t *hpwm, uint16_t phas)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
void setPhase(signal_gen_t *sig_gen)
|
||||||
|
{
|
||||||
|
static signal_gen_t *curr_sig_gen = NULL;
|
||||||
|
|
||||||
|
if (curr_sig_gen == NULL)
|
||||||
|
{
|
||||||
|
curr_sig_gen = sig_gen;
|
||||||
|
}
|
||||||
|
|
||||||
|
switch (sig_gen->type)
|
||||||
|
{
|
||||||
|
case GEN_FG_TYPE:
|
||||||
|
{
|
||||||
|
dds_gen_t *dds_gen = (dds_gen_t *)sig_gen;
|
||||||
|
signal_gen_t *next_sig_gen = dds_gen->link.next;
|
||||||
|
|
||||||
|
ad9833_spi_activate(&dds_gen->handle.hdds);
|
||||||
|
|
||||||
|
if (next_sig_gen != curr_sig_gen)
|
||||||
|
{
|
||||||
|
setPhase(next_sig_gen);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
_setPhaseDdsGen(&dds_gen->handle.hdds, dds_gen->settings.phase);
|
||||||
|
curr_sig_gen = NULL;
|
||||||
|
}
|
||||||
|
|
||||||
|
ad9833_spi_deactivate(&dds_gen->handle.hdds);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case GEN_PWM_TYPE:
|
||||||
|
{
|
||||||
|
pwm_gen_t *pwm_gen = (pwm_gen_t *)sig_gen;
|
||||||
|
signal_gen_t *next_sig_gen = pwm_gen->link.next;
|
||||||
|
|
||||||
|
_setPhasePwmGen(&pwm_gen->handle.hpwm, pwm_gen->settings.phase);
|
||||||
|
|
||||||
|
if (next_sig_gen != curr_sig_gen)
|
||||||
|
{
|
||||||
|
setPhase(next_sig_gen);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
curr_sig_gen = NULL;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
default:
|
||||||
|
ULOG_ERROR("%s:%d: Unknown generator type: %d", __FILE__, __LINE__, sig_gen->type);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// ************************
|
||||||
|
// DUTY
|
||||||
|
// ************************
|
||||||
|
|
||||||
|
static void _setDutyPwmGen(timer_handle_t *hpwm, uint8_t duty)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
void setDuty(signal_gen_t *sig_gen)
|
||||||
|
{
|
||||||
|
switch (sig_gen->type)
|
||||||
|
{
|
||||||
|
case GEN_PWM_TYPE:
|
||||||
|
{
|
||||||
|
pwm_gen_t *pwm_gen = (pwm_gen_t *)sig_gen;
|
||||||
|
_setDutyPwmGen(&pwm_gen->handle.hpwm, pwm_gen->settings.duty);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
default:
|
||||||
|
ULOG_ERROR("%s:%d: Unknown generator type: %d", __FILE__, __LINE__, sig_gen->type);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// ************************
|
||||||
|
// WAVE
|
||||||
|
// ************************
|
||||||
|
|
||||||
|
static void _setWaveDdsGen(ad9833_handle_t *hdds, GEN_wave_t wave)
|
||||||
|
{
|
||||||
|
ULOG_DEBUG("(%d:_setWaveDdsGen) wave: %d", __LINE__, wave);
|
||||||
|
switch (wave)
|
||||||
|
{
|
||||||
|
case GEN_SIN:
|
||||||
|
ad9833_setMode(hdds, MODE_SINE);
|
||||||
|
break;
|
||||||
|
case GEN_TRI:
|
||||||
|
ad9833_setMode(hdds, MODE_TRIANGLE);
|
||||||
|
break;
|
||||||
|
case GEN_SQR:
|
||||||
|
ad9833_setMode(hdds, MODE_SQUARE1);
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
ULOG_ERROR("%s:%d: Unknown wave type: %d", __FILE__, __LINE__, wave);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void setWave(signal_gen_t *sig_gen)
|
||||||
|
{
|
||||||
|
switch (sig_gen->type)
|
||||||
|
{
|
||||||
|
case GEN_FG_TYPE:
|
||||||
|
{
|
||||||
|
dds_gen_t *dds_gen = (dds_gen_t *)sig_gen;
|
||||||
|
_setWaveDdsGen(&dds_gen->handle.hdds, dds_gen->settings.wave);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
default:
|
||||||
|
ULOG_ERROR("%s:%d: Unknown generator type: %d", __FILE__, __LINE__, sig_gen->type);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// ************************
|
||||||
|
// ENABLE
|
||||||
|
// ************************
|
||||||
|
|
||||||
|
static void _setEnabledDdsGen(dds_handle_t *hfg, dds_settings_t *settings)
|
||||||
|
{
|
||||||
|
ULOG_DEBUG("(%d:_setEnabledDdsGen) enabled: %d", __LINE__, settings->enabled);
|
||||||
|
switch (settings->enabled)
|
||||||
|
{
|
||||||
|
case FALSE:
|
||||||
|
ad9833_setMode(&hfg->hdds, MODE_OFF);
|
||||||
|
led_off(&hfg->hled);
|
||||||
|
break;
|
||||||
|
case TRUE:
|
||||||
|
_setWaveDdsGen(&hfg->hdds, settings->wave);
|
||||||
|
led_on(&hfg->hled);
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
ULOG_ERROR("%s:%d: Value out of range: %d", __FILE__, __LINE__, settings->enabled);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static void _setEnabledPwmGen(timer_handle_t *hpwm, bool_t en)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
void setEnabled(signal_gen_t *sig_gen)
|
||||||
|
{
|
||||||
|
switch (sig_gen->type)
|
||||||
|
{
|
||||||
|
case GEN_FG_TYPE:
|
||||||
|
{
|
||||||
|
dds_gen_t *dds_gen = (dds_gen_t *)sig_gen;
|
||||||
|
_setEnabledDdsGen(&dds_gen->handle, &dds_gen->settings);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case GEN_PWM_TYPE:
|
||||||
|
{
|
||||||
|
pwm_gen_t *pwm_gen = (pwm_gen_t *)sig_gen;
|
||||||
|
_setEnabledPwmGen(&pwm_gen->handle.hpwm, pwm_gen->settings.enabled);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
default:
|
||||||
|
ULOG_ERROR("%s:%d: Unknown generator type: %d", __FILE__, __LINE__, sig_gen->type);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// ************************
|
||||||
|
// LINK
|
||||||
|
// ************************
|
||||||
|
|
||||||
|
void setLink(signal_gen_t *source_gen, signal_gen_t *dest_gen)
|
||||||
|
{
|
||||||
|
}
|
||||||
12
firmware/shared_libs/controllers/ctrl_signal_gen.h
Normal file
12
firmware/shared_libs/controllers/ctrl_signal_gen.h
Normal file
@@ -0,0 +1,12 @@
|
|||||||
|
#pragma once
|
||||||
|
#include "ctrl_app_types.h"
|
||||||
|
|
||||||
|
void setLink(signal_gen_t *source_gen, signal_gen_t *dest_gen);
|
||||||
|
void setEnabled(signal_gen_t *gen);
|
||||||
|
void setDuty(signal_gen_t *gen);
|
||||||
|
void setWave(signal_gen_t *gen);
|
||||||
|
void setPhase(signal_gen_t *gen);
|
||||||
|
void setOfsset(signal_gen_t *gen);
|
||||||
|
void setAmplitude(signal_gen_t *gen);
|
||||||
|
void setFrequency(signal_gen_t *gen);
|
||||||
|
void GEN_init(signal_gen_t **signal_gen);
|
||||||
343
firmware/shared_libs/disp_layout/disp_layout.c
Normal file
343
firmware/shared_libs/disp_layout/disp_layout.c
Normal file
@@ -0,0 +1,343 @@
|
|||||||
|
#include "main.h"
|
||||||
|
#include "printf.h"
|
||||||
|
#include "bitmap_fonts.h"
|
||||||
|
#include "bitmap_disp_buttons.h"
|
||||||
|
#include "bitmap_wave.h"
|
||||||
|
#include "tim.h"
|
||||||
|
#include "SEGGER_RTT.h"
|
||||||
|
|
||||||
|
#include "disp_layout.h"
|
||||||
|
|
||||||
|
#define ABS(x) ((x) < 0 ? -(x) : (x))
|
||||||
|
#define MAX(x, y) (((x) > (y)) ? (x) : (y))
|
||||||
|
#define MIN(x, y) (((x) < (y)) ? (x) : (y))
|
||||||
|
|
||||||
|
#define SEVEN_DIGIT 7
|
||||||
|
#define FOUR_DIGIT 3
|
||||||
|
#define THREE_DIGIT 2
|
||||||
|
|
||||||
|
const uint8_t btn_pos_x[DISP_BTN_MAX] = {0, 26, 52, 78, 104};
|
||||||
|
const uint8_t marker_pos_7dig[SEVEN_DIGIT] = {76, 84, 90, 96, 105, 111, 118};
|
||||||
|
const uint8_t marker_pos_4dig[FOUR_DIGIT] = {82, 94, 100};
|
||||||
|
const uint8_t marker_pos_3dig[THREE_DIGIT] = {82, 88};
|
||||||
|
|
||||||
|
// clang-format off
|
||||||
|
const GFX_bitmap_t marker_down = {05, 03, (uint8_t[]){0x01,0x03,0x07,0x03,0x01}};// res: 5x3(8) - 5 bytes
|
||||||
|
const GFX_bitmap_t marker_up = {05, 03, (uint8_t[]){0x04,0x06,0x07,0x06,0x04}}; // res: 5x3(8) - 5 bytes
|
||||||
|
|
||||||
|
// clang-format on
|
||||||
|
|
||||||
|
static void _drawFreqValue(GFX_display_t *disp, uint32_t freq, uint8_t pos_y)
|
||||||
|
{
|
||||||
|
uint8_t data[8];
|
||||||
|
snprintf((char *)data, 8, "%07u", freq);
|
||||||
|
DISP_writeString(disp, &font5x7Info, (uint8_t[]){data[0], 0}, 76, pos_y, BM_NORMAL);
|
||||||
|
DISP_writeString(disp, &font5x7Info, (uint8_t[]){data[1], data[2], data[3], 0}, 84, pos_y, BM_NORMAL);
|
||||||
|
DISP_writeString(disp, &font5x7Info, (uint8_t[]){data[4], data[5], data[6], 0}, 105, pos_y, BM_NORMAL);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void _drawAmplValue(GFX_display_t *disp, uint16_t ampl, uint8_t pos_y)
|
||||||
|
{
|
||||||
|
uint8_t data[8];
|
||||||
|
snprintf((char *)data, 8, "%02d.%02d V", ampl / 100, ampl % 100);
|
||||||
|
DISP_writeString(disp, &font5x7Info, data, 76, pos_y, BM_NORMAL);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void _drawOffsValue(GFX_display_t *disp, int16_t offs, uint8_t pos_y)
|
||||||
|
{
|
||||||
|
uint8_t data[8];
|
||||||
|
snprintf((char *)data, 8, "%+01d.%02d V", offs / 100, ABS(offs) % 100);
|
||||||
|
if (offs < 0)
|
||||||
|
{
|
||||||
|
data[0] = '-';
|
||||||
|
}
|
||||||
|
DISP_writeString(disp, &font5x7Info, data, 76, pos_y, BM_NORMAL);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void _drawPhasValue(GFX_display_t *disp, uint16_t phase, uint8_t pos_y)
|
||||||
|
{
|
||||||
|
uint8_t data[8];
|
||||||
|
snprintf((char *)data, 8, "%03u'", phase);
|
||||||
|
DISP_writeString(disp, &font5x7Info, data, 76, pos_y, BM_NORMAL);
|
||||||
|
}
|
||||||
|
|
||||||
|
// static void _drawDutyValue(GFX_display_t *disp, uint8_t duty, uint8_t pos_y)
|
||||||
|
// {
|
||||||
|
// uint8_t data[8];
|
||||||
|
// snprintf((char *)data, 8, "%03u%%", duty);
|
||||||
|
// DISP_writeString(disp, &font5x7Info, data, 76, pos_y, BM_NORMAL);
|
||||||
|
// }
|
||||||
|
|
||||||
|
static void _blinkButtons(GFX_display_t *disp, APP_data_t *app_data)
|
||||||
|
{
|
||||||
|
// input: display buttons, invert
|
||||||
|
BITMAP_buttonName_t bitmap_idx;
|
||||||
|
for (LAY_dispBtn_t btn_idx = DISP_BTN_1; btn_idx < DISP_BTN_MAX; btn_idx++)
|
||||||
|
{
|
||||||
|
if (!(app_data->button_blink & (1 << btn_idx)))
|
||||||
|
{
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
|
bitmap_idx = CTRL_getBitmapName(btn_idx);
|
||||||
|
if (app_data->timer_blink[btn_idx] > 0)
|
||||||
|
{
|
||||||
|
DISP_drawBitmap(disp, &bitmap_btnBottom[bitmap_idx + 1], btn_pos_x[btn_idx], 53, BM_NORMAL);
|
||||||
|
app_data->timer_blink[btn_idx]--;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
DISP_drawBitmap(disp, &bitmap_btnBottom[bitmap_idx], btn_pos_x[btn_idx], 53, BM_NORMAL);
|
||||||
|
app_data->button_blink &= ~(1 << btn_idx);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static void _drawButtons(GFX_display_t *disp, APP_data_t *app_data)
|
||||||
|
{
|
||||||
|
// input: display buttons, invert
|
||||||
|
BITMAP_buttonName_t bitmap_idx;
|
||||||
|
DISP_clearRegion(disp, 0, 53, disp->width, 11);
|
||||||
|
|
||||||
|
for (LAY_dispBtn_t btn_idx = DISP_BTN_1; btn_idx < DISP_BTN_MAX; btn_idx++)
|
||||||
|
{
|
||||||
|
bitmap_idx = CTRL_getBitmapName(btn_idx);
|
||||||
|
DISP_drawBitmap(disp, &bitmap_btnBottom[bitmap_idx], btn_pos_x[btn_idx], 53, BM_NORMAL);
|
||||||
|
}
|
||||||
|
|
||||||
|
app_data->disp_update &= ~(UPDATE_BUTTON);
|
||||||
|
}
|
||||||
|
|
||||||
|
static uint8_t _calcMarkerPos(uint32_t value, uint32_t max)
|
||||||
|
{
|
||||||
|
return ((61 * value) + (max / 2)) / max;
|
||||||
|
// return (value < 0) ? ((62 * value) - (max / 2)) / max : ((62 * value) + (max / 2)) / max;
|
||||||
|
}
|
||||||
|
|
||||||
|
static uint8_t _calcPhaseShiftInPxl(uint32_t value, uint32_t max)
|
||||||
|
{
|
||||||
|
return ((48 * value) + (max / 2)) / max;
|
||||||
|
}
|
||||||
|
|
||||||
|
static int32_t _calcVerticalShiftInPxl(int16_t value, int16_t max)
|
||||||
|
{
|
||||||
|
return (value < 0) ? ((12 * value) - (max / 2)) / max : ((12 * value) + (max / 2)) / max;
|
||||||
|
}
|
||||||
|
|
||||||
|
static uint8_t _sizeOfCharArray(char *array)
|
||||||
|
{
|
||||||
|
uint8_t size = 0;
|
||||||
|
while (*array++)
|
||||||
|
{
|
||||||
|
size++;
|
||||||
|
}
|
||||||
|
return size;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void _drawMeterHelper(GFX_display_t *disp, char *min, char *max, uint8_t pos)
|
||||||
|
{
|
||||||
|
uint8_t max_size = _sizeOfCharArray(max);
|
||||||
|
DISP_drawPixel(disp, 64, 40, GFX_WHITE);
|
||||||
|
DISP_drawPixel(disp, 125, 40, GFX_WHITE);
|
||||||
|
DISP_drawHorizontalLine(disp, 64, 41, 62, GFX_WHITE);
|
||||||
|
DISP_writeString(disp, &font5x7Info, (uint8_t *)min, 62, 43, BM_NORMAL);
|
||||||
|
DISP_writeString(disp, &font5x7Info, (uint8_t *)max, 127 - (6 * max_size), 43, BM_NORMAL);
|
||||||
|
// marker 0% - 62, 100% - 123
|
||||||
|
DISP_drawBitmap(disp, &marker_down, 62 + pos, 35, BM_NORMAL);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void _drawFreqValueHelper(GFX_display_t *disp, uint32_t freq, uint8_t focus_digit)
|
||||||
|
{
|
||||||
|
DISP_clearRegion(disp, 64, 13, 66, 40);
|
||||||
|
DISP_writeString(disp, &font5x7Info, (uint8_t *)"F:", 64, 20, BM_NORMAL);
|
||||||
|
_drawFreqValue(disp, freq, 20);
|
||||||
|
DISP_drawBitmap(disp, &marker_down, marker_pos_7dig[(SEVEN_DIGIT - 1) - focus_digit], 15, BM_NORMAL);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void _drawAmplValueHelper(GFX_display_t *disp, uint32_t ampl, uint8_t focus_digit)
|
||||||
|
{
|
||||||
|
DISP_clearRegion(disp, 64, 13, 66, 40);
|
||||||
|
DISP_writeString(disp, &font5x7Info, (uint8_t *)"A:", 64, 20, BM_NORMAL);
|
||||||
|
_drawAmplValue(disp, ampl, 20);
|
||||||
|
DISP_drawBitmap(disp, &marker_down, marker_pos_4dig[(FOUR_DIGIT - 1) - focus_digit], 15, BM_NORMAL);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void _drawOffsValueHelper(GFX_display_t *disp, int32_t offs, uint8_t focus_digit)
|
||||||
|
{
|
||||||
|
DISP_clearRegion(disp, 64, 13, 66, 40);
|
||||||
|
DISP_writeString(disp, &font5x7Info, (uint8_t *)"O:", 64, 20, BM_NORMAL);
|
||||||
|
_drawOffsValue(disp, offs, 20);
|
||||||
|
DISP_drawBitmap(disp, &marker_down, marker_pos_4dig[(FOUR_DIGIT - 1) - focus_digit], 15, BM_NORMAL);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void _drawPhaseValueHelper(GFX_display_t *disp, uint32_t phase, uint8_t focus_digit)
|
||||||
|
{
|
||||||
|
DISP_clearRegion(disp, 64, 13, 66, 40);
|
||||||
|
DISP_writeString(disp, &font5x7Info, (uint8_t *)"P:", 64, 20, BM_NORMAL);
|
||||||
|
_drawPhasValue(disp, phase, 20);
|
||||||
|
DISP_drawBitmap(disp, &marker_down, marker_pos_3dig[(THREE_DIGIT - 1) - focus_digit], 15, BM_NORMAL);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void _drawFuncGenValues(GFX_display_t *disp, APP_data_t *app_data)
|
||||||
|
{
|
||||||
|
dds_gen_t *fun_gen = (dds_gen_t *)app_data->curr_gen;
|
||||||
|
switch (app_data->curr_state_lay)
|
||||||
|
{
|
||||||
|
case LAY_FREQ:
|
||||||
|
_drawFreqValueHelper(disp, fun_gen->settings.frequency, app_data->freq_focus_digit);
|
||||||
|
_drawMeterHelper(disp, "1", "1M", _calcMarkerPos(fun_gen->settings.frequency, MAX_FREQ));
|
||||||
|
break;
|
||||||
|
case LAY_AMPL:
|
||||||
|
_drawAmplValueHelper(disp, fun_gen->settings.amplitude, app_data->ampl_focus_digit);
|
||||||
|
_drawMeterHelper(disp, "0V", "5V", _calcMarkerPos(fun_gen->settings.amplitude, MAX_VOLT_POS));
|
||||||
|
break;
|
||||||
|
case LAY_OFFS:
|
||||||
|
_drawOffsValueHelper(disp, fun_gen->settings.offset, app_data->offs_focus_digit);
|
||||||
|
_drawMeterHelper(disp, "-5V", "+5V", _calcMarkerPos(MAX_VOLT_POS + fun_gen->settings.offset, MAX_VOLT_POS * 2));
|
||||||
|
break;
|
||||||
|
case LAY_PHAS:
|
||||||
|
_drawPhaseValueHelper(disp, fun_gen->settings.phase, app_data->phas_focus_digit);
|
||||||
|
_drawMeterHelper(disp, "0", "360", _calcMarkerPos(fun_gen->settings.phase, MAX_PHAS));
|
||||||
|
break;
|
||||||
|
case LAY_MAIN:
|
||||||
|
DISP_clearRegion(disp, 62, 13, 66, 40);
|
||||||
|
DISP_writeString(disp, &font5x7Info, (uint8_t *)"F:", 64, 13, BM_NORMAL);
|
||||||
|
DISP_writeString(disp, &font5x7Info, (uint8_t *)"A:", 64, 23, BM_NORMAL);
|
||||||
|
DISP_writeString(disp, &font5x7Info, (uint8_t *)"O:", 64, 33, BM_NORMAL);
|
||||||
|
DISP_writeString(disp, &font5x7Info, (uint8_t *)"P:", 64, 43, BM_NORMAL);
|
||||||
|
|
||||||
|
_drawFreqValue(disp, fun_gen->settings.frequency, 13);
|
||||||
|
_drawAmplValue(disp, fun_gen->settings.amplitude, 23);
|
||||||
|
_drawOffsValue(disp, fun_gen->settings.offset, 33);
|
||||||
|
_drawPhasValue(disp, fun_gen->settings.phase, 43);
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
// focus
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static void _drawPwmGenValues(GFX_display_t *disp, APP_data_t *app_data)
|
||||||
|
{
|
||||||
|
// GEN_pwm_t *pwm_gen = app_data->curr_gen;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void _drawValues(GFX_display_t *disp, APP_data_t *app_data)
|
||||||
|
{
|
||||||
|
// input: frequency(value), amplitiude(value), offset(value), phase(value), duty(value), invert(info), position(value)
|
||||||
|
switch (app_data->curr_gen->type)
|
||||||
|
{
|
||||||
|
case GEN_FG_TYPE:
|
||||||
|
_drawFuncGenValues(disp, app_data);
|
||||||
|
break;
|
||||||
|
case GEN_PWM_TYPE:
|
||||||
|
_drawPwmGenValues(disp, app_data);
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
app_data->disp_update &= ~(UPDATE_VALUE);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void _drawOffsetLine(GFX_display_t *disp, int16_t offs, uint32_t ampl)
|
||||||
|
{
|
||||||
|
int8_t vert_shift = _calcVerticalShiftInPxl(offs, ampl);
|
||||||
|
|
||||||
|
vert_shift = MIN(vert_shift, 20);
|
||||||
|
vert_shift = MAX(vert_shift, -19);
|
||||||
|
|
||||||
|
// ULOG_DEBUG("<OFFSLINE> shift: %i", vert_shift);
|
||||||
|
DISP_drawHorizontalLine(disp, 2, 31 + vert_shift, 57, GFX_WHITE);
|
||||||
|
}
|
||||||
|
|
||||||
|
// static void _drawMaxAmpLine(GFX_display_t *disp, int16_t offs, uint32_t ampl)
|
||||||
|
// {
|
||||||
|
// DISP_drawHorizontalLine(disp, 2, 12, 57, GFX_WHITE);
|
||||||
|
// DISP_drawBitmap(disp, &marker_up, 0, 13, BM_NORMAL);
|
||||||
|
|
||||||
|
// DISP_drawHorizontalLine(disp, 2, 51, 57, GFX_WHITE);
|
||||||
|
// DISP_drawBitmap(disp, &marker_down, 0, 48, BM_NORMAL);
|
||||||
|
// }
|
||||||
|
|
||||||
|
static void _drawFunGenGraph(GFX_display_t *disp, APP_data_t *app_data)
|
||||||
|
{
|
||||||
|
dds_gen_t *fun_gen = (dds_gen_t *)app_data->curr_gen;
|
||||||
|
DISP_clearRegion(disp, 3, 12, 57, 40);
|
||||||
|
|
||||||
|
switch (fun_gen->settings.wave)
|
||||||
|
{
|
||||||
|
case GEN_SIN:
|
||||||
|
DISP_drawBitmapShift(disp, &wave[WAVE_SIN], 6, 19, _calcPhaseShiftInPxl(fun_gen->settings.phase, 360), BM_NORMAL);
|
||||||
|
break;
|
||||||
|
case GEN_TRI:
|
||||||
|
DISP_drawBitmapShift(disp, &wave[WAVE_TRI], 6, 19, _calcPhaseShiftInPxl(fun_gen->settings.phase, 360), BM_NORMAL);
|
||||||
|
break;
|
||||||
|
case GEN_SQR:
|
||||||
|
DISP_drawBitmapShift(disp, &wave[WAVE_SQR], 6, 19, _calcPhaseShiftInPxl(fun_gen->settings.phase, 360), BM_NORMAL);
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
_drawOffsetLine(disp, fun_gen->settings.offset, fun_gen->settings.amplitude);
|
||||||
|
// _drawMaxAmpLine(disp, fun_gen->settings.offset, fun_gen->settings.amplitude);
|
||||||
|
}
|
||||||
|
static void _drawPwmGenGraph(GFX_display_t *disp, APP_data_t *app_data)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
static void _drawGraph(GFX_display_t *disp, APP_data_t *app_data)
|
||||||
|
{
|
||||||
|
// input: graph type(sin, triangle, squere, pwm), frequency(info), amplitiude(value), offset(value), phase(value), invert(pwm),
|
||||||
|
DISP_drawVerticalLine(disp, 2, 12, 40, GFX_WHITE);
|
||||||
|
|
||||||
|
switch (app_data->curr_gen->type)
|
||||||
|
{
|
||||||
|
case GEN_FG_TYPE:
|
||||||
|
_drawFunGenGraph(disp, app_data);
|
||||||
|
break;
|
||||||
|
case GEN_PWM_TYPE:
|
||||||
|
_drawPwmGenGraph(disp, app_data);
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
app_data->disp_update &= ~(UPDATE_GRAPH);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void _drawChannels(GFX_display_t *disp, APP_data_t *app_data)
|
||||||
|
{
|
||||||
|
// input: active channel
|
||||||
|
DISP_writeString(disp, &font5x7Info, (uint8_t *)"CH1", 2, 1, CHANNEL1 == app_data->curr_channel ? BM_INVERSE : BM_NORMAL);
|
||||||
|
DISP_writeString(disp, &font5x7Info, (uint8_t *)"CH2", 23, 2, CHANNEL2 == app_data->curr_channel ? BM_INVERSE : BM_NORMAL);
|
||||||
|
DISP_writeString(disp, &font5x7Info, (uint8_t *)"CH3", 44, 2, CHANNEL3 == app_data->curr_channel ? BM_INVERSE : BM_NORMAL);
|
||||||
|
DISP_writeString(disp, &font5x7Info, (uint8_t *)"CH4", 65, 2, CHANNEL4 == app_data->curr_channel ? BM_INVERSE : BM_NORMAL);
|
||||||
|
DISP_writeString(disp, &font5x7Info, (uint8_t *)"CH5", 86, 2, CHANNEL5 == app_data->curr_channel ? BM_INVERSE : BM_NORMAL);
|
||||||
|
DISP_writeString(disp, &font5x7Info, (uint8_t *)"CH6", 107, 2, CHANNEL6 == app_data->curr_channel ? BM_INVERSE : BM_NORMAL);
|
||||||
|
DISP_drawHorizontalLine(disp, 0, 10, 127, GFX_WHITE);
|
||||||
|
|
||||||
|
app_data->disp_update &= ~(UPDATE_CHANNEL);
|
||||||
|
}
|
||||||
|
|
||||||
|
void LAY_drawDisplayLayout(GFX_display_t *disp, APP_data_t *app_data)
|
||||||
|
{
|
||||||
|
if (app_data->disp_update & UPDATE_CHANNEL)
|
||||||
|
_drawChannels(disp, app_data);
|
||||||
|
|
||||||
|
if (app_data->disp_update & UPDATE_VALUE)
|
||||||
|
_drawValues(disp, app_data);
|
||||||
|
|
||||||
|
if (app_data->disp_update & UPDATE_GRAPH)
|
||||||
|
_drawGraph(disp, app_data);
|
||||||
|
|
||||||
|
if (app_data->disp_update & UPDATE_BUTTON)
|
||||||
|
_drawButtons(disp, app_data);
|
||||||
|
|
||||||
|
if (app_data->button_blink)
|
||||||
|
_blinkButtons(disp, app_data);
|
||||||
|
}
|
||||||
6
firmware/shared_libs/disp_layout/disp_layout.h
Normal file
6
firmware/shared_libs/disp_layout/disp_layout.h
Normal file
@@ -0,0 +1,6 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "display_gfx.h"
|
||||||
|
#include "ctrl_app.h"
|
||||||
|
|
||||||
|
void LAY_drawDisplayLayout(GFX_display_t *disp, APP_data_t *app_data);
|
||||||
498
firmware/shared_libs/display/display_gfx.c
Normal file
498
firmware/shared_libs/display/display_gfx.c
Normal file
@@ -0,0 +1,498 @@
|
|||||||
|
#include "main.h"
|
||||||
|
#include "display_gfx.h"
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
uint16_t bitmap_max_idx;
|
||||||
|
uint8_t buf_row_first;
|
||||||
|
uint8_t buf_row_last;
|
||||||
|
uint8_t buf_col_first;
|
||||||
|
uint8_t buf_col_last;
|
||||||
|
uint8_t buf_mask_top;
|
||||||
|
uint8_t buf_mask_bottom;
|
||||||
|
uint8_t bitmap_col;
|
||||||
|
uint8_t bitmap_row_first;
|
||||||
|
uint8_t bitmap_row_last;
|
||||||
|
uint8_t bitmap_shift;
|
||||||
|
} buf_bitmap_boundry_t;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Draw one pixel in a buffer.
|
||||||
|
*
|
||||||
|
* @param disp A pointer to display struct
|
||||||
|
* @param x Top-most x coordinate
|
||||||
|
* @param y Top-most y coordinate
|
||||||
|
* @param color Color of pixel WHITE(0), BLACK(1) or INVERSE(2)
|
||||||
|
*/
|
||||||
|
void DISP_drawPixel(GFX_display_t *disp, uint8_t x, uint8_t y, GFX_Color_t color)
|
||||||
|
{
|
||||||
|
if (x > disp->width || y > disp->height)
|
||||||
|
return;
|
||||||
|
|
||||||
|
switch (color)
|
||||||
|
{
|
||||||
|
case GFX_WHITE:
|
||||||
|
disp->buffor[(y / 8) * disp->width + x] |= (1 << (y % 8));
|
||||||
|
break;
|
||||||
|
case GFX_BLACK:
|
||||||
|
disp->buffor[(y / 8) * disp->width + x] &= ~(1 << (y % 8));
|
||||||
|
break;
|
||||||
|
case GFX_INVERSE:
|
||||||
|
disp->buffor[(y / 8) * disp->width + x] ^= (1 << (y % 8));
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
void DISP_drawBitmapSlow(GFX_display_t *disp, const GFX_bitmap_t *bitmap, uint8_t x, uint8_t y)
|
||||||
|
{
|
||||||
|
uint8_t row_div_by_8 = 0;
|
||||||
|
uint8_t mask = 0;
|
||||||
|
uint8_t bitmap_byte = 0;
|
||||||
|
|
||||||
|
for (uint8_t row = 0; row < bitmap->height; row++)
|
||||||
|
{
|
||||||
|
row_div_by_8 = row / 8;
|
||||||
|
mask = (row % 8);
|
||||||
|
for (uint8_t col = 0; col < bitmap->width; col++)
|
||||||
|
{
|
||||||
|
|
||||||
|
bitmap_byte = bitmap->bitmap[row_div_by_8 * bitmap->width + col];
|
||||||
|
if (bitmap_byte & (1 << mask))
|
||||||
|
{
|
||||||
|
DISP_drawPixel(disp, col + x, row + y, GFX_WHITE);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
DISP_drawPixel(disp, col + x, row + y, GFX_BLACK);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Draw a vertical line.
|
||||||
|
*
|
||||||
|
* @param disp A pointer to display struct
|
||||||
|
* @param x0 Start point x coordinate
|
||||||
|
* @param y0 Start point y coordinate
|
||||||
|
* @param x1 End point x coordinate
|
||||||
|
* @param y1 End point y coordinate
|
||||||
|
* @param color Color of pixel WHITE(0), BLACK(1) or INVERSE(2)
|
||||||
|
*/
|
||||||
|
void DISP_drawSlashLine(GFX_display_t *disp, int16_t x0, int16_t y0, int16_t x1, int16_t y1, GFX_Color_t color)
|
||||||
|
{
|
||||||
|
uint8_t steep = _diff(y1, y0) > _diff(x1, x0); // bool
|
||||||
|
if (steep)
|
||||||
|
{
|
||||||
|
_swap_int16_t(x0, y0);
|
||||||
|
_swap_int16_t(x1, y1);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (x0 > x1)
|
||||||
|
{
|
||||||
|
_swap_int16_t(x0, x1);
|
||||||
|
_swap_int16_t(y0, y1);
|
||||||
|
}
|
||||||
|
|
||||||
|
int16_t dx = x1 - x0;
|
||||||
|
int16_t dy = _diff(y1, y0);
|
||||||
|
int16_t err = dx >> 1;
|
||||||
|
int16_t step = (y0 < y1) ? 1 : -1;
|
||||||
|
|
||||||
|
for (; x0 <= x1; x0++)
|
||||||
|
{
|
||||||
|
if (steep)
|
||||||
|
{
|
||||||
|
DISP_drawPixel(disp, y0, x0, color);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
DISP_drawPixel(disp, x0, y0, color);
|
||||||
|
}
|
||||||
|
err -= dy;
|
||||||
|
if (err < 0)
|
||||||
|
{
|
||||||
|
err += dx;
|
||||||
|
y0 += step;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Write a perfectly vertical line
|
||||||
|
* @param disp A pointer to display struct
|
||||||
|
* @param x Left-most x coordinate
|
||||||
|
* @param y Top-most y coordinate
|
||||||
|
* @param height Height in pixels
|
||||||
|
* @param color Color of pixel WHITE(0), BLACK(1) or INVERSE(2)
|
||||||
|
*/
|
||||||
|
void DISP_drawVerticalLine(GFX_display_t *disp, int16_t x, int16_t y, int16_t height, GFX_Color_t color)
|
||||||
|
{
|
||||||
|
for (int16_t i = y; i < y + height; i++)
|
||||||
|
{
|
||||||
|
DISP_drawPixel(disp, x, i, color);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
@brief Write a perfectly horizontal line
|
||||||
|
@param disp A pointer to display struct
|
||||||
|
@param x Left-most x coordinate
|
||||||
|
@param y Top-most y coordinate
|
||||||
|
@param width Width in pixels
|
||||||
|
@param color Color of pixel WHITE(0), BLACK(1) or INVERSE(2)
|
||||||
|
*/
|
||||||
|
void DISP_drawHorizontalLine(GFX_display_t *disp, uint8_t x, uint8_t y, uint8_t width, GFX_Color_t color)
|
||||||
|
{
|
||||||
|
for (int16_t i = x; i < x + width; i++)
|
||||||
|
{
|
||||||
|
DISP_drawPixel(disp, i, y, color);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Draw a rectangle with no fill color
|
||||||
|
* @param disp A pointer to display struct
|
||||||
|
* @param x Top left corner x coordinate
|
||||||
|
* @param y Top left corner y coordinate
|
||||||
|
* @param width Width in pixels
|
||||||
|
* @param height Height in pixels
|
||||||
|
* @param radius Radius of corner rounding
|
||||||
|
* @param color Color of pixel WHITE(0), BLACK(1) or INVERSE(2)
|
||||||
|
*/
|
||||||
|
void DISP_drawRect(GFX_display_t *disp, int16_t x, int16_t y, int16_t width, int16_t height, GFX_Color_t color)
|
||||||
|
{
|
||||||
|
DISP_drawHorizontalLine(disp, x, y, width, color);
|
||||||
|
DISP_drawHorizontalLine(disp, x, y + height - 1, width, color);
|
||||||
|
DISP_drawVerticalLine(disp, x, y, height, color);
|
||||||
|
DISP_drawVerticalLine(disp, x + width - 1, y, height, color);
|
||||||
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
@brief Draw a circle outline
|
||||||
|
@param disp A pointer to display struct
|
||||||
|
@param x0 Center-point x coordinate
|
||||||
|
@param y0 Center-point y coordinate
|
||||||
|
@param radius Radius of circle
|
||||||
|
@param color Color of pixel WHITE(0), BLACK(1) or INVERSE(2)
|
||||||
|
*/
|
||||||
|
void DISP_drawCircle(GFX_display_t *disp, int16_t x0, int16_t y0, uint8_t radius, GFX_Color_t color)
|
||||||
|
{
|
||||||
|
|
||||||
|
int16_t f = 1 - radius;
|
||||||
|
int16_t ddF_x = 1;
|
||||||
|
int16_t ddF_y = -2 * radius;
|
||||||
|
int16_t x = 0;
|
||||||
|
int16_t y = radius;
|
||||||
|
|
||||||
|
DISP_drawPixel(disp, x0, y0 + radius, color);
|
||||||
|
DISP_drawPixel(disp, x0, y0 - radius, color);
|
||||||
|
DISP_drawPixel(disp, x0 + radius, y0, color);
|
||||||
|
DISP_drawPixel(disp, x0 - radius, y0, color);
|
||||||
|
|
||||||
|
while (x < y)
|
||||||
|
{
|
||||||
|
if (f >= 0)
|
||||||
|
{
|
||||||
|
y--;
|
||||||
|
ddF_y += 2;
|
||||||
|
f += ddF_y;
|
||||||
|
}
|
||||||
|
x++;
|
||||||
|
ddF_x += 2;
|
||||||
|
f += ddF_x;
|
||||||
|
|
||||||
|
DISP_drawPixel(disp, x0 + x, y0 + y, color);
|
||||||
|
DISP_drawPixel(disp, x0 - x, y0 + y, color);
|
||||||
|
DISP_drawPixel(disp, x0 + x, y0 - y, color);
|
||||||
|
DISP_drawPixel(disp, x0 - x, y0 - y, color);
|
||||||
|
DISP_drawPixel(disp, x0 + y, y0 + x, color);
|
||||||
|
DISP_drawPixel(disp, x0 - y, y0 + x, color);
|
||||||
|
DISP_drawPixel(disp, x0 + y, y0 - x, color);
|
||||||
|
DISP_drawPixel(disp, x0 - y, y0 - x, color);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/*!
|
||||||
|
@brief Quarter-circle drawer, used to do circles and roundrects
|
||||||
|
@param disp A pointer to display struct
|
||||||
|
@param x0 Center-point x coordinate
|
||||||
|
@param y0 Center-point y coordinate
|
||||||
|
@param radius Radius of circle
|
||||||
|
@param corner Mask bit to indicate which quarters of the circle we're doing
|
||||||
|
@param color Color of pixel WHITE(0), BLACK(1) or INVERSE(2)
|
||||||
|
*/
|
||||||
|
void DISP_drawQuarterCircle(GFX_display_t *disp, int16_t x0, int16_t y0, uint8_t radius, GFX_CircCorners_t corner, GFX_Color_t color)
|
||||||
|
{
|
||||||
|
int16_t f = 1 - radius;
|
||||||
|
int16_t ddF_x = 1;
|
||||||
|
int16_t ddF_y = -2 * radius;
|
||||||
|
int16_t x = 0;
|
||||||
|
int16_t y = radius;
|
||||||
|
|
||||||
|
while (x < y)
|
||||||
|
{
|
||||||
|
if (f >= 0)
|
||||||
|
{
|
||||||
|
y--;
|
||||||
|
ddF_y += 2;
|
||||||
|
f += ddF_y;
|
||||||
|
}
|
||||||
|
x++;
|
||||||
|
ddF_x += 2;
|
||||||
|
f += ddF_x;
|
||||||
|
if (corner & BOTTOM_LEFT)
|
||||||
|
{
|
||||||
|
DISP_drawPixel(disp, x0 + x, y0 + y, color);
|
||||||
|
DISP_drawPixel(disp, x0 + y, y0 + x, color);
|
||||||
|
}
|
||||||
|
if (corner & BOTTOM_RIGHT)
|
||||||
|
{
|
||||||
|
DISP_drawPixel(disp, x0 + x, y0 - y, color);
|
||||||
|
DISP_drawPixel(disp, x0 + y, y0 - x, color);
|
||||||
|
}
|
||||||
|
if (corner & TOP_LEFT)
|
||||||
|
{
|
||||||
|
DISP_drawPixel(disp, x0 - y, y0 + x, color);
|
||||||
|
DISP_drawPixel(disp, x0 - x, y0 + y, color);
|
||||||
|
}
|
||||||
|
if (corner & TOP_RIGHT)
|
||||||
|
{
|
||||||
|
DISP_drawPixel(disp, x0 - y, y0 - x, color);
|
||||||
|
DISP_drawPixel(disp, x0 - x, y0 - y, color);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Draw a rounded rectangle with no fill color
|
||||||
|
* @param disp A pointer to display struct
|
||||||
|
* @param x Top left corner x coordinate
|
||||||
|
* @param y Top left corner y coordinate
|
||||||
|
* @param width Width in pixels
|
||||||
|
* @param height Height in pixels
|
||||||
|
* @param radius Radius of corner rounding
|
||||||
|
* @param color Color of pixel WHITE(0), BLACK(1) or INVERSE(2)
|
||||||
|
*/
|
||||||
|
void DISP_drawRoundRect(GFX_display_t *disp, int16_t x, int16_t y, int16_t width, int16_t height, int16_t radius, GFX_Color_t color)
|
||||||
|
{
|
||||||
|
int16_t max_radius = ((width < height) ? width : height) / 2; // 1/2 minor axis
|
||||||
|
if (radius > max_radius)
|
||||||
|
radius = max_radius;
|
||||||
|
// smarter version
|
||||||
|
DISP_drawHorizontalLine(disp, x + radius, y, width - 2 * radius, color); // Top
|
||||||
|
DISP_drawHorizontalLine(disp, x + radius, y + height - 1, width - 2 * radius, color); // Bottom
|
||||||
|
DISP_drawVerticalLine(disp, x, y + radius, height - 2 * radius, color); // Left
|
||||||
|
DISP_drawVerticalLine(disp, x + width - 1, y + radius, height - 2 * radius, color); // Right
|
||||||
|
// draw four corners
|
||||||
|
DISP_drawQuarterCircle(disp, x + radius, y + radius, radius, 1, color);
|
||||||
|
DISP_drawQuarterCircle(disp, x + width - radius - 1, y + radius, radius, 2, color);
|
||||||
|
DISP_drawQuarterCircle(disp, x + width - radius - 1, y + height - radius - 1, radius, 4, color);
|
||||||
|
DISP_drawQuarterCircle(disp, x + radius, y + height - radius - 1, radius, 8, color);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void _getBoundry(GFX_display_t *disp, buf_bitmap_boundry_t *boundry, uint8_t bitmap_width, uint8_t bitmap_height, int8_t pos_x, int8_t pos_y)
|
||||||
|
{
|
||||||
|
if (pos_x < 0)
|
||||||
|
{
|
||||||
|
boundry->bitmap_col = pos_x * -1;
|
||||||
|
boundry->buf_col_first = 0;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
boundry->bitmap_col = 0;
|
||||||
|
boundry->buf_col_first = pos_x;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (pos_y < 0)
|
||||||
|
{
|
||||||
|
boundry->bitmap_shift = 8 + (pos_y % 8);
|
||||||
|
boundry->bitmap_row_first = (pos_y / 8) * (-1) + 1;
|
||||||
|
boundry->buf_row_first = 0;
|
||||||
|
boundry->buf_mask_top = 0;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
boundry->bitmap_shift = pos_y % 8;
|
||||||
|
boundry->bitmap_row_first = 0;
|
||||||
|
boundry->buf_row_first = pos_y / 8;
|
||||||
|
boundry->buf_mask_top = 0xFF >> (8 - boundry->bitmap_shift);
|
||||||
|
}
|
||||||
|
boundry->buf_mask_bottom = 0xFF << ((pos_y + bitmap_height) % 8);
|
||||||
|
if (boundry->buf_mask_bottom == 0xFF)
|
||||||
|
{
|
||||||
|
boundry->buf_mask_bottom = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
if ((bitmap_width + pos_x) > disp->width)
|
||||||
|
{
|
||||||
|
boundry->buf_col_last = disp->width;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
boundry->buf_col_last = bitmap_width + pos_x;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (bitmap_height + pos_y > disp->height)
|
||||||
|
{
|
||||||
|
boundry->buf_row_last = disp->height / 8;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
boundry->buf_row_last = (bitmap_height + pos_y + 7) / 8;
|
||||||
|
}
|
||||||
|
|
||||||
|
boundry->bitmap_row_last = (pos_y + bitmap_height) / 8;
|
||||||
|
boundry->bitmap_max_idx = bitmap_width * ((bitmap_height + 7) / 8);
|
||||||
|
}
|
||||||
|
|
||||||
|
static inline uint8_t _getBitmapByte(const uint8_t *bitmap, uint16_t index, GFX_BitmapColor_t color)
|
||||||
|
{
|
||||||
|
switch (color)
|
||||||
|
{
|
||||||
|
case BM_INVERSE:
|
||||||
|
return ~(bitmap[index]);
|
||||||
|
case BM_FILL_WHITE:
|
||||||
|
return 0xFF;
|
||||||
|
case BM_FILL_BLACK:
|
||||||
|
return 0x00;
|
||||||
|
default:
|
||||||
|
return bitmap[index];
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Draw a 1-bit image at the specified (x,y) position.
|
||||||
|
* @param disp A pointer to display struct
|
||||||
|
* @param bitmap byte array with monochrome bitmap
|
||||||
|
* @param bitmap_width Width in pixels
|
||||||
|
* @param bitmap_height Height in pixels
|
||||||
|
* @param pos_x Top left corner x coordinate
|
||||||
|
* @param pos_y Top left corner y coordinate
|
||||||
|
* @param color Color of pixel BM_NORMAL or BM_INVERSE for bitmap. BM_WHITE or BM_BLACK for fill region.
|
||||||
|
*/
|
||||||
|
void DISP_drawBitmap(GFX_display_t *disp, const GFX_bitmap_t *bitmap, int8_t pos_x, int8_t pos_y, GFX_BitmapColor_t color)
|
||||||
|
{
|
||||||
|
if (bitmap->width + pos_x < 0 || bitmap->height + pos_y < 0)
|
||||||
|
return;
|
||||||
|
|
||||||
|
uint16_t tmp_buf16, bitmap_idx, buf_idx;
|
||||||
|
uint8_t tmp_bitmap, bitmap_row;
|
||||||
|
|
||||||
|
buf_bitmap_boundry_t b;
|
||||||
|
_getBoundry(disp, &b, bitmap->width, bitmap->height, pos_x, pos_y);
|
||||||
|
|
||||||
|
for (uint8_t col = b.buf_col_first; col < b.buf_col_last; col++, b.bitmap_col++)
|
||||||
|
{
|
||||||
|
tmp_buf16 = 0;
|
||||||
|
bitmap_row = b.bitmap_row_first;
|
||||||
|
|
||||||
|
if (b.bitmap_row_first > 0)
|
||||||
|
{
|
||||||
|
tmp_buf16 = _getBitmapByte(bitmap->bitmap, bitmap->width * (b.bitmap_row_first - 1) + b.bitmap_col, color) >> (8 - b.bitmap_shift);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
tmp_buf16 = disp->buffor[b.buf_row_first * disp->width + col] & b.buf_mask_top;
|
||||||
|
}
|
||||||
|
|
||||||
|
for (uint8_t buf_row = b.buf_row_first; buf_row < b.buf_row_last; buf_row++, bitmap_row++)
|
||||||
|
{
|
||||||
|
bitmap_idx = bitmap->width * bitmap_row + b.bitmap_col;
|
||||||
|
buf_idx = buf_row * disp->width + col;
|
||||||
|
|
||||||
|
if (bitmap_idx < b.bitmap_max_idx)
|
||||||
|
{
|
||||||
|
tmp_bitmap = _getBitmapByte(bitmap->bitmap, bitmap_idx, color);
|
||||||
|
tmp_buf16 |= tmp_bitmap << b.bitmap_shift;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (b.bitmap_row_last == buf_row)
|
||||||
|
{
|
||||||
|
disp->buffor[buf_idx] = (disp->buffor[buf_idx] & b.buf_mask_bottom) | (tmp_buf16 & ~(b.buf_mask_bottom));
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
disp->buffor[buf_idx] = (uint8_t)tmp_buf16;
|
||||||
|
}
|
||||||
|
tmp_buf16 = tmp_buf16 >> 8;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void DISP_drawBitmapShift(GFX_display_t *disp, const GFX_bitmap_t *bitmap, int8_t pos_x, int8_t pos_y, uint8_t shift_left, GFX_BitmapColor_t color)
|
||||||
|
{
|
||||||
|
if (bitmap->width + pos_x < 0 || bitmap->height + pos_y < 0)
|
||||||
|
return;
|
||||||
|
|
||||||
|
uint16_t tmp_buf16, bitmap_idx, buf_idx;
|
||||||
|
uint8_t tmp_bitmap, bitmap_row;
|
||||||
|
|
||||||
|
buf_bitmap_boundry_t b;
|
||||||
|
_getBoundry(disp, &b, bitmap->width, bitmap->height, pos_x, pos_y);
|
||||||
|
|
||||||
|
b.bitmap_col = (b.bitmap_col + shift_left) % bitmap->width;
|
||||||
|
for (uint8_t col = b.buf_col_first; col < b.buf_col_last; col++, b.bitmap_col = (b.bitmap_col + 1) % bitmap->width)
|
||||||
|
{
|
||||||
|
tmp_buf16 = 0;
|
||||||
|
bitmap_row = b.bitmap_row_first;
|
||||||
|
|
||||||
|
if (b.bitmap_row_first > 0)
|
||||||
|
{
|
||||||
|
tmp_buf16 = _getBitmapByte(bitmap->bitmap, bitmap->width * (b.bitmap_row_first - 1) + b.bitmap_col, color) >> (8 - b.bitmap_shift);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
tmp_buf16 = disp->buffor[b.buf_row_first * disp->width + col] & b.buf_mask_top;
|
||||||
|
}
|
||||||
|
|
||||||
|
for (uint8_t buf_row = b.buf_row_first; buf_row < b.buf_row_last; buf_row++, bitmap_row++)
|
||||||
|
{
|
||||||
|
bitmap_idx = bitmap->width * bitmap_row + b.bitmap_col;
|
||||||
|
buf_idx = buf_row * disp->width + col;
|
||||||
|
|
||||||
|
if (bitmap_idx < b.bitmap_max_idx)
|
||||||
|
{
|
||||||
|
tmp_bitmap = _getBitmapByte(bitmap->bitmap, bitmap_idx, color);
|
||||||
|
tmp_buf16 |= tmp_bitmap << b.bitmap_shift;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (b.bitmap_row_last == buf_row)
|
||||||
|
{
|
||||||
|
disp->buffor[buf_idx] = (disp->buffor[buf_idx] & b.buf_mask_bottom) | (tmp_buf16 & ~(b.buf_mask_bottom));
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
disp->buffor[buf_idx] = (uint8_t)tmp_buf16;
|
||||||
|
}
|
||||||
|
tmp_buf16 = tmp_buf16 >> 8;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void DISP_drawFillRect(GFX_display_t *disp, int16_t x, int16_t y, int16_t width, int16_t height)
|
||||||
|
{
|
||||||
|
GFX_bitmap_t area = {
|
||||||
|
.height = height,
|
||||||
|
.width = width,
|
||||||
|
.bitmap = NULL,
|
||||||
|
};
|
||||||
|
DISP_drawBitmap(disp, &area, x, y, BM_FILL_WHITE);
|
||||||
|
}
|
||||||
|
|
||||||
|
void DISP_clearRegion(GFX_display_t *disp, int16_t x, int16_t y, int16_t width, int16_t height)
|
||||||
|
{
|
||||||
|
GFX_bitmap_t area = {
|
||||||
|
.height = height,
|
||||||
|
.width = width,
|
||||||
|
.bitmap = NULL,
|
||||||
|
};
|
||||||
|
DISP_drawBitmap(disp, &area, x, y, BM_FILL_BLACK);
|
||||||
|
}
|
||||||
|
|
||||||
|
void DISP_clearScreen(GFX_display_t *disp)
|
||||||
|
{
|
||||||
|
GFX_bitmap_t area = {.height = disp->height, .width = disp->width, .bitmap = NULL};
|
||||||
|
DISP_drawBitmap(disp, &area, 0, 0, BM_FILL_BLACK);
|
||||||
|
}
|
||||||
66
firmware/shared_libs/display/display_gfx.h
Normal file
66
firmware/shared_libs/display/display_gfx.h
Normal file
@@ -0,0 +1,66 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#ifndef _swap_int16_t
|
||||||
|
#define _swap_int16_t(a, b) \
|
||||||
|
{ \
|
||||||
|
int16_t t = a; \
|
||||||
|
a = b; \
|
||||||
|
b = t; \
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#ifndef _diff
|
||||||
|
#define _diff(a, b) ((a > b) ? (a - b) : (b - a))
|
||||||
|
#endif
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
GFX_WHITE,
|
||||||
|
GFX_BLACK,
|
||||||
|
GFX_INVERSE
|
||||||
|
} GFX_Color_t;
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
BM_FILL_WHITE,
|
||||||
|
BM_FILL_BLACK,
|
||||||
|
BM_NORMAL,
|
||||||
|
BM_INVERSE
|
||||||
|
} GFX_BitmapColor_t;
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
TOP_RIGHT = 1,
|
||||||
|
BOTTOM_RIGHT = 2,
|
||||||
|
BOTTOM_LEFT = 4,
|
||||||
|
TOP_LEFT = 8
|
||||||
|
} GFX_CircCorners_t;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
uint8_t width;
|
||||||
|
uint8_t height;
|
||||||
|
uint8_t *buffor;
|
||||||
|
} GFX_display_t;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
uint8_t width;
|
||||||
|
uint8_t height;
|
||||||
|
const uint8_t *bitmap;
|
||||||
|
} GFX_bitmap_t;
|
||||||
|
|
||||||
|
void DISP_drawPixel(GFX_display_t *disp, uint8_t x, uint8_t y, GFX_Color_t color);
|
||||||
|
void DISP_drawVerticalLine(GFX_display_t *disp, int16_t x, int16_t y, int16_t height, GFX_Color_t color);
|
||||||
|
void DISP_drawHorizontalLine(GFX_display_t *disp, uint8_t x, uint8_t y, uint8_t width, GFX_Color_t color);
|
||||||
|
void DISP_drawSlashLine(GFX_display_t *disp, int16_t x0, int16_t y0, int16_t x1, int16_t y1, GFX_Color_t color);
|
||||||
|
void DISP_drawRect(GFX_display_t *disp, int16_t x, int16_t y, int16_t width, int16_t height, GFX_Color_t color);
|
||||||
|
void DISP_drawFillRect(GFX_display_t *disp, int16_t x, int16_t y, int16_t width, int16_t height);
|
||||||
|
void DISP_drawCircle(GFX_display_t *disp, int16_t x0, int16_t y0, uint8_t radius, GFX_Color_t color);
|
||||||
|
void DISP_drawQuarterCircle(GFX_display_t *disp, int16_t x0, int16_t y0, uint8_t radius, GFX_CircCorners_t corner, GFX_Color_t color);
|
||||||
|
void DISP_drawRoundRect(GFX_display_t *disp, int16_t x, int16_t y, int16_t width, int16_t height, int16_t radius, GFX_Color_t color);
|
||||||
|
void DISP_drawBitmap(GFX_display_t *disp, const GFX_bitmap_t *bitmap, int8_t pos_x, int8_t pos_y, GFX_BitmapColor_t color);
|
||||||
|
void DISP_drawBitmapShift(GFX_display_t *disp, const GFX_bitmap_t *bitmap, int8_t pos_x, int8_t pos_y, uint8_t shift_left, GFX_BitmapColor_t color);
|
||||||
|
void DISP_clearRegion(GFX_display_t *disp, int16_t x, int16_t y, int16_t width, int16_t height);
|
||||||
|
void DISP_clearScreen(GFX_display_t *disp);
|
||||||
|
|
||||||
|
void DISP_drawBitmapSlow(GFX_display_t *disp, const GFX_bitmap_t *bitmap, uint8_t x, uint8_t y);
|
||||||
88
firmware/shared_libs/display/font_gfx.c
Normal file
88
firmware/shared_libs/display/font_gfx.c
Normal file
@@ -0,0 +1,88 @@
|
|||||||
|
/*
|
||||||
|
* fonts.c
|
||||||
|
*
|
||||||
|
* Created on: 23 maj 2021
|
||||||
|
* Author: bartool
|
||||||
|
*/
|
||||||
|
|
||||||
|
// #include "main.h"
|
||||||
|
#include "font_gfx.h"
|
||||||
|
|
||||||
|
static uint8_t font_string_lenght_px(const GFX_font_t *font, uint8_t *text);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Write string at at the specified (x,y) position.
|
||||||
|
* @param disp A pointer to display struct
|
||||||
|
* @param font A pointer to font struct.
|
||||||
|
* @param text A pointer to string data.
|
||||||
|
* @param pos_x Top left corner x coordinate
|
||||||
|
* @param pos_yTop left corner y coordinate
|
||||||
|
* @param color Color of pixel BM_NORMAL or BM_INVERSE for bitmap.
|
||||||
|
* @return uint8_t
|
||||||
|
*/
|
||||||
|
uint8_t DISP_writeString(GFX_display_t *disp, const GFX_font_t *font, uint8_t *text, uint8_t pos_x, uint8_t pos_y, GFX_BitmapColor_t color)
|
||||||
|
{
|
||||||
|
uint8_t actual_char, char_nr;
|
||||||
|
GFX_bitmap_t char_bitmap;
|
||||||
|
const GFX_fontChar_t *charinfo;
|
||||||
|
|
||||||
|
uint8_t height = font->heightPixels;
|
||||||
|
uint8_t x = pos_x;
|
||||||
|
uint8_t width = font_string_lenght_px(font, text);
|
||||||
|
|
||||||
|
switch (color)
|
||||||
|
{
|
||||||
|
case BM_INVERSE:;
|
||||||
|
DISP_drawFillRect(disp, pos_x - 1, pos_y - 1, width + 2, height + 2);
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
DISP_clearRegion(disp, pos_x - 1, pos_y - 1, width + 2, height + 2);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
while (*text)
|
||||||
|
{
|
||||||
|
actual_char = *text++;
|
||||||
|
if (actual_char < font->startChar || actual_char > font->endChar)
|
||||||
|
{
|
||||||
|
if (actual_char == ' ')
|
||||||
|
{
|
||||||
|
x += font->spacePixels;
|
||||||
|
}
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
|
char_nr = actual_char - font->startChar;
|
||||||
|
charinfo = &font->charInfo[char_nr];
|
||||||
|
|
||||||
|
char_bitmap.height = height,
|
||||||
|
char_bitmap.width = charinfo->widthBits,
|
||||||
|
char_bitmap.bitmap = font->data + charinfo->offset,
|
||||||
|
|
||||||
|
DISP_drawBitmap(disp, &char_bitmap, x, pos_y, color);
|
||||||
|
|
||||||
|
x += charinfo->widthBits + font->interspacePixels;
|
||||||
|
}
|
||||||
|
|
||||||
|
return x;
|
||||||
|
}
|
||||||
|
|
||||||
|
static uint8_t font_string_lenght_px(const GFX_font_t *font, uint8_t *text)
|
||||||
|
{
|
||||||
|
uint8_t width = 0;
|
||||||
|
while (*text)
|
||||||
|
{
|
||||||
|
uint8_t actual_char = *text++;
|
||||||
|
uint8_t char_nr = actual_char - font->startChar;
|
||||||
|
if (actual_char < font->startChar || actual_char > font->endChar)
|
||||||
|
{
|
||||||
|
if (actual_char == ' ')
|
||||||
|
{
|
||||||
|
width += font->spacePixels;
|
||||||
|
}
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
width += font->charInfo[char_nr].widthBits + font->interspacePixels;
|
||||||
|
}
|
||||||
|
return width;
|
||||||
|
}
|
||||||
28
firmware/shared_libs/display/font_gfx.h
Normal file
28
firmware/shared_libs/display/font_gfx.h
Normal file
@@ -0,0 +1,28 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "main.h"
|
||||||
|
#include "display_gfx.h"
|
||||||
|
// This structure describes a single character's display information
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
const uint8_t widthBits; // width, in bits (or pixels), of the character
|
||||||
|
const uint16_t offset; // offset of the character's bitmap, in bytes, into the the GFX_font_t's data array
|
||||||
|
|
||||||
|
} GFX_fontChar_t;
|
||||||
|
|
||||||
|
// Describes a single font
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
// uint8_t DownSpace; // Downs Space in pixels
|
||||||
|
uint8_t heightPixels; // height, in pages (8 pixels), of the font's characters
|
||||||
|
uint8_t startChar; // the first character in the font (e.g. in charInfo and data)
|
||||||
|
uint8_t endChar;
|
||||||
|
uint8_t interspacePixels; // number of pixels of interspace between characters
|
||||||
|
uint8_t spacePixels; // number of pixels of space character
|
||||||
|
const GFX_fontChar_t *charInfo; // pointer to array of char information
|
||||||
|
const uint8_t *data; // pointer to generated array of character visual representation
|
||||||
|
// char * FontFileName; // (Pointer) Font filename saved on SD card or 0 (null) otherwise
|
||||||
|
// uint8_t bitOrientation; // bits and byte orientation 0-T2B, 1-L2R
|
||||||
|
} GFX_font_t;
|
||||||
|
|
||||||
|
uint8_t DISP_writeString(GFX_display_t *disp, const GFX_font_t *font, uint8_t *text, uint8_t pos_x, uint8_t pos_y, GFX_BitmapColor_t color);
|
||||||
235
firmware/shared_libs/drivers/ad9833/ad9833.c
Normal file
235
firmware/shared_libs/drivers/ad9833/ad9833.c
Normal file
@@ -0,0 +1,235 @@
|
|||||||
|
// Author: https://github.com/MajicDesigns/MD_AD9833
|
||||||
|
#include "main.h"
|
||||||
|
#include "ad9833_def.h"
|
||||||
|
#include "ad9833.h"
|
||||||
|
|
||||||
|
// Convenience calculations
|
||||||
|
// static uint32_t ad9833_calcFreq(float f); // Calculate AD9833 frequency register from a frequency
|
||||||
|
// static uint16_t ad9833_calcPhase(float a); // Calculate AD9833 phase register from phase
|
||||||
|
|
||||||
|
void ad9833_spi_activate(ad9833_handle_t *hfg)
|
||||||
|
{
|
||||||
|
// HAL_GPIO_WritePin(hfg->cs_port, hfg->cs_pin, GPIO_PIN_RESET);
|
||||||
|
hfg->hcs->cs_on(hfg->hcs);
|
||||||
|
}
|
||||||
|
|
||||||
|
void ad9833_spi_deactivate(ad9833_handle_t *hfg)
|
||||||
|
{
|
||||||
|
// HAL_GPIO_WritePin(hfg->cs_port, hfg->cs_pin, GPIO_PIN_SET);
|
||||||
|
hfg->hcs->cs_off(hfg->hcs);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void ad9833_transmit16(ad9833_handle_t *hfg, uint16_t data)
|
||||||
|
{
|
||||||
|
uint8_t data8;
|
||||||
|
ad9833_spi_activate(hfg);
|
||||||
|
data8 = (uint8_t)((data >> 8) & 0x00FF);
|
||||||
|
HAL_SPI_Transmit(hfg->hspi, &data8, 1, HAL_MAX_DELAY);
|
||||||
|
data8 = (uint8_t)(data & 0x00FF);
|
||||||
|
HAL_SPI_Transmit(hfg->hspi, &data8, 1, HAL_MAX_DELAY);
|
||||||
|
ad9833_spi_deactivate(hfg);
|
||||||
|
}
|
||||||
|
|
||||||
|
void ad9833_reset(ad9833_handle_t *hfg, uint8_t hold)
|
||||||
|
// Reset is done on a 1 to 0 transition
|
||||||
|
{
|
||||||
|
hfg->_regCtl |= (1 << AD_RESET);
|
||||||
|
ad9833_transmit16(hfg, hfg->_regCtl);
|
||||||
|
|
||||||
|
if (!hold)
|
||||||
|
{
|
||||||
|
hfg->_regCtl &= ~(1 << AD_RESET);
|
||||||
|
ad9833_transmit16(hfg, hfg->_regCtl);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void ad9833_init(ad9833_handle_t *hfg, SPI_HandleTypeDef *hspi, cs_handle_t *hcs)
|
||||||
|
// Initialise the AD9833 and then set up safe values for the AD9833 device
|
||||||
|
// Procedure from Figure 27 of in the AD9833 Data Sheet
|
||||||
|
{
|
||||||
|
// initialise our preferred CS pin (could be same as SS)
|
||||||
|
hfg->hspi = hspi;
|
||||||
|
hfg->hcs = hcs;
|
||||||
|
|
||||||
|
hfg->hcs->cs_off(hfg->hcs);
|
||||||
|
|
||||||
|
hfg->_regCtl = 0;
|
||||||
|
hfg->_regCtl |= (1 << AD_B28); // always write 2 words consecutively for frequency
|
||||||
|
ad9833_transmit16(hfg, hfg->_regCtl);
|
||||||
|
|
||||||
|
ad9833_reset(hfg, 1); // Reset and hold
|
||||||
|
ad9833_setFrequency(hfg, CHAN_0, AD_DEFAULT_FREQ);
|
||||||
|
ad9833_setFrequency(hfg, CHAN_1, AD_DEFAULT_FREQ);
|
||||||
|
ad9833_setPhase(hfg, CHAN_0, AD_DEFAULT_PHASE);
|
||||||
|
ad9833_setPhase(hfg, CHAN_1, AD_DEFAULT_PHASE);
|
||||||
|
ad9833_setActiveChannelPhase(hfg, CHAN_0);
|
||||||
|
ad9833_setActiveChannelFreq(hfg, CHAN_0);
|
||||||
|
ad9833_setMode(hfg, MODE_OFF);
|
||||||
|
ad9833_reset(hfg, 0); // full transition
|
||||||
|
}
|
||||||
|
|
||||||
|
void ad9833_setActiveChannelFreq(ad9833_handle_t *hfg, AD_channel_t chan)
|
||||||
|
{
|
||||||
|
// PRINT("\nsetActiveFreq CHAN_", chan);
|
||||||
|
|
||||||
|
switch (chan)
|
||||||
|
{
|
||||||
|
case CHAN_0:
|
||||||
|
hfg->_regCtl &= ~(1 << AD_FSELECT);
|
||||||
|
break;
|
||||||
|
case CHAN_1:
|
||||||
|
hfg->_regCtl |= (1 << AD_FSELECT);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
ad9833_transmit16(hfg, hfg->_regCtl);
|
||||||
|
}
|
||||||
|
|
||||||
|
AD_channel_t ad9833_getActiveChannelFreq(ad9833_handle_t *hfg)
|
||||||
|
{
|
||||||
|
return (hfg->_regCtl & (1 << AD_FSELECT)) ? CHAN_1 : CHAN_0;
|
||||||
|
};
|
||||||
|
|
||||||
|
void ad9833_setActiveChannelPhase(ad9833_handle_t *hfg, AD_channel_t chan)
|
||||||
|
{
|
||||||
|
// PRINT("\nsetActivePhase CHAN_", chan);
|
||||||
|
|
||||||
|
switch (chan)
|
||||||
|
{
|
||||||
|
case CHAN_0:
|
||||||
|
hfg->_regCtl &= ~(1 << AD_PSELECT);
|
||||||
|
break;
|
||||||
|
case CHAN_1:
|
||||||
|
hfg->_regCtl |= (1 << AD_PSELECT);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
ad9833_transmit16(hfg, hfg->_regCtl);
|
||||||
|
}
|
||||||
|
|
||||||
|
AD_channel_t ad9833_getActiveChannelPhase(ad9833_handle_t *hfg)
|
||||||
|
{
|
||||||
|
return (hfg->_regCtl & (1 << AD_PSELECT)) ? CHAN_1 : CHAN_0;
|
||||||
|
};
|
||||||
|
|
||||||
|
void ad9833_setMode(ad9833_handle_t *hfg, AD_mode_t mode)
|
||||||
|
{
|
||||||
|
// PRINTS("\nsetWave ");
|
||||||
|
hfg->_mode = mode;
|
||||||
|
|
||||||
|
switch (mode)
|
||||||
|
{
|
||||||
|
case MODE_OFF:
|
||||||
|
hfg->_regCtl &= ~(1 << AD_OPBITEN);
|
||||||
|
hfg->_regCtl &= ~(1 << AD_MODE);
|
||||||
|
hfg->_regCtl |= (1 << AD_SLEEP1);
|
||||||
|
hfg->_regCtl |= (1 << AD_SLEEP12);
|
||||||
|
break;
|
||||||
|
case MODE_SINE:
|
||||||
|
hfg->_regCtl &= ~(1 << AD_OPBITEN);
|
||||||
|
hfg->_regCtl &= ~(1 << AD_MODE);
|
||||||
|
hfg->_regCtl &= ~(1 << AD_SLEEP1);
|
||||||
|
hfg->_regCtl &= ~(1 << AD_SLEEP12);
|
||||||
|
break;
|
||||||
|
case MODE_SQUARE1:
|
||||||
|
hfg->_regCtl |= (1 << AD_OPBITEN);
|
||||||
|
hfg->_regCtl &= ~(1 << AD_MODE);
|
||||||
|
hfg->_regCtl |= (1 << AD_DIV2);
|
||||||
|
hfg->_regCtl &= ~(1 << AD_SLEEP1);
|
||||||
|
hfg->_regCtl &= ~(1 << AD_SLEEP12);
|
||||||
|
break;
|
||||||
|
case MODE_SQUARE2:
|
||||||
|
hfg->_regCtl |= (1 << AD_OPBITEN);
|
||||||
|
hfg->_regCtl &= ~(1 << AD_MODE);
|
||||||
|
hfg->_regCtl &= ~(1 << AD_DIV2);
|
||||||
|
hfg->_regCtl &= ~(1 << AD_SLEEP1);
|
||||||
|
hfg->_regCtl &= ~(1 << AD_SLEEP12);
|
||||||
|
break;
|
||||||
|
case MODE_TRIANGLE:
|
||||||
|
hfg->_regCtl &= ~(1 << AD_OPBITEN);
|
||||||
|
hfg->_regCtl |= (1 << AD_MODE);
|
||||||
|
hfg->_regCtl &= ~(1 << AD_SLEEP1);
|
||||||
|
hfg->_regCtl &= ~(1 << AD_SLEEP12);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
ad9833_transmit16(hfg, hfg->_regCtl);
|
||||||
|
}
|
||||||
|
|
||||||
|
// static uint32_t ad9833_calcFreq(float f)
|
||||||
|
// // Calculate register value for AD9833 frequency register from a frequency
|
||||||
|
// {
|
||||||
|
// return (uint32_t)((f * AD_2POW28 / AD_MCLK) + 0.5f);
|
||||||
|
// }
|
||||||
|
|
||||||
|
static uint32_t ad9833_calcFreq_uint(uint32_t f)
|
||||||
|
{
|
||||||
|
return ((f * AD_2POW28 + AD_MCLK_DIV2) / AD_MCLK); // ((n + d/2)/d)
|
||||||
|
}
|
||||||
|
|
||||||
|
// static uint16_t ad9833_calcPhase(float a)
|
||||||
|
// // Calculate the value for AD9833 phase register from given phase in tenths of a degree
|
||||||
|
// {
|
||||||
|
// return (uint16_t)((512.0f * (a / 10) / 45) + 0.5f);
|
||||||
|
// }
|
||||||
|
|
||||||
|
static uint16_t ad9833_calcPhase_uint(uint16_t p)
|
||||||
|
{
|
||||||
|
return ((p * 4096U + 180) / 360);
|
||||||
|
}
|
||||||
|
void ad9833_setFrequency(ad9833_handle_t *hfg, AD_channel_t chan, uint32_t freq)
|
||||||
|
{
|
||||||
|
// PRINT("\nsetFreq CHAN_", chan);
|
||||||
|
uint16_t freq_channel = 0;
|
||||||
|
|
||||||
|
hfg->_regFreq[chan] = ad9833_calcFreq_uint(freq);
|
||||||
|
|
||||||
|
// select the address mask
|
||||||
|
|
||||||
|
switch (chan)
|
||||||
|
{
|
||||||
|
case CHAN_0:
|
||||||
|
freq_channel = SEL_FREQ0;
|
||||||
|
break;
|
||||||
|
case CHAN_1:
|
||||||
|
freq_channel = SEL_FREQ1;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
// error
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Assumes B28 is on so we can send consecutive words
|
||||||
|
// B28 is set by default for the library, so just send it here
|
||||||
|
// Now send the two parts of the frequency 14 bits at a time,
|
||||||
|
// LSBs first
|
||||||
|
|
||||||
|
// spiSend(_regCtl); // set B28
|
||||||
|
ad9833_transmit16(hfg, freq_channel | (uint16_t)(hfg->_regFreq[chan] & 0x3fff));
|
||||||
|
ad9833_transmit16(hfg, freq_channel | (uint16_t)((hfg->_regFreq[chan] >> 14) & 0x3fff));
|
||||||
|
}
|
||||||
|
|
||||||
|
void ad9833_setPhase(ad9833_handle_t *hfg, AD_channel_t chan, uint16_t phase)
|
||||||
|
{
|
||||||
|
// PRINT("\nsetPhase CHAN_", chan);
|
||||||
|
uint16_t phase_channel = 0;
|
||||||
|
|
||||||
|
hfg->_regPhase[chan] = ad9833_calcPhase_uint(phase);
|
||||||
|
|
||||||
|
// select the address mask
|
||||||
|
switch (chan)
|
||||||
|
{
|
||||||
|
case CHAN_0:
|
||||||
|
phase_channel = SEL_PHASE0;
|
||||||
|
break;
|
||||||
|
case CHAN_1:
|
||||||
|
phase_channel = SEL_PHASE1;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
// error
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Now send the phase as 12 bits with appropriate address bits
|
||||||
|
ad9833_transmit16(hfg, phase_channel | (0xfff & hfg->_regPhase[chan]));
|
||||||
|
}
|
||||||
58
firmware/shared_libs/drivers/ad9833/ad9833.h
Normal file
58
firmware/shared_libs/drivers/ad9833/ad9833.h
Normal file
@@ -0,0 +1,58 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "spi_cs_if.h"
|
||||||
|
|
||||||
|
#define AD_DEFAULT_FREQ 1000U ///< Default initialisation frequency (Hz)
|
||||||
|
#define AD_DEFAULT_PHASE 0 ///< Default initialisation phase angle (degrees)
|
||||||
|
#define AD_MCLK 25000000U ///< Clock speed of the AD9833 reference clock in Hz
|
||||||
|
#define AD_MCLK_DIV2 12500000U ///< Clock speed of the AD9833 reference clock in Hz
|
||||||
|
/**
|
||||||
|
* Channel enumerated type.
|
||||||
|
*
|
||||||
|
* This enumerated type is used with the to specify which channel
|
||||||
|
* is being invoked on operations that could be channel related.
|
||||||
|
*/
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
CHAN_0 = 0, ///< Channel 0 definition
|
||||||
|
CHAN_1 = 1, ///< Channel 1 definition
|
||||||
|
} AD_channel_t;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Output mode request enumerated type.
|
||||||
|
*
|
||||||
|
* This enumerated type is used with the \ref setMode() methods to identify
|
||||||
|
* the mode request.
|
||||||
|
*/
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
MODE_OFF, ///< Set output all off
|
||||||
|
MODE_SINE, ///< Set output to a sine wave at selected frequency
|
||||||
|
MODE_SQUARE1, ///< Set output to a square wave at selected frequency
|
||||||
|
MODE_SQUARE2, ///< Set output to a square wave at half selected frequency
|
||||||
|
MODE_TRIANGLE, ///< Set output to a triangle wave at selected frequency
|
||||||
|
} AD_mode_t;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
uint16_t _regCtl; // control register image
|
||||||
|
uint32_t _regFreq[2]; // frequency registers
|
||||||
|
uint32_t _regPhase[2]; // phase registers
|
||||||
|
|
||||||
|
AD_mode_t _mode; // last set mode
|
||||||
|
|
||||||
|
SPI_HandleTypeDef *hspi;
|
||||||
|
cs_handle_t *hcs;
|
||||||
|
} ad9833_handle_t;
|
||||||
|
|
||||||
|
void ad9833_init(ad9833_handle_t *hfg, SPI_HandleTypeDef *hspi, cs_handle_t *hcs);
|
||||||
|
void ad9833_spi_activate(ad9833_handle_t *hfg);
|
||||||
|
void ad9833_spi_deactivate(ad9833_handle_t *hfg);
|
||||||
|
void ad9833_reset(ad9833_handle_t *hfg, uint8_t hold);
|
||||||
|
void ad9833_setActiveChannelFreq(ad9833_handle_t *hfg, AD_channel_t chan);
|
||||||
|
AD_channel_t ad9833_getActiveChannelFreq(ad9833_handle_t *hfg);
|
||||||
|
void ad9833_setActiveChannelPhase(ad9833_handle_t *hfg, AD_channel_t chan);
|
||||||
|
AD_channel_t ad9833_getActiveChannelPhase(ad9833_handle_t *hfg);
|
||||||
|
void ad9833_setMode(ad9833_handle_t *hfg, AD_mode_t mode);
|
||||||
|
void ad9833_setFrequency(ad9833_handle_t *hfg, AD_channel_t chan, uint32_t freq);
|
||||||
|
void ad9833_setPhase(ad9833_handle_t *hfg, AD_channel_t chan, uint16_t phase);
|
||||||
44
firmware/shared_libs/drivers/ad9833/ad9833_def.h
Normal file
44
firmware/shared_libs/drivers/ad9833/ad9833_def.h
Normal file
@@ -0,0 +1,44 @@
|
|||||||
|
// Author: https://github.com/MajicDesigns/MD_AD9833
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
/** @}*/
|
||||||
|
|
||||||
|
// AD9833 Control Register bit definitions
|
||||||
|
#define AD_B28 13 ///< B28 = 1 allows a complete word to be loaded into a frequency register in
|
||||||
|
///< two consecutive writes. When B28 = 0, the 28-bit frequency register
|
||||||
|
///< operates as two 14-bit registers.
|
||||||
|
#define AD_HLB 12 ///< Control bit allows the user to continuously load the MSBs or LSBs of a
|
||||||
|
///< frequency register while ignoring the remaining 14 bits. HLB is used
|
||||||
|
///< in conjunction with B28; when B28 = 1, this control bit is ignored.
|
||||||
|
#define AD_FSELECT 11 ///< Defines whether the FREQ0 register or the FREQ1 register is used in
|
||||||
|
///< the phase accumulator.
|
||||||
|
#define AD_PSELECT 10 ///< Defines whether the PHASE0 register or the PHASE1 register data is
|
||||||
|
///< added to the output of the phase accumulator.
|
||||||
|
#define AD_RESET 8 ///< Reset = 1 resets internal registers to 0, which corresponds to an
|
||||||
|
///< analog output of midscale. Reset = 0 disables reset.
|
||||||
|
#define AD_SLEEP1 7 ///< When SLEEP1 = 1, the internal MCLK clock is disabled, and the DAC output
|
||||||
|
///< remains at its present value. When SLEEP1 = 0, MCLK is enabled.
|
||||||
|
#define AD_SLEEP12 6 ///< SLEEP12 = 1 powers down the on-chip DAC. SLEEP12 = 0 implies that
|
||||||
|
///< the DAC is active.
|
||||||
|
#define AD_OPBITEN 5 ///< When OPBITEN = 1, the output of the DAC is no longer available at the
|
||||||
|
///< VOUT pin, replaced by MSB (or MSB/2) of the DAC. When OPBITEN = 0, the
|
||||||
|
///< DAC is connected to VOUT.
|
||||||
|
#define AD_DIV2 3 ///< When DIV2 = 1, the MSB of the DAC data is passed to the VOUT pin. When
|
||||||
|
///< DIV2 = 0, the MSB/2 of the DAC data is output at the VOUT pin.
|
||||||
|
#define AD_MODE 1 ///< When MODE = 1, the SIN ROM is bypassed, resulting in a triangle output
|
||||||
|
///< from the DAC. When MODE = 0, the SIN ROM is used which results in a
|
||||||
|
///< sinusoidal signal at the output.
|
||||||
|
|
||||||
|
// AD9833 Frequency and Phase register bit definitions
|
||||||
|
#define AD_FREQ1 15 ///< Select frequency 1 register
|
||||||
|
#define AD_FREQ0 14 ///< Select frequency 0 register
|
||||||
|
#define AD_PHASE 13 ///< Select the phase register
|
||||||
|
|
||||||
|
// AD9833 Freq and Phase register address identifiers
|
||||||
|
#define SEL_FREQ0 (1 << AD_FREQ0)
|
||||||
|
#define SEL_FREQ1 (1 << AD_FREQ1)
|
||||||
|
#define SEL_PHASE0 (1 << AD_FREQ0 | 1 << AD_FREQ1 | 0 << AD_PHASE)
|
||||||
|
#define SEL_PHASE1 (1 << AD_FREQ0 | 1 << AD_FREQ1 | 1 << AD_PHASE)
|
||||||
|
|
||||||
|
// AD9833 frequency and phase calculation macros
|
||||||
|
#define AD_2POW28 (1ULL << 28) ///< Used when calculating output frequency
|
||||||
106
firmware/shared_libs/drivers/hw_button/hw_button.c
Normal file
106
firmware/shared_libs/drivers/hw_button/hw_button.c
Normal file
@@ -0,0 +1,106 @@
|
|||||||
|
#include "main.h"
|
||||||
|
#include "hw_button.h"
|
||||||
|
|
||||||
|
static void buttonIdleRoutine(ButtonKey_t *key);
|
||||||
|
static void buttonDebounceRoutine(ButtonKey_t *key);
|
||||||
|
static void buttonPressedRoutine(ButtonKey_t *key);
|
||||||
|
static void buttonLongPressedRoutine(ButtonKey_t *key);
|
||||||
|
|
||||||
|
typedef void (*ButtonRoutine_t)(ButtonKey_t *);
|
||||||
|
|
||||||
|
ButtonRoutine_t button_routine[MAX_STATE] = {
|
||||||
|
buttonIdleRoutine,
|
||||||
|
buttonDebounceRoutine,
|
||||||
|
buttonPressedRoutine,
|
||||||
|
buttonLongPressedRoutine,
|
||||||
|
buttonLongPressedRoutine,
|
||||||
|
};
|
||||||
|
|
||||||
|
void buttonHandler(ButtonKey_t *key)
|
||||||
|
{
|
||||||
|
button_routine[key->state](key);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void buttonIdleRoutine(ButtonKey_t *key)
|
||||||
|
{
|
||||||
|
if (key->pushed_state == HAL_GPIO_ReadPin(key->gpio_port, key->gpio_pin))
|
||||||
|
{
|
||||||
|
key->state = DEBOUNCE;
|
||||||
|
key->last_tick = HAL_GetTick();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static void buttonDebounceRoutine(ButtonKey_t *key)
|
||||||
|
{
|
||||||
|
if (HAL_GetTick() - key->last_tick < key->timer_debounce)
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (key->pushed_state != HAL_GPIO_ReadPin(key->gpio_port, key->gpio_pin))
|
||||||
|
{
|
||||||
|
key->state = IDLE;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
key->state = PRESSED;
|
||||||
|
key->last_tick = HAL_GetTick();
|
||||||
|
// if (key->buttonPressed)
|
||||||
|
// {
|
||||||
|
// key->buttonPressed(key);
|
||||||
|
// }
|
||||||
|
}
|
||||||
|
|
||||||
|
static void buttonPressedRoutine(ButtonKey_t *key)
|
||||||
|
{
|
||||||
|
if (key->pushed_state != HAL_GPIO_ReadPin(key->gpio_port, key->gpio_pin))
|
||||||
|
{
|
||||||
|
key->state = IDLE;
|
||||||
|
// if (key->buttonReleased)
|
||||||
|
// {
|
||||||
|
// key->buttonReleased(key);
|
||||||
|
// }
|
||||||
|
if (key->buttonPressed)
|
||||||
|
{
|
||||||
|
key->buttonPressed(key);
|
||||||
|
}
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (HAL_GetTick() - key->last_tick < key->timer_long_pressed)
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
key->state = LONGPRESSED;
|
||||||
|
key->last_tick = HAL_GetTick();
|
||||||
|
if (key->buttonLongPressed)
|
||||||
|
{
|
||||||
|
key->buttonLongPressed(key);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static void buttonLongPressedRoutine(ButtonKey_t *key)
|
||||||
|
{
|
||||||
|
if (key->pushed_state != HAL_GPIO_ReadPin(key->gpio_port, key->gpio_pin))
|
||||||
|
{
|
||||||
|
key->state = IDLE;
|
||||||
|
if (key->buttonReleased)
|
||||||
|
{
|
||||||
|
key->buttonReleased(key);
|
||||||
|
}
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (HAL_GetTick() - key->last_tick < key->timer_repeat_delay)
|
||||||
|
{
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
key->state = REPEAT;
|
||||||
|
key->last_tick = HAL_GetTick();
|
||||||
|
if (key->buttonRepeat)
|
||||||
|
{
|
||||||
|
key->buttonRepeat(key);
|
||||||
|
}
|
||||||
|
}
|
||||||
46
firmware/shared_libs/drivers/hw_button/hw_button.h
Normal file
46
firmware/shared_libs/drivers/hw_button/hw_button.h
Normal file
@@ -0,0 +1,46 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#define BTN_DEFAULT_DEBOUNCE_MS 20
|
||||||
|
#define BTN_DEFAULT_LONGPRESSED_MS 1000
|
||||||
|
#define BTN_DEFAULT_REPEAT_MS 200
|
||||||
|
|
||||||
|
// States for state machine
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
IDLE = 0,
|
||||||
|
DEBOUNCE,
|
||||||
|
PRESSED,
|
||||||
|
LONGPRESSED,
|
||||||
|
REPEAT,
|
||||||
|
MAX_STATE
|
||||||
|
} ButtonState_t;
|
||||||
|
|
||||||
|
// Struct for button
|
||||||
|
typedef struct ButtonKey ButtonKey_t;
|
||||||
|
typedef void (*buttonPressed_t)(ButtonKey_t *key);
|
||||||
|
typedef void (*buttonLongPressed_t)(ButtonKey_t *key);
|
||||||
|
typedef void (*buttonRepeat_t)(ButtonKey_t *key);
|
||||||
|
|
||||||
|
struct ButtonKey
|
||||||
|
{
|
||||||
|
uint8_t instance; // Button name/number
|
||||||
|
ButtonState_t state; // Button current state
|
||||||
|
|
||||||
|
GPIO_TypeDef *gpio_port; // GPIO Port for a button
|
||||||
|
uint16_t gpio_pin; // GPIO Pin for a button
|
||||||
|
GPIO_PinState pushed_state;
|
||||||
|
|
||||||
|
uint32_t last_tick; // Last remembered time before steps
|
||||||
|
uint32_t timer_debounce; // Fixed, settable time for debounce timer
|
||||||
|
uint32_t timer_long_pressed; // Fixed, adjustable time for long press timer
|
||||||
|
uint32_t timer_repeat_delay; // Fixed, adjustable interval time
|
||||||
|
|
||||||
|
buttonPressed_t buttonReleased; // A callback for button released
|
||||||
|
buttonPressed_t buttonPressed; // A callback for button pressed
|
||||||
|
buttonLongPressed_t buttonLongPressed; // A callback for long pressed
|
||||||
|
buttonRepeat_t buttonRepeat; // A callback for repeat
|
||||||
|
};
|
||||||
|
|
||||||
|
// Public functions
|
||||||
|
|
||||||
|
void buttonHandler(ButtonKey_t *key);
|
||||||
19
firmware/shared_libs/drivers/led/led.c
Normal file
19
firmware/shared_libs/drivers/led/led.c
Normal file
@@ -0,0 +1,19 @@
|
|||||||
|
#include "led.h"
|
||||||
|
|
||||||
|
void led_init(led_handle_t *hled, GPIO_TypeDef *port, uint16_t pin)
|
||||||
|
{
|
||||||
|
hled->port = port;
|
||||||
|
hled->pin = pin;
|
||||||
|
|
||||||
|
HAL_GPIO_WritePin(port, pin, GPIO_PIN_SET);
|
||||||
|
}
|
||||||
|
|
||||||
|
void led_on(led_handle_t *hled)
|
||||||
|
{
|
||||||
|
HAL_GPIO_WritePin(hled->port, hled->pin, GPIO_PIN_RESET);
|
||||||
|
}
|
||||||
|
|
||||||
|
void led_off(led_handle_t *hled)
|
||||||
|
{
|
||||||
|
HAL_GPIO_WritePin(hled->port, hled->pin, GPIO_PIN_SET);
|
||||||
|
}
|
||||||
8
firmware/shared_libs/drivers/led/led.h
Normal file
8
firmware/shared_libs/drivers/led/led.h
Normal file
@@ -0,0 +1,8 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "gpio.h"
|
||||||
|
#include "ctrl_app_types.h"
|
||||||
|
|
||||||
|
void led_init(led_handle_t *hled, GPIO_TypeDef *port, uint16_t pin);
|
||||||
|
void led_on(led_handle_t *hled);
|
||||||
|
void led_off(led_handle_t *hled);
|
||||||
90
firmware/shared_libs/drivers/ltc2631/ltc2631.c
Normal file
90
firmware/shared_libs/drivers/ltc2631/ltc2631.c
Normal file
@@ -0,0 +1,90 @@
|
|||||||
|
#include "main.h"
|
||||||
|
#include "ltc2631.h"
|
||||||
|
|
||||||
|
void ltc2631_transmit(ltc2631_handle_t *hdac, uint8_t *data)
|
||||||
|
{
|
||||||
|
HAL_I2C_Master_Transmit(hdac->hi2c, hdac->addr, data, 3, 1);
|
||||||
|
}
|
||||||
|
|
||||||
|
void ltc2631_init(ltc2631_handle_t *hdac, I2C_HandleTypeDef *hi2c, uint8_t addr, ltc2631_res_t res, float ref)
|
||||||
|
{
|
||||||
|
hdac->hi2c = hi2c;
|
||||||
|
hdac->addr = addr;
|
||||||
|
hdac->resolution = res;
|
||||||
|
hdac->ref_voltage_f = ref;
|
||||||
|
hdac->ref_voltage_u = ref * 1000U;
|
||||||
|
}
|
||||||
|
|
||||||
|
void ltc2631_setOutputVoltage_f(ltc2631_handle_t *hdac, float volt)
|
||||||
|
{
|
||||||
|
uint16_t value = 0;
|
||||||
|
uint8_t data[3] = {0};
|
||||||
|
|
||||||
|
if (volt > hdac->ref_voltage_f)
|
||||||
|
{
|
||||||
|
volt = hdac->ref_voltage_f;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (volt < 0)
|
||||||
|
{
|
||||||
|
volt = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
value = (volt / hdac->ref_voltage_f + 0.005f) * (hdac->resolution - 1);
|
||||||
|
|
||||||
|
value = value << (16 - hdac->resolution);
|
||||||
|
data[0] = LTC_WRTIEUPDATE;
|
||||||
|
data[1] = (value >> 8);
|
||||||
|
data[2] = value;
|
||||||
|
|
||||||
|
ltc2631_transmit(hdac, data);
|
||||||
|
}
|
||||||
|
void ltc2631_setOutputVoltage_u(ltc2631_handle_t *hdac, uint32_t volt_x1000)
|
||||||
|
{
|
||||||
|
uint16_t value = 0;
|
||||||
|
uint8_t data[3] = {0};
|
||||||
|
|
||||||
|
if (volt_x1000 > hdac->ref_voltage_u)
|
||||||
|
{
|
||||||
|
volt_x1000 = hdac->ref_voltage_u;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (volt_x1000 < 0)
|
||||||
|
{
|
||||||
|
volt_x1000 = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
value = (volt_x1000 * (hdac->resolution - 1)) / hdac->ref_voltage_u;
|
||||||
|
|
||||||
|
value = value << (16 - hdac->resolution);
|
||||||
|
data[0] = LTC_WRTIEUPDATE;
|
||||||
|
data[1] = (value >> 8);
|
||||||
|
data[2] = value;
|
||||||
|
|
||||||
|
ltc2631_transmit(hdac, data);
|
||||||
|
}
|
||||||
|
|
||||||
|
void ltc2631_setOutputValue(ltc2631_handle_t *hdac, uint16_t value)
|
||||||
|
{
|
||||||
|
uint8_t data[3] = {0};
|
||||||
|
|
||||||
|
if (value >= (1 << hdac->resolution))
|
||||||
|
{
|
||||||
|
value = (1 << hdac->resolution) - 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
value = value << (16 - hdac->resolution);
|
||||||
|
data[0] = LTC_WRTIEUPDATE;
|
||||||
|
data[1] = (value >> 8);
|
||||||
|
data[2] = value;
|
||||||
|
|
||||||
|
ltc2631_transmit(hdac, data);
|
||||||
|
}
|
||||||
|
|
||||||
|
void ltc2631_sleep(ltc2631_handle_t *hdac)
|
||||||
|
{
|
||||||
|
uint8_t data[3] = {0};
|
||||||
|
data[0] = LTC_SLEEP;
|
||||||
|
|
||||||
|
ltc2631_transmit(hdac, data);
|
||||||
|
}
|
||||||
34
firmware/shared_libs/drivers/ltc2631/ltc2631.h
Normal file
34
firmware/shared_libs/drivers/ltc2631/ltc2631.h
Normal file
@@ -0,0 +1,34 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
// C3 C2 C1 C0
|
||||||
|
#define LTC_WRITE 0b00000000 // 0 0 0 0 Write to Input Register
|
||||||
|
#define LTC_UPDATE 0b00010000 // 0 0 0 1 Update (Power Up) DAC Register
|
||||||
|
#define LTC_WRTIEUPDATE 0b00110000 // 0 0 1 1 Write to and Update (Power Up) DAC Register
|
||||||
|
#define LTC_SLEEP 0b01000000 // 0 1 0 0 Power Down
|
||||||
|
#define LTC_INTERNALREF 0b01100000 // 0 1 1 0 Select Internal Reference
|
||||||
|
#define LTC_EXTERNALREF 0b01110000 // 0 1 1 1 Select External Reference
|
||||||
|
|
||||||
|
#define LTC_REF_2V5 2.5
|
||||||
|
#define LTC_REF_4V096 4.096
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
LTC2631_8BIT = 8,
|
||||||
|
LTC2631_10BIT = 10,
|
||||||
|
LTC2631_12BIT = 12
|
||||||
|
} ltc2631_res_t;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
I2C_HandleTypeDef *hi2c;
|
||||||
|
uint8_t addr;
|
||||||
|
ltc2631_res_t resolution;
|
||||||
|
float ref_voltage_f;
|
||||||
|
uint32_t ref_voltage_u;
|
||||||
|
} ltc2631_handle_t;
|
||||||
|
|
||||||
|
void ltc2631_init(ltc2631_handle_t *hdac, I2C_HandleTypeDef *hi2c, uint8_t addr, ltc2631_res_t res, float ref);
|
||||||
|
void ltc2631_setOutputVoltage_f(ltc2631_handle_t *hdac, float volt);
|
||||||
|
void ltc2631_setOutputVoltage_u(ltc2631_handle_t *hdac, uint32_t volt_x1000);
|
||||||
|
void ltc2631_setOutputValue(ltc2631_handle_t *hdac, uint16_t value);
|
||||||
|
void ltc2631_sleep(ltc2631_handle_t *hdac);
|
||||||
75
firmware/shared_libs/drivers/mcp41x/mcp41x.c
Normal file
75
firmware/shared_libs/drivers/mcp41x/mcp41x.c
Normal file
@@ -0,0 +1,75 @@
|
|||||||
|
#include "main.h"
|
||||||
|
#include "mcp41x.h"
|
||||||
|
|
||||||
|
static uint32_t pot_value[MCP41X_RES_MAX] = {10000, 50000, 100000};
|
||||||
|
|
||||||
|
static void mcp41x_transmit(mcp41x_handle_t *hpot, uint8_t *data)
|
||||||
|
{
|
||||||
|
hpot->hcs->cs_on(hpot->hcs);
|
||||||
|
HAL_SPI_Transmit(hpot->hspi, data, 2, HAL_MAX_DELAY);
|
||||||
|
hpot->hcs->cs_off(hpot->hcs);
|
||||||
|
}
|
||||||
|
|
||||||
|
void mcp41x_init(mcp41x_handle_t *hpot, SPI_HandleTypeDef *hspi, cs_handle_t *hcs, mcp41x_res_t res)
|
||||||
|
{
|
||||||
|
hpot->hspi = hspi;
|
||||||
|
hpot->hcs = hcs;
|
||||||
|
hpot->max_res = res;
|
||||||
|
hpot->dir = MCP41X_ATOB;
|
||||||
|
|
||||||
|
hpot->hcs->cs_off(hcs);
|
||||||
|
}
|
||||||
|
|
||||||
|
void mcp41x_setValue(mcp41x_handle_t *hpot, uint8_t value)
|
||||||
|
{
|
||||||
|
if (hpot->dir == MCP41X_BTOA)
|
||||||
|
{
|
||||||
|
value = 255 - value;
|
||||||
|
}
|
||||||
|
|
||||||
|
hpot->value = value;
|
||||||
|
uint8_t data[2] = {MCP41X_WRITE0, value};
|
||||||
|
mcp41x_transmit(hpot, data);
|
||||||
|
}
|
||||||
|
|
||||||
|
void mcp41x_setVolume(mcp41x_handle_t *hpot, uint8_t volume)
|
||||||
|
{
|
||||||
|
if (volume > 100)
|
||||||
|
{
|
||||||
|
volume = 100;
|
||||||
|
}
|
||||||
|
uint32_t value = volume * 255U / 100U;
|
||||||
|
mcp41x_setValue(hpot, value);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t mcp41x_getVolume(mcp41x_handle_t *hpot)
|
||||||
|
{
|
||||||
|
return hpot->value * 100U / 255U;
|
||||||
|
}
|
||||||
|
|
||||||
|
void mcp41x_setResistance(mcp41x_handle_t *hpot, uint32_t resistance)
|
||||||
|
{
|
||||||
|
if (resistance > pot_value[hpot->max_res])
|
||||||
|
{
|
||||||
|
resistance = pot_value[hpot->max_res];
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t value = resistance * 255U / pot_value[hpot->max_res];
|
||||||
|
mcp41x_setValue(hpot, value);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t mcp41x_getResistance(mcp41x_handle_t *hpot)
|
||||||
|
{
|
||||||
|
return hpot->value * pot_value[hpot->max_res] / 255;
|
||||||
|
}
|
||||||
|
|
||||||
|
void mcp41x_setWiperDir(mcp41x_handle_t *hpot, mcp41x_dir_t dir)
|
||||||
|
{
|
||||||
|
hpot->dir = dir;
|
||||||
|
}
|
||||||
|
|
||||||
|
void mcp41x_sleep(mcp41x_handle_t *hpot)
|
||||||
|
{
|
||||||
|
uint8_t data[2] = {MCP41X_SLEEP, 0};
|
||||||
|
mcp41x_transmit(hpot, data);
|
||||||
|
}
|
||||||
51
firmware/shared_libs/drivers/mcp41x/mcp41x.h
Normal file
51
firmware/shared_libs/drivers/mcp41x/mcp41x.h
Normal file
@@ -0,0 +1,51 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "spi_cs_if.h"
|
||||||
|
|
||||||
|
#define MCP41X_C1 5
|
||||||
|
#define MCP41X_C0 4
|
||||||
|
#define MCP41X_P1 1
|
||||||
|
#define MCP41X_P0 0
|
||||||
|
|
||||||
|
#define MCP41X_SHUTDOWN_BIT (1 << MCP41X_C1)
|
||||||
|
#define MCP41X_WRITE_BIT (1 << MCP41X_C0)
|
||||||
|
#define MCP41X_POT0_BIT (1 << MCP41X_P0)
|
||||||
|
#define MCP41X_POT1_BIT (1 << MCP41X_P1)
|
||||||
|
|
||||||
|
#define MCP41X_SLEEP (MCP41X_SHUTDOWN_BIT | MCP41X_POT0_BIT | MCP41X_POT0_BIT)
|
||||||
|
#define MCP41X_WRITE0 (MCP41X_WRITE_BIT | MCP41X_POT0_BIT)
|
||||||
|
#define MCP41X_WRITE1 (MCP41X_WRITE_BIT | MCP41X_POT1_BIT)
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
MCP41X_ATOB,
|
||||||
|
MCP41X_BTOA
|
||||||
|
} mcp41x_dir_t;
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
MCP41X_10K,
|
||||||
|
MCP41X_50K,
|
||||||
|
MCP41X_100K,
|
||||||
|
MCP41X_RES_MAX
|
||||||
|
} mcp41x_res_t;
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
mcp41x_res_t max_res;
|
||||||
|
mcp41x_dir_t dir;
|
||||||
|
|
||||||
|
uint8_t value;
|
||||||
|
|
||||||
|
SPI_HandleTypeDef *hspi;
|
||||||
|
cs_handle_t *hcs;
|
||||||
|
} mcp41x_handle_t;
|
||||||
|
|
||||||
|
void mcp41x_init(mcp41x_handle_t *hpot, SPI_HandleTypeDef *hspi, cs_handle_t *hcs, mcp41x_res_t res);
|
||||||
|
void mcp41x_setValue(mcp41x_handle_t *hpot, uint8_t value);
|
||||||
|
void mcp41x_setVolume(mcp41x_handle_t *hpot, uint8_t volume);
|
||||||
|
uint8_t mcp41x_getVolume(mcp41x_handle_t *hpot);
|
||||||
|
void mcp41x_setResistance(mcp41x_handle_t *hpot, uint32_t resistance);
|
||||||
|
uint32_t mcp41x_getResistance(mcp41x_handle_t *hpot);
|
||||||
|
void mcp41x_setWiperDir(mcp41x_handle_t *hpot, mcp41x_dir_t dir);
|
||||||
|
void mcp41x_sleep(mcp41x_handle_t *hpot);
|
||||||
24
firmware/shared_libs/drivers/mcu_cs/mcu_cs.c
Normal file
24
firmware/shared_libs/drivers/mcu_cs/mcu_cs.c
Normal file
@@ -0,0 +1,24 @@
|
|||||||
|
#include "mcu_cs.h"
|
||||||
|
|
||||||
|
// static cs_handle_t const _cs_handle = {.cs_on = mcu_cs_on, .cs_off = mcu_cs_off};
|
||||||
|
|
||||||
|
void mcu_cs_init(MCU_cs_t *hcs, GPIO_TypeDef *cs_port, uint16_t cs_pin, uint8_t cs_idle)
|
||||||
|
{
|
||||||
|
hcs->super.cs_on = mcu_cs_on;
|
||||||
|
hcs->super.cs_off = mcu_cs_off;
|
||||||
|
hcs->cs_port = cs_port;
|
||||||
|
hcs->cs_pin = cs_pin;
|
||||||
|
hcs->cs_idle = cs_idle;
|
||||||
|
}
|
||||||
|
|
||||||
|
void mcu_cs_on(cs_handle_t *hcs)
|
||||||
|
{
|
||||||
|
MCU_cs_t *_hcs = (MCU_cs_t *)hcs;
|
||||||
|
HAL_GPIO_WritePin(_hcs->cs_port, _hcs->cs_pin, !_hcs->cs_idle);
|
||||||
|
}
|
||||||
|
|
||||||
|
void mcu_cs_off(cs_handle_t *hcs)
|
||||||
|
{
|
||||||
|
MCU_cs_t *_hcs = (MCU_cs_t *)hcs;
|
||||||
|
HAL_GPIO_WritePin(_hcs->cs_port, _hcs->cs_pin, _hcs->cs_idle);
|
||||||
|
}
|
||||||
16
firmware/shared_libs/drivers/mcu_cs/mcu_cs.h
Normal file
16
firmware/shared_libs/drivers/mcu_cs/mcu_cs.h
Normal file
@@ -0,0 +1,16 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "main.h"
|
||||||
|
#include "spi_cs_if.h"
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
cs_handle_t super;
|
||||||
|
GPIO_TypeDef *cs_port;
|
||||||
|
uint16_t cs_pin;
|
||||||
|
uint8_t cs_idle;
|
||||||
|
} MCU_cs_t;
|
||||||
|
|
||||||
|
void mcu_cs_init(MCU_cs_t *hcs, GPIO_TypeDef *cs_port, uint16_t cs_pin, uint8_t cs_idle);
|
||||||
|
void mcu_cs_on(cs_handle_t *me);
|
||||||
|
void mcu_cs_off(cs_handle_t *me);
|
||||||
87
firmware/shared_libs/drivers/st7565/st7565.c
Normal file
87
firmware/shared_libs/drivers/st7565/st7565.c
Normal file
@@ -0,0 +1,87 @@
|
|||||||
|
#include "main.h"
|
||||||
|
#include "display_gfx.h"
|
||||||
|
#include "st7565.h"
|
||||||
|
// #include "spi.h"
|
||||||
|
#include "string.h"
|
||||||
|
|
||||||
|
static uint8_t st7565_buffor[ST7565_BUFFER_SIZE];
|
||||||
|
|
||||||
|
static void ST7565_SendCommand(st7565_handle_t *hdisp, uint8_t data)
|
||||||
|
{
|
||||||
|
HAL_GPIO_WritePin(hdisp->a0_port, hdisp->a0_pin, GPIO_PIN_RESET);
|
||||||
|
|
||||||
|
HAL_SPI_Transmit(hdisp->hspi, &data, 1, HAL_MAX_DELAY);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void ST7565_SendData(st7565_handle_t *hdisp, uint8_t *data, uint16_t size)
|
||||||
|
{
|
||||||
|
HAL_GPIO_WritePin(hdisp->a0_port, hdisp->a0_pin, GPIO_PIN_SET);
|
||||||
|
|
||||||
|
HAL_SPI_Transmit(hdisp->hspi, data, size, HAL_MAX_DELAY);
|
||||||
|
}
|
||||||
|
|
||||||
|
void ST7565_Init(st7565_handle_t *hdisp, GFX_display_t *disp)
|
||||||
|
{
|
||||||
|
if (hdisp == NULL || hdisp->hspi == NULL || hdisp->a0_port == NULL || hdisp->cs_port == NULL || hdisp->rst_port == NULL)
|
||||||
|
{
|
||||||
|
Error_Handler();
|
||||||
|
}
|
||||||
|
|
||||||
|
disp->width = ST7565_WIDTH;
|
||||||
|
disp->height = ST7565_HEIGHT;
|
||||||
|
disp->buffor = st7565_buffor;
|
||||||
|
// toggle RST low to reset; CS low so it'll listen to us
|
||||||
|
HAL_GPIO_WritePin(hdisp->cs_port, hdisp->cs_pin, GPIO_PIN_RESET);
|
||||||
|
|
||||||
|
HAL_GPIO_WritePin(hdisp->rst_port, hdisp->rst_pin, GPIO_PIN_RESET);
|
||||||
|
HAL_Delay(500);
|
||||||
|
HAL_GPIO_WritePin(hdisp->rst_port, hdisp->rst_pin, GPIO_PIN_SET);
|
||||||
|
|
||||||
|
// LCD bias select
|
||||||
|
ST7565_SendCommand(hdisp, CMD_SET_BIAS_7);
|
||||||
|
// ADC select
|
||||||
|
ST7565_SendCommand(hdisp, CMD_SET_ADC_REVERSE);
|
||||||
|
// SHL select
|
||||||
|
ST7565_SendCommand(hdisp, CMD_SET_COM_NORMAL);
|
||||||
|
// Initial display line
|
||||||
|
ST7565_SendCommand(hdisp, CMD_SET_DISP_START_LINE);
|
||||||
|
|
||||||
|
// turn on voltage converter (VC=1, VR=0, VF=0)
|
||||||
|
ST7565_SendCommand(hdisp, CMD_SET_POWER_CONTROL | 0x4);
|
||||||
|
// wait for 50% rising
|
||||||
|
HAL_Delay(50);
|
||||||
|
|
||||||
|
// turn on voltage regulator (VC=1, VR=1, VF=0)
|
||||||
|
ST7565_SendCommand(hdisp, CMD_SET_POWER_CONTROL | 0x6);
|
||||||
|
// wait >=50ms
|
||||||
|
HAL_Delay(50);
|
||||||
|
|
||||||
|
// turn on voltage follower (VC=1, VR=1, VF=1)
|
||||||
|
ST7565_SendCommand(hdisp, CMD_SET_POWER_CONTROL | 0x7);
|
||||||
|
// wait
|
||||||
|
HAL_Delay(10);
|
||||||
|
|
||||||
|
// set lcd operating voltage (regulator resistor, ref voltage resistor)
|
||||||
|
ST7565_SendCommand(hdisp, CMD_SET_RESISTOR_RATIO | 0x6);
|
||||||
|
|
||||||
|
ST7565_SendCommand(hdisp, CMD_DISPLAY_ON);
|
||||||
|
ST7565_SendCommand(hdisp, CMD_SET_ALLPTS_NORMAL);
|
||||||
|
ST7565_SendCommand(hdisp, CMD_SET_VOLUME_FIRST);
|
||||||
|
ST7565_SendCommand(hdisp, CMD_SET_VOLUME_SECOND | (0x00 & 0x3f));
|
||||||
|
|
||||||
|
HAL_GPIO_WritePin(hdisp->cs_port, hdisp->cs_pin, GPIO_PIN_SET);
|
||||||
|
}
|
||||||
|
|
||||||
|
void ST7565_DisplayAll(st7565_handle_t *hdisp)
|
||||||
|
{
|
||||||
|
HAL_GPIO_WritePin(hdisp->cs_port, hdisp->cs_pin, GPIO_PIN_RESET);
|
||||||
|
for (uint8_t p = 0; p < 8; p++)
|
||||||
|
{
|
||||||
|
ST7565_SendCommand(hdisp, CMD_SET_PAGE | p);
|
||||||
|
ST7565_SendCommand(hdisp, CMD_SET_COLUMN_UPPER | 0);
|
||||||
|
ST7565_SendCommand(hdisp, CMD_SET_COLUMN_LOWER | 0);
|
||||||
|
|
||||||
|
ST7565_SendData(hdisp, &st7565_buffor[128 * p], 128);
|
||||||
|
}
|
||||||
|
HAL_GPIO_WritePin(hdisp->cs_port, hdisp->cs_pin, GPIO_PIN_SET);
|
||||||
|
}
|
||||||
58
firmware/shared_libs/drivers/st7565/st7565.h
Normal file
58
firmware/shared_libs/drivers/st7565/st7565.h
Normal file
@@ -0,0 +1,58 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#define ST7565_WIDTH 128
|
||||||
|
#define ST7565_HEIGHT 64
|
||||||
|
#define ST7565_BUFFER_SIZE ST7565_WIDTH *ST7565_HEIGHT / 8
|
||||||
|
|
||||||
|
#define CMD_DISPLAY_OFF 0xAE
|
||||||
|
#define CMD_DISPLAY_ON 0xAF
|
||||||
|
|
||||||
|
#define CMD_SET_DISP_START_LINE 0x40
|
||||||
|
#define CMD_SET_PAGE 0xB0
|
||||||
|
|
||||||
|
#define CMD_SET_COLUMN_UPPER 0x10
|
||||||
|
#define CMD_SET_COLUMN_LOWER 0x00
|
||||||
|
|
||||||
|
#define CMD_SET_ADC_NORMAL 0xA0
|
||||||
|
#define CMD_SET_ADC_REVERSE 0xA1
|
||||||
|
|
||||||
|
#define CMD_SET_DISP_NORMAL 0xA6
|
||||||
|
#define CMD_SET_DISP_REVERSE 0xA7
|
||||||
|
|
||||||
|
#define CMD_SET_ALLPTS_NORMAL 0xA4
|
||||||
|
#define CMD_SET_ALLPTS_ON 0xA5
|
||||||
|
#define CMD_SET_BIAS_9 0xA2
|
||||||
|
#define CMD_SET_BIAS_7 0xA3
|
||||||
|
|
||||||
|
#define CMD_RMW 0xE0
|
||||||
|
#define CMD_RMW_CLEAR 0xEE
|
||||||
|
#define CMD_INTERNAL_RESET 0xE2
|
||||||
|
#define CMD_SET_COM_NORMAL 0xC0
|
||||||
|
#define CMD_SET_COM_REVERSE 0xC8
|
||||||
|
#define CMD_SET_POWER_CONTROL 0x28
|
||||||
|
#define CMD_SET_RESISTOR_RATIO 0x20
|
||||||
|
#define CMD_SET_VOLUME_FIRST 0x81
|
||||||
|
#define CMD_SET_VOLUME_SECOND 0
|
||||||
|
#define CMD_SET_STATIC_OFF 0xAC
|
||||||
|
#define CMD_SET_STATIC_ON 0xAD
|
||||||
|
#define CMD_SET_STATIC_REG 0x0
|
||||||
|
#define CMD_SET_BOOSTER_FIRST 0xF8
|
||||||
|
#define CMD_SET_BOOSTER_234 0
|
||||||
|
#define CMD_SET_BOOSTER_5 1
|
||||||
|
#define CMD_SET_BOOSTER_6 3
|
||||||
|
#define CMD_NOP 0xE3
|
||||||
|
#define CMD_TEST 0xF0
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
SPI_HandleTypeDef *hspi;
|
||||||
|
GPIO_TypeDef *cs_port; // ST7565_CS_GPIO_Port
|
||||||
|
GPIO_TypeDef *a0_port; // ST7565_A0_GPIO_Port
|
||||||
|
GPIO_TypeDef *rst_port; // ST7565_RST_GPIO_Port
|
||||||
|
uint16_t cs_pin; // ST7565_CS_Pin
|
||||||
|
uint16_t a0_pin; // ST7565_A0_Pin
|
||||||
|
uint16_t rst_pin; // ST7565_RST_Pin
|
||||||
|
} st7565_handle_t;
|
||||||
|
|
||||||
|
void ST7565_Init(st7565_handle_t *hdisp, GFX_display_t *disp);
|
||||||
|
void ST7565_DisplayAll(st7565_handle_t *hdisp);
|
||||||
1043
firmware/shared_libs/utils/printf/printf.c
Normal file
1043
firmware/shared_libs/utils/printf/printf.c
Normal file
File diff suppressed because it is too large
Load Diff
109
firmware/shared_libs/utils/printf/printf.h
Normal file
109
firmware/shared_libs/utils/printf/printf.h
Normal file
@@ -0,0 +1,109 @@
|
|||||||
|
///////////////////////////////////////////////////////////////////////////////
|
||||||
|
// \author (c) Marco Paland (info@paland.com)
|
||||||
|
// 2014-2019, PALANDesign Hannover, Germany
|
||||||
|
//
|
||||||
|
// \license The MIT License (MIT)
|
||||||
|
//
|
||||||
|
// 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.
|
||||||
|
//
|
||||||
|
// \brief Tiny printf, sprintf and snprintf implementation, optimized for speed on
|
||||||
|
// embedded systems with a very limited resources.
|
||||||
|
// Use this instead of bloated standard/newlib printf.
|
||||||
|
// These routines are thread safe and reentrant.
|
||||||
|
//
|
||||||
|
///////////////////////////////////////////////////////////////////////////////
|
||||||
|
|
||||||
|
#ifndef _PRINTF_H_
|
||||||
|
#define _PRINTF_H_
|
||||||
|
|
||||||
|
#include <stdarg.h>
|
||||||
|
#include <stddef.h>
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C"
|
||||||
|
{
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Output a character to a custom device like UART, used by the printf() function
|
||||||
|
* This function is declared here only. You have to write your custom implementation somewhere
|
||||||
|
* \param character Character to output
|
||||||
|
*/
|
||||||
|
void _putchar(char character);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Tiny printf implementation
|
||||||
|
* You have to implement _putchar if you use printf()
|
||||||
|
* To avoid conflicts with the regular printf() API it is overridden by macro defines
|
||||||
|
* and internal underscore-appended functions like printf_() are used
|
||||||
|
* \param format A string that specifies the format of the output
|
||||||
|
* \return The number of characters that are written into the array, not counting the terminating null character
|
||||||
|
*/
|
||||||
|
#define printf printf_
|
||||||
|
int printf_(const char *format, ...);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Tiny sprintf implementation
|
||||||
|
* Due to security reasons (buffer overflow) YOU SHOULD CONSIDER USING (V)SNPRINTF INSTEAD!
|
||||||
|
* \param buffer A pointer to the buffer where to store the formatted string. MUST be big enough to store the output!
|
||||||
|
* \param format A string that specifies the format of the output
|
||||||
|
* \return The number of characters that are WRITTEN into the buffer, not counting the terminating null character
|
||||||
|
*/
|
||||||
|
#define sprintf sprintf_
|
||||||
|
int sprintf_(char *buffer, const char *format, ...);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Tiny snprintf/vsnprintf implementation
|
||||||
|
* \param buffer A pointer to the buffer where to store the formatted string
|
||||||
|
* \param count The maximum number of characters to store in the buffer, including a terminating null character
|
||||||
|
* \param format A string that specifies the format of the output
|
||||||
|
* \param va A value identifying a variable arguments list
|
||||||
|
* \return The number of characters that COULD have been written into the buffer, not counting the terminating
|
||||||
|
* null character. A value equal or larger than count indicates truncation. Only when the returned value
|
||||||
|
* is non-negative and less than count, the string has been completely written.
|
||||||
|
*/
|
||||||
|
#define snprintf snprintf_
|
||||||
|
#define vsnprintf vsnprintf_
|
||||||
|
int snprintf_(char *buffer, size_t count, const char *format, ...);
|
||||||
|
int vsnprintf_(char *buffer, size_t count, const char *format, va_list va);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Tiny vprintf implementation
|
||||||
|
* \param format A string that specifies the format of the output
|
||||||
|
* \param va A value identifying a variable arguments list
|
||||||
|
* \return The number of characters that are WRITTEN into the buffer, not counting the terminating null character
|
||||||
|
*/
|
||||||
|
#define vprintf vprintf_
|
||||||
|
int vprintf_(const char *format, va_list va);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* printf with output function
|
||||||
|
* You may use this as dynamic alternative to printf() with its fixed _putchar() output
|
||||||
|
* \param out An output function which takes one character and an argument pointer
|
||||||
|
* \param arg An argument pointer for user data passed to output function
|
||||||
|
* \param format A string that specifies the format of the output
|
||||||
|
* \return The number of characters that are sent to the output function, not counting the terminating null character
|
||||||
|
*/
|
||||||
|
int fctprintf(void (*out)(char character, void *arg), void *arg, const char *format, ...);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif // _PRINTF_H_
|
||||||
2103
firmware/shared_libs/utils/rtt/SEGGER_RTT.c
Normal file
2103
firmware/shared_libs/utils/rtt/SEGGER_RTT.c
Normal file
File diff suppressed because it is too large
Load Diff
529
firmware/shared_libs/utils/rtt/SEGGER_RTT.h
Normal file
529
firmware/shared_libs/utils/rtt/SEGGER_RTT.h
Normal file
@@ -0,0 +1,529 @@
|
|||||||
|
/*********************************************************************
|
||||||
|
* SEGGER Microcontroller GmbH *
|
||||||
|
* The Embedded Experts *
|
||||||
|
**********************************************************************
|
||||||
|
* *
|
||||||
|
* (c) 1995 - 2021 SEGGER Microcontroller GmbH *
|
||||||
|
* *
|
||||||
|
* www.segger.com Support: support@segger.com *
|
||||||
|
* *
|
||||||
|
**********************************************************************
|
||||||
|
* *
|
||||||
|
* SEGGER RTT * Real Time Transfer for embedded targets *
|
||||||
|
* *
|
||||||
|
**********************************************************************
|
||||||
|
* *
|
||||||
|
* All rights reserved. *
|
||||||
|
* *
|
||||||
|
* SEGGER strongly recommends to not make any changes *
|
||||||
|
* to or modify the source code of this software in order to stay *
|
||||||
|
* compatible with the RTT protocol and J-Link. *
|
||||||
|
* *
|
||||||
|
* Redistribution and use in source and binary forms, with or *
|
||||||
|
* without modification, are permitted provided that the following *
|
||||||
|
* condition is met: *
|
||||||
|
* *
|
||||||
|
* o Redistributions of source code must retain the above copyright *
|
||||||
|
* notice, this condition and the following disclaimer. *
|
||||||
|
* *
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND *
|
||||||
|
* CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, *
|
||||||
|
* INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF *
|
||||||
|
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE *
|
||||||
|
* DISCLAIMED. IN NO EVENT SHALL SEGGER Microcontroller BE LIABLE FOR *
|
||||||
|
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR *
|
||||||
|
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT *
|
||||||
|
* OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; *
|
||||||
|
* OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF *
|
||||||
|
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT *
|
||||||
|
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE *
|
||||||
|
* USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH *
|
||||||
|
* DAMAGE. *
|
||||||
|
* *
|
||||||
|
**********************************************************************
|
||||||
|
* *
|
||||||
|
* RTT version: 7.80a *
|
||||||
|
* *
|
||||||
|
**********************************************************************
|
||||||
|
|
||||||
|
---------------------------END-OF-HEADER------------------------------
|
||||||
|
File : SEGGER_RTT.h
|
||||||
|
Purpose : Implementation of SEGGER real-time transfer which allows
|
||||||
|
real-time communication on targets which support debugger
|
||||||
|
memory accesses while the CPU is running.
|
||||||
|
Revision: $Rev: 25842 $
|
||||||
|
----------------------------------------------------------------------
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef SEGGER_RTT_H
|
||||||
|
#define SEGGER_RTT_H
|
||||||
|
|
||||||
|
#include "SEGGER_RTT_Conf.h"
|
||||||
|
|
||||||
|
/*********************************************************************
|
||||||
|
*
|
||||||
|
* Defines, defaults
|
||||||
|
*
|
||||||
|
**********************************************************************
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef RTT_USE_ASM
|
||||||
|
//
|
||||||
|
// Some cores support out-of-order memory accesses (reordering of memory accesses in the core)
|
||||||
|
// For such cores, we need to define a memory barrier to guarantee the order of certain accesses to the RTT ring buffers.
|
||||||
|
// Needed for:
|
||||||
|
// Cortex-M7 (ARMv7-M)
|
||||||
|
// Cortex-M23 (ARM-v8M)
|
||||||
|
// Cortex-M33 (ARM-v8M)
|
||||||
|
// Cortex-A/R (ARM-v7A/R)
|
||||||
|
//
|
||||||
|
// We do not explicitly check for "Embedded Studio" as the compiler in use determines what we support.
|
||||||
|
// You can use an external toolchain like IAR inside ES. So there is no point in checking for "Embedded Studio"
|
||||||
|
//
|
||||||
|
#if (defined __CROSSWORKS_ARM) // Rowley Crossworks
|
||||||
|
#define _CC_HAS_RTT_ASM_SUPPORT 1
|
||||||
|
#if (defined __ARM_ARCH_7M__) // Cortex-M3
|
||||||
|
#define _CORE_HAS_RTT_ASM_SUPPORT 1
|
||||||
|
#elif (defined __ARM_ARCH_7EM__) // Cortex-M4/M7
|
||||||
|
#define _CORE_HAS_RTT_ASM_SUPPORT 1
|
||||||
|
#define _CORE_NEEDS_DMB 1
|
||||||
|
#define RTT__DMB() __asm volatile("dmb\n" \
|
||||||
|
: \
|
||||||
|
: \
|
||||||
|
:);
|
||||||
|
#elif (defined __ARM_ARCH_8M_BASE__) // Cortex-M23
|
||||||
|
#define _CORE_HAS_RTT_ASM_SUPPORT 0
|
||||||
|
#define _CORE_NEEDS_DMB 1
|
||||||
|
#define RTT__DMB() __asm volatile("dmb\n" \
|
||||||
|
: \
|
||||||
|
: \
|
||||||
|
:);
|
||||||
|
#elif (defined __ARM_ARCH_8M_MAIN__) // Cortex-M33
|
||||||
|
#define _CORE_HAS_RTT_ASM_SUPPORT 1
|
||||||
|
#define _CORE_NEEDS_DMB 1
|
||||||
|
#define RTT__DMB() __asm volatile("dmb\n" \
|
||||||
|
: \
|
||||||
|
: \
|
||||||
|
:);
|
||||||
|
#else
|
||||||
|
#define _CORE_HAS_RTT_ASM_SUPPORT 0
|
||||||
|
#endif
|
||||||
|
#elif (defined __ARMCC_VERSION)
|
||||||
|
//
|
||||||
|
// ARM compiler
|
||||||
|
// ARM compiler V6.0 and later is clang based.
|
||||||
|
// Our ASM part is compatible to clang.
|
||||||
|
//
|
||||||
|
#if (__ARMCC_VERSION >= 6000000)
|
||||||
|
#define _CC_HAS_RTT_ASM_SUPPORT 1
|
||||||
|
#else
|
||||||
|
#define _CC_HAS_RTT_ASM_SUPPORT 0
|
||||||
|
#endif
|
||||||
|
#if (defined __ARM_ARCH_6M__) // Cortex-M0 / M1
|
||||||
|
#define _CORE_HAS_RTT_ASM_SUPPORT 0 // No ASM support for this architecture
|
||||||
|
#elif (defined __ARM_ARCH_7M__) // Cortex-M3
|
||||||
|
#define _CORE_HAS_RTT_ASM_SUPPORT 1
|
||||||
|
#elif (defined __ARM_ARCH_7EM__) // Cortex-M4/M7
|
||||||
|
#define _CORE_HAS_RTT_ASM_SUPPORT 1
|
||||||
|
#define _CORE_NEEDS_DMB 1
|
||||||
|
#define RTT__DMB() __asm volatile("dmb\n" \
|
||||||
|
: \
|
||||||
|
: \
|
||||||
|
:);
|
||||||
|
#elif (defined __ARM_ARCH_8M_BASE__) // Cortex-M23
|
||||||
|
#define _CORE_HAS_RTT_ASM_SUPPORT 0
|
||||||
|
#define _CORE_NEEDS_DMB 1
|
||||||
|
#define RTT__DMB() __asm volatile("dmb\n" \
|
||||||
|
: \
|
||||||
|
: \
|
||||||
|
:);
|
||||||
|
#elif (defined __ARM_ARCH_8M_MAIN__) // Cortex-M33
|
||||||
|
#define _CORE_HAS_RTT_ASM_SUPPORT 1
|
||||||
|
#define _CORE_NEEDS_DMB 1
|
||||||
|
#define RTT__DMB() __asm volatile("dmb\n" \
|
||||||
|
: \
|
||||||
|
: \
|
||||||
|
:);
|
||||||
|
#elif ((defined __ARM_ARCH_7A__) || (defined __ARM_ARCH_7R__)) // Cortex-A/R 32-bit ARMv7-A/R
|
||||||
|
#define _CORE_NEEDS_DMB 1
|
||||||
|
#define RTT__DMB() __asm volatile("dmb\n" \
|
||||||
|
: \
|
||||||
|
: \
|
||||||
|
:);
|
||||||
|
#else
|
||||||
|
#define _CORE_HAS_RTT_ASM_SUPPORT 0
|
||||||
|
#endif
|
||||||
|
#elif ((defined __GNUC__) || (defined __clang__))
|
||||||
|
//
|
||||||
|
// GCC / Clang
|
||||||
|
//
|
||||||
|
#define _CC_HAS_RTT_ASM_SUPPORT 1
|
||||||
|
// ARM 7/9: __ARM_ARCH_5__ / __ARM_ARCH_5E__ / __ARM_ARCH_5T__ / __ARM_ARCH_5T__ / __ARM_ARCH_5TE__
|
||||||
|
#if (defined __ARM_ARCH_7M__) // Cortex-M3
|
||||||
|
#define _CORE_HAS_RTT_ASM_SUPPORT 1
|
||||||
|
#elif (defined __ARM_ARCH_7EM__) // Cortex-M4/M7
|
||||||
|
#define _CORE_HAS_RTT_ASM_SUPPORT 1
|
||||||
|
#define _CORE_NEEDS_DMB 1 // Only Cortex-M7 needs a DMB but we cannot distinguish M4 and M7 here...
|
||||||
|
#define RTT__DMB() __asm volatile("dmb\n" \
|
||||||
|
: \
|
||||||
|
: \
|
||||||
|
:);
|
||||||
|
#elif (defined __ARM_ARCH_8M_BASE__) // Cortex-M23
|
||||||
|
#define _CORE_HAS_RTT_ASM_SUPPORT 0
|
||||||
|
#define _CORE_NEEDS_DMB 1
|
||||||
|
#define RTT__DMB() __asm volatile("dmb\n" \
|
||||||
|
: \
|
||||||
|
: \
|
||||||
|
:);
|
||||||
|
#elif (defined __ARM_ARCH_8M_MAIN__) // Cortex-M33
|
||||||
|
#define _CORE_HAS_RTT_ASM_SUPPORT 1
|
||||||
|
#define _CORE_NEEDS_DMB 1
|
||||||
|
#define RTT__DMB() __asm volatile("dmb\n" \
|
||||||
|
: \
|
||||||
|
: \
|
||||||
|
:);
|
||||||
|
#elif ((defined __ARM_ARCH_7A__) || (defined __ARM_ARCH_7R__)) // Cortex-A/R 32-bit ARMv7-A/R
|
||||||
|
#define _CORE_NEEDS_DMB 1
|
||||||
|
#define RTT__DMB() __asm volatile("dmb\n" \
|
||||||
|
: \
|
||||||
|
: \
|
||||||
|
:);
|
||||||
|
#else
|
||||||
|
#define _CORE_HAS_RTT_ASM_SUPPORT 0
|
||||||
|
#endif
|
||||||
|
#elif ((defined __IASMARM__) || (defined __ICCARM__))
|
||||||
|
//
|
||||||
|
// IAR assembler/compiler
|
||||||
|
//
|
||||||
|
#define _CC_HAS_RTT_ASM_SUPPORT 1
|
||||||
|
#if (__VER__ < 6300000)
|
||||||
|
#define VOLATILE
|
||||||
|
#else
|
||||||
|
#define VOLATILE volatile
|
||||||
|
#endif
|
||||||
|
#if (defined __ARM7M__) // Needed for old versions that do not know the define yet
|
||||||
|
#if (__CORE__ == __ARM7M__) // Cortex-M3
|
||||||
|
#define _CORE_HAS_RTT_ASM_SUPPORT 1
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#if (defined __ARM7EM__)
|
||||||
|
#if (__CORE__ == __ARM7EM__) // Cortex-M4/M7
|
||||||
|
#define _CORE_HAS_RTT_ASM_SUPPORT 1
|
||||||
|
#define _CORE_NEEDS_DMB 1
|
||||||
|
#define RTT__DMB() asm VOLATILE("DMB");
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#if (defined __ARM8M_BASELINE__)
|
||||||
|
#if (__CORE__ == __ARM8M_BASELINE__) // Cortex-M23
|
||||||
|
#define _CORE_HAS_RTT_ASM_SUPPORT 0
|
||||||
|
#define _CORE_NEEDS_DMB 1
|
||||||
|
#define RTT__DMB() asm VOLATILE("DMB");
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#if (defined __ARM8M_MAINLINE__)
|
||||||
|
#if (__CORE__ == __ARM8M_MAINLINE__) // Cortex-M33
|
||||||
|
#define _CORE_HAS_RTT_ASM_SUPPORT 1
|
||||||
|
#define _CORE_NEEDS_DMB 1
|
||||||
|
#define RTT__DMB() asm VOLATILE("DMB");
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#if (defined __ARM8EM_MAINLINE__)
|
||||||
|
#if (__CORE__ == __ARM8EM_MAINLINE__) // Cortex-???
|
||||||
|
#define _CORE_HAS_RTT_ASM_SUPPORT 1
|
||||||
|
#define _CORE_NEEDS_DMB 1
|
||||||
|
#define RTT__DMB() asm VOLATILE("DMB");
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#if (defined __ARM7A__)
|
||||||
|
#if (__CORE__ == __ARM7A__) // Cortex-A 32-bit ARMv7-A
|
||||||
|
#define _CORE_NEEDS_DMB 1
|
||||||
|
#define RTT__DMB() asm VOLATILE("DMB");
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#if (defined __ARM7R__)
|
||||||
|
#if (__CORE__ == __ARM7R__) // Cortex-R 32-bit ARMv7-R
|
||||||
|
#define _CORE_NEEDS_DMB 1
|
||||||
|
#define RTT__DMB() asm VOLATILE("DMB");
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
// TBD: __ARM8A__ => Cortex-A 64-bit ARMv8-A
|
||||||
|
// TBD: __ARM8R__ => Cortex-R 64-bit ARMv8-R
|
||||||
|
#else
|
||||||
|
//
|
||||||
|
// Other compilers
|
||||||
|
//
|
||||||
|
#define _CC_HAS_RTT_ASM_SUPPORT 0
|
||||||
|
#define _CORE_HAS_RTT_ASM_SUPPORT 0
|
||||||
|
#endif
|
||||||
|
//
|
||||||
|
// If IDE and core support the ASM version, enable ASM version by default
|
||||||
|
//
|
||||||
|
#ifndef _CORE_HAS_RTT_ASM_SUPPORT
|
||||||
|
#define _CORE_HAS_RTT_ASM_SUPPORT 0 // Default for unknown cores
|
||||||
|
#endif
|
||||||
|
#if (_CC_HAS_RTT_ASM_SUPPORT && _CORE_HAS_RTT_ASM_SUPPORT)
|
||||||
|
#define RTT_USE_ASM (1)
|
||||||
|
#else
|
||||||
|
#define RTT_USE_ASM (0)
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef _CORE_NEEDS_DMB
|
||||||
|
#define _CORE_NEEDS_DMB 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef RTT__DMB
|
||||||
|
#if _CORE_NEEDS_DMB
|
||||||
|
#error "Don't know how to place inline assembly for DMB"
|
||||||
|
#else
|
||||||
|
#define RTT__DMB()
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef SEGGER_RTT_CPU_CACHE_LINE_SIZE
|
||||||
|
#define SEGGER_RTT_CPU_CACHE_LINE_SIZE (0) // On most target systems where RTT is used, we do not have a CPU cache, therefore 0 is a good default here
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef SEGGER_RTT_UNCACHED_OFF
|
||||||
|
#if SEGGER_RTT_CPU_CACHE_LINE_SIZE
|
||||||
|
#error "SEGGER_RTT_UNCACHED_OFF must be defined when setting SEGGER_RTT_CPU_CACHE_LINE_SIZE != 0"
|
||||||
|
#else
|
||||||
|
#define SEGGER_RTT_UNCACHED_OFF (0)
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#if RTT_USE_ASM
|
||||||
|
#if SEGGER_RTT_CPU_CACHE_LINE_SIZE
|
||||||
|
#error "RTT_USE_ASM is not available if SEGGER_RTT_CPU_CACHE_LINE_SIZE != 0"
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef SEGGER_RTT_ASM // defined when SEGGER_RTT.h is included from assembly file
|
||||||
|
#include <stdlib.h>
|
||||||
|
#include <stdarg.h>
|
||||||
|
|
||||||
|
/*********************************************************************
|
||||||
|
*
|
||||||
|
* Defines, fixed
|
||||||
|
*
|
||||||
|
**********************************************************************
|
||||||
|
*/
|
||||||
|
|
||||||
|
//
|
||||||
|
// Determine how much we must pad the control block to make it a multiple of a cache line in size
|
||||||
|
// Assuming: U8 = 1B
|
||||||
|
// U16 = 2B
|
||||||
|
// U32 = 4B
|
||||||
|
// U8/U16/U32* = 4B
|
||||||
|
//
|
||||||
|
#if SEGGER_RTT_CPU_CACHE_LINE_SIZE // Avoid division by zero in case we do not have any cache
|
||||||
|
#define SEGGER_RTT__ROUND_UP_2_CACHE_LINE_SIZE(NumBytes) (((NumBytes + SEGGER_RTT_CPU_CACHE_LINE_SIZE - 1) / SEGGER_RTT_CPU_CACHE_LINE_SIZE) * SEGGER_RTT_CPU_CACHE_LINE_SIZE)
|
||||||
|
#else
|
||||||
|
#define SEGGER_RTT__ROUND_UP_2_CACHE_LINE_SIZE(NumBytes) (NumBytes)
|
||||||
|
#endif
|
||||||
|
#define SEGGER_RTT__CB_SIZE (16 + 4 + 4 + (SEGGER_RTT_MAX_NUM_UP_BUFFERS * 24) + (SEGGER_RTT_MAX_NUM_DOWN_BUFFERS * 24))
|
||||||
|
#define SEGGER_RTT__CB_PADDING (SEGGER_RTT__ROUND_UP_2_CACHE_LINE_SIZE(SEGGER_RTT__CB_SIZE) - SEGGER_RTT__CB_SIZE)
|
||||||
|
|
||||||
|
/*********************************************************************
|
||||||
|
*
|
||||||
|
* Types
|
||||||
|
*
|
||||||
|
**********************************************************************
|
||||||
|
*/
|
||||||
|
|
||||||
|
//
|
||||||
|
// Description for a circular buffer (also called "ring buffer")
|
||||||
|
// which is used as up-buffer (T->H)
|
||||||
|
//
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
const char *sName; // Optional name. Standard names so far are: "Terminal", "SysView", "J-Scope_t4i4"
|
||||||
|
char *pBuffer; // Pointer to start of buffer
|
||||||
|
unsigned SizeOfBuffer; // Buffer size in bytes. Note that one byte is lost, as this implementation does not fill up the buffer in order to avoid the problem of being unable to distinguish between full and empty.
|
||||||
|
unsigned WrOff; // Position of next item to be written by either target.
|
||||||
|
volatile unsigned RdOff; // Position of next item to be read by host. Must be volatile since it may be modified by host.
|
||||||
|
unsigned Flags; // Contains configuration flags. Flags[31:24] are used for validity check and must be zero. Flags[23:2] are reserved for future use. Flags[1:0] = RTT operating mode.
|
||||||
|
} SEGGER_RTT_BUFFER_UP;
|
||||||
|
|
||||||
|
//
|
||||||
|
// Description for a circular buffer (also called "ring buffer")
|
||||||
|
// which is used as down-buffer (H->T)
|
||||||
|
//
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
const char *sName; // Optional name. Standard names so far are: "Terminal", "SysView", "J-Scope_t4i4"
|
||||||
|
char *pBuffer; // Pointer to start of buffer
|
||||||
|
unsigned SizeOfBuffer; // Buffer size in bytes. Note that one byte is lost, as this implementation does not fill up the buffer in order to avoid the problem of being unable to distinguish between full and empty.
|
||||||
|
volatile unsigned WrOff; // Position of next item to be written by host. Must be volatile since it may be modified by host.
|
||||||
|
unsigned RdOff; // Position of next item to be read by target (down-buffer).
|
||||||
|
unsigned Flags; // Contains configuration flags. Flags[31:24] are used for validity check and must be zero. Flags[23:2] are reserved for future use. Flags[1:0] = RTT operating mode.
|
||||||
|
} SEGGER_RTT_BUFFER_DOWN;
|
||||||
|
|
||||||
|
//
|
||||||
|
// RTT control block which describes the number of buffers available
|
||||||
|
// as well as the configuration for each buffer
|
||||||
|
//
|
||||||
|
//
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
char acID[16]; // Initialized to "SEGGER RTT"
|
||||||
|
int MaxNumUpBuffers; // Initialized to SEGGER_RTT_MAX_NUM_UP_BUFFERS (type. 2)
|
||||||
|
int MaxNumDownBuffers; // Initialized to SEGGER_RTT_MAX_NUM_DOWN_BUFFERS (type. 2)
|
||||||
|
SEGGER_RTT_BUFFER_UP aUp[SEGGER_RTT_MAX_NUM_UP_BUFFERS]; // Up buffers, transferring information up from target via debug probe to host
|
||||||
|
SEGGER_RTT_BUFFER_DOWN aDown[SEGGER_RTT_MAX_NUM_DOWN_BUFFERS]; // Down buffers, transferring information down from host via debug probe to target
|
||||||
|
#if SEGGER_RTT__CB_PADDING
|
||||||
|
unsigned char aDummy[SEGGER_RTT__CB_PADDING];
|
||||||
|
#endif
|
||||||
|
} SEGGER_RTT_CB;
|
||||||
|
|
||||||
|
/*********************************************************************
|
||||||
|
*
|
||||||
|
* Global data
|
||||||
|
*
|
||||||
|
**********************************************************************
|
||||||
|
*/
|
||||||
|
extern SEGGER_RTT_CB _SEGGER_RTT;
|
||||||
|
|
||||||
|
/*********************************************************************
|
||||||
|
*
|
||||||
|
* RTT API functions
|
||||||
|
*
|
||||||
|
**********************************************************************
|
||||||
|
*/
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C"
|
||||||
|
{
|
||||||
|
#endif
|
||||||
|
int SEGGER_RTT_AllocDownBuffer(const char *sName, void *pBuffer, unsigned BufferSize, unsigned Flags);
|
||||||
|
int SEGGER_RTT_AllocUpBuffer(const char *sName, void *pBuffer, unsigned BufferSize, unsigned Flags);
|
||||||
|
int SEGGER_RTT_ConfigUpBuffer(unsigned BufferIndex, const char *sName, void *pBuffer, unsigned BufferSize, unsigned Flags);
|
||||||
|
int SEGGER_RTT_ConfigDownBuffer(unsigned BufferIndex, const char *sName, void *pBuffer, unsigned BufferSize, unsigned Flags);
|
||||||
|
int SEGGER_RTT_GetKey(void);
|
||||||
|
unsigned SEGGER_RTT_HasData(unsigned BufferIndex);
|
||||||
|
int SEGGER_RTT_HasKey(void);
|
||||||
|
unsigned SEGGER_RTT_HasDataUp(unsigned BufferIndex);
|
||||||
|
void SEGGER_RTT_Init(void);
|
||||||
|
unsigned SEGGER_RTT_Read(unsigned BufferIndex, void *pBuffer, unsigned BufferSize);
|
||||||
|
unsigned SEGGER_RTT_ReadNoLock(unsigned BufferIndex, void *pData, unsigned BufferSize);
|
||||||
|
int SEGGER_RTT_SetNameDownBuffer(unsigned BufferIndex, const char *sName);
|
||||||
|
int SEGGER_RTT_SetNameUpBuffer(unsigned BufferIndex, const char *sName);
|
||||||
|
int SEGGER_RTT_SetFlagsDownBuffer(unsigned BufferIndex, unsigned Flags);
|
||||||
|
int SEGGER_RTT_SetFlagsUpBuffer(unsigned BufferIndex, unsigned Flags);
|
||||||
|
int SEGGER_RTT_WaitKey(void);
|
||||||
|
unsigned SEGGER_RTT_Write(unsigned BufferIndex, const void *pBuffer, unsigned NumBytes);
|
||||||
|
unsigned SEGGER_RTT_WriteNoLock(unsigned BufferIndex, const void *pBuffer, unsigned NumBytes);
|
||||||
|
unsigned SEGGER_RTT_WriteSkipNoLock(unsigned BufferIndex, const void *pBuffer, unsigned NumBytes);
|
||||||
|
unsigned SEGGER_RTT_ASM_WriteSkipNoLock(unsigned BufferIndex, const void *pBuffer, unsigned NumBytes);
|
||||||
|
unsigned SEGGER_RTT_WriteString(unsigned BufferIndex, const char *s);
|
||||||
|
void SEGGER_RTT_WriteWithOverwriteNoLock(unsigned BufferIndex, const void *pBuffer, unsigned NumBytes);
|
||||||
|
unsigned SEGGER_RTT_PutChar(unsigned BufferIndex, char c);
|
||||||
|
unsigned SEGGER_RTT_PutCharSkip(unsigned BufferIndex, char c);
|
||||||
|
unsigned SEGGER_RTT_PutCharSkipNoLock(unsigned BufferIndex, char c);
|
||||||
|
unsigned SEGGER_RTT_GetAvailWriteSpace(unsigned BufferIndex);
|
||||||
|
unsigned SEGGER_RTT_GetBytesInBuffer(unsigned BufferIndex);
|
||||||
|
//
|
||||||
|
// Function macro for performance optimization
|
||||||
|
//
|
||||||
|
#define SEGGER_RTT_HASDATA(n) (((SEGGER_RTT_BUFFER_DOWN *)((char *)&_SEGGER_RTT.aDown[n] + SEGGER_RTT_UNCACHED_OFF))->WrOff - ((SEGGER_RTT_BUFFER_DOWN *)((char *)&_SEGGER_RTT.aDown[n] + SEGGER_RTT_UNCACHED_OFF))->RdOff)
|
||||||
|
|
||||||
|
#if RTT_USE_ASM
|
||||||
|
#define SEGGER_RTT_WriteSkipNoLock SEGGER_RTT_ASM_WriteSkipNoLock
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/*********************************************************************
|
||||||
|
*
|
||||||
|
* RTT transfer functions to send RTT data via other channels.
|
||||||
|
*
|
||||||
|
**********************************************************************
|
||||||
|
*/
|
||||||
|
unsigned SEGGER_RTT_ReadUpBuffer(unsigned BufferIndex, void *pBuffer, unsigned BufferSize);
|
||||||
|
unsigned SEGGER_RTT_ReadUpBufferNoLock(unsigned BufferIndex, void *pData, unsigned BufferSize);
|
||||||
|
unsigned SEGGER_RTT_WriteDownBuffer(unsigned BufferIndex, const void *pBuffer, unsigned NumBytes);
|
||||||
|
unsigned SEGGER_RTT_WriteDownBufferNoLock(unsigned BufferIndex, const void *pBuffer, unsigned NumBytes);
|
||||||
|
|
||||||
|
#define SEGGER_RTT_HASDATA_UP(n) (((SEGGER_RTT_BUFFER_UP *)((char *)&_SEGGER_RTT.aUp[n] + SEGGER_RTT_UNCACHED_OFF))->WrOff - ((SEGGER_RTT_BUFFER_UP *)((char *)&_SEGGER_RTT.aUp[n] + SEGGER_RTT_UNCACHED_OFF))->RdOff) // Access uncached to make sure we see changes made by the J-Link side and all of our changes go into HW directly
|
||||||
|
|
||||||
|
/*********************************************************************
|
||||||
|
*
|
||||||
|
* RTT "Terminal" API functions
|
||||||
|
*
|
||||||
|
**********************************************************************
|
||||||
|
*/
|
||||||
|
int SEGGER_RTT_SetTerminal(unsigned char TerminalId);
|
||||||
|
int SEGGER_RTT_TerminalOut(unsigned char TerminalId, const char *s);
|
||||||
|
|
||||||
|
/*********************************************************************
|
||||||
|
*
|
||||||
|
* RTT printf functions (require SEGGER_RTT_printf.c)
|
||||||
|
*
|
||||||
|
**********************************************************************
|
||||||
|
*/
|
||||||
|
int SEGGER_RTT_printf(unsigned BufferIndex, const char *sFormat, ...);
|
||||||
|
int SEGGER_RTT_vprintf(unsigned BufferIndex, const char *sFormat, va_list *pParamList);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif // ifndef(SEGGER_RTT_ASM)
|
||||||
|
|
||||||
|
/*********************************************************************
|
||||||
|
*
|
||||||
|
* Defines
|
||||||
|
*
|
||||||
|
**********************************************************************
|
||||||
|
*/
|
||||||
|
|
||||||
|
//
|
||||||
|
// Operating modes. Define behavior if buffer is full (not enough space for entire message)
|
||||||
|
//
|
||||||
|
#define SEGGER_RTT_MODE_NO_BLOCK_SKIP (0) // Skip. Do not block, output nothing. (Default)
|
||||||
|
#define SEGGER_RTT_MODE_NO_BLOCK_TRIM (1) // Trim: Do not block, output as much as fits.
|
||||||
|
#define SEGGER_RTT_MODE_BLOCK_IF_FIFO_FULL (2) // Block: Wait until there is space in the buffer.
|
||||||
|
#define SEGGER_RTT_MODE_MASK (3)
|
||||||
|
|
||||||
|
//
|
||||||
|
// Control sequences, based on ANSI.
|
||||||
|
// Can be used to control color, and clear the screen
|
||||||
|
//
|
||||||
|
#define RTT_CTRL_RESET "\x1B[0m" // Reset to default colors
|
||||||
|
#define RTT_CTRL_CLEAR "\x1B[2J" // Clear screen, reposition cursor to top left
|
||||||
|
|
||||||
|
#define RTT_CTRL_TEXT_BLACK "\x1B[2;30m"
|
||||||
|
#define RTT_CTRL_TEXT_RED "\x1B[2;31m"
|
||||||
|
#define RTT_CTRL_TEXT_GREEN "\x1B[2;32m"
|
||||||
|
#define RTT_CTRL_TEXT_YELLOW "\x1B[2;33m"
|
||||||
|
#define RTT_CTRL_TEXT_BLUE "\x1B[2;34m"
|
||||||
|
#define RTT_CTRL_TEXT_MAGENTA "\x1B[2;35m"
|
||||||
|
#define RTT_CTRL_TEXT_CYAN "\x1B[2;36m"
|
||||||
|
#define RTT_CTRL_TEXT_WHITE "\x1B[2;37m"
|
||||||
|
|
||||||
|
#define RTT_CTRL_TEXT_BRIGHT_BLACK "\x1B[1;30m"
|
||||||
|
#define RTT_CTRL_TEXT_BRIGHT_RED "\x1B[1;31m"
|
||||||
|
#define RTT_CTRL_TEXT_BRIGHT_GREEN "\x1B[1;32m"
|
||||||
|
#define RTT_CTRL_TEXT_BRIGHT_YELLOW "\x1B[1;33m"
|
||||||
|
#define RTT_CTRL_TEXT_BRIGHT_BLUE "\x1B[1;34m"
|
||||||
|
#define RTT_CTRL_TEXT_BRIGHT_MAGENTA "\x1B[1;35m"
|
||||||
|
#define RTT_CTRL_TEXT_BRIGHT_CYAN "\x1B[1;36m"
|
||||||
|
#define RTT_CTRL_TEXT_BRIGHT_WHITE "\x1B[1;37m"
|
||||||
|
|
||||||
|
#define RTT_CTRL_BG_BLACK "\x1B[24;40m"
|
||||||
|
#define RTT_CTRL_BG_RED "\x1B[24;41m"
|
||||||
|
#define RTT_CTRL_BG_GREEN "\x1B[24;42m"
|
||||||
|
#define RTT_CTRL_BG_YELLOW "\x1B[24;43m"
|
||||||
|
#define RTT_CTRL_BG_BLUE "\x1B[24;44m"
|
||||||
|
#define RTT_CTRL_BG_MAGENTA "\x1B[24;45m"
|
||||||
|
#define RTT_CTRL_BG_CYAN "\x1B[24;46m"
|
||||||
|
#define RTT_CTRL_BG_WHITE "\x1B[24;47m"
|
||||||
|
|
||||||
|
#define RTT_CTRL_BG_BRIGHT_BLACK "\x1B[4;40m"
|
||||||
|
#define RTT_CTRL_BG_BRIGHT_RED "\x1B[4;41m"
|
||||||
|
#define RTT_CTRL_BG_BRIGHT_GREEN "\x1B[4;42m"
|
||||||
|
#define RTT_CTRL_BG_BRIGHT_YELLOW "\x1B[4;43m"
|
||||||
|
#define RTT_CTRL_BG_BRIGHT_BLUE "\x1B[4;44m"
|
||||||
|
#define RTT_CTRL_BG_BRIGHT_MAGENTA "\x1B[4;45m"
|
||||||
|
#define RTT_CTRL_BG_BRIGHT_CYAN "\x1B[4;46m"
|
||||||
|
#define RTT_CTRL_BG_BRIGHT_WHITE "\x1B[4;47m"
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/*************************** End of file ****************************/
|
||||||
429
firmware/shared_libs/utils/rtt/SEGGER_RTT_Conf.h
Normal file
429
firmware/shared_libs/utils/rtt/SEGGER_RTT_Conf.h
Normal file
@@ -0,0 +1,429 @@
|
|||||||
|
/*********************************************************************
|
||||||
|
* SEGGER Microcontroller GmbH *
|
||||||
|
* The Embedded Experts *
|
||||||
|
**********************************************************************
|
||||||
|
* *
|
||||||
|
* (c) 1995 - 2021 SEGGER Microcontroller GmbH *
|
||||||
|
* *
|
||||||
|
* www.segger.com Support: support@segger.com *
|
||||||
|
* *
|
||||||
|
**********************************************************************
|
||||||
|
* *
|
||||||
|
* SEGGER RTT * Real Time Transfer for embedded targets *
|
||||||
|
* *
|
||||||
|
**********************************************************************
|
||||||
|
* *
|
||||||
|
* All rights reserved. *
|
||||||
|
* *
|
||||||
|
* SEGGER strongly recommends to not make any changes *
|
||||||
|
* to or modify the source code of this software in order to stay *
|
||||||
|
* compatible with the RTT protocol and J-Link. *
|
||||||
|
* *
|
||||||
|
* Redistribution and use in source and binary forms, with or *
|
||||||
|
* without modification, are permitted provided that the following *
|
||||||
|
* condition is met: *
|
||||||
|
* *
|
||||||
|
* o Redistributions of source code must retain the above copyright *
|
||||||
|
* notice, this condition and the following disclaimer. *
|
||||||
|
* *
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND *
|
||||||
|
* CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, *
|
||||||
|
* INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF *
|
||||||
|
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE *
|
||||||
|
* DISCLAIMED. IN NO EVENT SHALL SEGGER Microcontroller BE LIABLE FOR *
|
||||||
|
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR *
|
||||||
|
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT *
|
||||||
|
* OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; *
|
||||||
|
* OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF *
|
||||||
|
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT *
|
||||||
|
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE *
|
||||||
|
* USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH *
|
||||||
|
* DAMAGE. *
|
||||||
|
* *
|
||||||
|
**********************************************************************
|
||||||
|
* *
|
||||||
|
* RTT version: 7.80a *
|
||||||
|
* *
|
||||||
|
**********************************************************************
|
||||||
|
|
||||||
|
---------------------------END-OF-HEADER------------------------------
|
||||||
|
File : SEGGER_RTT_Conf.h
|
||||||
|
Purpose : Implementation of SEGGER real-time transfer (RTT) which
|
||||||
|
allows real-time communication on targets which support
|
||||||
|
debugger memory accesses while the CPU is running.
|
||||||
|
Revision: $Rev: 24316 $
|
||||||
|
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef SEGGER_RTT_CONF_H
|
||||||
|
#define SEGGER_RTT_CONF_H
|
||||||
|
|
||||||
|
#ifdef __IAR_SYSTEMS_ICC__
|
||||||
|
#include <intrinsics.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/*********************************************************************
|
||||||
|
*
|
||||||
|
* Defines, configurable
|
||||||
|
*
|
||||||
|
**********************************************************************
|
||||||
|
*/
|
||||||
|
|
||||||
|
//
|
||||||
|
// Take in and set to correct values for Cortex-A systems with CPU cache
|
||||||
|
//
|
||||||
|
//#define SEGGER_RTT_CPU_CACHE_LINE_SIZE (32) // Largest cache line size (in bytes) in the current system
|
||||||
|
//#define SEGGER_RTT_UNCACHED_OFF (0xFB000000) // Address alias where RTT CB and buffers can be accessed uncached
|
||||||
|
//
|
||||||
|
// Most common case:
|
||||||
|
// Up-channel 0: RTT
|
||||||
|
// Up-channel 1: SystemView
|
||||||
|
//
|
||||||
|
#ifndef SEGGER_RTT_MAX_NUM_UP_BUFFERS
|
||||||
|
#define SEGGER_RTT_MAX_NUM_UP_BUFFERS (3) // Max. number of up-buffers (T->H) available on this target (Default: 3)
|
||||||
|
#endif
|
||||||
|
//
|
||||||
|
// Most common case:
|
||||||
|
// Down-channel 0: RTT
|
||||||
|
// Down-channel 1: SystemView
|
||||||
|
//
|
||||||
|
#ifndef SEGGER_RTT_MAX_NUM_DOWN_BUFFERS
|
||||||
|
#define SEGGER_RTT_MAX_NUM_DOWN_BUFFERS (3) // Max. number of down-buffers (H->T) available on this target (Default: 3)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef BUFFER_SIZE_UP
|
||||||
|
#define BUFFER_SIZE_UP (1024) // Size of the buffer for terminal output of target, up to host (Default: 1k)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef BUFFER_SIZE_DOWN
|
||||||
|
#define BUFFER_SIZE_DOWN (16) // Size of the buffer for terminal input to target from host (Usually keyboard input) (Default: 16)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef SEGGER_RTT_PRINTF_BUFFER_SIZE
|
||||||
|
#define SEGGER_RTT_PRINTF_BUFFER_SIZE (64u) // Size of buffer for RTT printf to bulk-send chars via RTT (Default: 64)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef SEGGER_RTT_MODE_DEFAULT
|
||||||
|
#define SEGGER_RTT_MODE_DEFAULT SEGGER_RTT_MODE_NO_BLOCK_SKIP // Mode for pre-initialized terminal channel (buffer 0)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/*********************************************************************
|
||||||
|
*
|
||||||
|
* RTT memcpy configuration
|
||||||
|
*
|
||||||
|
* memcpy() is good for large amounts of data,
|
||||||
|
* but the overhead is big for small amounts, which are usually stored via RTT.
|
||||||
|
* With SEGGER_RTT_MEMCPY_USE_BYTELOOP a simple byte loop can be used instead.
|
||||||
|
*
|
||||||
|
* SEGGER_RTT_MEMCPY() can be used to replace standard memcpy() in RTT functions.
|
||||||
|
* This is may be required with memory access restrictions,
|
||||||
|
* such as on Cortex-A devices with MMU.
|
||||||
|
*/
|
||||||
|
#ifndef SEGGER_RTT_MEMCPY_USE_BYTELOOP
|
||||||
|
#define SEGGER_RTT_MEMCPY_USE_BYTELOOP 0 // 0: Use memcpy/SEGGER_RTT_MEMCPY, 1: Use a simple byte-loop
|
||||||
|
#endif
|
||||||
|
//
|
||||||
|
// Example definition of SEGGER_RTT_MEMCPY to external memcpy with GCC toolchains and Cortex-A targets
|
||||||
|
//
|
||||||
|
//#if ((defined __SES_ARM) || (defined __CROSSWORKS_ARM) || (defined __GNUC__)) && (defined (__ARM_ARCH_7A__))
|
||||||
|
// #define SEGGER_RTT_MEMCPY(pDest, pSrc, NumBytes) SEGGER_memcpy((pDest), (pSrc), (NumBytes))
|
||||||
|
//#endif
|
||||||
|
|
||||||
|
//
|
||||||
|
// Target is not allowed to perform other RTT operations while string still has not been stored completely.
|
||||||
|
// Otherwise we would probably end up with a mixed string in the buffer.
|
||||||
|
// If using RTT from within interrupts, multiple tasks or multi processors, define the SEGGER_RTT_LOCK() and SEGGER_RTT_UNLOCK() function here.
|
||||||
|
//
|
||||||
|
// SEGGER_RTT_MAX_INTERRUPT_PRIORITY can be used in the sample lock routines on Cortex-M3/4.
|
||||||
|
// Make sure to mask all interrupts which can send RTT data, i.e. generate SystemView events, or cause task switches.
|
||||||
|
// When high-priority interrupts must not be masked while sending RTT data, SEGGER_RTT_MAX_INTERRUPT_PRIORITY needs to be adjusted accordingly.
|
||||||
|
// (Higher priority = lower priority number)
|
||||||
|
// Default value for embOS: 128u
|
||||||
|
// Default configuration in FreeRTOS: configMAX_SYSCALL_INTERRUPT_PRIORITY: ( configLIBRARY_MAX_SYSCALL_INTERRUPT_PRIORITY << (8 - configPRIO_BITS) )
|
||||||
|
// In case of doubt mask all interrupts: 1 << (8 - BASEPRI_PRIO_BITS) i.e. 1 << 5 when 3 bits are implemented in NVIC
|
||||||
|
// or define SEGGER_RTT_LOCK() to completely disable interrupts.
|
||||||
|
//
|
||||||
|
#ifndef SEGGER_RTT_MAX_INTERRUPT_PRIORITY
|
||||||
|
#define SEGGER_RTT_MAX_INTERRUPT_PRIORITY (0x20) // Interrupt priority to lock on SEGGER_RTT_LOCK on Cortex-M3/4 (Default: 0x20)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/*********************************************************************
|
||||||
|
*
|
||||||
|
* RTT lock configuration for SEGGER Embedded Studio,
|
||||||
|
* Rowley CrossStudio and GCC
|
||||||
|
*/
|
||||||
|
#if ((defined(__SES_ARM) || defined(__SES_RISCV) || defined(__CROSSWORKS_ARM) || defined(__GNUC__) || defined(__clang__)) && !defined (__CC_ARM) && !defined(WIN32))
|
||||||
|
#if (defined(__ARM_ARCH_6M__) || defined(__ARM_ARCH_8M_BASE__))
|
||||||
|
#define SEGGER_RTT_LOCK() { \
|
||||||
|
unsigned int _SEGGER_RTT__LockState; \
|
||||||
|
__asm volatile ("mrs %0, primask \n\t" \
|
||||||
|
"movs r1, #1 \n\t" \
|
||||||
|
"msr primask, r1 \n\t" \
|
||||||
|
: "=r" (_SEGGER_RTT__LockState) \
|
||||||
|
: \
|
||||||
|
: "r1", "cc" \
|
||||||
|
);
|
||||||
|
|
||||||
|
#define SEGGER_RTT_UNLOCK() __asm volatile ("msr primask, %0 \n\t" \
|
||||||
|
: \
|
||||||
|
: "r" (_SEGGER_RTT__LockState) \
|
||||||
|
: \
|
||||||
|
); \
|
||||||
|
}
|
||||||
|
#elif (defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__) || defined(__ARM_ARCH_8M_MAIN__))
|
||||||
|
#ifndef SEGGER_RTT_MAX_INTERRUPT_PRIORITY
|
||||||
|
#define SEGGER_RTT_MAX_INTERRUPT_PRIORITY (0x20)
|
||||||
|
#endif
|
||||||
|
#define SEGGER_RTT_LOCK() { \
|
||||||
|
unsigned int _SEGGER_RTT__LockState; \
|
||||||
|
__asm volatile ("mrs %0, basepri \n\t" \
|
||||||
|
"mov r1, %1 \n\t" \
|
||||||
|
"msr basepri, r1 \n\t" \
|
||||||
|
: "=r" (_SEGGER_RTT__LockState) \
|
||||||
|
: "i"(SEGGER_RTT_MAX_INTERRUPT_PRIORITY) \
|
||||||
|
: "r1", "cc" \
|
||||||
|
);
|
||||||
|
|
||||||
|
#define SEGGER_RTT_UNLOCK() __asm volatile ("msr basepri, %0 \n\t" \
|
||||||
|
: \
|
||||||
|
: "r" (_SEGGER_RTT__LockState) \
|
||||||
|
: \
|
||||||
|
); \
|
||||||
|
}
|
||||||
|
|
||||||
|
#elif (defined(__ARM_ARCH_7A__) || defined(__ARM_ARCH_7R__))
|
||||||
|
#define SEGGER_RTT_LOCK() { \
|
||||||
|
unsigned int _SEGGER_RTT__LockState; \
|
||||||
|
__asm volatile ("mrs r1, CPSR \n\t" \
|
||||||
|
"mov %0, r1 \n\t" \
|
||||||
|
"orr r1, r1, #0xC0 \n\t" \
|
||||||
|
"msr CPSR_c, r1 \n\t" \
|
||||||
|
: "=r" (_SEGGER_RTT__LockState) \
|
||||||
|
: \
|
||||||
|
: "r1", "cc" \
|
||||||
|
);
|
||||||
|
|
||||||
|
#define SEGGER_RTT_UNLOCK() __asm volatile ("mov r0, %0 \n\t" \
|
||||||
|
"mrs r1, CPSR \n\t" \
|
||||||
|
"bic r1, r1, #0xC0 \n\t" \
|
||||||
|
"and r0, r0, #0xC0 \n\t" \
|
||||||
|
"orr r1, r1, r0 \n\t" \
|
||||||
|
"msr CPSR_c, r1 \n\t" \
|
||||||
|
: \
|
||||||
|
: "r" (_SEGGER_RTT__LockState) \
|
||||||
|
: "r0", "r1", "cc" \
|
||||||
|
); \
|
||||||
|
}
|
||||||
|
#elif defined(__riscv) || defined(__riscv_xlen)
|
||||||
|
#define SEGGER_RTT_LOCK() { \
|
||||||
|
unsigned int _SEGGER_RTT__LockState; \
|
||||||
|
__asm volatile ("csrr %0, mstatus \n\t" \
|
||||||
|
"csrci mstatus, 8 \n\t" \
|
||||||
|
"andi %0, %0, 8 \n\t" \
|
||||||
|
: "=r" (_SEGGER_RTT__LockState) \
|
||||||
|
: \
|
||||||
|
: \
|
||||||
|
);
|
||||||
|
|
||||||
|
#define SEGGER_RTT_UNLOCK() __asm volatile ("csrr a1, mstatus \n\t" \
|
||||||
|
"or %0, %0, a1 \n\t" \
|
||||||
|
"csrs mstatus, %0 \n\t" \
|
||||||
|
: \
|
||||||
|
: "r" (_SEGGER_RTT__LockState) \
|
||||||
|
: "a1" \
|
||||||
|
); \
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
#define SEGGER_RTT_LOCK()
|
||||||
|
#define SEGGER_RTT_UNLOCK()
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/*********************************************************************
|
||||||
|
*
|
||||||
|
* RTT lock configuration for IAR EWARM
|
||||||
|
*/
|
||||||
|
#ifdef __ICCARM__
|
||||||
|
#if (defined (__ARM6M__) && (__CORE__ == __ARM6M__)) || \
|
||||||
|
(defined (__ARM8M_BASELINE__) && (__CORE__ == __ARM8M_BASELINE__))
|
||||||
|
#define SEGGER_RTT_LOCK() { \
|
||||||
|
unsigned int _SEGGER_RTT__LockState; \
|
||||||
|
_SEGGER_RTT__LockState = __get_PRIMASK(); \
|
||||||
|
__set_PRIMASK(1);
|
||||||
|
|
||||||
|
#define SEGGER_RTT_UNLOCK() __set_PRIMASK(_SEGGER_RTT__LockState); \
|
||||||
|
}
|
||||||
|
#elif (defined (__ARM7EM__) && (__CORE__ == __ARM7EM__)) || \
|
||||||
|
(defined (__ARM7M__) && (__CORE__ == __ARM7M__)) || \
|
||||||
|
(defined (__ARM8M_MAINLINE__) && (__CORE__ == __ARM8M_MAINLINE__)) || \
|
||||||
|
(defined (__ARM8M_MAINLINE__) && (__CORE__ == __ARM8M_MAINLINE__))
|
||||||
|
#ifndef SEGGER_RTT_MAX_INTERRUPT_PRIORITY
|
||||||
|
#define SEGGER_RTT_MAX_INTERRUPT_PRIORITY (0x20)
|
||||||
|
#endif
|
||||||
|
#define SEGGER_RTT_LOCK() { \
|
||||||
|
unsigned int _SEGGER_RTT__LockState; \
|
||||||
|
_SEGGER_RTT__LockState = __get_BASEPRI(); \
|
||||||
|
__set_BASEPRI(SEGGER_RTT_MAX_INTERRUPT_PRIORITY);
|
||||||
|
|
||||||
|
#define SEGGER_RTT_UNLOCK() __set_BASEPRI(_SEGGER_RTT__LockState); \
|
||||||
|
}
|
||||||
|
#elif (defined (__ARM7A__) && (__CORE__ == __ARM7A__)) || \
|
||||||
|
(defined (__ARM7R__) && (__CORE__ == __ARM7R__))
|
||||||
|
#define SEGGER_RTT_LOCK() { \
|
||||||
|
unsigned int _SEGGER_RTT__LockState; \
|
||||||
|
__asm volatile ("mrs r1, CPSR \n\t" \
|
||||||
|
"mov %0, r1 \n\t" \
|
||||||
|
"orr r1, r1, #0xC0 \n\t" \
|
||||||
|
"msr CPSR_c, r1 \n\t" \
|
||||||
|
: "=r" (_SEGGER_RTT__LockState) \
|
||||||
|
: \
|
||||||
|
: "r1", "cc" \
|
||||||
|
);
|
||||||
|
|
||||||
|
#define SEGGER_RTT_UNLOCK() __asm volatile ("mov r0, %0 \n\t" \
|
||||||
|
"mrs r1, CPSR \n\t" \
|
||||||
|
"bic r1, r1, #0xC0 \n\t" \
|
||||||
|
"and r0, r0, #0xC0 \n\t" \
|
||||||
|
"orr r1, r1, r0 \n\t" \
|
||||||
|
"msr CPSR_c, r1 \n\t" \
|
||||||
|
: \
|
||||||
|
: "r" (_SEGGER_RTT__LockState) \
|
||||||
|
: "r0", "r1", "cc" \
|
||||||
|
); \
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/*********************************************************************
|
||||||
|
*
|
||||||
|
* RTT lock configuration for IAR RX
|
||||||
|
*/
|
||||||
|
#ifdef __ICCRX__
|
||||||
|
#define SEGGER_RTT_LOCK() { \
|
||||||
|
unsigned long _SEGGER_RTT__LockState; \
|
||||||
|
_SEGGER_RTT__LockState = __get_interrupt_state(); \
|
||||||
|
__disable_interrupt();
|
||||||
|
|
||||||
|
#define SEGGER_RTT_UNLOCK() __set_interrupt_state(_SEGGER_RTT__LockState); \
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/*********************************************************************
|
||||||
|
*
|
||||||
|
* RTT lock configuration for IAR RL78
|
||||||
|
*/
|
||||||
|
#ifdef __ICCRL78__
|
||||||
|
#define SEGGER_RTT_LOCK() { \
|
||||||
|
__istate_t _SEGGER_RTT__LockState; \
|
||||||
|
_SEGGER_RTT__LockState = __get_interrupt_state(); \
|
||||||
|
__disable_interrupt();
|
||||||
|
|
||||||
|
#define SEGGER_RTT_UNLOCK() __set_interrupt_state(_SEGGER_RTT__LockState); \
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/*********************************************************************
|
||||||
|
*
|
||||||
|
* RTT lock configuration for KEIL ARM
|
||||||
|
*/
|
||||||
|
#ifdef __CC_ARM
|
||||||
|
#if (defined __TARGET_ARCH_6S_M)
|
||||||
|
#define SEGGER_RTT_LOCK() { \
|
||||||
|
unsigned int _SEGGER_RTT__LockState; \
|
||||||
|
register unsigned char _SEGGER_RTT__PRIMASK __asm( "primask"); \
|
||||||
|
_SEGGER_RTT__LockState = _SEGGER_RTT__PRIMASK; \
|
||||||
|
_SEGGER_RTT__PRIMASK = 1u; \
|
||||||
|
__schedule_barrier();
|
||||||
|
|
||||||
|
#define SEGGER_RTT_UNLOCK() _SEGGER_RTT__PRIMASK = _SEGGER_RTT__LockState; \
|
||||||
|
__schedule_barrier(); \
|
||||||
|
}
|
||||||
|
#elif (defined(__TARGET_ARCH_7_M) || defined(__TARGET_ARCH_7E_M))
|
||||||
|
#ifndef SEGGER_RTT_MAX_INTERRUPT_PRIORITY
|
||||||
|
#define SEGGER_RTT_MAX_INTERRUPT_PRIORITY (0x20)
|
||||||
|
#endif
|
||||||
|
#define SEGGER_RTT_LOCK() { \
|
||||||
|
unsigned int _SEGGER_RTT__LockState; \
|
||||||
|
register unsigned char BASEPRI __asm( "basepri"); \
|
||||||
|
_SEGGER_RTT__LockState = BASEPRI; \
|
||||||
|
BASEPRI = SEGGER_RTT_MAX_INTERRUPT_PRIORITY; \
|
||||||
|
__schedule_barrier();
|
||||||
|
|
||||||
|
#define SEGGER_RTT_UNLOCK() BASEPRI = _SEGGER_RTT__LockState; \
|
||||||
|
__schedule_barrier(); \
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/*********************************************************************
|
||||||
|
*
|
||||||
|
* RTT lock configuration for TI ARM
|
||||||
|
*/
|
||||||
|
#ifdef __TI_ARM__
|
||||||
|
#if defined (__TI_ARM_V6M0__)
|
||||||
|
#define SEGGER_RTT_LOCK() { \
|
||||||
|
unsigned int _SEGGER_RTT__LockState; \
|
||||||
|
_SEGGER_RTT__LockState = __get_PRIMASK(); \
|
||||||
|
__set_PRIMASK(1);
|
||||||
|
|
||||||
|
#define SEGGER_RTT_UNLOCK() __set_PRIMASK(_SEGGER_RTT__LockState); \
|
||||||
|
}
|
||||||
|
#elif (defined (__TI_ARM_V7M3__) || defined (__TI_ARM_V7M4__))
|
||||||
|
#ifndef SEGGER_RTT_MAX_INTERRUPT_PRIORITY
|
||||||
|
#define SEGGER_RTT_MAX_INTERRUPT_PRIORITY (0x20)
|
||||||
|
#endif
|
||||||
|
#define SEGGER_RTT_LOCK() { \
|
||||||
|
unsigned int _SEGGER_RTT__LockState; \
|
||||||
|
_SEGGER_RTT__LockState = _set_interrupt_priority(SEGGER_RTT_MAX_INTERRUPT_PRIORITY);
|
||||||
|
|
||||||
|
#define SEGGER_RTT_UNLOCK() _set_interrupt_priority(_SEGGER_RTT__LockState); \
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/*********************************************************************
|
||||||
|
*
|
||||||
|
* RTT lock configuration for CCRX
|
||||||
|
*/
|
||||||
|
#ifdef __RX
|
||||||
|
#include <machine.h>
|
||||||
|
#define SEGGER_RTT_LOCK() { \
|
||||||
|
unsigned long _SEGGER_RTT__LockState; \
|
||||||
|
_SEGGER_RTT__LockState = get_psw() & 0x010000; \
|
||||||
|
clrpsw_i();
|
||||||
|
|
||||||
|
#define SEGGER_RTT_UNLOCK() set_psw(get_psw() | _SEGGER_RTT__LockState); \
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/*********************************************************************
|
||||||
|
*
|
||||||
|
* RTT lock configuration for embOS Simulation on Windows
|
||||||
|
* (Can also be used for generic RTT locking with embOS)
|
||||||
|
*/
|
||||||
|
#if defined(WIN32) || defined(SEGGER_RTT_LOCK_EMBOS)
|
||||||
|
|
||||||
|
void OS_SIM_EnterCriticalSection(void);
|
||||||
|
void OS_SIM_LeaveCriticalSection(void);
|
||||||
|
|
||||||
|
#define SEGGER_RTT_LOCK() { \
|
||||||
|
OS_SIM_EnterCriticalSection();
|
||||||
|
|
||||||
|
#define SEGGER_RTT_UNLOCK() OS_SIM_LeaveCriticalSection(); \
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/*********************************************************************
|
||||||
|
*
|
||||||
|
* RTT lock configuration fallback
|
||||||
|
*/
|
||||||
|
#ifndef SEGGER_RTT_LOCK
|
||||||
|
#define SEGGER_RTT_LOCK() // Lock RTT (nestable) (i.e. disable interrupts)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef SEGGER_RTT_UNLOCK
|
||||||
|
#define SEGGER_RTT_UNLOCK() // Unlock RTT (nestable) (i.e. enable previous interrupt lock state)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif
|
||||||
|
/*************************** End of file ****************************/
|
||||||
505
firmware/shared_libs/utils/rtt/SEGGER_RTT_printf.c
Normal file
505
firmware/shared_libs/utils/rtt/SEGGER_RTT_printf.c
Normal file
@@ -0,0 +1,505 @@
|
|||||||
|
/*********************************************************************
|
||||||
|
* SEGGER Microcontroller GmbH *
|
||||||
|
* The Embedded Experts *
|
||||||
|
**********************************************************************
|
||||||
|
* *
|
||||||
|
* (c) 1995 - 2021 SEGGER Microcontroller GmbH *
|
||||||
|
* *
|
||||||
|
* www.segger.com Support: support@segger.com *
|
||||||
|
* *
|
||||||
|
**********************************************************************
|
||||||
|
* *
|
||||||
|
* SEGGER RTT * Real Time Transfer for embedded targets *
|
||||||
|
* *
|
||||||
|
**********************************************************************
|
||||||
|
* *
|
||||||
|
* All rights reserved. *
|
||||||
|
* *
|
||||||
|
* SEGGER strongly recommends to not make any changes *
|
||||||
|
* to or modify the source code of this software in order to stay *
|
||||||
|
* compatible with the RTT protocol and J-Link. *
|
||||||
|
* *
|
||||||
|
* Redistribution and use in source and binary forms, with or *
|
||||||
|
* without modification, are permitted provided that the following *
|
||||||
|
* condition is met: *
|
||||||
|
* *
|
||||||
|
* o Redistributions of source code must retain the above copyright *
|
||||||
|
* notice, this condition and the following disclaimer. *
|
||||||
|
* *
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND *
|
||||||
|
* CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, *
|
||||||
|
* INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF *
|
||||||
|
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE *
|
||||||
|
* DISCLAIMED. IN NO EVENT SHALL SEGGER Microcontroller BE LIABLE FOR *
|
||||||
|
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR *
|
||||||
|
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT *
|
||||||
|
* OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; *
|
||||||
|
* OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF *
|
||||||
|
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT *
|
||||||
|
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE *
|
||||||
|
* USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH *
|
||||||
|
* DAMAGE. *
|
||||||
|
* *
|
||||||
|
**********************************************************************
|
||||||
|
* *
|
||||||
|
* RTT version: 7.80a *
|
||||||
|
* *
|
||||||
|
**********************************************************************
|
||||||
|
|
||||||
|
---------------------------END-OF-HEADER------------------------------
|
||||||
|
File : SEGGER_RTT_printf.c
|
||||||
|
Purpose : Replacement for printf to write formatted data via RTT
|
||||||
|
Revision: $Rev: 17697 $
|
||||||
|
----------------------------------------------------------------------
|
||||||
|
*/
|
||||||
|
#include "SEGGER_RTT.h"
|
||||||
|
#include "SEGGER_RTT_Conf.h"
|
||||||
|
|
||||||
|
/*********************************************************************
|
||||||
|
*
|
||||||
|
* Defines, configurable
|
||||||
|
*
|
||||||
|
**********************************************************************
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef SEGGER_RTT_PRINTF_BUFFER_SIZE
|
||||||
|
#define SEGGER_RTT_PRINTF_BUFFER_SIZE (64)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include <stdlib.h>
|
||||||
|
#include <stdarg.h>
|
||||||
|
|
||||||
|
|
||||||
|
#define FORMAT_FLAG_LEFT_JUSTIFY (1u << 0)
|
||||||
|
#define FORMAT_FLAG_PAD_ZERO (1u << 1)
|
||||||
|
#define FORMAT_FLAG_PRINT_SIGN (1u << 2)
|
||||||
|
#define FORMAT_FLAG_ALTERNATE (1u << 3)
|
||||||
|
|
||||||
|
/*********************************************************************
|
||||||
|
*
|
||||||
|
* Types
|
||||||
|
*
|
||||||
|
**********************************************************************
|
||||||
|
*/
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
char* pBuffer;
|
||||||
|
unsigned BufferSize;
|
||||||
|
unsigned Cnt;
|
||||||
|
|
||||||
|
int ReturnValue;
|
||||||
|
|
||||||
|
unsigned RTTBufferIndex;
|
||||||
|
} SEGGER_RTT_PRINTF_DESC;
|
||||||
|
|
||||||
|
/*********************************************************************
|
||||||
|
*
|
||||||
|
* Function prototypes
|
||||||
|
*
|
||||||
|
**********************************************************************
|
||||||
|
*/
|
||||||
|
|
||||||
|
/*********************************************************************
|
||||||
|
*
|
||||||
|
* Static code
|
||||||
|
*
|
||||||
|
**********************************************************************
|
||||||
|
*/
|
||||||
|
/*********************************************************************
|
||||||
|
*
|
||||||
|
* _StoreChar
|
||||||
|
*/
|
||||||
|
static void _StoreChar(SEGGER_RTT_PRINTF_DESC * p, char c) {
|
||||||
|
unsigned Cnt;
|
||||||
|
|
||||||
|
Cnt = p->Cnt;
|
||||||
|
if ((Cnt + 1u) <= p->BufferSize) {
|
||||||
|
*(p->pBuffer + Cnt) = c;
|
||||||
|
p->Cnt = Cnt + 1u;
|
||||||
|
p->ReturnValue++;
|
||||||
|
}
|
||||||
|
//
|
||||||
|
// Write part of string, when the buffer is full
|
||||||
|
//
|
||||||
|
if (p->Cnt == p->BufferSize) {
|
||||||
|
if (SEGGER_RTT_Write(p->RTTBufferIndex, p->pBuffer, p->Cnt) != p->Cnt) {
|
||||||
|
p->ReturnValue = -1;
|
||||||
|
} else {
|
||||||
|
p->Cnt = 0u;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/*********************************************************************
|
||||||
|
*
|
||||||
|
* _PrintUnsigned
|
||||||
|
*/
|
||||||
|
static void _PrintUnsigned(SEGGER_RTT_PRINTF_DESC * pBufferDesc, unsigned v, unsigned Base, unsigned NumDigits, unsigned FieldWidth, unsigned FormatFlags) {
|
||||||
|
static const char _aV2C[16] = {'0', '1', '2', '3', '4', '5', '6', '7', '8', '9', 'A', 'B', 'C', 'D', 'E', 'F' };
|
||||||
|
unsigned Div;
|
||||||
|
unsigned Digit;
|
||||||
|
unsigned Number;
|
||||||
|
unsigned Width;
|
||||||
|
char c;
|
||||||
|
|
||||||
|
Number = v;
|
||||||
|
Digit = 1u;
|
||||||
|
//
|
||||||
|
// Get actual field width
|
||||||
|
//
|
||||||
|
Width = 1u;
|
||||||
|
while (Number >= Base) {
|
||||||
|
Number = (Number / Base);
|
||||||
|
Width++;
|
||||||
|
}
|
||||||
|
if (NumDigits > Width) {
|
||||||
|
Width = NumDigits;
|
||||||
|
}
|
||||||
|
//
|
||||||
|
// Print leading chars if necessary
|
||||||
|
//
|
||||||
|
if ((FormatFlags & FORMAT_FLAG_LEFT_JUSTIFY) == 0u) {
|
||||||
|
if (FieldWidth != 0u) {
|
||||||
|
if (((FormatFlags & FORMAT_FLAG_PAD_ZERO) == FORMAT_FLAG_PAD_ZERO) && (NumDigits == 0u)) {
|
||||||
|
c = '0';
|
||||||
|
} else {
|
||||||
|
c = ' ';
|
||||||
|
}
|
||||||
|
while ((FieldWidth != 0u) && (Width < FieldWidth)) {
|
||||||
|
FieldWidth--;
|
||||||
|
_StoreChar(pBufferDesc, c);
|
||||||
|
if (pBufferDesc->ReturnValue < 0) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (pBufferDesc->ReturnValue >= 0) {
|
||||||
|
//
|
||||||
|
// Compute Digit.
|
||||||
|
// Loop until Digit has the value of the highest digit required.
|
||||||
|
// Example: If the output is 345 (Base 10), loop 2 times until Digit is 100.
|
||||||
|
//
|
||||||
|
while (1) {
|
||||||
|
if (NumDigits > 1u) { // User specified a min number of digits to print? => Make sure we loop at least that often, before checking anything else (> 1 check avoids problems with NumDigits being signed / unsigned)
|
||||||
|
NumDigits--;
|
||||||
|
} else {
|
||||||
|
Div = v / Digit;
|
||||||
|
if (Div < Base) { // Is our divider big enough to extract the highest digit from value? => Done
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
Digit *= Base;
|
||||||
|
}
|
||||||
|
//
|
||||||
|
// Output digits
|
||||||
|
//
|
||||||
|
do {
|
||||||
|
Div = v / Digit;
|
||||||
|
v -= Div * Digit;
|
||||||
|
_StoreChar(pBufferDesc, _aV2C[Div]);
|
||||||
|
if (pBufferDesc->ReturnValue < 0) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
Digit /= Base;
|
||||||
|
} while (Digit);
|
||||||
|
//
|
||||||
|
// Print trailing spaces if necessary
|
||||||
|
//
|
||||||
|
if ((FormatFlags & FORMAT_FLAG_LEFT_JUSTIFY) == FORMAT_FLAG_LEFT_JUSTIFY) {
|
||||||
|
if (FieldWidth != 0u) {
|
||||||
|
while ((FieldWidth != 0u) && (Width < FieldWidth)) {
|
||||||
|
FieldWidth--;
|
||||||
|
_StoreChar(pBufferDesc, ' ');
|
||||||
|
if (pBufferDesc->ReturnValue < 0) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/*********************************************************************
|
||||||
|
*
|
||||||
|
* _PrintInt
|
||||||
|
*/
|
||||||
|
static void _PrintInt(SEGGER_RTT_PRINTF_DESC * pBufferDesc, int v, unsigned Base, unsigned NumDigits, unsigned FieldWidth, unsigned FormatFlags) {
|
||||||
|
unsigned Width;
|
||||||
|
int Number;
|
||||||
|
|
||||||
|
Number = (v < 0) ? -v : v;
|
||||||
|
|
||||||
|
//
|
||||||
|
// Get actual field width
|
||||||
|
//
|
||||||
|
Width = 1u;
|
||||||
|
while (Number >= (int)Base) {
|
||||||
|
Number = (Number / (int)Base);
|
||||||
|
Width++;
|
||||||
|
}
|
||||||
|
if (NumDigits > Width) {
|
||||||
|
Width = NumDigits;
|
||||||
|
}
|
||||||
|
if ((FieldWidth > 0u) && ((v < 0) || ((FormatFlags & FORMAT_FLAG_PRINT_SIGN) == FORMAT_FLAG_PRINT_SIGN))) {
|
||||||
|
FieldWidth--;
|
||||||
|
}
|
||||||
|
|
||||||
|
//
|
||||||
|
// Print leading spaces if necessary
|
||||||
|
//
|
||||||
|
if ((((FormatFlags & FORMAT_FLAG_PAD_ZERO) == 0u) || (NumDigits != 0u)) && ((FormatFlags & FORMAT_FLAG_LEFT_JUSTIFY) == 0u)) {
|
||||||
|
if (FieldWidth != 0u) {
|
||||||
|
while ((FieldWidth != 0u) && (Width < FieldWidth)) {
|
||||||
|
FieldWidth--;
|
||||||
|
_StoreChar(pBufferDesc, ' ');
|
||||||
|
if (pBufferDesc->ReturnValue < 0) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
//
|
||||||
|
// Print sign if necessary
|
||||||
|
//
|
||||||
|
if (pBufferDesc->ReturnValue >= 0) {
|
||||||
|
if (v < 0) {
|
||||||
|
v = -v;
|
||||||
|
_StoreChar(pBufferDesc, '-');
|
||||||
|
} else if ((FormatFlags & FORMAT_FLAG_PRINT_SIGN) == FORMAT_FLAG_PRINT_SIGN) {
|
||||||
|
_StoreChar(pBufferDesc, '+');
|
||||||
|
} else {
|
||||||
|
|
||||||
|
}
|
||||||
|
if (pBufferDesc->ReturnValue >= 0) {
|
||||||
|
//
|
||||||
|
// Print leading zeros if necessary
|
||||||
|
//
|
||||||
|
if (((FormatFlags & FORMAT_FLAG_PAD_ZERO) == FORMAT_FLAG_PAD_ZERO) && ((FormatFlags & FORMAT_FLAG_LEFT_JUSTIFY) == 0u) && (NumDigits == 0u)) {
|
||||||
|
if (FieldWidth != 0u) {
|
||||||
|
while ((FieldWidth != 0u) && (Width < FieldWidth)) {
|
||||||
|
FieldWidth--;
|
||||||
|
_StoreChar(pBufferDesc, '0');
|
||||||
|
if (pBufferDesc->ReturnValue < 0) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (pBufferDesc->ReturnValue >= 0) {
|
||||||
|
//
|
||||||
|
// Print number without sign
|
||||||
|
//
|
||||||
|
_PrintUnsigned(pBufferDesc, (unsigned)v, Base, NumDigits, FieldWidth, FormatFlags);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/*********************************************************************
|
||||||
|
*
|
||||||
|
* Public code
|
||||||
|
*
|
||||||
|
**********************************************************************
|
||||||
|
*/
|
||||||
|
/*********************************************************************
|
||||||
|
*
|
||||||
|
* SEGGER_RTT_vprintf
|
||||||
|
*
|
||||||
|
* Function description
|
||||||
|
* Stores a formatted string in SEGGER RTT control block.
|
||||||
|
* This data is read by the host.
|
||||||
|
*
|
||||||
|
* Parameters
|
||||||
|
* BufferIndex Index of "Up"-buffer to be used. (e.g. 0 for "Terminal")
|
||||||
|
* sFormat Pointer to format string
|
||||||
|
* pParamList Pointer to the list of arguments for the format string
|
||||||
|
*
|
||||||
|
* Return values
|
||||||
|
* >= 0: Number of bytes which have been stored in the "Up"-buffer.
|
||||||
|
* < 0: Error
|
||||||
|
*/
|
||||||
|
int SEGGER_RTT_vprintf(unsigned BufferIndex, const char * sFormat, va_list * pParamList) {
|
||||||
|
char c;
|
||||||
|
SEGGER_RTT_PRINTF_DESC BufferDesc;
|
||||||
|
int v;
|
||||||
|
unsigned NumDigits;
|
||||||
|
unsigned FormatFlags;
|
||||||
|
unsigned FieldWidth;
|
||||||
|
char acBuffer[SEGGER_RTT_PRINTF_BUFFER_SIZE];
|
||||||
|
|
||||||
|
BufferDesc.pBuffer = acBuffer;
|
||||||
|
BufferDesc.BufferSize = SEGGER_RTT_PRINTF_BUFFER_SIZE;
|
||||||
|
BufferDesc.Cnt = 0u;
|
||||||
|
BufferDesc.RTTBufferIndex = BufferIndex;
|
||||||
|
BufferDesc.ReturnValue = 0;
|
||||||
|
|
||||||
|
do {
|
||||||
|
c = *sFormat;
|
||||||
|
sFormat++;
|
||||||
|
if (c == 0u) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
if (c == '%') {
|
||||||
|
//
|
||||||
|
// Filter out flags
|
||||||
|
//
|
||||||
|
FormatFlags = 0u;
|
||||||
|
v = 1;
|
||||||
|
do {
|
||||||
|
c = *sFormat;
|
||||||
|
switch (c) {
|
||||||
|
case '-': FormatFlags |= FORMAT_FLAG_LEFT_JUSTIFY; sFormat++; break;
|
||||||
|
case '0': FormatFlags |= FORMAT_FLAG_PAD_ZERO; sFormat++; break;
|
||||||
|
case '+': FormatFlags |= FORMAT_FLAG_PRINT_SIGN; sFormat++; break;
|
||||||
|
case '#': FormatFlags |= FORMAT_FLAG_ALTERNATE; sFormat++; break;
|
||||||
|
default: v = 0; break;
|
||||||
|
}
|
||||||
|
} while (v);
|
||||||
|
//
|
||||||
|
// filter out field with
|
||||||
|
//
|
||||||
|
FieldWidth = 0u;
|
||||||
|
do {
|
||||||
|
c = *sFormat;
|
||||||
|
if ((c < '0') || (c > '9')) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
sFormat++;
|
||||||
|
FieldWidth = (FieldWidth * 10u) + ((unsigned)c - '0');
|
||||||
|
} while (1);
|
||||||
|
|
||||||
|
//
|
||||||
|
// Filter out precision (number of digits to display)
|
||||||
|
//
|
||||||
|
NumDigits = 0u;
|
||||||
|
c = *sFormat;
|
||||||
|
if (c == '.') {
|
||||||
|
sFormat++;
|
||||||
|
do {
|
||||||
|
c = *sFormat;
|
||||||
|
if ((c < '0') || (c > '9')) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
sFormat++;
|
||||||
|
NumDigits = NumDigits * 10u + ((unsigned)c - '0');
|
||||||
|
} while (1);
|
||||||
|
}
|
||||||
|
//
|
||||||
|
// Filter out length modifier
|
||||||
|
//
|
||||||
|
c = *sFormat;
|
||||||
|
do {
|
||||||
|
if ((c == 'l') || (c == 'h')) {
|
||||||
|
sFormat++;
|
||||||
|
c = *sFormat;
|
||||||
|
} else {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
} while (1);
|
||||||
|
//
|
||||||
|
// Handle specifiers
|
||||||
|
//
|
||||||
|
switch (c) {
|
||||||
|
case 'c': {
|
||||||
|
char c0;
|
||||||
|
v = va_arg(*pParamList, int);
|
||||||
|
c0 = (char)v;
|
||||||
|
_StoreChar(&BufferDesc, c0);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 'd':
|
||||||
|
v = va_arg(*pParamList, int);
|
||||||
|
_PrintInt(&BufferDesc, v, 10u, NumDigits, FieldWidth, FormatFlags);
|
||||||
|
break;
|
||||||
|
case 'u':
|
||||||
|
v = va_arg(*pParamList, int);
|
||||||
|
_PrintUnsigned(&BufferDesc, (unsigned)v, 10u, NumDigits, FieldWidth, FormatFlags);
|
||||||
|
break;
|
||||||
|
case 'x':
|
||||||
|
case 'X':
|
||||||
|
v = va_arg(*pParamList, int);
|
||||||
|
_PrintUnsigned(&BufferDesc, (unsigned)v, 16u, NumDigits, FieldWidth, FormatFlags);
|
||||||
|
break;
|
||||||
|
case 's':
|
||||||
|
{
|
||||||
|
const char * s = va_arg(*pParamList, const char *);
|
||||||
|
do {
|
||||||
|
c = *s;
|
||||||
|
s++;
|
||||||
|
if (c == '\0') {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
_StoreChar(&BufferDesc, c);
|
||||||
|
} while (BufferDesc.ReturnValue >= 0);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case 'p':
|
||||||
|
v = va_arg(*pParamList, int);
|
||||||
|
_PrintUnsigned(&BufferDesc, (unsigned)v, 16u, 8u, 8u, 0u);
|
||||||
|
break;
|
||||||
|
case '%':
|
||||||
|
_StoreChar(&BufferDesc, '%');
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
sFormat++;
|
||||||
|
} else {
|
||||||
|
_StoreChar(&BufferDesc, c);
|
||||||
|
}
|
||||||
|
} while (BufferDesc.ReturnValue >= 0);
|
||||||
|
|
||||||
|
if (BufferDesc.ReturnValue > 0) {
|
||||||
|
//
|
||||||
|
// Write remaining data, if any
|
||||||
|
//
|
||||||
|
if (BufferDesc.Cnt != 0u) {
|
||||||
|
SEGGER_RTT_Write(BufferIndex, acBuffer, BufferDesc.Cnt);
|
||||||
|
}
|
||||||
|
BufferDesc.ReturnValue += (int)BufferDesc.Cnt;
|
||||||
|
}
|
||||||
|
return BufferDesc.ReturnValue;
|
||||||
|
}
|
||||||
|
|
||||||
|
/*********************************************************************
|
||||||
|
*
|
||||||
|
* SEGGER_RTT_printf
|
||||||
|
*
|
||||||
|
* Function description
|
||||||
|
* Stores a formatted string in SEGGER RTT control block.
|
||||||
|
* This data is read by the host.
|
||||||
|
*
|
||||||
|
* Parameters
|
||||||
|
* BufferIndex Index of "Up"-buffer to be used. (e.g. 0 for "Terminal")
|
||||||
|
* sFormat Pointer to format string, followed by the arguments for conversion
|
||||||
|
*
|
||||||
|
* Return values
|
||||||
|
* >= 0: Number of bytes which have been stored in the "Up"-buffer.
|
||||||
|
* < 0: Error
|
||||||
|
*
|
||||||
|
* Notes
|
||||||
|
* (1) Conversion specifications have following syntax:
|
||||||
|
* %[flags][FieldWidth][.Precision]ConversionSpecifier
|
||||||
|
* (2) Supported flags:
|
||||||
|
* -: Left justify within the field width
|
||||||
|
* +: Always print sign extension for signed conversions
|
||||||
|
* 0: Pad with 0 instead of spaces. Ignored when using '-'-flag or precision
|
||||||
|
* Supported conversion specifiers:
|
||||||
|
* c: Print the argument as one char
|
||||||
|
* d: Print the argument as a signed integer
|
||||||
|
* u: Print the argument as an unsigned integer
|
||||||
|
* x: Print the argument as an hexadecimal integer
|
||||||
|
* s: Print the string pointed to by the argument
|
||||||
|
* p: Print the argument as an 8-digit hexadecimal integer. (Argument shall be a pointer to void.)
|
||||||
|
*/
|
||||||
|
int SEGGER_RTT_printf(unsigned BufferIndex, const char * sFormat, ...) {
|
||||||
|
int r;
|
||||||
|
va_list ParamList;
|
||||||
|
|
||||||
|
va_start(ParamList, sFormat);
|
||||||
|
r = SEGGER_RTT_vprintf(BufferIndex, sFormat, &ParamList);
|
||||||
|
va_end(ParamList);
|
||||||
|
return r;
|
||||||
|
}
|
||||||
|
/*************************** End of file ****************************/
|
||||||
14
firmware/shared_libs/utils/spi_cs/spi_cs_if.h
Normal file
14
firmware/shared_libs/utils/spi_cs/spi_cs_if.h
Normal file
@@ -0,0 +1,14 @@
|
|||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "stdint.h"
|
||||||
|
|
||||||
|
typedef struct cs_handle_t cs_handle_t;
|
||||||
|
|
||||||
|
typedef void (*cs_on_t)(cs_handle_t *hcs);
|
||||||
|
typedef void (*cs_off_t)(cs_handle_t *hcs);
|
||||||
|
|
||||||
|
struct cs_handle_t
|
||||||
|
{
|
||||||
|
cs_on_t cs_on;
|
||||||
|
cs_off_t cs_off;
|
||||||
|
};
|
||||||
154
firmware/shared_libs/utils/ulog/ulog.c
Normal file
154
firmware/shared_libs/utils/ulog/ulog.c
Normal file
@@ -0,0 +1,154 @@
|
|||||||
|
/**
|
||||||
|
MIT License
|
||||||
|
|
||||||
|
Copyright (c) 2019 R. Dunbar Poor <rdpoor@gmail.com>
|
||||||
|
|
||||||
|
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.
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \file ulog.c
|
||||||
|
*
|
||||||
|
* \brief uLog: lightweight logging for embedded systems
|
||||||
|
*
|
||||||
|
* See ulog.h for sparse documentation.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "ulog.h"
|
||||||
|
|
||||||
|
#ifdef ULOG_ENABLED // whole file...
|
||||||
|
|
||||||
|
// #include <stdio.h>
|
||||||
|
#include "printf.h"
|
||||||
|
#include <string.h>
|
||||||
|
#include <stdarg.h>
|
||||||
|
|
||||||
|
// =============================================================================
|
||||||
|
// types and definitions
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
ulog_function_t fn;
|
||||||
|
ulog_level_t threshold;
|
||||||
|
} subscriber_t;
|
||||||
|
|
||||||
|
// =============================================================================
|
||||||
|
// local storage
|
||||||
|
|
||||||
|
static subscriber_t s_subscribers[ULOG_MAX_SUBSCRIBERS];
|
||||||
|
static char s_message[ULOG_MAX_MESSAGE_LENGTH];
|
||||||
|
|
||||||
|
// =============================================================================
|
||||||
|
// user-visible code
|
||||||
|
|
||||||
|
void ulog_init()
|
||||||
|
{
|
||||||
|
memset(s_subscribers, 0, sizeof(s_subscribers));
|
||||||
|
}
|
||||||
|
|
||||||
|
// search the s_subscribers table to install or update fn
|
||||||
|
ulog_err_t ulog_subscribe(ulog_function_t fn, ulog_level_t threshold)
|
||||||
|
{
|
||||||
|
int available_slot = -1;
|
||||||
|
int i;
|
||||||
|
for (i = 0; i < ULOG_MAX_SUBSCRIBERS; i++)
|
||||||
|
{
|
||||||
|
if (s_subscribers[i].fn == fn)
|
||||||
|
{
|
||||||
|
// already subscribed: update threshold and return immediately.
|
||||||
|
s_subscribers[i].threshold = threshold;
|
||||||
|
return ULOG_ERR_NONE;
|
||||||
|
}
|
||||||
|
else if (s_subscribers[i].fn == NULL)
|
||||||
|
{
|
||||||
|
// found a free slot
|
||||||
|
available_slot = i;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// fn is not yet a subscriber. assign if possible.
|
||||||
|
if (available_slot == -1)
|
||||||
|
{
|
||||||
|
return ULOG_ERR_SUBSCRIBERS_EXCEEDED;
|
||||||
|
}
|
||||||
|
s_subscribers[available_slot].fn = fn;
|
||||||
|
s_subscribers[available_slot].threshold = threshold;
|
||||||
|
return ULOG_ERR_NONE;
|
||||||
|
}
|
||||||
|
|
||||||
|
// search the s_subscribers table to remove
|
||||||
|
ulog_err_t ulog_unsubscribe(ulog_function_t fn)
|
||||||
|
{
|
||||||
|
int i;
|
||||||
|
for (i = 0; i < ULOG_MAX_SUBSCRIBERS; i++)
|
||||||
|
{
|
||||||
|
if (s_subscribers[i].fn == fn)
|
||||||
|
{
|
||||||
|
s_subscribers[i].fn = NULL; // mark as empty
|
||||||
|
return ULOG_ERR_NONE;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return ULOG_ERR_NOT_SUBSCRIBED;
|
||||||
|
}
|
||||||
|
|
||||||
|
const char *ulog_level_name(ulog_level_t severity)
|
||||||
|
{
|
||||||
|
switch (severity)
|
||||||
|
{
|
||||||
|
case ULOG_TRACE_LEVEL:
|
||||||
|
return "TRACE";
|
||||||
|
case ULOG_DEBUG_LEVEL:
|
||||||
|
return "DEBUG";
|
||||||
|
case ULOG_INFO_LEVEL:
|
||||||
|
return "INFO";
|
||||||
|
case ULOG_WARNING_LEVEL:
|
||||||
|
return "WARNING";
|
||||||
|
case ULOG_ERROR_LEVEL:
|
||||||
|
return "ERROR";
|
||||||
|
case ULOG_CRITICAL_LEVEL:
|
||||||
|
return "CRITICAL";
|
||||||
|
case ULOG_ALWAYS_LEVEL:
|
||||||
|
return "ALWAYS";
|
||||||
|
default:
|
||||||
|
return "UNKNOWN";
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void ulog_message(ulog_level_t severity, const char *fmt, ...)
|
||||||
|
{
|
||||||
|
va_list ap;
|
||||||
|
int i;
|
||||||
|
va_start(ap, fmt);
|
||||||
|
vsnprintf(s_message, ULOG_MAX_MESSAGE_LENGTH, fmt, ap);
|
||||||
|
va_end(ap);
|
||||||
|
|
||||||
|
for (i = 0; i < ULOG_MAX_SUBSCRIBERS; i++)
|
||||||
|
{
|
||||||
|
if (s_subscribers[i].fn != NULL)
|
||||||
|
{
|
||||||
|
if (severity >= s_subscribers[i].threshold)
|
||||||
|
{
|
||||||
|
s_subscribers[i].fn(severity, s_message);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// =============================================================================
|
||||||
|
// private code
|
||||||
|
|
||||||
|
#endif // #ifdef ULOG_ENABLED
|
||||||
188
firmware/shared_libs/utils/ulog/ulog.h
Normal file
188
firmware/shared_libs/utils/ulog/ulog.h
Normal file
@@ -0,0 +1,188 @@
|
|||||||
|
/**
|
||||||
|
MIT License
|
||||||
|
|
||||||
|
Copyright (c) 2019 R. Dunbar Poor <rdpoor@gmail.com>
|
||||||
|
|
||||||
|
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.
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \file
|
||||||
|
*
|
||||||
|
* \brief uLog: lightweight logging for embedded systems
|
||||||
|
*
|
||||||
|
* A quick intro by example:
|
||||||
|
*
|
||||||
|
* #include "ulog.h"
|
||||||
|
*
|
||||||
|
* // To use uLog, you must define a function to process logging messages.
|
||||||
|
* // It can write the messages to a console, to a file, to an in-memory
|
||||||
|
* // buffer: the choice is yours. And you get to choose the format of
|
||||||
|
* // the message. This example prints to the console. One caveat: msg
|
||||||
|
* // is a static string and will be over-written at the next call to ULOG.
|
||||||
|
* // You may print it or copy it, but saving a pointer to it will lead to
|
||||||
|
* // confusion and astonishment.
|
||||||
|
* //
|
||||||
|
* void my_console_logger(ulog_level_t level, const char *msg) {
|
||||||
|
* printf("%s [%s]: %s\n",
|
||||||
|
* get_timestamp(),
|
||||||
|
* ulog_level_name(level),
|
||||||
|
* msg);
|
||||||
|
* }
|
||||||
|
*
|
||||||
|
* int main() {
|
||||||
|
* ULOG_INIT();
|
||||||
|
*
|
||||||
|
* // log to the console messages that are WARNING or more severe. You
|
||||||
|
* // can re-subscribe at any point to change the severity level.
|
||||||
|
* ULOG_SUBSCRIBE(my_console_logger, ULOG_WARNING);
|
||||||
|
*
|
||||||
|
* // log to a file messages that are DEBUG or more severe
|
||||||
|
* ULOG_SUBSCRIBE(my_file_logger, ULOG_DEBUG);
|
||||||
|
*
|
||||||
|
* int arg = 42;
|
||||||
|
* ULOG_INFO("Arg is %d", arg); // logs to file but not console
|
||||||
|
* }
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef ULOG_H_
|
||||||
|
#define ULOG_H_
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C"
|
||||||
|
{
|
||||||
|
#endif
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
ULOG_TRACE_LEVEL = 100,
|
||||||
|
ULOG_DEBUG_LEVEL,
|
||||||
|
ULOG_INFO_LEVEL,
|
||||||
|
ULOG_WARNING_LEVEL,
|
||||||
|
ULOG_ERROR_LEVEL,
|
||||||
|
ULOG_CRITICAL_LEVEL,
|
||||||
|
ULOG_ALWAYS_LEVEL
|
||||||
|
} ulog_level_t;
|
||||||
|
|
||||||
|
// The following macros enable or disable uLog. If `ULOG_ENABLED` is
|
||||||
|
// defined at compile time, a macro such as `ULOG_INFO(...)` expands
|
||||||
|
// into `ulog_message(ULOG_INFO_LEVEL, ...)`. If `ULOG_ENABLED` is not
|
||||||
|
// defined, then the same macro expands into `do {} while(0)` and will
|
||||||
|
// not generate any code at all.
|
||||||
|
//
|
||||||
|
// There are two ways to enable uLog: you can uncomment the following
|
||||||
|
// line, or -- if it is commented out -- you can add -DULOG_ENABLED to
|
||||||
|
// your compiler switches.
|
||||||
|
// #define ULOG_ENABLED
|
||||||
|
|
||||||
|
#ifdef ULOG_ENABLED
|
||||||
|
#define ULOG_INIT() ulog_init()
|
||||||
|
#define ULOG_SUBSCRIBE(a, b) ulog_subscribe(a, b)
|
||||||
|
#define ULOG_UNSUBSCRIBE(a) ulog_unsubscribe(a)
|
||||||
|
#define ULOG_LEVEL_NAME(a) ulog_level_name(a)
|
||||||
|
#define ULOG(...) ulog_message(__VA_ARGS__)
|
||||||
|
#define ULOG_TRACE(...) ulog_message(ULOG_TRACE_LEVEL, __VA_ARGS__)
|
||||||
|
#define ULOG_DEBUG(...) ulog_message(ULOG_DEBUG_LEVEL, __VA_ARGS__)
|
||||||
|
#define ULOG_INFO(...) ulog_message(ULOG_INFO_LEVEL, __VA_ARGS__)
|
||||||
|
#define ULOG_WARNING(...) ulog_message(ULOG_WARNING_LEVEL, __VA_ARGS__)
|
||||||
|
#define ULOG_ERROR(...) ulog_message(ULOG_ERROR_LEVEL, __VA_ARGS__)
|
||||||
|
#define ULOG_CRITICAL(...) ulog_message(ULOG_CRITICAL_LEVEL, __VA_ARGS__)
|
||||||
|
#define ULOG_ALWAYS(...) ulog_message(ULOG_ALWAYS_LEVEL, __VA_ARGS__)
|
||||||
|
#else
|
||||||
|
// uLog vanishes when disabled at compile time...
|
||||||
|
#define ULOG_INIT() \
|
||||||
|
do \
|
||||||
|
{ \
|
||||||
|
} while (0)
|
||||||
|
#define ULOG_SUBSCRIBE(a, b) \
|
||||||
|
do \
|
||||||
|
{ \
|
||||||
|
} while (0)
|
||||||
|
#define ULOG_UNSUBSCRIBE(a) \
|
||||||
|
do \
|
||||||
|
{ \
|
||||||
|
} while (0)
|
||||||
|
#define ULOG_LEVEL_NAME(a) \
|
||||||
|
do \
|
||||||
|
{ \
|
||||||
|
} while (0)
|
||||||
|
#define ULOG(s, f, ...) \
|
||||||
|
do \
|
||||||
|
{ \
|
||||||
|
} while (0)
|
||||||
|
#define ULOG_TRACE(f, ...) \
|
||||||
|
do \
|
||||||
|
{ \
|
||||||
|
} while (0)
|
||||||
|
#define ULOG_DEBUG(f, ...) \
|
||||||
|
do \
|
||||||
|
{ \
|
||||||
|
} while (0)
|
||||||
|
#define ULOG_INFO(f, ...) \
|
||||||
|
do \
|
||||||
|
{ \
|
||||||
|
} while (0)
|
||||||
|
#define ULOG_WARNING(f, ...) \
|
||||||
|
do \
|
||||||
|
{ \
|
||||||
|
} while (0)
|
||||||
|
#define ULOG_ERROR(f, ...) \
|
||||||
|
do \
|
||||||
|
{ \
|
||||||
|
} while (0)
|
||||||
|
#define ULOG_CRITICAL(f, ...) \
|
||||||
|
do \
|
||||||
|
{ \
|
||||||
|
} while (0)
|
||||||
|
#define ULOG_ALWAYS(f, ...) \
|
||||||
|
do \
|
||||||
|
{ \
|
||||||
|
} while (0)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
typedef enum
|
||||||
|
{
|
||||||
|
ULOG_ERR_NONE = 0,
|
||||||
|
ULOG_ERR_SUBSCRIBERS_EXCEEDED,
|
||||||
|
ULOG_ERR_NOT_SUBSCRIBED,
|
||||||
|
} ulog_err_t;
|
||||||
|
|
||||||
|
// define the maximum number of concurrent subscribers
|
||||||
|
#ifndef ULOG_MAX_SUBSCRIBERS
|
||||||
|
#define ULOG_MAX_SUBSCRIBERS 6
|
||||||
|
#endif
|
||||||
|
// maximum length of formatted log message
|
||||||
|
#ifndef ULOG_MAX_MESSAGE_LENGTH
|
||||||
|
#define ULOG_MAX_MESSAGE_LENGTH 120
|
||||||
|
#endif
|
||||||
|
/**
|
||||||
|
* @brief: prototype for uLog subscribers.
|
||||||
|
*/
|
||||||
|
typedef void (*ulog_function_t)(ulog_level_t severity, char *msg);
|
||||||
|
|
||||||
|
void ulog_init(void);
|
||||||
|
ulog_err_t ulog_subscribe(ulog_function_t fn, ulog_level_t threshold);
|
||||||
|
ulog_err_t ulog_unsubscribe(ulog_function_t fn);
|
||||||
|
const char *ulog_level_name(ulog_level_t level);
|
||||||
|
void ulog_message(ulog_level_t severity, const char *fmt, ...);
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif /* ULOG_H_ */
|
||||||
Reference in New Issue
Block a user