调整驱动

This commit is contained in:
许晟昊 2024-12-31 16:43:37 +08:00
parent 8064eae0d9
commit 452c229a55
871 changed files with 241643 additions and 2393 deletions

View File

@ -38,7 +38,10 @@
"C_Cpp_Runner.compilerArgs": [],
"C_Cpp_Runner.linkerArgs": [],
"C_Cpp_Runner.includePaths": [],
"C_Cpp_Runner.includeSearch": ["*", "**/*"],
"C_Cpp_Runner.includeSearch": [
"*",
"**/*"
],
"C_Cpp_Runner.excludeSearch": [
"**/build",
"**/build/**",
@ -54,4 +57,4 @@
"C_Cpp_Runner.useLinkTimeOptimization": false,
"C_Cpp_Runner.msvcSecureNoWarnings": false,
"C_Cpp.errorSquiggles": "disabled"
}
}

View File

@ -1,5 +1,8 @@
#include "main.h"
#include "stm32l4xx_ll_pwr.h"
#include "stm32l4xx_ll_bus.h"
#include "stm32l4xx_ll_exti.h"
#include "stm32l4xx_ll_system.h"
#include "bsp.h"
#define EXIT_LINE LL_EXTI_LINE_16
@ -31,8 +34,8 @@ void pvd_configuration(uint32_t pwr_level, pvd_irq_handle_cb call)
LL_EXTI_EnableFallingTrig_0_31(EXIT_LINE);
// 启用PVD中断向量
// NVIC_EnableIRQ(PVD_PVM_IRQn);
// NVIC_SetPriority(PVD_PVM_IRQn, 0);
NVIC_EnableIRQ(PVD_PVM_IRQn);
NVIC_SetPriority(PVD_PVM_IRQn, 0);
}
/**
@ -65,27 +68,27 @@ void pvd_irq_handle(void)
*/
void disable_debug_interface(void)
{
// // 使能 SYSCFG 时钟
// LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_SYSCFG);
// 使能 SYSCFG 时钟
LL_APB2_GRP1_EnableClock(LL_APB2_GRP1_PERIPH_SYSCFG);
// // 关闭调试接口
// LL_DBGMCU_DisableDBGStopMode();
// LL_DBGMCU_DisableDBGStandbyMode();
// LL_DBGMCU_DisableDBGSleepMode();
// 关闭调试接口
LL_DBGMCU_DisableDBGStopMode();
LL_DBGMCU_DisableDBGStandbyMode();
LL_DBGMCU_DisableDBGSleepMode();
// // 关闭 SWD 和 JTAG 接口
// LL_GPIO_InitTypeDef GPIO_InitStruct = {0};
// 关闭 SWD 和 JTAG 接口
LL_GPIO_InitTypeDef GPIO_InitStruct = {0};
// // 配置 SWDIO (PA13) 和 SWCLK (PA14) 引脚为普通 GPIO
// GPIO_InitStruct.Pin = LL_GPIO_PIN_13 | LL_GPIO_PIN_14;
// GPIO_InitStruct.Mode = LL_GPIO_MODE_ANALOG;
// GPIO_InitStruct.Pull = LL_GPIO_PULL_NO;
// LL_GPIO_Init(GPIOA, &GPIO_InitStruct);
// 配置 SWDIO (PA13) 和 SWCLK (PA14) 引脚为普通 GPIO
GPIO_InitStruct.Pin = LL_GPIO_PIN_13 | LL_GPIO_PIN_14;
GPIO_InitStruct.Mode = LL_GPIO_MODE_ANALOG;
GPIO_InitStruct.Pull = LL_GPIO_PULL_NO;
LL_GPIO_Init(GPIOA, &GPIO_InitStruct);
// // 如果使用的是 JTAG 接口,还需要配置 JTDI (PA15), JTDO (PB3), 和 NJTRST (PB4) 引脚
// GPIO_InitStruct.Pin = LL_GPIO_PIN_15;
// LL_GPIO_Init(GPIOA, &GPIO_InitStruct);
// 如果使用的是 JTAG 接口,还需要配置 JTDI (PA15), JTDO (PB3), 和 NJTRST (PB4) 引脚
GPIO_InitStruct.Pin = LL_GPIO_PIN_15;
LL_GPIO_Init(GPIOA, &GPIO_InitStruct);
// GPIO_InitStruct.Pin = LL_GPIO_PIN_3 | LL_GPIO_PIN_4;
// LL_GPIO_Init(GPIOB, &GPIO_InitStruct);
GPIO_InitStruct.Pin = LL_GPIO_PIN_3 | LL_GPIO_PIN_4;
LL_GPIO_Init(GPIOB, &GPIO_InitStruct);
}

View File

@ -11,17 +11,18 @@
*/
#ifndef __BSP_H__
#define __BSP_H__
#include "dma.h"
#include "gpios.h"
// #include "adcs.h"
// #include "dacs.h"
#include "dmas.h"
#include "adcs.h"
#include "dacs.h"
#include "tims.h"
#include "pwms.h"
#include "uarts.h"
#include "eeprom.h"
#include "spis.h"
#include "i2cs.h"
// #include "eeprom.h"
///< 定义回调函数类型
typedef void (*pvd_irq_handle_cb)(void);

View File

@ -1,5 +1,5 @@
#ifndef __DMAS_H__
#define __DMAS_H__
#ifndef __DMA_H__
#define __DMA_H__
/**
* @brief DMA传输完成标志
@ -132,4 +132,4 @@
} \
} while (__LINE__ == -1)
#endif // __DMAS_H__
#endif // __DMA_H__

View File

@ -44,11 +44,11 @@ static uint8_t _read(gpio_t gpio)
/**
* @brief GPIO对象
* @param {GPIO_TypeDef} *port - GPIO寄存器指针
* @param {uint32_t} pin -
* @param {uint16_t} pin -
* @return {gpio_t *} - GPIO对象指针
* @note: GPIO对象GPIO功能
*/
gpio_t *gpio_create(GPIO_TypeDef *port, uint32_t pin)
gpio_t *gpio_create(GPIO_TypeDef *port, uint16_t pin)
{
gpio_t *gpio = (gpio_t *)osel_mem_alloc(sizeof(gpio_t));
DBG_ASSERT(gpio != NULL __DBG_LINE);

View File

@ -14,7 +14,6 @@
#define __GPIOS_H__
#include "lib.h"
#include "main.h"
/**
* @brief Set the GPIO pin to high.
*
@ -94,7 +93,7 @@
typedef struct GPIO
{
GPIO_TypeDef *port; ///< The GPIO port.
uint32_t pin; ///< The GPIO pin.
uint16_t pin; ///< The GPIO pin.
/**
* @brief Set the GPIO pin to high.
@ -133,7 +132,7 @@ typedef struct GPIO
* @param pin The GPIO pin.
* @return The created GPIO pin.
*/
extern gpio_t *gpio_create(GPIO_TypeDef *port, uint32_t pin);
extern gpio_t *gpio_create(GPIO_TypeDef *port, uint16_t pin);
/**
* @brief Free the memory allocated for a GPIO pin.

View File

@ -20,7 +20,7 @@
* @file i2cs.h
* @brief Header file containing the definition of the I2C slave (I2CS) structure and related functions.
*/
typedef struct GPIO gpio_t;
typedef struct I2CS i2c_t;
typedef void i2cs_dma_callback(i2c_t *handle);

View File

@ -1 +0,0 @@
#include "pwms.h"

View File

@ -39,11 +39,6 @@
LL_TIM_CC_DisableChannel(TIMx, CHx); \
} while (__LINE__ == -1)
#define PWM_GET_ARR(TIMx) LL_TIM_GetAutoReload(TIMx)
#define PWM_SET_ARR(TIMx, ARR) LL_TIM_SetAutoReload(TIMx, ARR - 1)
#define PWM_GET_PSC(TIMx) LL_TIM_GetPrescaler(TIMx)
#define PWM_SET_PSC(TIMx, PSC) LL_TIM_SetPrescaler(TIMx, PSC - 1)
/**
* @brief Sets the PWM frequency
* @param TIMx: TIM instance
@ -92,30 +87,4 @@ static inline uint32_t PWM_GET_FREQ(TIM_TypeDef *TIMx)
return SystemCoreClock / (LL_TIM_GetPrescaler(TIMx) + 1) / (LL_TIM_GetAutoReload(TIMx) + 1);
}
/**
* @brief PWM比较值
*
* PWM比较值
*
* @param TIMx TIM_TypeDef结构体
* @param CHx LL_TIM_CHANNEL_CH1到LL_TIM_CHANNEL_CH4
*
* @return uint16_t类型的值PWM比较值0
*/
static inline uint16_t PWM_GET_COMPARE(TIM_TypeDef *TIMx, uint32_t CHx)
{
switch (CHx)
{
case LL_TIM_CHANNEL_CH1:
return LL_TIM_OC_GetCompareCH1(TIMx);
case LL_TIM_CHANNEL_CH2:
return LL_TIM_OC_GetCompareCH2(TIMx);
case LL_TIM_CHANNEL_CH3:
return LL_TIM_OC_GetCompareCH3(TIMx);
case LL_TIM_CHANNEL_CH4:
return LL_TIM_OC_GetCompareCH4(TIMx);
default:
return 0;
}
}
#endif ///< __PWMS_H__

View File

@ -1,7 +1,7 @@
#include "spis.h"
#include "delay.h"
#define SPI_TIMEOUT 0xffffffff
#define SPI_TIMEOUT 2000
#define CMD_RDSR 0x05 /*!< Read Status Register instruction */
#define CMD_WRSR 0x01 /*!< Write Status Register instruction */
@ -460,10 +460,6 @@ static uint8_t spi_read_write_byte(spi_t *handle, uint8_t tx_data)
}
else
{
if (spi_wait_flag(handle, LL_SPI_SR_TXE, SPI_TIMEOUT) == FALSE)
{
return 0xff;
}
LL_SPI_TransmitData8(handle->spi, tx_data);
if (spi_wait_flag(handle, LL_SPI_SR_RXNE, SPI_TIMEOUT) == FALSE)
@ -677,7 +673,7 @@ static BOOL spi_read(spi_t *handle, uint32_t read_addr, uint8_t *data, uint16_t
return FALSE;
}
}
else if (handle->cfg.address_bytes == 3)
else
{
cnt = handle->interface.u.normal.spi_send(handle, read_addr >> 16);
if (cnt == 0)
@ -695,10 +691,6 @@ static BOOL spi_read(spi_t *handle, uint32_t read_addr, uint8_t *data, uint16_t
return FALSE;
}
}
else
{
DBG_ASSERT(FALSE __DBG_LINE);
}
for (uint16_t i = 0; i < length; i++) // 循环读取数据
{
data[i] = handle->interface.u.normal.spi_send(handle, handle->cfg.dummy_byte); // 发送空字节,读取实际数据

View File

@ -19,7 +19,6 @@
#define SPI_ENABLE(SPIX) LL_SPI_Enable(SPIX)
typedef struct GPIO gpio_t;
typedef struct SPIS spi_t;
typedef void spis_dma_callback(spi_t *handle);

View File

@ -19,6 +19,19 @@ Given Tclk as 84MHz, we need Tout to be 200ms or 200000us. Let's assume PSC is 8
With these calculated values, both ARR and PSC are within the range of 0 to 65535, so we can use this parameter set.
*/
#define ENABLE_TIM_COUNT(TIMx) \
do \
{ \
LL_TIM_EnableCounter(TIMx); \
} while (__LINE__ == -1);
#define RESET_TIM_COUNT(TIMx) \
do \
{ \
LL_TIM_DisableCounter(TIMx); \
LL_TIM_SetCounter(TIMx, 0); \
LL_TIM_EnableCounter(TIMx); \
} while (__LINE__ == -1);
/**
* @brief Enables the specified TIMx.
* @param TIMx TIM instance.
@ -112,5 +125,4 @@ With these calculated values, both ARR and PSC are within the range of 0 to 6553
* @return
*/
#define TIM_CYCLE(TIMx) ((LL_TIM_GetAutoReload(TIMx) + 1) * 0.1)
#endif ///< __TIMS_H__

View File

@ -104,7 +104,7 @@ void uart_recv_en(uart_t *uart, BOOL rx_err_en)
LL_DMA_DisableChannel(uart->dma, uart->dma_rx_channel);
// 配置RX DMA
LL_DMA_SetPeriphAddress(uart->dma, uart->dma_rx_channel, LL_USART_DMA_GetRegAddr(uart->huart));
LL_DMA_SetPeriphAddress(uart->dma, uart->dma_rx_channel, LL_USART_DMA_GetRegAddr(uart->huart, LL_USART_DMA_REG_DATA_RECEIVE));
LL_DMA_SetMemoryAddress(uart->dma, uart->dma_rx_channel, (uint32_t)uart->rxbuf);
LL_DMA_SetDataLength(uart->dma, uart->dma_rx_channel, uart->rxsize);
LL_DMA_EnableIT_TC(uart->dma, uart->dma_rx_channel);
@ -113,7 +113,7 @@ void uart_recv_en(uart_t *uart, BOOL rx_err_en)
LL_USART_EnableIT_IDLE(uart->huart);
// 配置TX DMA
LL_DMA_SetPeriphAddress(uart->dma, uart->dma_tx_channel, LL_USART_DMA_GetRegAddr(uart->huart));
LL_DMA_SetPeriphAddress(uart->dma, uart->dma_tx_channel, LL_USART_DMA_GetRegAddr(uart->huart, LL_USART_DMA_REG_DATA_TRANSMIT));
// 配置内存地址
LL_DMA_SetMemoryAddress(uart->dma, uart->dma_tx_channel, (uint32_t)uart->txbuf);
LL_DMA_EnableIT_TC(uart->dma, uart->dma_tx_channel);
@ -178,7 +178,7 @@ void uart_free(uart_t *uart)
*/
void uart_set_baudrate(USART_TypeDef *uart, uint32_t baudrate)
{
LL_USART_SetBaudRate(uart, SystemCoreClock, LL_USART_OVERSAMPLING_16);
LL_USART_SetBaudRate(uart, SystemCoreClock, LL_USART_OVERSAMPLING_16, baudrate);
}
/**

2
btn.c
View File

@ -8,7 +8,7 @@
* Copyright (c) 2023 by xxx, All Rights Reserved.
*/
#include "../inc/btn.h"
#include "btn.h"
#define EVENT_CB(ev) \
if (handle->cb[ev]) \

4
btn.h
View File

@ -47,8 +47,8 @@ while(1) {
// 根据您的需求修改常量。
#define TICKS_INTERVAL 10 // 按钮扫描间隔单位ms
#define DEBOUNCE_TICKS 30 / TICKS_INTERVAL // 按键去抖动时间单位ms
#define SHORT_TICKS (30 / TICKS_INTERVAL) // 短按时间阈值单位ms
#define DEBOUNCE_TICKS 20 / TICKS_INTERVAL // 按键去抖动时间单位ms
#define SHORT_TICKS (100 / TICKS_INTERVAL) // 短按时间阈值单位ms
#define LONG_TICKS (500 / TICKS_INTERVAL) // 长按时间阈值单位ms
typedef void (*BtnCallback)(void *);

View File

@ -9,6 +9,7 @@
*/
#include "delay.h"
// static uint16_t g_fac_ms = 0; // ms延时倍乘数,在os下,代表每个节拍的ms数
static uint32_t g_fac_us = 0; /* us延时倍乘数 */
@ -79,6 +80,13 @@ void delay_us(uint32_t nus)
}
}
void delay_hardware_us(TIM_TypeDef *timer_us, uint32_t us)
{
RESET_TIM_COUNT(timer_us);
while (LL_TIM_GetCounter(timer_us) < us)
; // 等待计数器达到指定值
}
/**
* @brief nms
* @param nms: ms数 (0< nms <= 65535)

10
delay.h
View File

@ -12,10 +12,12 @@
#define __DELAY_H
#include "sys.h"
#include "tims.h"
void delay_init(uint16_t sysclk); /* 初始化延迟函数 */
void delay_ms(uint16_t nms); /* 延时nms */
void delay_us(uint32_t nus); /* 延时nus */
void delay_tick(uint32_t ticks); /* 延时ticks */
void delay_init(uint16_t sysclk); /* 初始化延迟函数 */
void delay_ms(uint16_t nms); /* 延时nms */
void delay_us(uint32_t nus); /* 延时nus */
void delay_hardware_us(TIM_TypeDef *timer_us, uint32_t us); /* 硬件延时nus */
void delay_tick(uint32_t ticks); /* 延时ticks */
#endif

View File

@ -1,36 +1,34 @@
#include "dac161p997.h"
#include "tims.h"
#include "delay.h"
static dac161p997_t _handle;
static void delay_us(uint32_t us)
static void _delay_us(uint32_t us)
{
RESET_TIM_COUNT(TIME_1US);
while (LL_TIM_GetCounter(TIME_1US) < us)
; // 等待计数器达到指定值
delay_hardware_us(_handle.timer_us, us);
}
static void dac161p997_output_0()
{
_handle.io->set(*_handle.io);
delay_us(DUTY_CYCLE_25);
_delay_us(DUTY_CYCLE_25);
_handle.io->reset(*_handle.io);
delay_us(DUTY_CYCLE_75);
_delay_us(DUTY_CYCLE_75);
}
static void dac161p997_output_1()
{
_handle.io->set(*_handle.io);
delay_us(DUTY_CYCLE_75);
_delay_us(DUTY_CYCLE_75);
_handle.io->reset(*_handle.io);
delay_us(DUTY_CYCLE_25);
_delay_us(DUTY_CYCLE_25);
}
static void dac161p997_output_d()
{
_handle.io->set(*_handle.io);
delay_us(DUTY_CYCLE_50);
_delay_us(DUTY_CYCLE_50);
_handle.io->reset(*_handle.io);
delay_us(DUTY_CYCLE_50);
_delay_us(DUTY_CYCLE_50);
}
/**
@ -144,9 +142,11 @@ void dac161p997_output_current(float32 current)
* 2. DAC161的错误下限寄存器
* 3. DAC161的配置寄存器
*/
void dac161p997_init()
void dac161p997_init(TIM_TypeDef *timer_us)
{
ENABLE_TIM_COUNT(TIME_1US);
DBG_ASSERT(timer_us != NULL __DBG_LINE);
_handle.timer_us = timer_us;
ENABLE_TIM_COUNT(_handle.timer_us);
_handle.io = gpio_create(DAC161P997_IO_PORT, DAC161P997_IO_PIN);
dac161p997_swif_write_reg(DAC161P997_LCK_REG + DAC161P997_LCK_REG_UNLOCK, CONFIG_WRITE);
dac161p997_swif_write_reg(DAC161P997_CONFIG2_REG, CONFIG_WRITE);

View File

@ -2,7 +2,7 @@
#define __DAC161P997_H__
#include "main.h"
#include "gpios.h"
#define TIME_1US TIM1
#define DAC161P997_IO_PORT (DAC161P997_GPIO_Port)
#define DAC161P997_IO_PIN (DAC161P997_Pin)
@ -67,6 +67,7 @@ typedef enum
} dac161p997_e;
typedef struct
{
TIM_TypeDef *timer_us;
gpio_t *io;
uint8_t count;
} dac161p997_t;
@ -78,5 +79,5 @@ void dac161p997_output_symbol(uint8_t sym);
void dac161p997_swif_write_reg(uint16_t data, uint8_t tag);
extern void dac161p997_output_current(float32 current);
extern void dac161p997_init(void);
extern void dac161p997_init(TIM_TypeDef *timer_us);
#endif

View File

@ -11,7 +11,20 @@
#define EEPROM_LC02B_SCL_PORT I2C1_SCL_GPIO_Port
#define EEPROM_LC02B_SCL_PIN I2C1_SCL_Pin
static i2c_t *eeprom_24lc028bt_i2c;
static i2c_t *_eeprom_24lc028bt_i2c;
static TIM_TypeDef *_timer_us;
static void _delay_us(uint32_t us)
{
if (_timer_us != NULL)
{
delay_hardware_us(_timer_us, us);
}
else
{
delay_us(us);
}
}
void eeprom_lc02b_test(void)
{
@ -24,7 +37,7 @@ void eeprom_lc02b_test(void)
}
eeprom_lc02b_write(test_address, buf, TEST_SIZE);
LL_mDelay(10);
_delay_us(10000);
osel_memset(buf, 0, ARRAY_LEN(buf));
eeprom_lc02b_read(test_address, buf, TEST_SIZE);
@ -49,13 +62,19 @@ BOOL eeprom_lc02b_status_get(void)
* @return {*}
* @note
*/
void eeprom_lc02b_init(void)
void eeprom_lc02b_init(TIM_TypeDef *timer_us)
{
if (timer_us != NULL)
{
_timer_us = timer_us;
ENABLE_TIM_COUNT(_timer_us);
}
i2c_gpio_group_t gpios;
gpios.scl = gpio_create(EEPROM_LC02B_SCL_PORT, EEPROM_LC02B_SCL_PIN);
gpios.sda = gpio_create(EEPROM_LC02B_SDA_PORT, EEPROM_LC02B_SDA_PIN);
eeprom_24lc028bt_i2c = i2c_create(gpios, 10);
_eeprom_24lc028bt_i2c = i2c_create(gpios, 10);
// eeprom_lc02b_test();
}
@ -80,37 +99,37 @@ void eeprom_lc02b_dinit(void)
void eeprom_lc02b_write(uint32_t write_addr, uint8_t *data, uint16_t length)
{
// 发送开始信号
eeprom_24lc028bt_i2c->interface.start(eeprom_24lc028bt_i2c);
_eeprom_24lc028bt_i2c->interface.start(_eeprom_24lc028bt_i2c);
// 发送写入地址命令
eeprom_24lc028bt_i2c->interface.write_byte(eeprom_24lc028bt_i2c, W_ADD_COM);
_eeprom_24lc028bt_i2c->interface.write_byte(_eeprom_24lc028bt_i2c, W_ADD_COM);
// 等待写入地址命令响应
eeprom_24lc028bt_i2c->interface.wait_ack(eeprom_24lc028bt_i2c);
_eeprom_24lc028bt_i2c->interface.wait_ack(_eeprom_24lc028bt_i2c);
// 发送要写入的地址
eeprom_24lc028bt_i2c->interface.write_byte(eeprom_24lc028bt_i2c, (uint8_t)write_addr);
eeprom_24lc028bt_i2c->interface.wait_ack(eeprom_24lc028bt_i2c);
_eeprom_24lc028bt_i2c->interface.write_byte(_eeprom_24lc028bt_i2c, (uint8_t)write_addr);
_eeprom_24lc028bt_i2c->interface.wait_ack(_eeprom_24lc028bt_i2c);
// 循环写入数据
for (uint16_t i = 0; i < length; i++)
{
// 写入一个字节数据
eeprom_24lc028bt_i2c->interface.write_byte(eeprom_24lc028bt_i2c, *data++);
_eeprom_24lc028bt_i2c->interface.write_byte(_eeprom_24lc028bt_i2c, *data++);
// 等待响应
eeprom_24lc028bt_i2c->interface.wait_ack(eeprom_24lc028bt_i2c);
_eeprom_24lc028bt_i2c->interface.wait_ack(_eeprom_24lc028bt_i2c);
write_addr++;
if (write_addr % PAGE_SIZE == 0)
{
eeprom_24lc028bt_i2c->interface.stop(eeprom_24lc028bt_i2c);
LL_mDelay(10); // 延时10ms等待写入完成
eeprom_24lc028bt_i2c->interface.start(eeprom_24lc028bt_i2c);
eeprom_24lc028bt_i2c->interface.write_byte(eeprom_24lc028bt_i2c, W_ADD_COM);
eeprom_24lc028bt_i2c->interface.wait_ack(eeprom_24lc028bt_i2c);
eeprom_24lc028bt_i2c->interface.write_byte(eeprom_24lc028bt_i2c, (uint8_t)write_addr);
eeprom_24lc028bt_i2c->interface.wait_ack(eeprom_24lc028bt_i2c);
_eeprom_24lc028bt_i2c->interface.stop(_eeprom_24lc028bt_i2c);
_delay_us(10000); // 延时10ms等待写入完成
_eeprom_24lc028bt_i2c->interface.start(_eeprom_24lc028bt_i2c);
_eeprom_24lc028bt_i2c->interface.write_byte(_eeprom_24lc028bt_i2c, W_ADD_COM);
_eeprom_24lc028bt_i2c->interface.wait_ack(_eeprom_24lc028bt_i2c);
_eeprom_24lc028bt_i2c->interface.write_byte(_eeprom_24lc028bt_i2c, (uint8_t)write_addr);
_eeprom_24lc028bt_i2c->interface.wait_ack(_eeprom_24lc028bt_i2c);
}
}
// 写入完成停止I2C总线
eeprom_24lc028bt_i2c->interface.stop(eeprom_24lc028bt_i2c);
_eeprom_24lc028bt_i2c->interface.stop(_eeprom_24lc028bt_i2c);
}
/**
@ -124,29 +143,29 @@ void eeprom_lc02b_write(uint32_t write_addr, uint8_t *data, uint16_t length)
void eeprom_lc02b_read(uint32_t read_addr, uint8_t *data, uint16_t length)
{
// 发送开始信号
eeprom_24lc028bt_i2c->interface.start(eeprom_24lc028bt_i2c);
_eeprom_24lc028bt_i2c->interface.start(_eeprom_24lc028bt_i2c);
// 发送写入地址命令
eeprom_24lc028bt_i2c->interface.write_byte(eeprom_24lc028bt_i2c, W_ADD_COM);
_eeprom_24lc028bt_i2c->interface.write_byte(_eeprom_24lc028bt_i2c, W_ADD_COM);
// 等待写入地址命令响应
eeprom_24lc028bt_i2c->interface.wait_ack(eeprom_24lc028bt_i2c);
_eeprom_24lc028bt_i2c->interface.wait_ack(_eeprom_24lc028bt_i2c);
// 发送要读取的地址
eeprom_24lc028bt_i2c->interface.write_byte(eeprom_24lc028bt_i2c, (uint8_t)read_addr);
eeprom_24lc028bt_i2c->interface.wait_ack(eeprom_24lc028bt_i2c);
_eeprom_24lc028bt_i2c->interface.write_byte(_eeprom_24lc028bt_i2c, (uint8_t)read_addr);
_eeprom_24lc028bt_i2c->interface.wait_ack(_eeprom_24lc028bt_i2c);
// 发送开始信号
eeprom_24lc028bt_i2c->interface.start(eeprom_24lc028bt_i2c);
_eeprom_24lc028bt_i2c->interface.start(_eeprom_24lc028bt_i2c);
// 发送读取地址命令
eeprom_24lc028bt_i2c->interface.write_byte(eeprom_24lc028bt_i2c, R_ADD_COM);
_eeprom_24lc028bt_i2c->interface.write_byte(_eeprom_24lc028bt_i2c, R_ADD_COM);
// 等待读取地址命令响应
eeprom_24lc028bt_i2c->interface.wait_ack(eeprom_24lc028bt_i2c);
_eeprom_24lc028bt_i2c->interface.wait_ack(_eeprom_24lc028bt_i2c);
// 循环读取数据
for (uint16_t i = 0; i < length - 1; i++)
{
// 读取一个字节数据
*data++ = eeprom_24lc028bt_i2c->interface.read_byte(eeprom_24lc028bt_i2c, TRUE);
*data++ = _eeprom_24lc028bt_i2c->interface.read_byte(_eeprom_24lc028bt_i2c, TRUE);
}
*data++ = eeprom_24lc028bt_i2c->interface.read_byte(eeprom_24lc028bt_i2c, FALSE);
*data++ = _eeprom_24lc028bt_i2c->interface.read_byte(_eeprom_24lc028bt_i2c, FALSE);
// 停止I2C总线
eeprom_24lc028bt_i2c->interface.stop(eeprom_24lc028bt_i2c);
_eeprom_24lc028bt_i2c->interface.stop(_eeprom_24lc028bt_i2c);
}

View File

@ -15,7 +15,7 @@
/**
* @brief Initializes the LC02B EEPROM module.
*/
void eeprom_lc02b_init(void);
void eeprom_lc02b_init(TIM_TypeDef *timer_us);
/**
* @brief Deinitializes the LC02B EEPROM module.

View File

@ -16,6 +16,19 @@
#define RTC_RX8010_SCL_PIN RTC_SCL_Pin
static i2c_t *rtc;
static TIM_TypeDef *_timer_us;
static void _delay_us(uint32_t us)
{
if (_timer_us != NULL)
{
delay_hardware_us(_timer_us, us);
}
else
{
delay_us(us);
}
}
/* sec, min, hour, week, day, month, year */
// static uint8_t calendar[7] = {0, 0, 0, 1, 29, 2, 98};
@ -316,7 +329,7 @@ static BOOL rtc_soft_reset(void)
if (ret == 0)
{
LL_mDelay(2);
_delay_us(2000);
}
return ret;
@ -354,8 +367,14 @@ static BOOL rtc_clock_reginit(void)
* @return {BOOL} TRUE = FALSE =
* @note
*/
BOOL rtc_init(void)
BOOL rtc_init(TIM_TypeDef *timer_us)
{
if (timer_us != NULL)
{
_timer_us = timer_us;
ENABLE_TIM_COUNT(_timer_us);
}
i2c_gpio_group_t gpios;
int ret = 1;
gpios.scl = gpio_create(RTC_RX8010_SCL_PORT, RTC_RX8010_SCL_PIN);

View File

@ -57,7 +57,7 @@ typedef struct
* @brief Initializes the RTC module.
* @return TRUE if the initialization is successful, FALSE otherwise.
*/
extern BOOL rtc_init(void);
extern BOOL rtc_init(TIM_TypeDef *timer_us);
/**
* @brief Deinitializes the RTC module.

View File

@ -1,5 +1,6 @@
#include "sht40.h"
#include "i2cs.h"
#include "delay.h"
#define SHT40_SDA_PORT I2C1_SDA_GPIO_Port
#define SHT40_SDA_PIN I2C1_SDA_Pin
#define SHT40_SCL_PORT I2C1_SCL_GPIO_Port
@ -8,9 +9,22 @@
#define SHT40_I2C_ADDRESS 0x44
#define SHT40_MEASURE_CMD 0xFD // 2*8-bit T-data:8-bit CRC:2*8-bit RH-data: 8-bit CRC
static i2c_t *sht40_i2c;
static i2c_t *_sht40_i2c;
static TIM_TypeDef *_timer_us;
static uint8_t crc8(uint8_t *data, uint8_t len);
static void _delay_us(uint32_t us)
{
if (_timer_us != NULL)
{
delay_hardware_us(_timer_us, us);
}
else
{
delay_us(us);
}
}
void sht40_test(void)
{
float32 temperature = 0;
@ -26,14 +40,21 @@ void sht40_test(void)
*
* sht40_i2c SHT40
*/
void sht40_init(void)
void sht40_init(TIM_TypeDef *timer_us)
{
DBG_ASSERT(timer_us != NULL __DBG_LINE);
if (timer_us != NULL)
{
_timer_us = timer_us;
ENABLE_TIM_COUNT(_timer_us);
}
i2c_gpio_group_t gpios;
gpios.scl = gpio_create(SHT40_SCL_PORT, SHT40_SCL_PIN);
gpios.sda = gpio_create(SHT40_SDA_PORT, SHT40_SDA_PIN);
sht40_i2c = i2c_create(gpios, 10);
DBG_ASSERT(sht40_i2c != NULL __DBG_LINE);
_sht40_i2c = i2c_create(gpios, 10);
DBG_ASSERT(_sht40_i2c != NULL __DBG_LINE);
// sht40_test(); // 测试 SHT40
}
@ -65,32 +86,32 @@ BOOL sht40_read(float32 *temperature, float32 *humidity)
osel_memset(data, 0, ARRAY_LEN(data));
// 发送开始信号
sht40_i2c->interface.start(sht40_i2c);
_sht40_i2c->interface.start(_sht40_i2c);
// 发送写入地址命令
sht40_i2c->interface.write_byte(sht40_i2c, SHT40_I2C_ADDRESS << 1);
_sht40_i2c->interface.write_byte(_sht40_i2c, SHT40_I2C_ADDRESS << 1);
// 等待写入地址命令响应
if (sht40_i2c->interface.wait_ack(sht40_i2c) == FALSE)
if (_sht40_i2c->interface.wait_ack(_sht40_i2c) == FALSE)
{
return FALSE;
}
// 发送测量命令
sht40_i2c->interface.write_byte(sht40_i2c, SHT40_MEASURE_CMD);
_sht40_i2c->interface.write_byte(_sht40_i2c, SHT40_MEASURE_CMD);
// 等待测量命令响应
if (sht40_i2c->interface.wait_ack(sht40_i2c) == FALSE)
if (_sht40_i2c->interface.wait_ack(_sht40_i2c) == FALSE)
{
return FALSE;
}
// 停止I2C总线
sht40_i2c->interface.stop(sht40_i2c);
_sht40_i2c->interface.stop(_sht40_i2c);
LL_mDelay(10); // 根据 SHT40 数据手册,等待至少 10ms
_delay_us(10000); // 根据 SHT40 数据手册,等待至少 10ms
// 发送开始信号
sht40_i2c->interface.start(sht40_i2c);
_sht40_i2c->interface.start(_sht40_i2c);
// 发送写入地址命令
sht40_i2c->interface.write_byte(sht40_i2c, (SHT40_I2C_ADDRESS << 1) | 1);
_sht40_i2c->interface.write_byte(_sht40_i2c, (SHT40_I2C_ADDRESS << 1) | 1);
// 等待写入地址命令响应
if (sht40_i2c->interface.wait_ack(sht40_i2c) == FALSE)
if (_sht40_i2c->interface.wait_ack(_sht40_i2c) == FALSE)
{
return FALSE;
}
@ -99,16 +120,16 @@ BOOL sht40_read(float32 *temperature, float32 *humidity)
{
if (i == 5)
{
data[i] = sht40_i2c->interface.read_byte(sht40_i2c, FALSE);
data[i] = _sht40_i2c->interface.read_byte(_sht40_i2c, FALSE);
}
else
{
data[i] = sht40_i2c->interface.read_byte(sht40_i2c, TRUE);
data[i] = _sht40_i2c->interface.read_byte(_sht40_i2c, TRUE);
}
}
// 停止I2C总线
sht40_i2c->interface.stop(sht40_i2c);
_sht40_i2c->interface.stop(_sht40_i2c);
*temperature = 0;
*humidity = 0;

View File

@ -2,7 +2,7 @@
#define __SHT40_H
#include "main.h"
void sht40_init(void); ///< 初始化 SHT40 传感器
void sht40_init(TIM_TypeDef *timer_us); ///< 初始化 SHT40 传感器
void sht40_dinit(void); ///< 反初始化 SHT40 传感器
BOOL sht40_read(float32 *temperature, float32 *humidity); ///< 读取温湿度传感器数据

File diff suppressed because it is too large Load Diff

View File

@ -1,80 +0,0 @@
#ifndef __SSD1306_OLED_H
#define __SSD1306_OLED_H
#include "main.h"
// OLED引脚定义
#define SSD1306_SDA_PORT OLED_SDA_GPIO_Port
#define SSD1306_SDA_PIN OLED_SDA_Pin
#define SSD1306_SCK_PORT OLDE_SCK_GPIO_Port
#define SSD1306_SCK_PIN OLDE_SCK_Pin
// I2C地址
#define SSD1306_I2C_ADDRESS 0x78
// OLED显示参数
#define SSD1306_WIDTH 128
#define SSD1306_HEIGHT 64
// OLED颜色
#define SSD1306_WHITE 1
#define SSD1306_BLACK 0
// OLED命令定义
#define SSD1306_CMD_DISPLAY_OFF 0xAE
#define SSD1306_CMD_DISPLAY_ON 0xAF
#define SSD1306_CMD_SET_CONTRAST 0x81
#define SSD1306_CMD_DISPLAY_ALL_ON_RESUME 0xA4
#define SSD1306_CMD_DISPLAY_ALL_ON 0xA5
#define SSD1306_CMD_NORMAL_DISPLAY 0xA6
#define SSD1306_CMD_INVERT_DISPLAY 0xA7
#define SSD1306_CMD_SET_DISPLAY_OFFSET 0xD3
#define SSD1306_CMD_SET_COM_PINS 0xDA
#define SSD1306_CMD_SET_VCOM_DETECT 0xDB
#define SSD1306_CMD_SET_DISPLAY_CLOCK_DIV 0xD5
#define SSD1306_CMD_SET_PRECHARGE 0xD9
#define SSD1306_CMD_SET_MULTIPLEX 0xA8
#define SSD1306_CMD_SET_LOW_COLUMN 0x00
#define SSD1306_CMD_SET_HIGH_COLUMN 0x10
#define SSD1306_CMD_SET_START_LINE 0x40
#define SSD1306_CMD_MEMORY_MODE 0x20
#define SSD1306_CMD_COLUMN_ADDR 0x21
#define SSD1306_CMD_PAGE_ADDR 0x22
#define SSD1306_CMD_COM_SCAN_INC 0xC0
#define SSD1306_CMD_COM_SCAN_DEC 0xC8
#define SSD1306_CMD_SEG_REMAP 0xA0
#define SSD1306_CMD_CHARGE_PUMP 0x8D
#define SSD1306_CMD_SET_DC_DC_ENABLE 0x14
#define SDA_OUT() \
{ \
GPIO_SET_OUTPUT(SSD1306_SDA_PORT, SSD1306_SDA_PIN); \
}
#define SDA_IN() \
{ \
GPIO_SET_INPUT(SSD1306_SDA_PORT, SSD1306_SDA_PIN); \
}
// 函数声明
void ssd1306_init(void);
void ssd1306_logo(void);
void ssd1306_display_on(void);
void ssd1306_display_off(void);
void ssd1306_update_screen(void);
void ssd1306_fill(uint8_t color);
void ssd1306_clear(void);
void ssd1306_clear_buffer(void);
void ssd1306_draw_bmp(uint8_t x0, uint8_t y0, uint8_t x1, uint8_t y1, const uint8_t *bmp);
void ssd1306_f6x8_string(uint8_t x, uint8_t y, const uint8_t *ch);
void ssd1306_f6x8_number(uint8_t x, uint8_t y, float32 num, uint8_t dot_num);
void ssd1306_f6x8_string_number(uint8_t x, uint8_t y, const uint8_t *ch, uint8_t unit, float32 num);
void ssd1306_f8x16_string(uint8_t x, uint8_t y, const uint8_t *ch);
void ssd1306_f8x16_number(uint8_t x, uint8_t y, float32 num, uint8_t dot_num);
void ssd1306_draw_text_center(uint8_t y, const char *text);
void ssd1306_draw_progress_bar(uint8_t progress);
void ssd1306_fill_rect_angle(uint8_t x, uint8_t y, uint8_t w, uint8_t h, uint8_t color);
void ssd1306_draw_rect_angle(uint8_t x, uint8_t y, uint8_t w, uint8_t h, uint8_t color);
void ssd1306_draw_line(uint8_t x1, uint8_t y1, uint8_t x2, uint8_t y2, uint8_t color);
void ssd1306_draw_pixel(uint8_t x, uint8_t y, uint8_t color);
#endif // __SSD1306_OLED_H

View File

@ -1,454 +0,0 @@
#include "tmc2240.h"
tmc2240_t _tmc2240[TMC2240_MAX];
static void tmc2240_write(tmc2240_index_e index, uint8_t *data)
{
DBG_ASSERT(index < TMC2240_MAX __DBG_LINE);
tmc2240_t *tmc = &_tmc2240[index];
DBG_ASSERT(tmc != NULL __DBG_LINE);
DBG_ASSERT(tmc->spi != NULL __DBG_LINE);
tmc->spi->gpios.cs->reset(*tmc->spi->gpios.cs);
for (uint16_t i = 0; i < 5; i++)
{
tmc->spi->interface.u.normal.spi_send(tmc->spi, data[i]);
}
tmc->spi->gpios.cs->set(*tmc->spi->gpios.cs);
}
static void tmc2240_read(tmc2240_index_e index, uint8_t *wdata, uint8_t *rdata)
{
DBG_ASSERT(index < TMC2240_MAX __DBG_LINE);
tmc2240_t *tmc = &_tmc2240[index];
DBG_ASSERT(tmc != NULL __DBG_LINE);
DBG_ASSERT(tmc->spi != NULL __DBG_LINE);
tmc->spi->gpios.cs->reset(*tmc->spi->gpios.cs);
for (uint16_t i = 0; i < 5; i++)
{
rdata[i] = tmc->spi->interface.u.normal.spi_send(tmc->spi, wdata[i]);
}
tmc->spi->gpios.cs->set(*tmc->spi->gpios.cs);
__NOP();
__NOP();
__NOP();
tmc->spi->gpios.cs->reset(*tmc->spi->gpios.cs);
for (uint16_t i = 0; i < 5; i++)
{
rdata[i] = tmc->spi->interface.u.normal.spi_send(tmc->spi, wdata[i]);
}
tmc->spi->gpios.cs->set(*tmc->spi->gpios.cs);
}
/**
* @brief TMC2240寄存器写入数据
*
* TMC2240的指定寄存器写入32位数据
*
* @param index TMC2240索引
* @param reg
* @param data
*/
static void tmc2240_reg_write(tmc2240_index_e index, uint8_t reg, uint32_t data)
{
DBG_ASSERT(index < TMC2240_MAX __DBG_LINE);
tmc2240_t *tmc = &_tmc2240[index];
DBG_ASSERT(tmc != NULL __DBG_LINE);
DBG_ASSERT(tmc->spi != NULL __DBG_LINE);
uint8_t wdata[5] = {0};
wdata[0] = TMC2240_HIGHT_BIT | reg;
wdata[1] = (data >> 24) & 0xFF;
wdata[2] = (data >> 16) & 0xFF;
wdata[3] = (data >> 8) & 0xFF;
wdata[4] = data & 0xFF;
tmc2240_write(index, wdata);
}
/**
* @brief TMC2240寄存器中读取数据
*
* TMC2240驱动器的指定寄存器中读取数据
*
* @param index TMC2240驱动器的索引
* @param reg
*
* @return 32
*/
static uint32_t tmc2240_reg_read(tmc2240_index_e index, uint8_t reg)
{
DBG_ASSERT(index < TMC2240_MAX __DBG_LINE);
tmc2240_t *tmc = &_tmc2240[index];
DBG_ASSERT(tmc != NULL __DBG_LINE);
DBG_ASSERT(tmc->spi != NULL __DBG_LINE);
uint8_t wdata[5] = {0};
uint8_t rdata[5] = {0};
wdata[0] = reg;
tmc2240_read(index, wdata, rdata);
return (rdata[1] << 24) | (rdata[2] << 16) | (rdata[3] << 8) | rdata[4];
}
/**
* @brief TMC2240步进电机驱动器
*
* TMC2240步进电机驱动器的各种参数线
*
* @param index TMC2240步进电机驱动器的索引
*/
static void tmc2240_config_write(tmc2240_index_e index)
{
DBG_ASSERT(index < TMC2240_MAX __DBG_LINE);
tmc2240_t *tmc = &_tmc2240[index];
DBG_ASSERT(tmc != NULL __DBG_LINE);
tmc->config.gconf.data = 0x00000000;
tmc->config.chopconf.data = 0x00410153;
tmc->config.chopconf.bits.mres = TMC2240_MRES_8;
tmc->config.drvconf.data = 0x00000021;
tmc->config.global_scaler.data = 0x00000000;
tmc->config.ihold_irun.bits.ihold = 31;
tmc->config.ihold_irun.bits.irun = 31;
tmc->config.ihold_irun.bits.iholddelay = 0;
tmc->config.ihold_irun.bits.irundelay = 0;
tmc->config.pwmconf.data = 0xC44C261E;
tmc->config.gstat.data = 0x00000007;
tmc2240_reg_write(index, TMC2240_GCONF, tmc->config.gconf.data);
tmc2240_reg_write(index, TMC2240_CHOPCONF, tmc->config.chopconf.data);
tmc2240_reg_write(index, TMC2240_DRV_CONF, tmc->config.drvconf.data);
tmc2240_reg_write(index, TMC2240_GLOBAL_SCALER, tmc->config.global_scaler.data);
tmc2240_reg_write(index, TMC2240_IHOLD_IRUN, tmc->config.ihold_irun.data);
tmc2240_reg_write(index, TMC2240_PWMCONF, tmc->config.pwmconf.data);
tmc2240_reg_write(index, TMC2240_GSTAT, tmc->config.gstat.data);
}
/**
* @brief TMC2240步进电机的步进角度和每圈脉冲数
*
* TMC2240的配置更新步进电机的步进角度和每圈脉冲数
*
* @param index TMC2240步进电机的索引
*/
static void _tmc2240_motor_update(tmc2240_index_e index)
{
DBG_ASSERT(index < TMC2240_MAX __DBG_LINE);
tmc2240_t *tmc = &_tmc2240[index];
DBG_ASSERT(tmc != NULL __DBG_LINE);
switch (tmc->config.chopconf.bits.mres)
{
case TMC2240_MRES_256:
tmc->motor.step_angle = MOTOR_42_STEP_ANGLE / 256;
break;
case TMC2240_MRES_128:
tmc->motor.step_angle = MOTOR_42_STEP_ANGLE / 128;
break;
case TMC2240_MRES_64:
tmc->motor.step_angle = MOTOR_42_STEP_ANGLE / 64;
break;
case TMC2240_MRES_32:
tmc->motor.step_angle = MOTOR_42_STEP_ANGLE / 32;
break;
case TMC2240_MRES_16:
tmc->motor.step_angle = MOTOR_42_STEP_ANGLE / 16;
break;
case TMC2240_MRES_8:
tmc->motor.step_angle = MOTOR_42_STEP_ANGLE / 8;
break;
case TMC2240_MRES_4:
tmc->motor.step_angle = MOTOR_42_STEP_ANGLE / 4;
break;
case TMC2240_MRES_2:
tmc->motor.step_angle = MOTOR_42_STEP_ANGLE / 2;
break;
case TMC2240_MRES_1:
tmc->motor.step_angle = MOTOR_42_STEP_ANGLE;
break;
default:
break;
}
tmc->motor.circle_pulse = 360 / tmc->motor.step_angle;
}
/**
* @brief TMC2240电机驱动器
*
* TMC2240电机驱动器
*
* @param index TMC2240驱动器的索引
* @param enable TRUE表示启用FALSE表示禁用
*/
static void _tmc2240_enable(tmc2240_index_e index, BOOL enable)
{
DBG_ASSERT(index < TMC2240_MAX __DBG_LINE);
tmc2240_t *tmc = &_tmc2240[index];
DBG_ASSERT(tmc != NULL __DBG_LINE);
BOOL state = tmc->en->read(*tmc->en) == 0 ? TRUE : FALSE;
if (state == enable)
{
return;
}
if (enable == TRUE)
{
PWM_START(tmc->timer, tmc->time_ch);
tmc->en->reset(*tmc->en);
tmc2240_reg_write(index, TMC2240_CHOPCONF, tmc->config.chopconf.data);
}
else
{
PWM_STOP(tmc->timer, tmc->time_ch);
tmc->en->set(*tmc->en);
chopconf_u chopconf;
osel_memset((uint8_t *)&chopconf, 0, sizeof(chopconf_u));
chopconf.bits.mres = TMC2240_MRES_1;
tmc2240_reg_write(index, TMC2240_CHOPCONF, chopconf.data);
}
}
/**
* @brief TMC2240驱动器的方向
*
* TMC2240驱动器的方向
*
* @param index TMC2240驱动器的索引
* @param dir TMC2240_FORWARD表示正向TMC2240_BACKWARD表示反向
*/
static void _tmc2240_direction(tmc2240_index_e index, tmc2240_direction_e dir)
{
DBG_ASSERT(index < TMC2240_MAX __DBG_LINE);
tmc2240_t *tmc = &_tmc2240[index];
DBG_ASSERT(tmc != NULL __DBG_LINE);
if (dir == TMC2240_FORWARD)
{
tmc->dir->reset(*tmc->dir);
}
else
{
tmc->dir->set(*tmc->dir);
}
}
/**
* @brief TMC2240电机驱动器
*
* TMC2240电机驱动器SPI通信GPIO引脚
*
* @param index TMC2240的索引号
* @param SPIx SPI外设指针
* @param timer
* @param time_ch
* @param gpios SPI通信相关的GPIO引脚组
*/
void tmc2240_init(tmc2240_index_e index, SPI_TypeDef *SPIx, TIM_TypeDef *timer, uint32_t time_ch, spi_gpio_group_t *gpios)
{
DBG_ASSERT(index < TMC2240_MAX __DBG_LINE);
tmc2240_t *tmc = &_tmc2240[index];
osel_memset((uint8_t *)tmc, 0, sizeof(tmc2240_t));
tmc->timer = timer;
tmc->time_ch = time_ch;
tmc->spi = spi_create(SPI_TYPE_NORMAL, *gpios, 0);
DBG_ASSERT(tmc->spi != NULL __DBG_LINE);
tmc->spi->interface.hardware_enable(tmc->spi, SPIx);
{
tmc->default_tm.sysclk = SystemCoreClock / 1000;
tmc->default_tm.psc = PWM_GET_PSC(tmc->timer);
tmc->default_tm.arr = PWM_GET_ARR(tmc->timer);
tmc->default_tm.freq = PWM_GET_FREQ(tmc->timer);
}
tmc->params.percent = TMC2240_PWM_DUTY_DEFAULT;
tmc->params.arr = 0;
tmc->params.freq = 0;
tmc->params.enable = FALSE;
tmc->params.direction = TMC2240_FORWARD;
tmc2240_config_write(index);
_tmc2240_motor_update(index);
}
tmc2240_t *tmc2240_get(tmc2240_index_e index)
{
DBG_ASSERT(index < TMC2240_MAX __DBG_LINE);
return &_tmc2240[index];
}
/**
* @brief TMC2240的占空比
*
* TMC2240的占空比
*
* @param index TMC2240的索引
* @param percent -100100
*/
void tmc2240_percent(tmc2240_index_e index, float32 percent)
{
DBG_ASSERT(index < TMC2240_MAX __DBG_LINE);
tmc2240_t *tmc = &_tmc2240[index];
DBG_ASSERT(tmc != NULL __DBG_LINE);
PWM_SET_DUTY(tmc->timer, tmc->time_ch, ABS(percent));
}
/**
* @brief TMC2240的配置参数
*
* TMC2240电机驱动器的寄存器中读取多个配置参数
*
* @param index TMC2240电机驱动器的索引
*/
void tmc2240_config_read(tmc2240_index_e index)
{
DBG_ASSERT(index < TMC2240_MAX __DBG_LINE);
tmc2240_t *tmc = &_tmc2240[index];
DBG_ASSERT(tmc != NULL __DBG_LINE);
tmc->read_config.gconf.data = tmc2240_reg_read(index, TMC2240_GCONF);
tmc->read_config.chopconf.data = tmc2240_reg_read(index, TMC2240_CHOPCONF);
tmc->read_config.drvconf.data = tmc2240_reg_read(index, TMC2240_DRV_CONF);
tmc->read_config.global_scaler.data = tmc2240_reg_read(index, TMC2240_GLOBAL_SCALER);
tmc->read_config.ihold_irun.data = tmc2240_reg_read(index, TMC2240_IHOLD_IRUN);
tmc->read_config.pwmconf.data = tmc2240_reg_read(index, TMC2240_PWMCONF);
tmc->read_config.gstat.data = tmc2240_reg_read(index, TMC2240_GSTAT);
tmc->data.tmc2240_adc_temp = tmc2240_reg_read(index, TMC2240_ADC_TEMP);
tmc->data.tmc2240_temperature = (float32)(tmc->data.tmc2240_adc_temp - 2038) / 7.7;
}
/**
* @brief TMC2240电机驱动器
*
* TMC2240电机驱动器
*
* @param index TMC2240电机驱动器的索引
*/
void tmc2240_test(tmc2240_index_e index)
{
DBG_ASSERT(index < TMC2240_MAX __DBG_LINE);
tmc2240_t *tmc = &_tmc2240[index];
DBG_ASSERT(tmc != NULL __DBG_LINE);
_tmc2240_enable(index, tmc->params.enable);
if (tmc->params.enable == TRUE)
{
_tmc2240_direction(index, tmc->params.direction);
if (PWM_GET_ARR(tmc->timer) != tmc->params.arr)
{
if (tmc->params.arr == 0)
{
tmc->params.arr = tmc->default_tm.arr;
}
PWM_SET_ARR(tmc->timer, tmc->params.arr);
tmc->params.freq = PWM_GET_FREQ(tmc->timer);
}
tmc2240_percent(index, tmc->params.percent);
if (tmc->config.chopconf.bits.mres != tmc->read_config.chopconf.bits.mres)
{
tmc2240_reg_write(index, TMC2240_CHOPCONF, tmc->config.chopconf.data);
_tmc2240_motor_update(index);
}
}
}
/**
* @brief TMC2240电机的角度
*
* TMC2240电机的目标角度
*
* @param index
* @param angle
*/
void tmc2240_motor_set_angle(tmc2240_index_e index, int32_t angle)
{
DBG_ASSERT(index < TMC2240_MAX __DBG_LINE);
tmc2240_t *tmc = &_tmc2240[index];
DBG_ASSERT(tmc != NULL __DBG_LINE);
if (angle == 0)
{
return;
}
if (angle > 0)
{
tmc->params.direction = TMC2240_FORWARD;
}
else
{
tmc->params.direction = TMC2240_BACKWARD;
}
tmc->motor.pulse_count = ABS(angle) / tmc->motor.step_angle;
tmc->motor.step_angle_count = 0;
tmc->params.enable = TRUE;
_tmc2240_direction(index, tmc->params.direction);
if (PWM_GET_ARR(tmc->timer) != tmc->params.arr)
{
if (tmc->params.arr == 0)
{
tmc->params.arr = tmc->default_tm.arr;
}
PWM_SET_ARR(tmc->timer, tmc->params.arr);
tmc->params.freq = PWM_GET_FREQ(tmc->timer);
}
tmc2240_percent(index, tmc->params.percent);
if (tmc->config.chopconf.bits.mres != tmc->read_config.chopconf.bits.mres)
{
tmc2240_reg_write(index, TMC2240_CHOPCONF, tmc->config.chopconf.data);
_tmc2240_motor_update(index);
}
_tmc2240_enable(index, tmc->params.enable);
}
/**
* @brief TMC2240步进电机的状态
*
* TMC2240步进电机的状态
*
* @param index TMC2240步进电机的索引
*/
void tmc2240_motor_update(tmc2240_index_e index)
{
DBG_ASSERT(index < TMC2240_MAX __DBG_LINE);
tmc2240_t *tmc = &_tmc2240[index];
DBG_ASSERT(tmc != NULL __DBG_LINE);
if (tmc->motor.pulse_count > 0)
{
tmc->motor.pulse_count--; // 脉冲数
tmc->motor.step_angle_count++; // 步距个数
if (tmc->params.direction == TMC2240_FORWARD)
{
tmc->motor.add_pulse_count++; /* 绝对位置++ */
}
else
{
tmc->motor.add_pulse_count--; /* 绝对位置-- */
}
}
/* 当脉冲数等于0的时候 代表需要发送的脉冲个数已完成,停止输出 */
if (tmc->motor.pulse_count <= 0)
{
tmc->params.enable = FALSE;
_tmc2240_enable(index, tmc->params.enable);
}
}

View File

@ -1,372 +0,0 @@
/**
* @file tmc2240.h
* @author xushenghao
* @brief TMC2240驱动头文件
* @version 0.1
* @note
* 1. VM需要供电SPI无法正常通信
* 2. 421.812001/81=0.2251600
*/
#ifndef __TMC2240_H
#define __TMC2240_H
#include "main.h"
#include "spis.h"
#define MOTOR_42_STEP_ANGLE 1.8f // 42步进电机每步1.8度
#define TMC2240_PWM_DUTY_DEFAULT 50 // PWM默认占空比
/*
0x00 = 0x00002108 ;; writing GCONF @ address 0=0x00 with 0x00002108=8456=0.0
0x03 = 0x00000000 ;; writing SLAVECONF @ address 1=0x03 with 0x00000000=0=0.0
0x04 = 0x4001682C ;; writing IOIN @ address 2=0x04 with 0x4001682C=1073834028=0.0
0x0A = 0x00000021 ;; writing DRV_CONF @ address 3=0x0A with 0x00000021=33=0.0
0x0B = 0x00000000 ;; writing GLOBAL_SCALER @ address 4=0x0B with 0x00000000=0=0.0
0x10 = 0x00001208 ;; writing IHOLD_IRUN @ address 5=0x10 with 0x00001208=4616=0.0
0x11 = 0x00000000 ;; writing TPOWERDOWN @ address 6=0x11 with 0x00000000=0=0.0
0x13 = 0x00000000 ;; writing TPWMTHRS @ address 7=0x13 with 0x00000000=0=0.0
0x14 = 0x000003BE ;; writing TCOOLTHRS @ address 8=0x14 with 0x000003BE=958=0.0
0x15 = 0x00000000 ;; writing THIGH @ address 9=0x15 with 0x00000000=0=0.0
0x2D = 0x00000000 ;; writing DIRECT_MODE @ address 10=0x2D with 0x00000000=0=0.0
0x38 = 0x00000000 ;; writing ENCMODE @ address 11=0x38 with 0x00000000=0=0.0
0x39 = 0x00000000 ;; writing X_ENC @ address 12=0x39 with 0x00000000=0=0.0
0x3A = 0x00010000 ;; writing ENC_CONST @ address 13=0x3A with 0x00010000=65536=0.0
0x52 = 0x0B920F25 ;; writing OTW_OV_VTH @ address 14=0x52 with 0x0B920F25=194121509=0.0
0x60 = 0xAAAAB554 ;; writing MSLUT[0] @ address 15=0x60 with 0xAAAAB554=0=0.0
0x61 = 0x4A9554AA ;; writing MSLUT[1] @ address 16=0x61 with 0x4A9554AA=1251300522=0.0
0x62 = 0x24492929 ;; writing MSLUT[2] @ address 17=0x62 with 0x24492929=608774441=0.0
0x63 = 0x10104222 ;; writing MSLUT[3] @ address 18=0x63 with 0x10104222=269500962=0.0
0x64 = 0xFBFFFFFF ;; writing MSLUT[4] @ address 19=0x64 with 0xFBFFFFFF=0=0.0
0x65 = 0xB5BB777D ;; writing MSLUT[5] @ address 20=0x65 with 0xB5BB777D=0=0.0
0x66 = 0x49295556 ;; writing MSLUT[6] @ address 21=0x66 with 0x49295556=1227445590=0.0
0x67 = 0x00404222 ;; writing MSLUT[7] @ address 22=0x67 with 0x00404222=4211234=0.0
0x68 = 0xFFFF8056 ;; writing MSLUTSEL @ address 23=0x68 with 0xFFFF8056=0=0.0
0x69 = 0x00F70000 ;; writing MSLUTSTART @ address 24=0x69 with 0x00F70000=16187392=0.0
0x6C = 0x00410153 ;; writing CHOPCONF @ address 25=0x6C with 0x00410153=4260179=0.0
0x6D = 0x00040000 ;; writing COOLCONF @ address 26=0x6D with 0x00040000=262144=0.0
0x70 = 0xC44C001E ;; writing PWMCONF @ address 27=0x70 with 0xC44C001E=0=0.0
0x74 = 0x00000000 ;; writing SG4_THRS @ address 28=0x74 with 0x00000000=0=0.0
*/
#define TMC2240_GCONF 0x00
#define TMC2240_GSTAT 0x01
#define TMC2240_IFCNT 0x02
#define TMC2240_SLAVECONF 0x03
#define TMC2240_IOIN 0x04
#define TMC2240_DRV_CONF 0x0A
#define TMC2240_GLOBAL_SCALER 0x0B
#define TMC2240_IHOLD_IRUN 0x10
#define TMC2240_TPOWERDOWN 0x11
#define TMC2240_TSTEP 0x12
#define TMC2240_TPWMTHRS 0x13
#define TMC2240_TCOOLTHRS 0x14
#define TMC2240_THIGH 0x15
#define TMC2240_DIRECT_MODE 0x2D
#define TMC2240_ENCMODE 0x38
#define TMC2240_XENC 0x39
#define TMC2240_ENC_CONST 0x3A
#define TMC2240_ENC_STATUS 0x3B
#define TMC2240_ENC_LATCH 0x3C
#define TMC2240_ADC_VSUPPLY_AIN 0x50
#define TMC2240_ADC_TEMP 0x51
#define TMC2240_OTW_OV_VTH 0x52
#define TMC2240_MSLUT0 0x60
#define TMC2240_MSLUT1 0x61
#define TMC2240_MSLUT2 0x62
#define TMC2240_MSLUT3 0x63
#define TMC2240_MSLUT4 0x64
#define TMC2240_MSLUT5 0x65
#define TMC2240_MSLUT6 0x66
#define TMC2240_MSLUT7 0x67
#define TMC2240_MSLUTSEL 0x68
#define TMC2240_MSLUTSTART 0x69
#define TMC2240_MSCNT 0x6A
#define TMC2240_MSCURACT 0x6B
#define TMC2240_CHOPCONF 0x6C
#define TMC2240_COOLCONF 0x6D
#define TMC2240_DCCTRL 0x6E
#define TMC2240_DRVSTATUS 0x6F
#define TMC2240_PWMCONF 0x70
#define TMC2240_PWMSCALE 0x71
#define TMC2240_PWM_AUTO 0x72
#define TMC2240_SG4_THRS 0x74
#define TMC2240_SG4_RESULT 0x75
#define TMC2240_SG4_IND 0x76
#define TMC2240_HIGHT_BIT 0x80
typedef enum
{
TMC2240_1,
TMC2240_MAX,
} tmc2240_index_e;
typedef enum
{
TMC2240_FORWARD, // 正转
TMC2240_BACKWARD, // 反转
} tmc2240_direction_e;
typedef enum
{
TMC2240_MRES_256,
TMC2240_MRES_128,
TMC2240_MRES_64,
TMC2240_MRES_32,
TMC2240_MRES_16,
TMC2240_MRES_8,
TMC2240_MRES_4,
TMC2240_MRES_2,
TMC2240_MRES_1, // FULL STEP
} tmc2240_mres_e;
// 0x00 GCONF
typedef union
{
uint32_t data;
struct
{
uint32_t reserved1 : 1;
/**
*
* 0x02^20
* 0x12^18
*/
uint32_t fast_standstill : 1;
/**
* StealthChop2模式
* 0x0StealthChop2
* 0x1StealthChop2电压PWM模式使能()
lHOLD =
*/
uint32_t en_pwm_mode : 1;
/**
* StealthChop2的步进输入筛选
* 0x0StealthChop2
* 0x1StealthChop2电压PWM模式使能
()
lHOLD=
*/
uint32_t multistep_filt : 1;
/**
* /
* 0x0
* 0x1
*/
uint32_t shaft : 1;
uint32_t diag0_error : 1;
uint32_t diag0_otpw : 1;
uint32_t diag0_stall : 1;
uint32_t diag1_stall : 1;
uint32_t diag1_index : 1;
uint32_t diag1_onstate : 1;
uint32_t reserved2 : 1;
uint32_t diag0_pushpull : 1;
uint32_t diag1_pushpull : 1;
uint32_t small_hysteresis : 1;
/**
*
* 0x0
* 0x1ENCA停止定序器
(
)
*/
uint32_t stop_enable : 1;
/**
* motpr相电流控制
* 0x0
* 0x1线
(0x2D)线A
(8..0)线B电流(24..16)
lHOLD设置进行定标
StealthChop2电流调节
StealthChop2电流调节仅适用于
*/
uint32_t direct_mode : 1;
} bits;
} gconf_u;
// 0x01 GSTAT
typedef union
{
uint32_t data;
struct
{
uint32_t reset : 1;
uint32_t drv_err : 1;
uint32_t uv_cp : 1;
uint32_t register_reset : 1;
uint32_t vm_uvlo : 1;
} bits;
} gstat_u;
// 0x0A DRVCONF
typedef union
{
uint32_t data;
struct
{
uint32_t current_range : 2; // 0-1
uint32_t reserved1 : 2; // 2-3
uint32_t slope_control : 2; // 4-5
} bits;
} drvconf_u;
// 0x0B GLOBAL_SCALER
typedef union
{
uint32_t data;
struct
{
uint32_t global_scale : 8; // 0-7
} bits;
} global_scaler_u;
// 0x10 IHOLD_IRUN
typedef union
{
uint32_t data;
struct
{
uint32_t ihold : 5; // 0-4
uint32_t reserved1 : 3; // 5-7
uint32_t irun : 5; // 8-12
uint32_t reserved2 : 3; // 13-15
uint32_t iholddelay : 4; // 16-19
uint32_t reserved3 : 4; // 20-23
uint32_t irundelay : 4; // 24-27
} bits;
} ihold_irun_u;
// 0x6C CHOPCONF
typedef union
{
uint32_t data;
struct
{
uint32_t toff : 4; // 0-3
uint32_t hstrt : 3; // 4-6
uint32_t hend : 4; // 7-10
uint32_t fd3 : 1; // 11
uint32_t disfdcc : 1; // 12
uint32_t reserved1 : 1;
uint32_t chm : 1; // 14
uint32_t tbl : 2; // 15-16
uint32_t reserved2 : 1;
uint32_t vhighfs : 1; // 18
uint32_t vhighchm : 1; // 19
uint32_t tpfd : 4; // 20-23
uint32_t mres : 4; // 24-27
uint32_t intpol : 1; // 28
uint32_t dedge : 1; // 29
uint32_t diss2g : 1; // 30
uint32_t diss2vs : 1; // 31
} bits;
} chopconf_u;
// 0x70 PWMCONF
typedef union
{
uint32_t data;
struct
{
/**
* PWM 0-255CS_ACTUAL=31 =30 使 PWM_OFS
* PWM_OFS pwm_autoscale 0 pwm_autoscale 1
* StealthChop2 PWM_OFS = 0 使
* PWM_OFS > 0 PWM
* IHOLD_IRUN
*/
uint32_t pwm_ofs : 8;
/**
* PWM PWM_GRAD x 256 / TSTEP PWM_OFS 使 PWM_GRAD
* PWM_GRAD pwm_autoscale 0 pwm_autoscale 1
* StealthChop2 PWM_GRAD_AUTO
*/
uint32_t pwm_grad : 8;
uint32_t pwm_freq : 2;
uint32_t pwm_autoscale : 1;
uint32_t pwm_autograd : 1;
} bits;
} pwmconf_u;
typedef struct
{
gconf_u gconf; // 0x00 GCONF
gstat_u gstat; // 0x01 GSTAT
drvconf_u drvconf; // 0x0A DRVCONF
global_scaler_u global_scaler; // 0x0B GLOBAL_SCALER
ihold_irun_u ihold_irun; // 0x10 IHOLD_IRUN
chopconf_u chopconf; // 0x6C CHOPCONF
pwmconf_u pwmconf; // 0x70 PWMCONF
} tmc2240_config_t;
typedef struct
{
gpio_t *en; ///< EN_PIN
gpio_t *dir; ///< DIR_PIN
TIM_TypeDef *timer;
uint32_t time_ch;
spi_t *spi;
tmc2240_config_t config;
tmc2240_config_t read_config;
uint32_t step;
__IO uint32_t step_count;
// PRIVATE
struct
{
uint32_t sysclk; // 系统时钟
uint32_t psc; // 预分频系数
uint16_t arr; // 自动重装值 auto reload value
uint32_t freq; // 频率
} default_tm;
struct
{
BOOL enable; // 使能
tmc2240_direction_e direction; // 方向
float32 percent; // 占空比
uint16_t arr; // 自动重装值(改变速度)
uint32_t freq; // 频率
} params;
struct
{
float32 step_angle; // 步进角度
uint16_t circle_pulse; // 一圈脉冲数
__IO int32_t add_pulse_count; /* 脉冲个数累计 */
__IO uint32_t pulse_count; /* 脉冲个数记录 */
__IO uint32_t step_angle_count; /* 步距个数 */
} motor;
struct
{
uint16_t tmc2240_adc_temp; // 温度ADC值
float32 tmc2240_temperature; // 温度
} data;
} tmc2240_t;
void tmc2240_init(tmc2240_index_e index, SPI_TypeDef *SPIx, TIM_TypeDef *timer, uint32_t time_ch, spi_gpio_group_t *gpios);
tmc2240_t *tmc2240_get(tmc2240_index_e index);
void tmc2240_motor_set_angle(tmc2240_index_e index, int32_t angle);
void tmc2240_motor_update(tmc2240_index_e index);
void tmc2240_test(tmc2240_index_e index);
void tmc2240_config_read(tmc2240_index_e index);
#endif // __TMC2240_H

View File

@ -0,0 +1,38 @@
#include "pid_c.h"
/**
* @brief PID控制器参数
* @param {PID_C} *self - PID控制器结构体指针
* @param {float32} kp -
* @param {float32} ki -
* @param {float32} kd -
* @param {float32} out_min -
* @param {float32} out_max -
* @return {*} -
*/
static void _set_ctrl_prm(struct PID_C *self, float32 kp, float32 ki, float32 kd, float32 out_min, float32 out_max)
{
self->pri.kp = kp; /*比例系数*/
self->pri.ki = ki; /*积分系数*/
self->pri.kd = kd; /*微分系数*/
self->pri.deadband = 0.5; /*死区*/
self->pri.maximum = out_max; /*最大输出*/
self->pri.minimum = out_min; /*最小输出*/
self->pri.last_error = 0; /*上一次误差*/
self->pri.prev_error = 0; /*上上次误差*/
}
static float32 _PID(struct PID_C *self, float32 target, float32 feedback)
{
/**
* PID算法
*/
return 0;
}
void pid_c_constructor(struct PID_C *self)
{
self->set_ctrl_prm = _set_ctrl_prm;
self->PID = _PID;
}

View File

@ -0,0 +1,34 @@
#ifndef __PID_C_H__
#define __PID_C_H__
#include "lib.h"
typedef struct PID_C
{
/* 设置PID三个参数 */
void (*set_ctrl_prm)(struct PID_C *self, float32 kp, float32 ki, float32 kd, float32 out_min, float32 out_max);
/* 控制接口 */
float32 (*PID)(struct PID_C *self, float32 target, float32 feedback);
// 自定义参数
/* 实际值与目标值之间的误差 */
float32 err;
/* 输出值 */
float32 out;
/* private */
struct
{
float32 kp; /*比例学习速度*/
float32 ki; /*积分学习速度*/
float32 kd; /*微分学习速度*/
float32 ki_error; /*积分误差*/
float32 last_error; /*前一拍偏差*/
float32 prev_error; /*前两拍偏差*/
float32 deadband; /*死区*/
float32 maximum; /*输出值的上限*/
float32 minimum; /*输出值的下限*/
} pri;
} pid_c_t;
extern void pid_c_constructor(struct PID_C *self);
#endif // __PID_C_H__

285
lib/control/custom/pid_g.c Normal file
View File

@ -0,0 +1,285 @@
#include "pid_g.h"
#include <math.h>
/**
* @brief PID积分及微分控制数据
* @param {PID_G} *self
* @return {*}
*/
static void _restctrl(struct PID_G *self)
{
self->pri.pre_error = 0;
self->pri.sum_iterm = 0;
}
/**
* @brief
* @param {PID_G} *self
* @param {float32} out_min
* @param {float32} out_max
* @return {*}
* @note
*/
static void _set_range(struct PID_G *self, float32 out_min, float32 out_max)
{
self->pri.out_max = out_max;
self->pri.out_min = out_min;
}
/**
* @brief kp
* @param {PID_G} *self
* @param {float32} kp
* @return {*}
* @note
*/
static void _set_kp(struct PID_G *self, float32 kp)
{
self->pri.kp = kp;
}
/**
* @brief ki
* @param {PID_G} *self
* @param {float32} ki
* @return {*}
* @note
*/
static void _set_ki(struct PID_G *self, float32 ki)
{
self->pri.ki = ki;
}
/**
* @brief kd
* @param {PID_G} *self
* @param {float32} kd
* @return {*}
* @note
*/
static void _set_kd(struct PID_G *self, float32 kd)
{
self->pri.kd = kd;
}
/**
* @brief 使
* @param {PID_G} *self
* @param {BOOL} enable
* @return {*}
* @note
*/
static void _set_ki_enable(struct PID_G *self, BOOL enable)
{
self->pri.ki_enable = enable;
}
/**
* @brief 使
* @param {PID_G} *self
* @param {BOOL} enable
* @return {*}
* @note
*/
static void _set_kd_enable(struct PID_G *self, BOOL enable)
{
self->pri.kd_enable = enable;
}
/**
* @brief
* @return {*}
* @note
*/
static void _set_ctrl_prm(struct PID_G *self, float32 kp, float32 ki, float32 kd, float32 err_dead, float32 out_min, float32 out_max)
{
g_param_t *pri = &self->pri;
osel_memset((uint8_t *)pri, 0, sizeof(pid_g_t));
pri->kp = kp;
pri->ki = ki;
pri->kd = kd;
pri->err_dead = err_dead;
pri->out_max = out_max;
pri->out_min = out_min;
pri->detach = FALSE;
}
static void _update_ctrl_prm(struct PID_G *self, float32 kp, float32 ki, float32 kd, float32 err_dead, float32 out_min, float32 out_max)
{
g_param_t *pri = &self->pri;
pri->kp = kp;
pri->ki = ki;
pri->kd = kd;
pri->err_dead = err_dead;
pri->out_max = out_max;
pri->out_min = out_min;
pri->detach = FALSE;
}
/**
* @brief 0+PID,PID
* @param {PID_G} *self
* @param {float32} max_err
* @param {BOOL} mode
* @return {*}
*/
static void _set_cfg(struct PID_G *self, float32 max_err, BOOL mode)
{
self->pri.err_limit = max_err;
self->pri.detach = mode == FALSE ? FALSE : TRUE;
}
/**
* @brief
* @param {PID_G} *self
* @param {float32} max_weight
* @return {*}
* @note
*/
static void _set_weight(struct PID_G *self, float32 max_ratio, BOOL mode)
{
self->pri.ui_ratio = max_ratio;
self->pri.weight = mode == FALSE ? FALSE : TRUE;
}
/**
* @brief PID算法函数
* @param {PID_G} *self
* @param {float32} target
* @param {float32} feedback
* @return {*}
* @note
*/
static float32 _PID(struct PID_G *self, float32 target, float32 feedback)
{
float32 error = 0.0f;
float32 insert = 0.0f; ///< 该值为0时积分不介入计算
float32 temp_iterm = 0.0f;
float32 temp_kd = 0.0f;
g_param_t *pri = &self->pri;
pri->ref = target; ///< 目标位置
pri->feed_back = feedback; ///< 实际位置
pri->error = pri->ref - pri->feed_back; /// 误差
error = pri->error;
if (fabs(pri->error) <= pri->err_dead) ///< 误差小于死区,不计算
{
error = 0;
}
/*根据PID配置的模式,获取积分数据,进行积分累加*/
if (pri->out >= pri->out_max) ///< 到达输出上限
{
if (fabs(error) > pri->err_limit && pri->detach) ///< 误差大于积分介入区间,积分不介入计算
{
insert = 0;
}
else
{
insert = 1;
if (error < 0)
{
temp_iterm = pri->ki * error;
}
}
}
else if (pri->out <= pri->out_min) ///< 到达输出下限
{
if (fabs(error) > pri->err_limit && pri->detach) ///< 误差大于积分介入区间,积分不介入计算
{
insert = 0;
}
else
{
insert = 1;
if (error > 0)
{
temp_iterm = pri->ki * error;
}
}
}
else
{
if (fabs(error) > pri->err_limit && pri->detach)
{
insert = 0;
}
else
{
insert = 1;
temp_iterm = pri->ki * error;
}
}
if (pri->ki_enable == FALSE)
{
temp_iterm = 0;
insert = 0;
}
/* integral */
pri->sum_iterm += temp_iterm;
if (pri->weight == TRUE)
{
if (pri->sum_iterm > pri->ui_ratio)
{
pri->sum_iterm = pri->ui_ratio;
}
else if (pri->sum_iterm < -pri->ui_ratio)
{
pri->sum_iterm = -pri->ui_ratio;
}
}
else
{
if (pri->sum_iterm > pri->out_max)
{
pri->sum_iterm = pri->out_max;
}
else if (pri->sum_iterm < pri->out_min)
{
pri->sum_iterm = pri->out_min;
}
}
/* differential */
if (pri->kd_enable == TRUE)
{
temp_kd = pri->kd;
}
else
{
temp_kd = 0;
}
pri->out = pri->kp * pri->error + pri->sum_iterm * insert + (pri->error - pri->pre_error) * temp_kd;
pri->pre_error = pri->error; ///< 记录这次误差,为下次微分计算做准备
pri->pre_feed_back = pri->feed_back;
/*limt pid output*/
pri->out = RANGE(pri->out, pri->out_min, pri->out_max); ///< 限制输出
return pri->out;
}
/**
* @brief PID接口
* @param {PID_G} *self
* @return {*}
* @note
*/
void pid_g_constructor(struct PID_G *self)
{
self->set_ctrl_prm = _set_ctrl_prm;
self->update_ctrl_prm = _update_ctrl_prm;
self->set_cfg = _set_cfg;
self->set_kp = _set_kp;
self->set_ki_enable = _set_ki_enable;
self->set_ki = _set_ki;
self->set_kd_enable = _set_kd_enable;
self->set_kd = _set_kd;
self->set_range = _set_range;
self->restctrl = _restctrl;
self->PID = _PID;
self->set_weight = _set_weight;
}

View File

@ -0,0 +1,65 @@
#ifndef __PID_G_H__
#define __PID_G_H__
#include "lib.h"
typedef struct
{
float32 ref; /*目标*/
float32 feed_back; /*实际*/
float32 pre_feed_back; /*上一次实际*/
float32 kp; /*比例学习速度*/
float32 ki; /*积分学习速度*/
float32 kd; /*微分学习速度*/
float32 ki_error; /*积分误差*/
float32 error; /*误差*/
float32 pre_error; /*前一拍偏差*/
float32 prev_error; /*前两拍偏差*/
float32 err_dead; /*死区*/
float32 err_limit; /*积分分离上限*/
float32 maximum; /*输出值的上限*/
float32 minimum; /*输出值的下限*/
float32 out; /*输出值*/
float32 sum_iterm; /*积分累加*/
float32 ui_ratio; /*积分权重*/
BOOL ki_enable; /*积分使能*/
BOOL kd_enable; /*微分使能*/
BOOL detach; /*积分分离标志*/
BOOL weight; /*积分权重标志*/
float32 out_max; /*输出最大值*/
float32 out_min; /*输出最小值*/
} g_param_t;
typedef struct PID_G
{
/* 设置PID三个参数 */
void (*set_ctrl_prm)(struct PID_G *self, float32 kp, float32 ki, float32 kd, float32 err_dead, float32 out_min, float32 out_max);
/* 更新PID参数 */
void (*update_ctrl_prm)(struct PID_G *self, float32 kp, float32 ki, float32 kd, float32 err_dead, float32 out_min, float32 out_max);
/* 控制接口 */
float32 (*PID)(struct PID_G *self, float32 target, float32 feedback);
/* 更新控制区间 */
void (*set_range)(struct PID_G *self, float32 out_min, float32 out_max);
/* 设置积分分离 */
void (*set_cfg)(struct PID_G *self, float32 max_err, BOOL mode);
/* 设置积分权重 */
void (*set_weight)(struct PID_G *self, float32 max_ratio, BOOL mode);
/* 更新kp */
void (*set_kp)(struct PID_G *self, float32 kp);
/* 使能ki */
void (*set_ki_enable)(struct PID_G *self, BOOL enable);
/* 更新ki */
void (*set_ki)(struct PID_G *self, float32 ki);
/* 使能kd */
void (*set_kd_enable)(struct PID_G *self, BOOL enable);
/* 更新kd */
void (*set_kd)(struct PID_G *self, float32 kd);
/* 复位PID积分及微分控制数据 */
void (*restctrl)(struct PID_G *self);
/* private */
g_param_t pri;
} pid_g_t;
extern void pid_g_constructor(struct PID_G *self);
#endif // __PID_G_H__

166
lib/control/custom/pid_hd.c Normal file
View File

@ -0,0 +1,166 @@
#include "pid_hd.h"
#include <math.h>
#include "sys.h"
#include "app.h"
#if INCOMPLETE_DIFFEREN_HD == 1 // 积分分离
/*计算微分项,使用追随误差微分项*/
static float32 td_derivative(struct PID_HD *self, float32 current_err, float32 pre_err, float32 dt)
{
pid_hd_position_t *pri = &self->pri_u.position;
float32 derivative = (current_err - pre_err) / dt; // 计算积分项
derivative = pri->td_alpha * derivative + (1 - pri->td_alpha) * pri->td_beta * pri->pre_derivative; // 追随误差微分器平滑输出
pri->pre_derivative = derivative; // 更新上一次误差
return derivative;
}
#endif
/*杭电设置位置式PID参数*/
static void _set_ctrl_prm_position(struct PID_HD *self, float32 kp, float32 ki, float32 kd)
{
pid_hd_position_t *pri = &self->pri_u.position;
osel_memset((uint8_t *)pri, 0, sizeof(pid_hd_position_t));
/*观测传进来的Kp、Ki、Kd*/
pri->kp = kp;
pri->ki = ki;
pri->kd = kd;
pri->ki_limit = 10; // 积分分离界限
pri->err_dead = 0.5; // 控制死区范围
#if INCOMPLETE_DIFFEREN_HD == 1
/*不完全微分系数*/
pri->td_alpha = 0.5;
pri->td_beta = 0.5;
#endif
}
/*杭电:设置输出限幅参数*/
static void _set_out_prm_position(struct PID_HD *self, float32 maximum, float32 minimum)
{
self->pri_u.position.out_max = maximum;
self->pri_u.position.out_min = minimum;
}
/*杭电位置式PID控制算法*/
static float32 _pid_position(struct PID_HD *self, float32 err)
{
/*计算控制的运行时间*/
// sys_millis_reset();
self->pri_u.position.control_time = sys_millis();
self->pri_u.position.tmp_time = 0;
/*测试4.18*/
if (fabs(err) < 0.1)
{
err = 0;
}
float32 x[3];
self->pri_u.position.err = err;
/*抗积分饱和*/
#if INTEGRAL_SEPARATION == 1 // 积分分离
if (self->pri_u.position.out > self->pri_u.position.out_max)
{
if (self->pri_u.position.err > self->pri_u.position.ki_limit) // 积分分离
{
self->pri_u.position.ki_error += 0;
}
else
{
if (self->pri_u.position.err < 0) // 若偏差为负值,执行负偏差的累加
{
self->pri_u.position.ki_error += self->pri_u.position.err;
}
}
}
else if (self->pri_u.position.out < self->pri_u.position.out_min)
{
if (self->pri_u.position.err > self->pri_u.position.ki_limit) // 若偏差为负值,停止积分
{
self->pri_u.position.ki_error += 0;
}
else
{
if (self->pri_u.position.err > 0) // 若偏差为正值,执行正偏差的累加
{
self->pri_u.position.ki_error += self->pri_u.position.err;
}
}
}
else
{
if (fabs(err) > self->pri_u.position.ki_limit || fabs(err) < 0.5)
{
self->pri_u.position.ki_error += 0;
}
else
{
self->pri_u.position.ki_error += self->pri_u.position.err;
}
}
#else /*无积分分离操作*/
if (fabs(err) < 0.4)
{
self->pri_u.position.ki_error += 0;
}
else
{
self->pri_u.position.ki_error += self->pri_u.position.err;
}
#endif
/*输出*/
if (fabs(err) < self->pri_u.position.err_dead)
{
/*输出上一次的值*/
// self->pri_u.position.out = self->pri_u.position.pre_out;
x[0] = self->pri_u.position.err;
x[1] = self->pri_u.position.ki_error;
self->pri_u.position.out = self->pri_u.position.kp * x[0] + self->pri_u.position.ki * x[1] + self->pri_u.position.kd * x[2];
}
else
{
x[0] = self->pri_u.position.err;
x[1] = self->pri_u.position.ki_error;
#if INCOMPLETE_DIFFEREN_HD == 1
/*不完全微分项为了解决普通PID为微分环节容易振荡的问题*/
self->pri_u.position.tmp_time = sys_millis();
self->pri_u.position.control_time -= self->pri_u.position.tmp_time;
self->pri_u.position.control_time /= 1000.0; // 将单位转换为秒
x[2] = td_derivative(&_pid.pid_u.hd, err, self->pri_u.position.pre_error, self->pri_u.position.control_time);
#else
// 普通的微分环节
x[2] = self->pri_u.position.err - self->pri_u.position.pre_error;
#endif
self->pri_u.position.out = self->pri_u.position.kp * x[0] + self->pri_u.position.ki * x[1] + self->pri_u.position.kd * x[2];
}
/*输出限幅*/
if (self->pri_u.position.out > self->pri_u.position.out_max)
{
self->pri_u.position.out = self->pri_u.position.out_max;
}
if (self->pri_u.position.out < self->pri_u.position.out_min)
{
self->pri_u.position.out = self->pri_u.position.out_min;
}
// 更新误差历史
self->pri_u.position.pre_error = self->pri_u.position.err; /*上一次误差值*/
// 更新输出历史
self->pri_u.position.pre_out = self->pri_u.position.out; /*上一次输出值*/
return self->pri_u.position.out;
}
/*杭电:参数控制器*/
void pid_hd_constructor(struct PID_HD *self)
{
self->set_ctrl_prm_position = _set_ctrl_prm_position;
self->set_out_prm_position = _set_out_prm_position;
self->pid_position = _pid_position;
}

View File

@ -0,0 +1,66 @@
#ifndef __PID_HD__
#define __PID_HD__
#include "lib.h"
#define INTEGRAL_SEPARATION 1 // 积分分离
#define INCOMPLETE_DIFFEREN_HD 1 // 不完全微分
typedef struct
{
float32 ref;
float32 feed_back;
float32 pre_feed_back;
float32 pre_error;
float32 ki_error; /*积分误差*/
float32 ki_limit; /*积分分离界限*/
float32 ki_alpha; /*变积分的系数*/
float32 err;
float32 sum_iterm;
float32 kp;
float32 kp_small; /*在接近稳态时的Kp*/
float32 kp_big; /*在大范围时的Kp*/
float32 ki;
float32 kd;
float32 err_limit;
BOOL detach;
float32 err_dead;
#if INCOMPLETE_DIFFEREN_HD == 1
float32 td_alpha; /*不完全微分系数*/
float32 td_beta; /*不完全微分系数beta*/
float32 pre_derivative; /*上一次微分值*/
#endif
float32 out;
float32 pre_out;
float32 out_max;
float32 out_min;
BOOL sm;
float32 sv_range;
uint32_t control_time; /*控制算法运行一次花费的时间*/
uint32_t tmp_time; /*临时用来记录控制的运行时间*/
} pid_hd_position_t; // 位置式PID
typedef struct PID_HD
{
/* 设置PID三个参数 */
void (*set_ctrl_prm_position)(struct PID_HD *self, float32 kp, float32 ki, float32 kd);
/* 设置输出范围 */
void (*set_out_prm_position)(struct PID_HD *self, float32 maximum, float32 minimum);
/* 控制接口 */
float32 (*pid_position)(struct PID_HD *self, float32 err);
// 自定义参数
/* 实际值与目标值之间的误差 */
float32 err;
/* 输出值 */
float32 out;
/* private */
struct
{
pid_hd_position_t position;
} pri_u;
} pid_hd_t;
extern void pid_hd_constructor(struct PID_HD *self);
#endif // __PID_HD__

481
lib/control/custom/pid_x.c Normal file
View File

@ -0,0 +1,481 @@
#include "pid_x.h"
#include "math.h"
#define LAG_PHASE (6) // 迟滞相位,单位:拍
#ifndef PI
#define PI 3.14159265358979f
#endif
// 注1自适应模糊pid最重要的就是论域的选择要和你应该控制的对象相切合
// 注2以下各阀值、限幅值、输出值均需要根据具体的使用情况进行更改
// 注3因为我的控制对象惯性比较大所以以下各部分取值较小
// 论域e:[-5,5] ec:[-0.5,0.5]
// 误差的阀值小于这个数值的时候不做PID调整避免误差较小时频繁调节引起震荡
#define Emin 0.3f
#define Emid 1.0f
#define Emax 5.0f
// 调整值限幅,防止积分饱和
#define Umax 1
#define Umin -1
#define NB 0
#define NM 1
#define NS 2
#define ZO 3
#define PS 4
#define PM 5
#define PB 6
int32_t kp[7][7] = {{PB, PB, PM, PM, PS, ZO, ZO},
{PB, PB, PM, PS, PS, ZO, ZO},
{PM, PM, PM, PS, ZO, NS, NS},
{PM, PM, PS, ZO, NS, NM, NM},
{PS, PS, ZO, NS, NS, NM, NM},
{PS, ZO, NS, NM, NM, NM, NB},
{ZO, ZO, NM, NM, NM, NB, NB}};
int32_t kd[7][7] = {{PS, NS, NB, NB, NB, NM, PS},
{PS, NS, NB, NM, NM, NS, ZO},
{ZO, NS, NM, NM, NS, NS, ZO},
{ZO, NS, NS, NS, NS, NS, ZO},
{ZO, ZO, ZO, ZO, ZO, ZO, ZO},
{PB, NS, PS, PS, PS, PS, PB},
{PB, PM, PM, PM, PS, PS, PB}};
int32_t ki[7][7] = {{NB, NB, NM, NM, NS, ZO, ZO},
{NB, NB, NM, NS, NS, ZO, ZO},
{NB, NM, NS, NS, ZO, PS, PS},
{NM, NM, NS, ZO, PS, PM, PM},
{NM, NS, ZO, PS, PS, PM, PB},
{ZO, ZO, PS, PS, PM, PB, PB},
{ZO, ZO, PS, PM, PM, PB, PB}};
static float32 ec; // 误差变化率
/**************求隶属度(三角形)***************/
float32 FTri(float32 x, float32 a, float32 b, float32 c) // FuzzyTriangle
{
if (x <= a)
return 0;
else if ((a < x) && (x <= b))
return (x - a) / (b - a);
else if ((b < x) && (x <= c))
return (c - x) / (c - b);
else if (x > c)
return 0;
else
return 0;
}
/*****************求隶属度(梯形左)*******************/
float32 FTraL(float32 x, float32 a, float32 b) // FuzzyTrapezoidLeft
{
if (x <= a)
return 1;
else if ((a < x) && (x <= b))
return (b - x) / (b - a);
else if (x > b)
return 0;
else
return 0;
}
/*****************求隶属度(梯形右)*******************/
float32 FTraR(float32 x, float32 a, float32 b) // FuzzyTrapezoidRight
{
if (x <= a)
return 0;
if ((a < x) && (x < b))
return (x - a) / (b - a);
if (x >= b)
return 1;
else
return 1;
}
/****************三角形反模糊化处理**********************/
float32 uFTri(float32 x, float32 a, float32 b, float32 c)
{
float32 y, z;
z = (b - a) * x + a;
y = c - (c - b) * x;
return (y + z) / 2;
}
/*******************梯形(左)反模糊化***********************/
float32 uFTraL(float32 x, float32 a, float32 b)
{
return b - (b - a) * x;
}
/*******************梯形(右)反模糊化***********************/
float32 uFTraR(float32 x, float32 a, float32 b)
{
return (b - a) * x + a;
}
/**************************求交集****************************/
float32 fand(float32 a, float32 b)
{
return (a < b) ? a : b;
}
/**************************求并集****************************/
float32 forr(float32 a, float32 b)
{
return (a < b) ? b : a;
}
static float32 _PID(struct PID_X *self, float32 target, float32 feedback)
{
float32 pwm_var; // pwm调整量
float32 iError; // 当前误差
float32 set, input;
CLASSICPID *pri = &self->pri;
// 计算隶属度表
float32 es[7], ecs[7], e;
float32 form[7][7];
int i = 0, j = 0;
int MaxX = 0, MaxY = 0;
// 记录隶属度最大项及相应推理表的p、i、d值
float32 lsd;
int temp_p, temp_d, temp_i;
float32 detkp, detkd, detki; // 推理后的结果
// 输入格式的转化及偏差计算
set = target;
input = feedback;
iError = set - input; // 偏差
e = iError;
ec = iError - pri->lasterror;
// 当温度差的绝对值小于Emax时对pid的参数进行调整
if (fabs(iError) <= Emax)
{
// 计算iError在es与ecs中各项的隶属度
es[NB] = FTraL(e * 5, -3, -1); // e
es[NM] = FTri(e * 5, -3, -2, 0);
es[NS] = FTri(e * 5, -3, -1, 1);
es[ZO] = FTri(e * 5, -2, 0, 2);
es[PS] = FTri(e * 5, -1, 1, 3);
es[PM] = FTri(e * 5, 0, 2, 3);
es[PB] = FTraR(e * 5, 1, 3);
ecs[NB] = FTraL(ec * 30, -3, -1); // ec
ecs[NM] = FTri(ec * 30, -3, -2, 0);
ecs[NS] = FTri(ec * 30, -3, -1, 1);
ecs[ZO] = FTri(ec * 30, -2, 0, 2);
ecs[PS] = FTri(ec * 30, -1, 1, 3);
ecs[PM] = FTri(ec * 30, 0, 2, 3);
ecs[PB] = FTraR(ec * 30, 1, 3);
// 计算隶属度表确定e和ec相关联后表格各项隶属度的值
for (i = 0; i < 7; i++)
{
for (j = 0; j < 7; j++)
{
form[i][j] = fand(es[i], ecs[j]);
}
}
// 取出具有最大隶属度的那一项
for (i = 0; i < 7; i++)
{
for (j = 0; j < 7; j++)
{
if (form[MaxX][MaxY] < form[i][j])
{
MaxX = i;
MaxY = j;
}
}
}
// 进行模糊推理,并去模糊
lsd = form[MaxX][MaxY];
temp_p = kp[MaxX][MaxY];
temp_d = kd[MaxX][MaxY];
temp_i = ki[MaxX][MaxY];
if (temp_p == NB)
detkp = uFTraL(lsd, -0.3, -0.1);
else if (temp_p == NM)
detkp = uFTri(lsd, -0.3, -0.2, 0);
else if (temp_p == NS)
detkp = uFTri(lsd, -0.3, -0.1, 0.1);
else if (temp_p == ZO)
detkp = uFTri(lsd, -0.2, 0, 0.2);
else if (temp_p == PS)
detkp = uFTri(lsd, -0.1, 0.1, 0.3);
else if (temp_p == PM)
detkp = uFTri(lsd, 0, 0.2, 0.3);
else if (temp_p == PB)
detkp = uFTraR(lsd, 0.1, 0.3);
if (temp_d == NB)
detkd = uFTraL(lsd, -3, -1);
else if (temp_d == NM)
detkd = uFTri(lsd, -3, -2, 0);
else if (temp_d == NS)
detkd = uFTri(lsd, -3, 1, 1);
else if (temp_d == ZO)
detkd = uFTri(lsd, -2, 0, 2);
else if (temp_d == PS)
detkd = uFTri(lsd, -1, 1, 3);
else if (temp_d == PM)
detkd = uFTri(lsd, 0, 2, 3);
else if (temp_d == PB)
detkd = uFTraR(lsd, 1, 3);
if (temp_i == NB)
detki = uFTraL(lsd, -0.06, -0.02);
else if (temp_i == NM)
detki = uFTri(lsd, -0.06, -0.04, 0);
else if (temp_i == NS)
detki = uFTri(lsd, -0.06, -0.02, 0.02);
else if (temp_i == ZO)
detki = uFTri(lsd, -0.04, 0, 0.04);
else if (temp_i == PS)
detki = uFTri(lsd, -0.02, 0.02, 0.06);
else if (temp_i == PM)
detki = uFTri(lsd, 0, 0.04, 0.06);
else if (temp_i == PB)
detki = uFTraR(lsd, 0.02, 0.06);
// pid三项系数的修改
pri->pKp += detkp;
pri->pKi += detki;
if (pri->kd_e)
{
pri->pKd += detkd;
}
else
{
pri->pKd = 0; // 取消微分作用
}
// 对Kp,Ki进行限幅
if (pri->pKp < 0)
{
pri->pKp = 0;
}
if (pri->pKi < 0)
{
pri->pKi = 0;
}
// 计算新的K1,nKi,nKd
pri->nKp = pri->pKp + pri->pKi + pri->pKd;
pri->nKi = -(pri->pKp + 2 * pri->pKd);
pri->nKd = pri->pKd;
}
if (iError > Emax)
{
pri->out = pri->max;
pwm_var = 0;
pri->flag = 1; // 设定标志位,如果误差超过了门限值,则认为当控制量第一次到达给定值时,应该采取下面的 抑制超调 的措施
}
else if (iError < -Emax)
{
pri->out = pri->min;
pwm_var = 0;
}
else if (fabsf(iError) <= Emin)
{
pwm_var = 0;
}
else
{
if (iError < Emid && pri->flag == 1) // 第一次超过(设定值-Emid(-0.08)摄氏度),是输出为零,防止超调,也可以输出其他值,不至于太小而引起震荡
{
pri->out = 0;
pri->flag = 0;
}
else if (-iError > Emid) // 超过(设定+Emid(+0.08)摄氏度)
{
pwm_var = -1;
}
else
{
// 增量计算
pwm_var = (pri->nKp * iError // e[k]
+ pri->nKi * pri->lasterror // e[k-1]
+ pri->nKd * pri->preverror); // e[k-2]
}
if (pwm_var >= Umax)
pwm_var = Umax; // 调整值限幅,防止积分饱和
if (pwm_var <= Umin)
pwm_var = Umin; // 调整值限幅,防止积分饱和
}
pri->preverror = pri->lasterror;
pri->lasterror = iError;
pri->out += pwm_var; // 调整PWM输出
if (pri->out > pri->max)
pri->out = pri->max; // 输出值限幅
if (pri->out < pri->min)
pri->out = pri->min; // 输出值限幅
return pri->out;
}
/*整定开始前的预处理,判断状态及初始化变量*/
static void tune_pretreatment(struct PID_X *self)
{
CLASSIC_AUTOTUNE *tune = &self->tune;
CLASSICPID *vPID = &self->pri;
tune->tuneTimer = 0;
tune->startTime = 0;
tune->endTime = 0;
tune->outputStep = 100;
if (*vPID->pSV >= *vPID->pPV)
{
tune->initialStatus = 1;
tune->outputStatus = 0;
}
else
{
tune->initialStatus = 0;
tune->outputStatus = 1;
}
tune->tuneEnable = 1;
tune->preEnable = 0;
tune->zeroAcrossCounter = 0;
tune->riseLagCounter = 0;
tune->fallLagCounter = 0;
}
/*计算PID参数值*/
static void calculation_parameters(struct PID_X *self)
{
CLASSIC_AUTOTUNE *tune = &self->tune;
CLASSICPID *vPID = &self->pri;
float32 kc = 0.0f;
float32 tc = 0.0f;
float32 zn[3][3] = {{0.5f, 100000.0f, 0.0f}, {0.45f, 0.8f, 0.0f}, {0.6f, 0.5f, 0.125f}};
tc = (tune->endTime - tune->startTime) * tune->tunePeriod / 1000.0;
kc = (8.0f * tune->outputStep) / (PI * (tune->maxPV - tune->minPV));
vPID->pKp = zn[tune->controllerType][0] * kc; // 比例系数
vPID->pKi = vPID->pKp * tune->tunePeriod / (zn[tune->controllerType][1] * tc); // 积分系数
vPID->pKd = vPID->pKp * zn[tune->controllerType][2] * tc / tune->tunePeriod; // 微分系数
}
/**
* @brief
* @param {PID_X} *self
* @return {*}
* @note tuneEnablepreEnable和controllerType需要提前赋值tuneEnable变量值为0时是使用PID控制器tuneEnable变量值为1时是开启整定过程tuneEnable变量值为2时是指示整定失败preEnable变量在整定前赋值为1controllerType则根据所整定的控制器的类型来定
*/
static uint8_t _auto_tune(struct PID_X *self)
{
CLASSIC_AUTOTUNE *tune = &self->tune;
CLASSICPID *vPID = &self->pri;
/*整定开始前的预处理,只执行一次*/
if (tune->preEnable == 1)
{
tune_pretreatment(self);
}
uint32_t tuneDuration = 0;
tune->tuneTimer++;
tuneDuration = (tune->tuneTimer * tune->tunePeriod) / 1000;
if (tuneDuration > (10 * 60)) // 整定过程持续超过10分钟未能形成有效振荡整定失败
{
tune->tuneEnable = 2;
tune->preEnable = 1;
return tune->tuneEnable;
}
if (*vPID->pSV >= *vPID->pPV) // 设定值大于测量值,则开执行单元
{
tune->riseLagCounter++;
tune->fallLagCounter = 0;
if (tune->riseLagCounter > LAG_PHASE)
{
*vPID->pMV = vPID->max;
if (tune->outputStatus == 0)
{
tune->outputStatus = 1;
tune->zeroAcrossCounter++;
if (tune->zeroAcrossCounter == 3)
{
tune->startTime = tune->tuneTimer;
}
}
}
}
else
{
tune->riseLagCounter = 0;
tune->fallLagCounter++;
if (tune->fallLagCounter > LAG_PHASE)
{
*vPID->pMV = vPID->min;
if (tune->outputStatus == 1)
{
tune->outputStatus = 0;
tune->zeroAcrossCounter++;
if (tune->zeroAcrossCounter == 3)
{
tune->startTime = tune->tuneTimer;
}
}
}
}
if (tune->zeroAcrossCounter == 3) // 已经两次过零,可以记录波形数据
{
if (tune->initialStatus == 1) // 初始设定值大于测量值则区域3出现最小值
{
if (*vPID->pPV < tune->minPV)
{
tune->minPV = *vPID->pPV;
}
}
else if (tune->initialStatus == 0) // 初始设定值小于测量值则区域3出现最大值
{
if (*vPID->pPV > tune->maxPV)
{
tune->maxPV = *vPID->pPV;
}
}
}
else if (tune->zeroAcrossCounter == 4) // 已经三次过零,记录另半波的数据
{
if (tune->initialStatus == 1) // 初始设定值大于测量值则区域4出现最大值
{
if (*vPID->pPV > tune->maxPV)
{
tune->maxPV = *vPID->pPV;
}
}
else if (tune->initialStatus == 0) // 初始设定值小于测量值则区域4出现最小值
{
if (*vPID->pPV < tune->minPV)
{
tune->minPV = *vPID->pPV;
}
}
}
else if (tune->zeroAcrossCounter == 5) // 已经四次过零,振荡已形成可以整定参数
{
calculation_parameters(self);
tune->tuneEnable = 0;
tune->preEnable = 1;
}
return tune->tuneEnable;
}
void pid_x_constructor(struct PID_X *self)
{
self->PID = _PID;
self->AUTO_TUNE = _auto_tune;
self->pri.flag = 0;
self->pri.out = 0;
self->tune.preEnable = 1;
}

View File

@ -0,0 +1,71 @@
#ifndef __PID_X_H__
#define __PID_X_H__
#include "lib.h"
/*定义PID对象类型*/
typedef struct CLASSIC
{
float32 *pPV; // 测量值指针
float32 *pSV; // 设定值指针
float32 *pMV; // 输出值指针
BOOL *pMA; // 手自动操作指针
float32 out; // 输出值
float32 setpoint; // 设定值
float32 lasterror; // 前一拍偏差
float32 preverror; // 前两拍偏差
float32 max; // 输出值上限
float32 min; // 输出值下限
uint16_t flag; // 状态标志位
float32 pKp; // 比例系数
float32 pKi; // 积分系数
float32 pKd; // 微分系数
float32 nKp; // 比例系数
float32 nKi; // 积分系数
float32 nKd; // 微分系数
BOOL direct; // 正反作用
BOOL sm; // 设定值平滑
BOOL cas; // 串级设定
BOOL pac; // 输出防陡变
BOOL kd_e; // 微分使能
} CLASSICPID;
// 定义整定参数
typedef struct
{
uint8_t tuneEnable : 2; // 整定与PID控制开关0PID控制1参数整定2整定失败
uint8_t preEnable : 2; // 预处理使能,在开始整定前置位
uint8_t initialStatus : 1; // 记录开始整定前偏差的初始状态
uint8_t outputStatus : 1; // 记录输出的初始状态0允许上升过零计数1允许下降过零计数
uint8_t controllerType : 2; // 控制器类型0P控制器1PI控制器2PID控制器
uint8_t zeroAcrossCounter; // 过零点计数器每次输出改变加1比实际过零次数多1
uint8_t riseLagCounter; // 上升迟滞时间计数器
uint8_t fallLagCounter; // 下降迟滞时间计数器
uint16_t tunePeriod; // 整定采样周期
uint32_t tuneTimer; // 整定计时器
uint32_t startTime; // 记录波形周期起始时间
uint32_t endTime; // 记录波形周期结束时间
float32 outputStep; // 输出阶跃d
float32 maxPV; // 振荡波形中测量值的最大值
float32 minPV; // 振荡波形中测量值的最小值
} CLASSIC_AUTOTUNE;
typedef struct PID_X
{
/* 控制接口 */
float32 (*PID)(struct PID_X *self, float32 target, float32 feedback);
uint8_t (*AUTO_TUNE)(struct PID_X *self);
/* private */
CLASSICPID pri;
CLASSIC_AUTOTUNE tune;
} pid_x_t;
extern void pid_x_constructor(struct PID_X *self);
#endif // __PID_X_H__

467
lib/control/custom/pid_zh.c Normal file
View File

@ -0,0 +1,467 @@
#include "pid_zh.h"
#include "sys.h"
#include <math.h>
// 定义输出量比例因子
#ifdef GPS3000
#define KUP 0.0f // #define KUP 3.0f
#define KUI 0.00f
#define KUD 0.0f // #define KUP 3.0f
#else
#define KUP 3.0f
#define KUI 0.0f
#define KUD 0.0f
#endif
// 模糊集合
#define NL -3
#define NM -2
#define NS -1
#define ZE 0
#define PS 1
#define PM 2
#define PL 3
// 定义偏差E的范围因为设置了非线性区间误差在10时才开始进行PID调节这里E的范围为10
#define MAXE (10)
#define MINE (-MAXE)
// 定义EC的范围因为变化非常缓慢每次的EC都非常小这里可以根据实际需求来调整
#define MAXEC (10)
#define MINEC (-MAXEC)
// 定义e,ec的量化因子
#define KE 3 / MAXE
#define KEC 3 / MAXEC
static const float32 fuzzyRuleKp[7][7] = {
PL, PL, PM, PL, PS, PM, PL,
PL, PM, PM, PM, PS, PM, PL,
PM, PS, PS, PS, PS, PS, PM,
PM, PS, ZE, ZE, ZE, PS, PM,
PS, PS, PS, PS, PS, PM, PM,
PM, PM, PM, PM, PL, PL, PL,
PM, PL, PL, PL, PL, PL, PL};
static const float32 fuzzyRuleKi[7][7] = {
PL, PL, PL, PL, PM, PL, PL,
PL, PL, PM, PM, PM, PL, PL,
PM, PM, PS, PS, PS, PM, PM,
PM, PS, ZE, ZE, ZE, PS, PM,
PM, PS, PS, PS, PS, PM, PM,
PM, PM, PS, PM, PM, PL, PL,
PM, PL, PM, PL, PL, PL, PL};
/*
static const float32 fuzzyRuleKi[7][7] = {
NL, NL, NL, NL, NM, NL, NL,
NL, NL, NM, NM, NM, NL, NL,
NM, NM, NS, NS, NS, NM, NM,
NM, NS, ZE, ZE, ZE, NS, NM,
NM, NS, NS, NS, NS, NM, NM,
NM, NM, NS, NM, NM, NL, NL,
NM, NL, NM, NL, NL, NL, NL};
*/
static const float32 fuzzyRuleKd[7][7] = {
PS, PS, ZE, ZE, ZE, PL, PL,
PS, PS, PS, PS, ZE, PS, PM,
PL, PL, PM, PS, ZE, PS, PM,
PL, PM, PM, PS, ZE, PS, PM,
PL, PM, PS, PS, ZE, PS, PS,
PM, PS, PS, PS, ZE, PS, PS,
PS, ZE, ZE, ZE, ZE, PL, PL};
/*
static const float32 fuzzyRuleKp[7][7] = {
PL, PL, PM, PM, PS, ZE, ZE,
PL, PL, PM, PS, PS, ZE, NS,
PM, PM, PM, PS, ZE, NS, NS,
PM, PM, PS, ZE, NS, NM, NM,
PS, PS, ZE, NS, NS, NM, NM,
PS, ZE, NS, NM, NM, NM, NL,
ZE, ZE, NM, NM, NM, NL, NL};
static const float32 fuzzyRuleKi[7][7] = {
NL, NL, NM, NM, NS, ZE, ZE,
NL, NL, NM, NS, NS, ZE, ZE,
NL, NM, NS, NS, ZE, PS, PS,
NM, NM, NS, ZE, PS, PM, PM,
NM, NS, ZE, PS, PS, NM, PL,
ZE, ZE, PS, PS, PM, PL, PL,
ZE, ZE, PS, PM, PM, PL, PL};
static const float32 fuzzyRuleKd[7][7] = {
PS, NS, NL, NL, NL, NM, PS,
PS, NS, NL, NM, NM, NS, ZE,
ZE, NS, NM, NM, NS, NS, ZE,
ZE, NS, NS, NS, NS, NS, ZE,
ZE, ZE, ZE, ZE, ZE, ZE, ZE,
PL, NS, PS, PS, PS, PS, PL,
PL, PM, PM, PM, PS, PS, PL};
*/
static void fuzzy(float32 e, float32 ec, FUZZY_PID_ZH_t *fuzzy_pid)
{
float32 etemp, ectemp;
float32 eLefttemp, ecLefttemp; // ec,e左隶属度
float32 eRighttemp, ecRighttemp;
int eLeftIndex, ecLeftIndex; // 模糊位置标号
int eRightIndex, ecRightIndex;
e = RANGE(e, MINE, MAXE);
ec = RANGE(ec, MINEC, MAXEC);
e = e * KE;
ec = ec * KEC;
etemp = e > 3.0f ? 0.0f : (e < -3.0f ? 0.0f : (e >= 0.0f ? (e >= 2.0f ? 2.5f : (e >= 1.0f ? 1.5f : 0.5f)) : (e >= -1.0f ? -0.5f : (e >= -2.0f ? -1.5f : (e >= -3.0f ? -2.5f : 0.0f)))));
eLeftIndex = (int)((etemp - 0.5f) + 3); //[-3,2] -> [0,5]
eRightIndex = (int)((etemp + 0.5f) + 3);
eLefttemp = etemp == 0.0f ? 0.0f : ((etemp + 0.5f) - e);
eRighttemp = etemp == 0.0f ? 0.0f : (e - (etemp - 0.5f));
ectemp = ec > 3.0f ? 0.0f : (ec < -3.0f ? 0.0f : (ec >= 0.0f ? (ec >= 2.0f ? 2.5f : (ec >= 1.0f ? 1.5f : 0.5f)) : (ec >= -1.0f ? -0.5f : (ec >= -2.0f ? -1.5f : (ec >= -3.0f ? -2.5f : 0.0f)))));
ecLeftIndex = (int)((ectemp - 0.5f) + 3); //[-3,2] -> [0,5]
ecRightIndex = (int)((ectemp + 0.5f) + 3);
ecLefttemp = ectemp == 0.0f ? 0.0f : ((ectemp + 0.5f) - ec);
ecRighttemp = ectemp == 0.0f ? 0.0f : (ec - (ectemp - 0.5f));
/*************************************反模糊*************************************/
fuzzy_pid->kp = (eLefttemp * ecLefttemp * fuzzyRuleKp[eLeftIndex][ecLeftIndex] + eLefttemp * ecRighttemp * fuzzyRuleKp[eLeftIndex][ecRightIndex] + eRighttemp * ecLefttemp * fuzzyRuleKp[eRightIndex][ecLeftIndex] + eRighttemp * ecRighttemp * fuzzyRuleKp[eRightIndex][ecRightIndex]);
fuzzy_pid->ki = (eLefttemp * ecLefttemp * fuzzyRuleKi[eLeftIndex][ecLeftIndex] + eLefttemp * ecRighttemp * fuzzyRuleKi[eLeftIndex][ecRightIndex] + eRighttemp * ecLefttemp * fuzzyRuleKi[eRightIndex][ecLeftIndex] + eRighttemp * ecRighttemp * fuzzyRuleKi[eRightIndex][ecRightIndex]);
fuzzy_pid->kd = (eLefttemp * ecLefttemp * fuzzyRuleKd[eLeftIndex][ecLeftIndex] + eLefttemp * ecRighttemp * fuzzyRuleKd[eLeftIndex][ecRightIndex] + eRighttemp * ecLefttemp * fuzzyRuleKd[eRightIndex][ecLeftIndex] + eRighttemp * ecRighttemp * fuzzyRuleKd[eRightIndex][ecRightIndex]);
// 对解算出的KP,KI,KD进行量化映射
fuzzy_pid->kp = fuzzy_pid->kp * fuzzy_pid->kup;
fuzzy_pid->ki = fuzzy_pid->ki * fuzzy_pid->kui;
fuzzy_pid->kd = fuzzy_pid->kd * fuzzy_pid->kud;
}
static void smoothSetpoint(struct PID_FUZZY_ZH *self, float32 target_sv)
{
#if FUZZY_SUB_TYPE == PID_SUB_TYPE_POSITION
pid_zh_position_t *pri = &self->pri;
#else
pid_common_increment_t *pri = &self->pri;
#endif
float32 stepIn = (pri->sv_range) * 0.1f;
float32 kFactor = 0.0f;
if (fabs(pri->ref - target_sv) <= stepIn)
{
pri->ref = target_sv;
}
else
{
if (pri->ref - target_sv > 0)
{
kFactor = -1.0f;
}
else if (pri->ref - target_sv < 0)
{
kFactor = 1.0f;
}
else
{
kFactor = 0.0f;
}
pri->ref = pri->ref + kFactor * stepIn;
}
}
/*封装模糊接口*/
static void compensate(float32 e, float32 ec, FUZZY_PID_ZH_t *fuzzy_d)
{
fuzzy(e, ec, fuzzy_d);
}
/**
* @brief PID积分及微分控制数据
* @param {PID_FUZZY_ZH} *self
* @return {*}
*/
static void _restctrl(struct PID_FUZZY_ZH *self)
{
self->pri.pre_error = 0;
self->pri.sum_iterm = 0;
#if INCOMPLETE_DIFFEREN == 1
self->pri.lastdev = 0;
#endif
}
/**
* @brief
* @param {PID_FUZZY_ZH} *self
* @param {float32} out_min
* @param {float32} out_max
* @return {*}
* @note
*/
static void _set_range(struct PID_FUZZY_ZH *self, float32 out_min, float32 out_max)
{
self->pri.out_max = out_max;
self->pri.out_min = out_min;
}
/**
* @brief 使
* @param {PID_FUZZY_ZH} *self
* @param {BOOL} enable
* @return {*}
* @note
*/
// static void _set_ki_enable(struct PID_FUZZY_ZH *self, BOOL enable)
// {
// self->pri.ki_enable = enable;
// }
/**
* @brief 使
* @param {PID_FUZZY_ZH} *self
* @param {BOOL} enable
* @return {*}
* @note
*/
static void _set_kd_enable(struct PID_FUZZY_ZH *self, BOOL enable)
{
self->pri.kd_enable = enable;
}
/*
* Function:使
* parameter:*pid需要配PID参数结构指针sv_range控制范围sv的范围
* return:
*/
static void _set_smooth_enable(struct PID_FUZZY_ZH *self, BOOL enable, float32 sv_range)
{
#if FUZZY_SUB_TYPE == PID_SUB_TYPE_POSITION
pid_zh_position_t *pri = &self->pri;
#else
pid_common_increment_t *pri = &self->pri;
#endif
pri->sm = enable;
pri->sv_range = sv_range;
}
// 设置控制参数
static void _set_ctrl_prm(struct PID_FUZZY_ZH *self, float32 kp, float32 ki, float32 kd, float32 err_dead,
float32 out_min, float32 out_max)
{
self->open = TRUE;
self->fuzzy.kup = KUP;
self->fuzzy.kui = KUI;
self->fuzzy.kud = KUD;
#if FUZZY_SUB_TYPE == PID_SUB_TYPE_POSITION
pid_zh_position_t *pri = &self->pri;
osel_memset((uint8_t *)pri, 0, sizeof(pid_zh_position_t));
pri->kp = kp;
pri->ki = ki;
pri->kd = kd;
pri->err_dead = err_dead;
pri->out_max = out_max;
pri->out_min = out_min;
pri->detach = FALSE;
pri->sm = FALSE;
#else
pid_common_increment_t *pri = &self->pri;
osel_memset((uint8_t *)pri, 0, sizeof(pid_common_increment_t));
pri->kp = kp;
pri->ki = ki;
pri->kd = kd;
pri->err_dead = err_dead;
pri->out_max = out_max;
pri->out_min = out_min;
#endif
if (kd > 0)
{
pri->kd_enable = TRUE;
}
else
{
pri->kd_enable = FALSE;
}
}
static void _update_ctrl_prm(struct PID_FUZZY_ZH *self, float32 kp, float32 ki, float32 kd, float32 err_dead,
float32 out_min, float32 out_max)
{
#if FUZZY_SUB_TYPE == PID_SUB_TYPE_POSITION
pid_zh_position_t *pri = &self->pri;
pri->kp = kp;
pri->ki = ki;
pri->kd = kd;
pri->err_dead = err_dead;
pri->out_max = out_max;
pri->out_min = out_min;
pri->detach = FALSE;
pri->sm = FALSE;
#else
pid_common_increment_t *pri = &self->pri;
pri->kp = kp;
pri->ki = ki;
pri->kd = kd;
pri->err_dead = err_dead;
pri->out_max = out_max;
pri->out_min = out_min;
#endif
if (kd > 0)
{
pri->kd_enable = TRUE;
}
else
{
pri->kd_enable = FALSE;
}
}
/**
* @brief 0+PID,PID
* @param {PID_FUZZY_ZH} *self
* @param {float32} max_err
* @param {BOOL} mode
* @return {*}
*/
static void _set_cfg(struct PID_FUZZY_ZH *self, float32 max_err, BOOL mode)
{
self->pri.err_limit = max_err;
self->pri.detach = mode == FALSE ? FALSE : TRUE;
}
#if FUZZY_SUB_TYPE == PID_SUB_TYPE_POSITION
static float32 _PID(struct PID_FUZZY_ZH *self, float32 target, float32 feedback)
{
float32 error = 0;
float32 insert = 0;
float32 ec = 0;
float32 kd = 0;
#if INCOMPLETE_DIFFEREN == 1
float32 thisdev = 0;
#else
// float32 dinput = 0.0f;
#endif
float32 temp_iterm = 0.0f;
pid_zh_position_t *pri = &self->pri;
/*获取期望值与实际值,进行偏差计算*/
if (pri->sm == 1)
{
smoothSetpoint(self, target);
}
else
{
pri->ref = target;
}
pri->feed_back = feedback;
error = pri->ref - pri->feed_back;
if (fabs(error) <= pri->err_dead)
error = 0;
/* fuzzy control caculate */
ec = error - pri->pre_error;
if (self->open == TRUE)
{
compensate(error, ec, &self->fuzzy);
}
/*根据PID配置的模式,获取积分数据,进行积分累加*/
if (pri->out >= pri->out_max)
{
if (fabs(error) > pri->err_limit && pri->detach)
{
insert = 0;
}
else
{
insert = 1;
if (error < 0)
{
temp_iterm = (pri->ki + self->fuzzy.ki) * error;
}
}
}
else if (pri->out <= pri->out_min)
{
if (fabs(error) > pri->err_limit && pri->detach)
{
insert = 0;
}
else
{
insert = 1;
if (error > 0)
{
temp_iterm = (pri->ki + self->fuzzy.ki) * error;
}
}
}
else
{
if (fabs(error) > pri->err_limit && pri->detach)
{
insert = 0;
}
else
{
insert = 1;
temp_iterm = (pri->ki + self->fuzzy.ki) * error;
}
}
pri->sum_iterm += temp_iterm;
/* limt integral */
pri->sum_iterm = RANGE(pri->sum_iterm, pri->out_min, pri->out_max);
/*
if (pri->sum_ref)
pri->sum_iterm = RANGE(pri->sum_iterm, pri->sum_ref - 1.0f, pri->sum_ref + 1.0f);
else
pri->sum_iterm = RANGE(pri->sum_iterm, pri->out_min, pri->out_max);
*/
#if INCOMPLETE_DIFFEREN == 1
/*不完全微分*/
thisdev = (pri->kd + self->fuzzy.kd) * (1.0 - pri->alpha) * (error - pri->pre_error) + pri->alpha * pri->lastdev;
/*caculate pid out*/
pri->out = (pri->kp + self->fuzzy.kp) * error + pri->sum_iterm * insert + thisdev;
/*record last dev result*/
pri->lastdev = thisdev;
#else
if (pri->kd_enable == TRUE)
{
kd = pri->kd + self->fuzzy.kd;
}
else
{
kd = 0;
}
pri->out = (pri->kp + self->fuzzy.kp) * error + pri->sum_iterm * insert + (error - pri->pre_error) * (kd);
// pri->out += pri->sum_ref;
#endif
pri->pre_error = error;
/*record last feedback sensor result*/
pri->pre_feed_back = pri->feed_back;
/*limt pid output*/
pri->out = RANGE(pri->out, pri->out_min, pri->out_max);
return pri->out;
}
#else
#endif
void pid_zh_constructor(struct PID_FUZZY_ZH *self)
{
self->set_ctrl_prm = _set_ctrl_prm;
self->update_ctrl_prm = _update_ctrl_prm;
self->set_cfg = _set_cfg;
self->set_smooth_enable = _set_smooth_enable;
// self->set_ki_enable = _set_ki_enable;
self->set_kd_enable = _set_kd_enable;
self->set_range = _set_range;
self->restctrl = _restctrl;
self->PID = _PID;
}

View File

@ -0,0 +1,73 @@
#ifndef __PID_ZH_H__
#define __PID_ZH_H__
#include "lib.h"
#include "pid_auto_tune.h"
#define GPS2000
typedef struct
{
float32 ref;
float32 feed_back;
float32 pre_feed_back;
float32 pre_error;
float32 sum_ref;
float32 sum_iterm;
float32 kp;
float32 ki;
float32 kd;
float32 err_limit;
BOOL detach;
float32 err_dead;
#if INCOMPLETE_DIFFEREN == 1
float32 alpha;
float32 lastdev;
#endif
float32 out;
float32 out_max;
float32 out_min;
float32 sv_range;
BOOL sm;
BOOL ki_enable;
BOOL kd_enable;
} pid_zh_position_t; // 位置式PID
typedef struct
{
float32 kp;
float32 ki;
float32 kd;
float32 kup;
float32 kui;
float32 kud;
} FUZZY_PID_ZH_t;
// 模糊PID
typedef struct PID_FUZZY_ZH
{
/* 设置PID三个参数 */
void (*set_ctrl_prm)(struct PID_FUZZY_ZH *self, float32 kp, float32 ki, float32 kd, float32 err_dead,
float32 out_min, float32 out_max); // 设置PID参数
void (*update_ctrl_prm)(struct PID_FUZZY_ZH *self, float32 kp, float32 ki, float32 kd, float32 err_dead,
float32 out_min, float32 out_max); // 更新PID参数
void (*set_range)(struct PID_FUZZY_ZH *self, float32 out_min, float32 out_max); // 更新最大最小值
void (*set_cfg)(struct PID_FUZZY_ZH *self, float32 max_err, BOOL mode); // 配置PID模式,默认不使用积分分离
void (*set_smooth_enable)(struct PID_FUZZY_ZH *self, BOOL enable, float32 sv_range); // 设置平滑范围
// void (*set_ki_enable)(struct PID_FUZZY *self, BOOL enable);
// 微分开启使能
void (*set_kd_enable)(struct PID_FUZZY_ZH *self, BOOL enable);
void (*restctrl)(struct PID_FUZZY_ZH *self); // 复位PID积分及微分控制数据
/* 控制接口 */
float32 (*PID)(struct PID_FUZZY_ZH *self, float32 target, float32 feedback);
pid_zh_position_t pri;
BOOL open; // 是否使用模糊PID控制
FUZZY_PID_ZH_t fuzzy;
} pid_zh_t; // 模糊PID
extern void pid_zh_constructor(struct PID_FUZZY_ZH *self);
#endif

View File

@ -0,0 +1,619 @@
#include <math.h>
#include "pid_zh1.h"
// 定义输出量比例因子
#define KUP 1.0f
#define KUI 1.0f
#define KUD 1.0f
// 模糊集合
#define NL -3
#define NM -2
#define NS -1
#define ZE 0
#define PS 1
#define PM 2
#define PL 3
// 定义偏差E的范围因为设置了非线性区间误差在10时才开始进行PID调节这里E的范围为10
#define MAXE (10)
#define MINE (-MAXE)
// 定义EC的范围因为变化非常缓慢每次的EC都非常小这里可以根据实际需求来调整
#define MAXEC (10)
#define MINEC (-MAXEC)
// 定义e,ec的量化因子
#define KE 3 / MAXE
#define KEC 3 / MAXEC
/*
static const float fuzzyRuleKp[7][7] = {
PL, PL, PM, PL, PS, PM, PL,
PL, PM, PM, PM, PS, PM, PL,
PM, PS, PS, PS, PS, PS, PM,
PM, PS, ZE, ZE, ZE, PS, PM,
PS, PS, PS, PS, PS, PM, PM,
PM, PM, PM, PM, PL, PL, PL,
PM, PL, PL, PL, PL, PL, PL};
static const float fuzzyRuleKi[7][7] = {
PL, PL, PL, PL, PM, PL, PL,
PL, PL, PM, PM, PM, PL, PL,
PM, PM, PS, PS, PS, PM, PM,
PM, PS, ZE, ZE, ZE, PS, PM,
PM, PS, PS, PS, PS, PM, PM,
PM, PM, PS, PM, PM, PL, PL,
PM, PL, PM, PL, PL, PL, PL};
static const float fuzzyRuleKd[7][7] = {
PS, PS, ZE, ZE, ZE, PL, PL,
PS, PS, PS, PS, ZE, PS, PM,
PL, PL, PM, PS, ZE, PS, PM,
PL, PM, PM, PS, ZE, PS, PM,
PL, PM, PS, PS, ZE, PS, PS,
PM, PS, PS, PS, ZE, PS, PS,
PS, ZE, ZE, ZE, ZE, PL, PL};
*/
static const float fuzzyRuleKp[7][7] = {
PL, PL, PM, PL, PS, PM, PL,
PL, PM, PM, PM, PS, PM, PL,
PM, PS, PS, PS, PS, PS, PM,
PM, PS, ZE, ZE, ZE, PS, PM,
PS, PS, PS, PS, PS, PM, PM,
PM, PM, PM, PM, PL, PL, PL,
PM, PL, PL, PL, PL, PL, PL};
static const float fuzzyRuleKi[7][7] = {
PL, PL, PL, PL, PM, PL, PL,
PL, PL, PM, PM, PM, PL, PL,
PM, PM, PS, PS, PS, PM, PM,
PM, PS, ZE, ZE, ZE, PS, PM,
PM, PS, PS, PS, PS, PM, PM,
PM, PM, PS, PM, PM, PL, PL,
PM, PL, PM, PL, PL, PL, PL};
static const float fuzzyRuleKd[7][7] = {
PS, PS, ZE, ZE, ZE, PL, PL,
PS, PS, PS, PS, ZE, PS, PM,
PL, PL, PM, PS, ZE, PS, PM,
PL, PM, PM, PS, ZE, PS, PM,
PL, PM, PS, PS, ZE, PS, PS,
PM, PS, PS, PS, ZE, PS, PS,
PS, ZE, ZE, ZE, ZE, PL, PL};
static void fuzzy(float e, float ec, fuzzy_pid_t *fuzzy_pid)
{
float etemp, ectemp;
float eLefttemp, ecLefttemp; // 左隶属度
float eRighttemp, ecRighttemp; // 右隶属度
int eLeftIndex, ecLeftIndex; // 模糊位置标号
int eRightIndex, ecRightIndex;
e = RANGE(e, MINE, MAXE);
ec = RANGE(ec, MINEC, MAXEC);
e = e * KE;
ec = ec * KEC;
etemp = e > 3.0f ? 0.0f : (e < -3.0f ? 0.0f : (e >= 0.0f ? (e >= 2.0f ? 2.5f : (e >= 1.0f ? 1.5f : 0.5f)) : (e >= -1.0f ? -0.5f : (e >= -2.0f ? -1.5f : (e >= -3.0f ? -2.5f : 0.0f)))));
eLeftIndex = (int)((etemp - 0.5f) + 3);
eRightIndex = (int)((etemp + 0.5f) + 3);
eLefttemp = etemp == 0.0f ? 0.0f : ((etemp + 0.5f) - e);
eRighttemp = etemp == 0.0f ? 0.0f : (e - (etemp - 0.5f));
ectemp = ec > 3.0f ? 0.0f : (ec < -3.0f ? 0.0f : (ec >= 0.0f ? (ec >= 2.0f ? 2.5f : (ec >= 1.0f ? 1.5f : 0.5f)) : (ec >= -1.0f ? -0.5f : (ec >= -2.0f ? -1.5f : (ec >= -3.0f ? -2.5f : 0.0f)))));
ecLeftIndex = (int)((ectemp - 0.5f) + 3);
ecRightIndex = (int)((ectemp + 0.5f) + 3);
ecLefttemp = ectemp == 0.0f ? 0.0f : ((ectemp + 0.5f) - ec);
ecRighttemp = ectemp == 0.0f ? 0.0f : (ec - (ectemp - 0.5f));
/*************************************反模糊*************************************/
fuzzy_pid->kp = (eLefttemp * ecLefttemp * fuzzyRuleKp[eLeftIndex][ecLeftIndex] + eLefttemp * ecRighttemp * fuzzyRuleKp[eLeftIndex][ecRightIndex] + eRighttemp * ecLefttemp * fuzzyRuleKp[eRightIndex][ecLeftIndex] + eRighttemp * ecRighttemp * fuzzyRuleKp[eRightIndex][ecRightIndex]);
fuzzy_pid->ki = (eLefttemp * ecLefttemp * fuzzyRuleKi[eLeftIndex][ecLeftIndex] + eLefttemp * ecRighttemp * fuzzyRuleKi[eLeftIndex][ecRightIndex] + eRighttemp * ecLefttemp * fuzzyRuleKi[eRightIndex][ecLeftIndex] + eRighttemp * ecRighttemp * fuzzyRuleKi[eRightIndex][ecRightIndex]);
fuzzy_pid->kd = (eLefttemp * ecLefttemp * fuzzyRuleKd[eLeftIndex][ecLeftIndex] + eLefttemp * ecRighttemp * fuzzyRuleKd[eLeftIndex][ecRightIndex] + eRighttemp * ecLefttemp * fuzzyRuleKd[eRightIndex][ecLeftIndex] + eRighttemp * ecRighttemp * fuzzyRuleKd[eRightIndex][ecRightIndex]);
// 对解算出的KP,KI,KD进行量化映射
fuzzy_pid->kp = fuzzy_pid->kp * fuzzy_pid->kup;
fuzzy_pid->ki = fuzzy_pid->ki * fuzzy_pid->kui;
fuzzy_pid->kd = fuzzy_pid->kd * fuzzy_pid->kud;
}
static void smooth_init(smart_pid_t *pid, BOOL sm_open, float maxTarget)
{
if (!pid)
return;
pid->sm_open = sm_open;
pid->maxTarget = maxTarget;
}
static void smooth_target(smart_pid_t *pid, float *target)
{
if ((!pid) || (!target))
return;
if (!pid->maxTarget)
return;
float sm_step = (pid->maxTarget) * 0.1f;
float k = 0.0f;
if (fabs(pid->target - *target) <= sm_step)
{
pid->target = *target;
}
else
{
if (pid->target - *target > 0)
{
k = -1.0f;
}
else if (pid->target - *target < 0)
{
k = 1.0f;
}
else
{
k = 0.0f;
}
pid->target += k * sm_step;
}
}
static void smart_pid_init(smart_pid_t *pid, float *duty, float *kp, float *ki, float *kd, float *errorDead, float *iDetachCondation, float *maxOut)
{
if ((!pid) || (!duty) || (!kp) || (!ki) || (!kd) || (!iDetachCondation) || (!maxOut))
return;
pid->duty = *duty;
pid->kp = *kp;
pid->ki = *ki;
pid->kd = *kd;
pid->errorDead = *errorDead;
pid->iDetachCondation = *iDetachCondation;
pid->maxOutput = *maxOut;
}
void cascade_pid_init(cascade_pid_t *pid, smart_pid_t *pid_outer, smart_pid_t *pid_inner)
{
smooth_init(&pid->outer, pid_outer->sm_open, pid_outer->maxTarget);
smooth_init(&pid->inner, pid_inner->sm_open, pid_inner->maxTarget);
smart_pid_init(&pid->outer, &pid_outer->duty, &pid_outer->kp, &pid_outer->ki, &pid_outer->kd, &pid_outer->errorDead, &pid_outer->iDetachCondation, &pid_outer->maxOutput);
smart_pid_init(&pid->inner, &pid_inner->duty, &pid_inner->kp, &pid_inner->ki, &pid_inner->kd, &pid_inner->errorDead, &pid_inner->iDetachCondation, &pid_inner->maxOutput);
}
void smart_pid_calc(smart_pid_t *pid, float *target, float *feedback)
{
// 将旧error存起来
pid->lastError = pid->error;
// 平滑处理目标值
if (pid->sm_open == TRUE)
smooth_target(pid, target);
else
pid->target = *target;
// 计算新error
pid->error = pid->target - *feedback;
if (fabs(pid->error) <= pid->errorDead)
pid->error = 0.0f;
// 计算误差变化
pid->dError = pid->error - pid->lastError;
// 选用模糊规则
if (pid->fuzzy_open == TRUE)
{
fuzzy(pid->error, pid->dError, &pid->fuzzy_pid);
}
// 计算微分
float dout = pid->dError * (pid->kd + pid->fuzzy_pid.kd);
// 计算比例
float pout = pid->error * (pid->kp + pid->fuzzy_pid.kp);
// 积分分离
if (fabs(pid->error) <= pid->iDetachCondation)
{
pid->integral += pid->error * (pid->ki + pid->fuzzy_pid.ki);
pid->iDetach = FALSE;
}
else
{
pid->iDetach = TRUE;
pid->integral = 0;
}
// 积分限幅
if (pid->integral > pid->maxOutput)
pid->integral = pid->maxOutput;
else if (pid->integral < -pid->maxOutput)
pid->integral = -pid->maxOutput;
// 计算输出
pid->output = pout + dout + pid->integral * (!pid->iDetach);
// 输出限幅
if (pid->output > pid->maxOutput)
pid->output = pid->maxOutput;
else if (pid->output < -pid->maxOutput)
pid->output = -pid->maxOutput;
}
void cascade_pid_calc(struct CascadePID *pid, float *outerRef, float *outerFdb, float *innerFdb)
{
// 外环位置控制
smart_pid_calc(&pid->cascade_pid.outer, outerRef, outerFdb);
// 内环速度控制
smart_pid_calc(&pid->cascade_pid.inner, &pid->cascade_pid.outer.output, innerFdb);
// 内环输出就是串级PID的输出
// pid->cascade_pid.output = pid->cascade_pid.inner.output;
pid->cascade_pid.output = pid->cascade_pid.outer.output;
}
void pid_zh_constructor1(struct CascadePID *pid)
{
pid->smart_pid_init = smart_pid_init;
pid->smart_pid_calc = smart_pid_calc;
pid->cascade_pid_init = cascade_pid_init;
pid->cascade_pid_calc = cascade_pid_calc;
}
/*
L[1] -> 1/s
L[t] -> 1/s^2
L[1/2t^2] -> 1/s^3
G(s) = k/(TS+1)
G(s) = k/S^i(TS+1)
i = 0 0 i = 1 I I = 2 II
G(s)
G闭(s) = G(s) / 1 + G(s)
R(s) = 1/1+G(s)
limf(t) = lim s*G(s)
t-> s->0
o型系统r/s
e = lim f(t) = lim s*G(s) = G(s) = k/1+G(s) = k/ 1 + (Ts+1+k)..
t-> s->0 s->0 s->0 = s->0
*
*线
*
tr td tp
G(s) = 1/ s^2 *(2ξwn)s + wn^2
ξ:
wn = 1/T:
K T
RC电路
Gs = 1/Ts+1
EPM气压控制等主导环节
G(s) = wn^2/ s*( s + 2ξwn)
G(s) = wn^2/ (s^2 + (2ξwn)s + wn^2)
ξ
Wn
0 < ξ < 1
s^2 + (2ξwn)s + wn^2 = 0
I型系统来消除静差PID控制器
EPM本身的控制特性线性度差
EMP本身的控制线性度差EPM性能的不足
EPM IP开度大小决定EPM本身的不足
:
PID
    u(t) = k*(e(t) +e(t)dt + de(t)dt)
u(n) = k*(e(n) +  e(n)/Ti + Td*(e(n) - e(n-1)))
:PID + PD控制
    [-5%,5%] PID < 0.3%
    [-100%,5%] [5%,100%] PD控制
   
    <= 5%
              > 5%
   
              >= 100%   =  100%
              <= -100% = -100%
    : 60%
    : < 60%
    ->->,t0 -> -> -> ,t1
      <|
    Tu
    : Ku = - / ( - )
    Kp = 0.8 * Ku
          Ti = 0.6 * Tu
          Td = 0.125 * Tu
          Ki = Kp / Ti = Kp / (0.6 * Tu)
          Kd = Kp * Td = Kp * 0.125 * Td
    s1:AD值
    s2:AD值
    v1:
    v2:  
    v:
a
t:
v = (s2 - s1) / t
a = (v2 - v1) / t
   
    PID
    = -
    =
= Kp*  +  Ki *  + Kd *
   
   
      = -
      = -
      = Kp1*  +  Ki1 *  + Kd1 *
      = -
      = -
      = Kp2*  +  Ki2 *  + Kd2 *
???
automatic control theory
control system
linear and nonlinear system
线
modelling
analysis
线
L变换 Z变换
problems
time consuming
nyquist
0
root locus
G(s) = k/s(s+1)
线
p-n/n-m
lambda
lambda
tao/t
PI D
PID
makefile
1->->
#source object target
SRC := *.c
OBJ := *.o
TARGET := mqtt_test
#compile library include
CC := cc
LIB:= -lpthread
LDFLAG := -L. libmosquitto.so
CFLAG :=
CXXFLAG :=
#link
$(TARGET):$(OBJ)
$(CC) -o $(TARGET) $(BOJ) $(LIB) $(LDFLAG)
$(CC) -o $@ $^ $(LIB) $(LDFLAG)
$(OBJ):$(SRC)
$(CC) -c $(SRC)
#all
all:$(TARGET)
$(CC) -o $(TARGET) $(SRC) $(LIB) $(LDFLAG)
#clean
clean:
rm -rf *.o $(TARGET)
*/
// ————————————————————————————————————
/*
typedef struct
{
int argc;
char **argv;
int sock;
}st_app_param;
const char *g_version = "V1.0.0 24.08.16";
int child_mian_ini()
{
int i_re;
i_re = gw_support_init();
if(i_re < 0)
{
printf("解析支持文件错误.\n");
return -1;
}
i_re = gw_config_init();
if(i_re < 0)
{
printf("解析配置文件错误.\n");
return -1;
}
i_re = gw_data_init();
if(i_re < 0)
{
printf("数据初始化错误.\n");
return -1;
}
i_re = gw_modol_init();
if(i_re < 0)
{
printf("解析模型文件错误.\n");
return -1;
}
i_re = gw_stat_init();
if(i_re < 0)
{
printf("数据统计初始化错误.\n");
return -1;
}
i_re = gw_process_init();
if(i_re < 0)
{
printf("规约初始化错误.\n");
return -1;
}
i_re = gw_manage_init();
if(i_re < 0)
{
printf("界面通讯初始化错误.\n");
return -1;
}
pthread_create(tid,thread_task1,p_param);
while(1)
{
get_sys_time();
sleep(1);
}
}
int child_main(int argc,char **argv)
{
if((argc == 2)&&(strcasecmp(argv[1],"-version") == 0))
{
printf("version [%s]",g_version);
}
child_mian_ini();
}
static int run_child_process_thread((void *)param)
{
st_app_param *p_param;
p_param = param;
chlid_main(p_parm->argc,p_param->argv);
}
static int run_child_process(int argc,char **argv,int sock)
{
int i_re;
pthread_t *tid;
st_app_param p_param;
p_param.argc = argc;
p_param.argv = argv;
p_param.sock = sock;
pthread_creat(tid,run_child_process_thread,(void *)p_param);
i_re = recv(sock,..,0);//阻塞接收
send(sock,'q',0);
}
int main(int argc,char**argv)
{
int i_re,fd,pid;
char lock_file[16];
socketpair sockpaire[2];
sprintf(lock_file,"%s.lock",argv[0]);
fd = open(lock_file,_O_WRONLY|_EXC,0777);
if(fd < 0)
{
printf("应用:[%s]已运行.\n",argv[0]);
return 0;
}
sockpaire[0] = -1;
while(1)
{
i_re = socketpaire(sockpaire,AN_UNIX,..);
if(i_re < 0)
{
printf("[%d]创建sockpaire失败.\n",getpid());
return 0;
}
pid = fork();
if(pid < 0)
{
printf("[%d]创建进程失败.\n",getpid());
close(sockpaire[0]);
sockpaire[0] = -1
close(sockpaire[1]);
return 0;
}
if(pid == 0)//child process
{
close(sockpair[0]);
return run_child_process(argc,argv,sockpair[1]);
}
printf("[%d]创建子进程成功.\n",getpid());
close(sockpair[1]);
while(1)//father process
{
i_re = recv(sockpaire[0],....,0);//阻塞接收
if(i_re <= 0)
{
//连接中断,重连
sockpaire[0] = -1;
break;
}
else
{
//正常退出
goto EXIT:
}
}
EXIT:
//退出操作
if(sockpaire[0] == -1)
{
//有子进程,关闭子进程
}
close(fd);
unlink(file_lock);
}
}
*/

View File

@ -0,0 +1,63 @@
/*
* @Author: zxm5337@163.com
* @Date: 2024-06-25 10:26:36
* @LastEditors: DaMingSY zxm5337@163.com
* @LastEditTime: 2024-09-03 09:19:23
* @FilePath: \controller-v2\User\lib\control\custom\cascade_pid_zh.h
* @Description: ,`customMade`, koroFileHeader查看配置 : https://github.com/OBKoro1/koro1FileHeader/wiki/%E9%85%8D%E7%BD%AE
*/
#ifndef __CASCADE_PID_ZH__
#define __CASCADE_PID_ZH__
#include "data_type_def.h"
typedef enum
{
TARGET_DIR_ADD,
TARGET_DIR_SUB,
} target_dir_e;
typedef struct
{
float kp;
float ki;
float kd;
float kup;
float kui;
float kud;
} fuzzy_pid_t;
typedef struct
{
BOOL iDetach, sm_open, fuzzy_open;
float feedBack;
float target, maxTarget;
float duty, kp, ki, kd;
float error, dError, lastError, errorDead;
float integral, iDetachCondation;
float output, maxOutput;
fuzzy_pid_t fuzzy_pid;
} smart_pid_t;
typedef struct
{
smart_pid_t inner;
smart_pid_t outer;
float output;
} cascade_pid_t;
typedef struct CascadePID
{
void (*smart_pid_init)(smart_pid_t *pid, float *duty, float *kp, float *ki, float *kd, float *errorDead, float *iDetachCondation, float *maxOut);
void (*cascade_pid_init)(cascade_pid_t *pid, smart_pid_t *pid_outer, smart_pid_t *pid_inner);
void (*smart_pid_calc)(smart_pid_t *pid, float *target, float *feedback);
void (*cascade_pid_calc)(struct CascadePID *pid, float *outerRef, float *outerFdb, float *innerFdb);
smart_pid_t smart_pid;
cascade_pid_t cascade_pid;
} pid_zh1_t; // PID_t;
extern void pid_zh_constructor1(struct CascadePID *pid);
#endif

View File

@ -0,0 +1,26 @@
# 架构
|文件|路径| <div style="width:300px">说明</div>|
|:--|:--|:--|
|pid|User\lib\control\src|PID算法模块|
|execute|User\application\src|执行器|
|app_flow|User|任务流程控制|
## APP_FLOW任务流程控制
> adjust_inspection 中在没有检测到调试信号时执行<b style="color:blue">execute_dac,EXECUTE_PLAN</b>定义了需要执行的算法任务计划
## PID算法模块
文件内容:
|文件| <div style="width:300px">说明</div>|
|:--|:--|
|pid.c|构造算法的入口|
|pid_common.c|普通算法|
|pid_neural.c|神经网络算法|
|pid_fuzzy.c|模糊算法|
<b style="color:blue">custom 目录下为各自算法实现</b>
## EXECUTE执行器
> execute_pid_init中定义了初始化参数
> execute_dac中定义了执行器

View File

@ -1,9 +1,17 @@
#ifndef __PID_H__
#define __PID_H__
#include "lib.h"
#include "pid_auto_tune.h"
#define INCOMPLETE_DIFFEREN 0 // 不完全微分
#include "pid_c.h"
#include "pid_g.h"
#include "pid_x.h"
#include "pid_zh.h"
#include "pid_zh1.h"
#include "pid_hd.h"
#define INCOMPLETE_DIFFEREN 1 // 不完全微分
typedef enum
{
@ -54,6 +62,7 @@ typedef struct
float32 err_limit;
BOOL detach;
float32 err_dead;
// 不完全微分方式在微分环节采用了低通滤波有效地提高了微分项的特性。其中α的取值是一个0~1之间的数。两个极限值在0时其实就是没有滤波的普通微分环节而取1时则没有微分作用。所以α的取值对不完全微分的效果是至关重要的一般要根据被控对象的特性来确定
float32 alpha;
float32 lastdev;
float32 out;
@ -219,6 +228,14 @@ typedef struct
pid_common_t common;
pid_neural_t neural;
pid_fuzzy_t fuzzy;
// 自定义PID
pid_c_t cao;
pid_g_t gao;
pid_x_t xu;
pid_zh_t zhang;
pid_zh1_t zhang1;
pid_hd_t hd;
} pid_u;
pid_auto_tune_t auto_tune;
} pid_t;

View File

@ -1,30 +0,0 @@
#ifndef __S_CURVE_H
#define __S_CURVE_H
#include "lib.h"
typedef struct
{
// 起始频率
float32 f0;
// 加加速段斜率
float32 faa;
// 减减速段斜率
float32 frr;
// 加加速段时间
float32 taa;
// 匀加速段时间
float32 tua;
// 减加速段时间
float32 tra;
// 匀速段时间
float32 tuu;
// 加减速段时间
float32 tar;
// 匀减速段时间
float32 tur;
// 减减速段时间
float32 trr;
} s_curve_t;
void s_curve_table_gen(uint16_t tmin, uint16_t tmax);
#endif // __S_CURVE_H

View File

@ -20,6 +20,22 @@ void pid_constructor(pid_t *self)
case PID_TYPE_AUTO_TUNE:
pid_auto_tune_constructor(&self->auto_tune);
break;
case PID_TYPE_CUSTOM_CAO:
pid_c_constructor(&self->pid_u.cao);
break;
case PID_TYPE_CUSTOM_GAO:
pid_g_constructor(&self->pid_u.gao);
break;
case PID_TYPE_CUSTOM_XU:
pid_x_constructor(&self->pid_u.xu);
break;
case PID_TYPE_CUSTOM_ZHANG:
// pid_zh_constructor(&self->pid_u.zhang);
pid_zh_constructor1(&self->pid_u.zhang1);
break;
case PID_TYPE_CUSTOM_HANGDIAN:
pid_hd_constructor(&self->pid_u.hd);
break;
default:
break;
}

View File

@ -13,17 +13,17 @@
#define PL 3
// 定义偏差E的范围因为设置了非线性区间误差在10时才开始进行PID调节这里E的范围为10
#define MAXE (100)
#define MAXE (30)
#define MINE (-MAXE)
// 定义EC的范围因为变化非常缓慢每次的EC都非常小这里可以根据实际需求来调整
#define MAXEC (100)
#define MAXEC (30)
#define MINEC (-MAXEC)
// 定义e,ec的量化因子
#define KE 3 / MAXE
#define KEC 3 / MAXEC
// 定义输出量比例因子
#define KUP 1.0f // 这里只使用了模糊PID的比例增益
#define KUP 3.0f // 这里只使用了模糊PID的比例增益
#define KUI 0.0f
#define KUD 0.0f
@ -442,6 +442,7 @@ static void _set_ctrl_prm(struct PID_FUZZY *self, float32 kp, float32 ki, float3
pri->detach = FALSE;
pri->sm = FALSE;
pri->ki_enable = TRUE;
pri->alpha = 0.25;
}
else
{
@ -456,6 +457,7 @@ static void _set_ctrl_prm(struct PID_FUZZY *self, float32 kp, float32 ki, float3
pri->out_max = out_max;
pri->out_min = out_min;
pri->ki_enable = TRUE;
pri->alpha = 0.25;
}
}

View File

@ -1,171 +0,0 @@
#include "s_curve.h"
// s曲线加速度各段参数定义
// 起始速度
#define F0 0.0f
// 加加速度与减减速度
#define FAA 0.0f
#define FRR 0.0f
// 加速段三个时间
#define TAA 0.1f
#define TUA 0.2f
#define TRA 0.1f
// 匀速段
#define TUU 5.0f
// 减速段
#define TAR 0.1f
#define TUR 0.2f
#define TRR 0.1f
// 表格长度
#define S_CURVE_TABLE_LEN 400
int16_t s_curve_table[S_CURVE_TABLE_LEN] = {0};
static int16_t s_curve_func(s_curve_t *s, float32 t, float32 *freq, float32 *acc)
{
// 辅助常数项
float32 A, B, C, D, E, F;
// 表达式中间值
float32 f3, f4, f5;
// 加速段,匀速段,减速段时间
float32 Ta, Tu, Tr;
// 减加速与加减速段斜率
float32 fra, far;
// 起始频率与加加速频率,减减速频率
float32 f0, faa, frr;
float32 taa, tua, tra, tuu, tar, tur, trr;
// 获取参数
faa = s->faa;
frr = s->frr;
taa = s->taa;
tua = s->tua;
tra = s->tra;
tuu = s->tuu;
tar = s->tar;
tur = s->tur;
trr = s->trr;
f0 = s->f0;
fra = faa * taa / tra;
far = frr * trr / tar;
Ta = taa + tua + tra;
Tu = tuu;
Tr = tar + tur + trr;
A = f0;
B = f0 - 0.5 * faa * taa * taa;
C = f0 + 0.5 * faa * taa * taa + faa * taa * tua + 0.5 * fra * (taa + tua) * (taa + tua) - fra * Ta * (taa + tua);
// f1 = f0 + 0.5 * faa * taa * taa;
// f2 = f0 + 0.5 * faa * taa * taa + faa * taa * tua;
f3 = 0.5 * fra * Ta * Ta + C;
D = f3 - 0.5 * far * (Ta + Tu) * (Ta + Tu);
f4 = -far * 0.5 * (Ta + Tu + tar) * (Ta + Tu + tar) + far * (Ta + Tu) * (Ta + Tu + tar) + D;
E = f4 + far * tar * (Ta + Tu + tar);
f5 = -far * tar * (Ta + Tu + Tr - trr) + E;
F = f5 + frr * (Ta + Tu + Tr) * (Ta + Tu + Tr - trr) - 0.5 * frr * (Ta + Tu + Tr - trr) * (Ta + Tu + Tr - trr);
// 如果时间点在全行程规定的时间段内
if ((t >= 0) && (t <= Ta + Tu + Tr))
{
// 加加速段
if ((t >= 0) && (t <= taa))
{
*freq = 0.5 * faa * t * t + A;
*acc = faa * t;
}
// 匀加速段
else if ((t >= taa) && (t <= taa + tua))
{
*freq = faa * taa * t + B;
*acc = faa * taa;
}
// 加减速段
else if ((t >= taa + tua) && (t <= taa + tua + tra))
{
*freq = -0.5 * fra * t * t + fra * Ta * t + C;
*acc = -fra * t + fra * Ta;
}
// 匀速段
else if ((t >= Ta) && (t <= Ta + tuu))
{
*freq = f3;
*acc = 0;
}
// 加减速段
else if ((t >= Ta + Tu) && (t <= Ta + Tu + tar))
{
*freq = -0.5 * far * t * t + far * (Ta + Tu) * t + D;
*acc = -far * t + far * (Ta + Tu);
}
// 匀减速
else if ((t >= Ta + Tu + tar) && (t <= Ta + Tu + tar + tur))
{
*freq = -far * tar * t + E;
*acc = -far * tar;
}
// 减减速
else if ((t >= Ta + Tu + Tr - trr) && (t <= Ta + Tu + Tr))
{
*freq = 0.5 * frr * t * t - frr * (Ta + Tu + Tr) * t + F;
*acc = frr * t - frr * (Ta + Tu + Tr);
}
}
else
{
return -1;
}
return 0;
}
// S型曲线初始化
void s_curve_table_gen(uint16_t tmin, uint16_t tmax)
{
uint16_t i, tint;
float32 ti;
float32 freq;
float32 acc;
float32 fi;
s_curve_t s;
osel_memset((uint8_t *)&s, 0, sizeof(s_curve_t));
s.f0 = F0;
s.taa = TAA;
s.tua = TUA;
s.tra = TRA;
s.tuu = TUU;
s.tar = TAR;
s.tur = TUR;
s.trr = TRR;
// 根据约束条件求出加加速段与减减速段斜率
s.faa = 2.0 / (s.taa * (s.taa + s.tra + 2 * s.tua));
s.frr = 2.0 / (s.trr * (s.tar + s.trr + 2 * s.tur));
for (i = 0; i < S_CURVE_TABLE_LEN; i++)
{
// 求出每个时间点对应的频率以及加速度
fi = i * (TAA + TUA + TRA + TUU + TAR + TUR + TRR) / S_CURVE_TABLE_LEN;
s_curve_func(&s, fi, &freq, &acc);
// 根据最大与最小装载值确定定时器实际值
ti = tmax - (tmax - tmin) * freq;
// 转换为整数值
tint = (uint16_t)ti;
// 存入s曲线表
s_curve_table[i] = tint;
}
}

View File

@ -0,0 +1,50 @@
/*
* Copyright (c) 2020, Armink, <armink.ztl@gmail.com>
*
* SPDX-License-Identifier: Apache-2.0
*/
/**
* @file
* @brief basic KV samples.
*
* basic Key-Value Database KV feature samples
* get and show currnet boot counts
*/
#include <flashdb.h>
#ifdef FDB_USING_KVDB
#define FDB_LOG_TAG "[sample][kvdb][basic]"
void kvdb_basic_sample(fdb_kvdb_t kvdb)
{
struct fdb_blob blob;
int boot_count = 0;
FDB_INFO("==================== kvdb_basic_sample ====================\n");
{ /* GET the KV value */
/* get the "boot_count" KV value */
fdb_kv_get_blob(kvdb, "boot_count", fdb_blob_make(&blob, &boot_count, sizeof(boot_count)));
/* the blob.saved.len is more than 0 when get the value successful */
if (blob.saved.len > 0) {
FDB_INFO("get the 'boot_count' value is %d\n", boot_count);
} else {
FDB_INFO("get the 'boot_count' failed\n");
}
}
{ /* CHANGE the KV value */
/* increase the boot count */
boot_count ++;
/* change the "boot_count" KV's value */
fdb_kv_set_blob(kvdb, "boot_count", fdb_blob_make(&blob, &boot_count, sizeof(boot_count)));
FDB_INFO("set the 'boot_count' value to %d\n", boot_count);
}
FDB_INFO("===========================================================\n");
}
#endif /* FDB_USING_KVDB */

View File

@ -0,0 +1,63 @@
/*
* Copyright (c) 2020, Armink, <armink.ztl@gmail.com>
*
* SPDX-License-Identifier: Apache-2.0
*/
/**
* @file
* @brief blob KV samples.
*
* Key-Value Database blob type KV feature samples
*/
#include <flashdb.h>
#ifdef FDB_USING_KVDB
#define FDB_LOG_TAG "[sample][kvdb][blob]"
void kvdb_type_blob_sample(fdb_kvdb_t kvdb)
{
struct fdb_blob blob;
FDB_INFO("==================== kvdb_type_blob_sample ====================\n");
{ /* CREATE new Key-Value */
int temp_data = 36;
/* It will create new KV node when "temp" KV not in database.
* fdb_blob_make: It's a blob make function, and it will return the blob when make finish.
*/
fdb_kv_set_blob(kvdb, "temp", fdb_blob_make(&blob, &temp_data, sizeof(temp_data)));
FDB_INFO("create the 'temp' blob KV, value is: %d\n", temp_data);
}
{ /* GET the KV value */
int temp_data = 0;
/* get the "temp" KV value */
fdb_kv_get_blob(kvdb, "temp", fdb_blob_make(&blob, &temp_data, sizeof(temp_data)));
/* the blob.saved.len is more than 0 when get the value successful */
if (blob.saved.len > 0) {
FDB_INFO("get the 'temp' value is: %d\n", temp_data);
}
}
{ /* CHANGE the KV value */
int temp_data = 38;
/* change the "temp" KV's value to 38 */
fdb_kv_set_blob(kvdb, "temp", fdb_blob_make(&blob, &temp_data, sizeof(temp_data)));
FDB_INFO("set 'temp' value to %d\n", temp_data);
}
{ /* DELETE the KV by name */
fdb_kv_del(kvdb, "temp");
FDB_INFO("delete the 'temp' finish\n");
}
FDB_INFO("===========================================================\n");
}
#endif /* FDB_USING_KVDB */

View File

@ -0,0 +1,63 @@
/*
* Copyright (c) 2020, Armink, <armink.ztl@gmail.com>
*
* SPDX-License-Identifier: Apache-2.0
*/
/**
* @file
* @brief string KV samples.
*
* Key-Value Database string type KV feature samples source file.
*/
#include <flashdb.h>
#include <string.h>
#ifdef FDB_USING_KVDB
#define FDB_LOG_TAG "[sample][kvdb][string]"
void kvdb_type_string_sample(fdb_kvdb_t kvdb)
{
FDB_INFO("==================== kvdb_type_string_sample ====================\n");
{ /* CREATE new Key-Value */
char temp_data[10] = "36C";
/* It will create new KV node when "temp" KV not in database. */
fdb_kv_set(kvdb, "temp", temp_data);
FDB_INFO("create the 'temp' string KV, value is: %s\n", temp_data);
}
{ /* GET the KV value */
char *return_value, temp_data[10] = { 0 };
/* Get the "temp" KV value.
* NOTE: The return value saved in fdb_kv_get's buffer. Please copy away as soon as possible.
*/
return_value = fdb_kv_get(kvdb, "temp");
/* the return value is NULL when get the value failed */
if (return_value != NULL) {
strncpy(temp_data, return_value, sizeof(temp_data));
FDB_INFO("get the 'temp' value is: %s\n", temp_data);
}
}
{ /* CHANGE the KV value */
char temp_data[10] = "38C";
/* change the "temp" KV's value to "38.1" */
fdb_kv_set(kvdb, "temp", temp_data);
FDB_INFO("set 'temp' value to %s\n", temp_data);
}
{ /* DELETE the KV by name */
fdb_kv_del(kvdb, "temp");
FDB_INFO("delete the 'temp' finish\n");
}
FDB_INFO("===========================================================\n");
}
#endif /* FDB_USING_KVDB */

View File

@ -0,0 +1,126 @@
/*
* Copyright (c) 2020, Armink, <armink.ztl@gmail.com>
*
* SPDX-License-Identifier: Apache-2.0
*/
/**
* @file
* @brief TSDB samples.
*
* Time series log (like TSDB) feature samples source file.
*
* TSL is time series log, the TSDB saved many TSLs.
*/
#include <flashdb.h>
#include <string.h>
#ifdef FDB_USING_TSDB
#define FDB_LOG_TAG "[sample][tsdb]"
#ifdef FDB_USING_TIMESTAMP_64BIT
#define __PRITS "ld"
#else
#define __PRITS "d"
#endif
struct env_status {
int temp;
int humi;
};
static bool query_cb(fdb_tsl_t tsl, void *arg);
static bool query_by_time_cb(fdb_tsl_t tsl, void *arg);
static bool set_status_cb(fdb_tsl_t tsl, void *arg);
void tsdb_sample(fdb_tsdb_t tsdb)
{
struct fdb_blob blob;
FDB_INFO("==================== tsdb_sample ====================\n");
{ /* APPEND new TSL (time series log) */
struct env_status status;
/* append new log to TSDB */
status.temp = 36;
status.humi = 85;
fdb_tsl_append(tsdb, fdb_blob_make(&blob, &status, sizeof(status)));
FDB_INFO("append the new status.temp (%d) and status.humi (%d)\n", status.temp, status.humi);
status.temp = 38;
status.humi = 90;
fdb_tsl_append(tsdb, fdb_blob_make(&blob, &status, sizeof(status)));
FDB_INFO("append the new status.temp (%d) and status.humi (%d)\n", status.temp, status.humi);
}
{ /* QUERY the TSDB */
/* query all TSL in TSDB by iterator */
fdb_tsl_iter(tsdb, query_cb, tsdb);
}
{ /* QUERY the TSDB by time */
/* prepare query time (from 1970-01-01 00:00:00 to 2020-05-05 00:00:00) */
struct tm tm_from = { .tm_year = 1970 - 1900, .tm_mon = 0, .tm_mday = 1, .tm_hour = 0, .tm_min = 0, .tm_sec = 0 };
struct tm tm_to = { .tm_year = 2020 - 1900, .tm_mon = 4, .tm_mday = 5, .tm_hour = 0, .tm_min = 0, .tm_sec = 0 };
time_t from_time = mktime(&tm_from), to_time = mktime(&tm_to);
size_t count;
/* query all TSL in TSDB by time */
fdb_tsl_iter_by_time(tsdb, from_time, to_time, query_by_time_cb, tsdb);
/* query all FDB_TSL_WRITE status TSL's count in TSDB by time */
count = fdb_tsl_query_count(tsdb, from_time, to_time, FDB_TSL_WRITE);
FDB_INFO("query count is: %zu\n", count);
}
{ /* SET the TSL status */
/* Change the TSL status by iterator or time iterator
* set_status_cb: the change operation will in this callback
*
* NOTE: The actions to modify the state must be in order.
* like: FDB_TSL_WRITE -> FDB_TSL_USER_STATUS1 -> FDB_TSL_DELETED -> FDB_TSL_USER_STATUS2
* The intermediate states can also be ignored.
* such as: FDB_TSL_WRITE -> FDB_TSL_DELETED
*/
fdb_tsl_iter(tsdb, set_status_cb, tsdb);
}
FDB_INFO("===========================================================\n");
}
static bool query_cb(fdb_tsl_t tsl, void *arg)
{
struct fdb_blob blob;
struct env_status status;
fdb_tsdb_t db = arg;
fdb_blob_read((fdb_db_t) db, fdb_tsl_to_blob(tsl, fdb_blob_make(&blob, &status, sizeof(status))));
FDB_INFO("[query_cb] queried a TSL: time: %" __PRITS ", temp: %d, humi: %d\n", tsl->time, status.temp, status.humi);
return false;
}
static bool query_by_time_cb(fdb_tsl_t tsl, void *arg)
{
struct fdb_blob blob;
struct env_status status;
fdb_tsdb_t db = arg;
fdb_blob_read((fdb_db_t) db, fdb_tsl_to_blob(tsl, fdb_blob_make(&blob, &status, sizeof(status))));
FDB_INFO("[query_by_time_cb] queried a TSL: time: %" __PRITS ", temp: %d, humi: %d\n", tsl->time, status.temp, status.humi);
return false;
}
static bool set_status_cb(fdb_tsl_t tsl, void *arg)
{
fdb_tsdb_t db = arg;
FDB_INFO("set the TSL (time %" __PRITS ") status from %d to %d\n", tsl->time, tsl->status, FDB_TSL_USER_STATUS1);
fdb_tsl_set_status(db, tsl, FDB_TSL_USER_STATUS1);
return false;
}
#endif /* FDB_USING_TSDB */

62
lib/flashdb/fal/fal.c Normal file
View File

@ -0,0 +1,62 @@
/*
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2018-05-17 armink the first version
*/
#include <fal.h>
static uint8_t init_ok = 0;
/**
* FAL (Flash Abstraction Layer) initialization.
* It will initialize all flash device and all flash partition.
*
* @return >= 0: partitions total number
*/
int fal_init(void)
{
extern int fal_flash_init(void);
extern int fal_partition_init(void);
int result;
/* initialize all flash device on FAL flash table */
result = fal_flash_init();
if (result < 0) {
goto __exit;
}
/* initialize all flash partition on FAL partition table */
result = fal_partition_init();
__exit:
if ((result > 0) && (!init_ok))
{
init_ok = 1;
log_i("Flash Abstraction Layer (V%s) initialize success.", FAL_SW_VERSION);
}
else if(result <= 0)
{
init_ok = 0;
log_e("Flash Abstraction Layer (V%s) initialize failed.", FAL_SW_VERSION);
}
return result;
}
/**
* Check if the FAL is initialized successfully
*
* @return 0: not init or init failed; 1: init success
*/
int fal_init_check(void)
{
return init_ok;
}

151
lib/flashdb/fal/fal.h Normal file
View File

@ -0,0 +1,151 @@
/*
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2018-05-17 armink the first version
*/
#ifndef _FAL_H_
#define _FAL_H_
#include <fal_cfg.h>
#include "fal_def.h"
/**
* FAL (Flash Abstraction Layer) initialization.
* It will initialize all flash device and all flash partition.
*
* @return >= 0: partitions total number
*/
int fal_init(void);
/* =============== flash device operator API =============== */
/**
* find flash device by name
*
* @param name flash device name
*
* @return != NULL: flash device
* NULL: not found
*/
const struct fal_flash_dev *fal_flash_device_find(const char *name);
/* =============== partition operator API =============== */
/**
* find the partition by name
*
* @param name partition name
*
* @return != NULL: partition
* NULL: not found
*/
const struct fal_partition *fal_partition_find(const char *name);
/**
* get the partition table
*
* @param len return the partition table length
*
* @return partition table
*/
const struct fal_partition *fal_get_partition_table(size_t *len);
/**
* set partition table temporarily
* This setting will modify the partition table temporarily, the setting will be lost after restart.
*
* @param table partition table
* @param len partition table length
*/
void fal_set_partition_table_temp(struct fal_partition *table, size_t len);
/**
* read data from partition
*
* @param part partition
* @param addr relative address for partition
* @param buf read buffer
* @param size read size
*
* @return >= 0: successful read data size
* -1: error
*/
int fal_partition_read(const struct fal_partition *part, uint32_t addr, uint8_t *buf, size_t size);
/**
* write data to partition
*
* @param part partition
* @param addr relative address for partition
* @param buf write buffer
* @param size write size
*
* @return >= 0: successful write data size
* -1: error
*/
int fal_partition_write(const struct fal_partition *part, uint32_t addr, const uint8_t *buf, size_t size);
/**
* erase partition data
*
* @param part partition
* @param addr relative address for partition
* @param size erase size
*
* @return >= 0: successful erased data size
* -1: error
*/
int fal_partition_erase(const struct fal_partition *part, uint32_t addr, size_t size);
/**
* erase partition all data
*
* @param part partition
*
* @return >= 0: successful erased data size
* -1: error
*/
int fal_partition_erase_all(const struct fal_partition *part);
/**
* print the partition table
*/
void fal_show_part_table(void);
/* =============== API provided to RT-Thread =============== */
/**
* create RT-Thread block device by specified partition
*
* @param parition_name partition name
*
* @return != NULL: created block device
* NULL: created failed
*/
struct rt_device *fal_blk_device_create(const char *parition_name);
#if defined(RT_USING_MTD_NOR)
/**
* create RT-Thread MTD NOR device by specified partition
*
* @param parition_name partition name
*
* @return != NULL: created MTD NOR device
* NULL: created failed
*/
struct rt_device *fal_mtd_nor_device_create(const char *parition_name);
#endif /* defined(RT_USING_MTD_NOR) */
/**
* create RT-Thread char device by specified partition
*
* @param parition_name partition name
*
* @return != NULL: created char device
* NULL: created failed
*/
struct rt_device *fal_char_device_create(const char *parition_name);
#endif /* _FAL_H_ */

56
lib/flashdb/fal/fal_cfg.h Normal file
View File

@ -0,0 +1,56 @@
/*
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2018-05-17 armink the first version
*/
#ifndef _FAL_CFG_H_
#define _FAL_CFG_H_
#include "eeprom_m95.h"
#include "eeprom_fm24.h"
#include "flash.h"
#define FAL_PART_HAS_TABLE_CFG
#define FAL_ERASE_SIZE 100
// 需要块大小为2的N次方
#define EEPROM_M95_1_BLOCK_SIZE M95_PAGE_SIZE_256 * 32
#define EEPROM_M95_2_BLOCK_SIZE M95_PAGE_SIZE_256 * 32
#define EEPROM_FM24_BLOCK_SIZE FM24_PAGE_SIZE * 16
#define EEPROM_M95_1_SIZE _M95M02_
#define EEPROM_M95_2_SIZE _M95M02_
#define EEPROM_FM24_SIZE FM24_SIZE
#define EEPROM_M95_1_DEV_NAME "eeprom_m95_1"
#define EEPROM_M95_2_DEV_NAME "eeprom_m95_2"
#define EEPROM_FM24_DEV_NAME "eeprom_fm24"
/* ===================== Flash device Configuration ========================= */
extern struct fal_flash_dev eeprom_m95_1;
extern struct fal_flash_dev eeprom_m95_2;
extern struct fal_flash_dev eeprom_fm24;
/* flash device table */
#define FAL_FLASH_DEV_TABLE \
{ \
&eeprom_m95_1, \
&eeprom_m95_2, \
}
/* ====================== Partition Configuration ========================== */
#ifdef FAL_PART_HAS_TABLE_CFG
/* partition table */
// issues :https://github.com/armink/FlashDB/issues/40 ;epprom的扇区太小
#define FAL_PART_TABLE \
{ \
{FAL_PART_MAGIC_WORD, "KVDB", EEPROM_M95_1_DEV_NAME, 0, EEPROM_M95_1_SIZE, 0}, \
{FAL_PART_MAGIC_WORD, "TSDB", EEPROM_M95_2_DEV_NAME, 0, EEPROM_M95_2_SIZE, 0}, \
}
#endif /* FAL_PART_HAS_TABLE_CFG */
#endif /* _FAL_CFG_H_ */

153
lib/flashdb/fal/fal_def.h Normal file
View File

@ -0,0 +1,153 @@
/*
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2018-05-17 armink the first version
*/
#ifndef _FAL_DEF_H_
#define _FAL_DEF_H_
#include <stdint.h>
#include <stdio.h>
#ifdef FDB_USING_NATIVE_ASSERT
#include <assert.h>
#endif
#define FAL_SW_VERSION "0.5.99"
#ifdef __RTTHREAD__ /* for RT-Thread platform */
#include <rtthread.h>
#define FAL_PRINTF rt_kprintf
#define FAL_MALLOC rt_malloc
#define FAL_CALLOC rt_calloc
#define FAL_REALLOC rt_realloc
#define FAL_FREE rt_free
#endif
#ifndef FAL_MALLOC
#define FAL_MALLOC malloc
#endif
#ifndef FAL_CALLOC
#define FAL_CALLOC calloc
#endif
#ifndef FAL_REALLOC
#define FAL_REALLOC realloc
#endif
#ifndef FAL_FREE
#define FAL_FREE free
#endif
#ifndef FAL_PRINTF
#define FAL_PRINTF printf
#endif
#ifndef FAL_DEBUG
#define FAL_DEBUG 0
#endif
#if FAL_DEBUG
#ifndef FDB_USING_NATIVE_ASSERT
#ifdef assert
#undef assert
#endif
#define assert(EXPR) \
if (!(EXPR)) \
{ \
FAL_PRINTF("(%s) has assert failed at %s.\n", #EXPR, __func__ ); \
while (1); \
}
#endif
/* debug level log */
#ifdef log_d
#undef log_d
#endif
#include <inttypes.h>
#define log_d(...) FAL_PRINTF("[D/FAL] (%s:%" PRIdLEAST16 ") ", __func__, __LINE__); FAL_PRINTF(__VA_ARGS__);FAL_PRINTF("\n")
#else
#ifndef FDB_USING_NATIVE_ASSERT
#ifdef assert
#undef assert
#endif
#define assert(EXPR) ((void)0);
#endif
/* debug level log */
#ifdef log_d
#undef log_d
#endif
#define log_d(...)
#endif /* FAL_DEBUG */
/* error level log */
#ifdef log_e
#undef log_e
#endif
#define log_e(...) FAL_PRINTF("\033[31;22m[E/FAL] (%s:%d) ", __func__, __LINE__);FAL_PRINTF(__VA_ARGS__);FAL_PRINTF("\033[0m\n")
/* info level log */
#ifdef log_i
#undef log_i
#endif
#define log_i(...) FAL_PRINTF("\033[32;22m[I/FAL] "); FAL_PRINTF(__VA_ARGS__);FAL_PRINTF("\033[0m\n")
/* FAL flash and partition device name max length */
#ifndef FAL_DEV_NAME_MAX
#define FAL_DEV_NAME_MAX 24
#endif
struct fal_flash_dev
{
char name[FAL_DEV_NAME_MAX];
/* flash device start address and len */
uint32_t addr;
size_t len;
/* the block size in the flash for erase minimum granularity */
size_t blk_size;
struct
{
int (*init)(void);
int (*read)(long offset, uint8_t *buf, size_t size);
int (*write)(long offset, const uint8_t *buf, size_t size);
int (*erase)(long offset, size_t size);
} ops;
/* write minimum granularity, unit: bit.
1(nor flash)/ 8(stm32f2/f4)/ 32(stm32f1)/ 64(stm32l4)
0 will not take effect. */
size_t write_gran;
};
typedef struct fal_flash_dev *fal_flash_dev_t;
/**
* FAL partition
*/
struct fal_partition
{
uint32_t magic_word;
/* partition name */
char name[FAL_DEV_NAME_MAX];
/* flash device name for partition */
char flash_name[FAL_DEV_NAME_MAX];
/* partition offset address on flash device */
long offset;
size_t len;
uint32_t reserved;
};
typedef struct fal_partition *fal_partition_t;
#endif /* _FAL_DEF_H_ */

View File

@ -0,0 +1,79 @@
/*
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2018-05-17 armink the first version
*/
#include <fal.h>
#include <string.h>
/* flash device table, must defined by user */
#if !defined(FAL_FLASH_DEV_TABLE)
#error "You must defined flash device table (FAL_FLASH_DEV_TABLE) on 'fal_cfg.h'"
#endif
static const struct fal_flash_dev * const device_table[] = FAL_FLASH_DEV_TABLE;
static const size_t device_table_len = sizeof(device_table) / sizeof(device_table[0]);
static uint8_t init_ok = 0;
/**
* Initialize all flash device on FAL flash table
*
* @return result
*/
int fal_flash_init(void)
{
size_t i;
if (init_ok)
{
return 0;
}
for (i = 0; i < device_table_len; i++)
{
assert(device_table[i]->ops.read);
assert(device_table[i]->ops.write);
assert(device_table[i]->ops.erase);
/* init flash device on flash table */
if (device_table[i]->ops.init)
{
device_table[i]->ops.init();
}
log_d("Flash device | %*.*s | addr: 0x%08lx | len: 0x%08x | blk_size: 0x%08x |initialized finish.",
FAL_DEV_NAME_MAX, FAL_DEV_NAME_MAX, device_table[i]->name, device_table[i]->addr, device_table[i]->len,
device_table[i]->blk_size);
}
init_ok = 1;
return 0;
}
/**
* find flash device by name
*
* @param name flash device name
*
* @return != NULL: flash device
* NULL: not found
*/
const struct fal_flash_dev *fal_flash_device_find(const char *name)
{
assert(init_ok);
assert(name);
size_t i;
for (i = 0; i < device_table_len; i++)
{
if (!strncmp(name, device_table[i]->name, FAL_DEV_NAME_MAX)) {
return device_table[i];
}
}
return NULL;
}

View File

@ -0,0 +1,525 @@
/*
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2018-05-17 armink the first version
*/
#include <fal.h>
#include <string.h>
#include <stdlib.h>
/* partition magic word */
#define FAL_PART_MAGIC_WORD 0x45503130
#define FAL_PART_MAGIC_WORD_H 0x4550L
#define FAL_PART_MAGIC_WORD_L 0x3130L
struct part_flash_info
{
const struct fal_flash_dev *flash_dev;
};
/**
* FAL partition table config has defined on 'fal_cfg.h'.
* When this option is disable, it will auto find the partition table on a specified location in flash partition.
*/
#ifdef FAL_PART_HAS_TABLE_CFG
/* check partition table definition */
#if !defined(FAL_PART_TABLE)
#error "You must defined FAL_PART_TABLE on 'fal_cfg.h'"
#endif
#ifdef __CC_ARM /* ARM Compiler */
#define SECTION(x) __attribute__((section(x)))
#define USED __attribute__((used))
#elif defined (__IAR_SYSTEMS_ICC__) /* for IAR Compiler */
#define SECTION(x) @ x
#define USED __root
#elif defined (__GNUC__) /* GNU GCC Compiler */
#define SECTION(x) __attribute__((section(x)))
#define USED __attribute__((used))
#else
#error not supported tool chain
#endif /* __CC_ARM */
//USED static const struct fal_partition partition_table_def[] SECTION("FalPartTable") = FAL_PART_TABLE;
static const struct fal_partition partition_table_def[] = FAL_PART_TABLE;
static const struct fal_partition *partition_table = NULL;
/* partition and flash object information cache table */
static struct part_flash_info part_flash_cache[sizeof(partition_table_def) / sizeof(partition_table_def[0])] = { 0 };
#else /* FAL_PART_HAS_TABLE_CFG */
#if !defined(FAL_PART_TABLE_FLASH_DEV_NAME)
#error "You must defined FAL_PART_TABLE_FLASH_DEV_NAME on 'fal_cfg.h'"
#endif
/* check partition table end offset address definition */
#if !defined(FAL_PART_TABLE_END_OFFSET)
#error "You must defined FAL_PART_TABLE_END_OFFSET on 'fal_cfg.h'"
#endif
static struct fal_partition *partition_table = NULL;
static struct part_flash_info *part_flash_cache = NULL;
#endif /* FAL_PART_HAS_TABLE_CFG */
static uint8_t init_ok = 0;
static size_t partition_table_len = 0;
/**
* print the partition table
*/
void fal_show_part_table(void)
{
char *item1 = "name", *item2 = "flash_dev";
size_t i, part_name_max = strlen(item1), flash_dev_name_max = strlen(item2);
const struct fal_partition *part;
if (partition_table_len)
{
for (i = 0; i < partition_table_len; i++)
{
part = &partition_table[i];
if (strlen(part->name) > part_name_max)
{
part_name_max = strlen(part->name);
}
if (strlen(part->flash_name) > flash_dev_name_max)
{
flash_dev_name_max = strlen(part->flash_name);
}
}
}
log_i("==================== FAL partition table ====================");
log_i("| %-*.*s | %-*.*s | offset | length |", part_name_max, FAL_DEV_NAME_MAX, item1, flash_dev_name_max,
FAL_DEV_NAME_MAX, item2);
log_i("-------------------------------------------------------------");
for (i = 0; i < partition_table_len; i++)
{
#ifdef FAL_PART_HAS_TABLE_CFG
part = &partition_table[i];
#else
part = &partition_table[partition_table_len - i - 1];
#endif
log_i("| %-*.*s | %-*.*s | 0x%08lx | 0x%08x |", part_name_max, FAL_DEV_NAME_MAX, part->name, flash_dev_name_max,
FAL_DEV_NAME_MAX, part->flash_name, part->offset, part->len);
}
log_i("=============================================================");
}
static int check_and_update_part_cache(const struct fal_partition *table, size_t len)
{
const struct fal_flash_dev *flash_dev = NULL;
size_t i;
#ifndef FAL_PART_HAS_TABLE_CFG
if (part_flash_cache)
{
FAL_FREE(part_flash_cache);
}
part_flash_cache = FAL_MALLOC(len * sizeof(struct part_flash_info));
if (part_flash_cache == NULL)
{
log_e("Initialize failed! No memory for partition table cache");
return -2;
}
#endif
for (i = 0; i < len; i++)
{
flash_dev = fal_flash_device_find(table[i].flash_name);
if (flash_dev == NULL)
{
log_d("Warning: Do NOT found the flash device(%s).", table[i].flash_name);
continue;
}
if (table[i].offset >= (long)flash_dev->len)
{
log_e("Initialize failed! Partition(%s) offset address(%ld) out of flash bound(<%d).",
table[i].name, table[i].offset, flash_dev->len);
partition_table_len = 0;
return -1;
}
part_flash_cache[i].flash_dev = flash_dev;
}
return 0;
}
/**
* Initialize all flash partition on FAL partition table
*
* @return partitions total number
*/
int fal_partition_init(void)
{
if (init_ok)
{
return partition_table_len;
}
#ifdef FAL_PART_HAS_TABLE_CFG
partition_table = &partition_table_def[0];
partition_table_len = sizeof(partition_table_def) / sizeof(partition_table_def[0]);
#else
/* load partition table from the end address FAL_PART_TABLE_END_OFFSET, error return 0 */
long part_table_offset = FAL_PART_TABLE_END_OFFSET;
size_t table_num = 0, table_item_size = 0;
uint8_t part_table_find_ok = 0;
uint32_t read_magic_word;
fal_partition_t new_part = NULL;
size_t i;
const struct fal_flash_dev *flash_dev = NULL;
flash_dev = fal_flash_device_find(FAL_PART_TABLE_FLASH_DEV_NAME);
if (flash_dev == NULL)
{
log_e("Initialize failed! Flash device (%s) NOT found.", FAL_PART_TABLE_FLASH_DEV_NAME);
goto _exit;
}
/* check partition table offset address */
if (part_table_offset < 0 || part_table_offset >= (long) flash_dev->len)
{
log_e("Setting partition table end offset address(%ld) out of flash bound(<%d).", part_table_offset, flash_dev->len);
goto _exit;
}
table_item_size = sizeof(struct fal_partition);
new_part = (fal_partition_t)FAL_MALLOC(table_item_size);
if (new_part == NULL)
{
log_e("Initialize failed! No memory for table buffer.");
goto _exit;
}
/* find partition table location */
{
uint8_t read_buf[64];
part_table_offset -= sizeof(read_buf);
while (part_table_offset >= 0)
{
if (flash_dev->ops.read(part_table_offset, read_buf, sizeof(read_buf)) > 0)
{
/* find magic word in read buf */
for (i = 0; i < sizeof(read_buf) - sizeof(read_magic_word) + 1; i++)
{
read_magic_word = read_buf[0 + i] + (read_buf[1 + i] << 8) + (read_buf[2 + i] << 16) + (read_buf[3 + i] << 24);
if (read_magic_word == ((FAL_PART_MAGIC_WORD_H << 16) + FAL_PART_MAGIC_WORD_L))
{
part_table_find_ok = 1;
part_table_offset += i;
log_d("Find the partition table on '%s' offset @0x%08lx.", FAL_PART_TABLE_FLASH_DEV_NAME,
part_table_offset);
break;
}
}
}
else
{
/* read failed */
break;
}
if (part_table_find_ok)
{
break;
}
else
{
/* calculate next read buf position */
if (part_table_offset >= (long)sizeof(read_buf))
{
part_table_offset -= sizeof(read_buf);
part_table_offset += (sizeof(read_magic_word) - 1);
}
else if (part_table_offset != 0)
{
part_table_offset = 0;
}
else
{
/* find failed */
break;
}
}
}
}
/* load partition table */
while (part_table_find_ok)
{
memset(new_part, 0x00, table_num);
if (flash_dev->ops.read(part_table_offset - table_item_size * (table_num), (uint8_t *) new_part,
table_item_size) < 0)
{
log_e("Initialize failed! Flash device (%s) read error!", flash_dev->name);
table_num = 0;
break;
}
if (new_part->magic_word != ((FAL_PART_MAGIC_WORD_H << 16) + FAL_PART_MAGIC_WORD_L))
{
break;
}
partition_table = (fal_partition_t) FAL_REALLOC(partition_table, table_item_size * (table_num + 1));
if (partition_table == NULL)
{
log_e("Initialize failed! No memory for partition table");
table_num = 0;
break;
}
memcpy(partition_table + table_num, new_part, table_item_size);
table_num++;
};
if (table_num == 0)
{
log_e("Partition table NOT found on flash: %s (len: %d) from offset: 0x%08x.", FAL_PART_TABLE_FLASH_DEV_NAME,
FAL_DEV_NAME_MAX, FAL_PART_TABLE_END_OFFSET);
goto _exit;
}
else
{
partition_table_len = table_num;
}
#endif /* FAL_PART_HAS_TABLE_CFG */
/* check the partition table device exists */
if (check_and_update_part_cache(partition_table, partition_table_len) != 0)
{
goto _exit;
}
init_ok = 1;
_exit:
#if FAL_DEBUG
fal_show_part_table();
#endif
#ifndef FAL_PART_HAS_TABLE_CFG
if (new_part)
{
FAL_FREE(new_part);
}
#endif /* !FAL_PART_HAS_TABLE_CFG */
return partition_table_len;
}
/**
* find the partition by name
*
* @param name partition name
*
* @return != NULL: partition
* NULL: not found
*/
const struct fal_partition *fal_partition_find(const char *name)
{
assert(init_ok);
size_t i;
for (i = 0; i < partition_table_len; i++)
{
if (!strcmp(name, partition_table[i].name))
{
return &partition_table[i];
}
}
return NULL;
}
static const struct fal_flash_dev *flash_device_find_by_part(const struct fal_partition *part)
{
assert(part >= partition_table);
assert(part <= &partition_table[partition_table_len - 1]);
return part_flash_cache[part - partition_table].flash_dev;
}
/**
* get the partition table
*
* @param len return the partition table length
*
* @return partition table
*/
const struct fal_partition *fal_get_partition_table(size_t *len)
{
assert(init_ok);
assert(len);
*len = partition_table_len;
return partition_table;
}
/**
* set partition table temporarily
* This setting will modify the partition table temporarily, the setting will be lost after restart.
*
* @param table partition table
* @param len partition table length
*/
void fal_set_partition_table_temp(struct fal_partition *table, size_t len)
{
assert(init_ok);
assert(table);
check_and_update_part_cache(table, len);
partition_table_len = len;
partition_table = table;
}
/**
* read data from partition
*
* @param part partition
* @param addr relative address for partition
* @param buf read buffer
* @param size read size
*
* @return >= 0: successful read data size
* -1: error
*/
int fal_partition_read(const struct fal_partition *part, uint32_t addr, uint8_t *buf, size_t size)
{
int ret = 0;
const struct fal_flash_dev *flash_dev = NULL;
assert(part);
assert(buf);
if (addr + size > part->len)
{
log_e("Partition read error! Partition address out of bound.");
return -1;
}
flash_dev = flash_device_find_by_part(part);
if (flash_dev == NULL)
{
log_e("Partition read error! Don't found flash device(%s) of the partition(%s).", part->flash_name, part->name);
return -1;
}
ret = flash_dev->ops.read(part->offset + addr, buf, size);
if (ret < 0)
{
log_e("Partition read error! Flash device(%s) read error!", part->flash_name);
}
return ret;
}
/**
* write data to partition
*
* @param part partition
* @param addr relative address for partition
* @param buf write buffer
* @param size write size
*
* @return >= 0: successful write data size
* -1: error
*/
int fal_partition_write(const struct fal_partition *part, uint32_t addr, const uint8_t *buf, size_t size)
{
int ret = 0;
const struct fal_flash_dev *flash_dev = NULL;
assert(part);
assert(buf);
if (addr + size > part->len)
{
log_e("Partition write error! Partition address out of bound.");
return -1;
}
flash_dev = flash_device_find_by_part(part);
if (flash_dev == NULL)
{
log_e("Partition write error! Don't found flash device(%s) of the partition(%s).", part->flash_name, part->name);
return -1;
}
ret = flash_dev->ops.write(part->offset + addr, buf, size);
if (ret < 0)
{
log_e("Partition write error! Flash device(%s) write error!", part->flash_name);
}
return ret;
}
/**
* erase partition data
*
* @param part partition
* @param addr relative address for partition
* @param size erase size
*
* @return >= 0: successful erased data size
* -1: error
*/
int fal_partition_erase(const struct fal_partition *part, uint32_t addr, size_t size)
{
int ret = 0;
const struct fal_flash_dev *flash_dev = NULL;
assert(part);
if (addr + size > part->len)
{
log_e("Partition erase error! Partition address out of bound.");
return -1;
}
flash_dev = flash_device_find_by_part(part);
if (flash_dev == NULL)
{
log_e("Partition erase error! Don't found flash device(%s) of the partition(%s).", part->flash_name, part->name);
return -1;
}
ret = flash_dev->ops.erase(part->offset + addr, size);
if (ret < 0)
{
log_e("Partition erase error! Flash device(%s) erase error!", part->flash_name);
}
return ret;
}
/**
* erase partition all data
*
* @param part partition
*
* @return >= 0: successful erased data size
* -1: error
*/
int fal_partition_erase_all(const struct fal_partition *part)
{
return fal_partition_erase(part, 0, part->len);
}

934
lib/flashdb/fal/fal_rtt.c Normal file
View File

@ -0,0 +1,934 @@
/*
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2018-06-23 armink the first version
* 2019-08-22 MurphyZhao adapt to none rt-thread case
*/
#include <fal.h>
#ifdef RT_VER_NUM
#include <rtthread.h>
#include <rtdevice.h>
#include <string.h>
/* ========================== block device ======================== */
struct fal_blk_device
{
struct rt_device parent;
struct rt_device_blk_geometry geometry;
const struct fal_partition *fal_part;
};
/* RT-Thread device interface */
#if RTTHREAD_VERSION >= 30000
static rt_err_t blk_dev_control(rt_device_t dev, int cmd, void *args)
#else
static rt_err_t blk_dev_control(rt_device_t dev, rt_uint8_t cmd, void *args)
#endif
{
struct fal_blk_device *part = (struct fal_blk_device*) dev;
assert(part != RT_NULL);
if (cmd == RT_DEVICE_CTRL_BLK_GETGEOME)
{
struct rt_device_blk_geometry *geometry;
geometry = (struct rt_device_blk_geometry *) args;
if (geometry == RT_NULL)
{
return -RT_ERROR;
}
memcpy(geometry, &part->geometry, sizeof(struct rt_device_blk_geometry));
}
else if (cmd == RT_DEVICE_CTRL_BLK_ERASE)
{
rt_uint32_t *addrs = (rt_uint32_t *) args, start_addr = addrs[0], end_addr = addrs[1], phy_start_addr;
rt_size_t phy_size;
if (addrs == RT_NULL || start_addr > end_addr)
{
return -RT_ERROR;
}
if (end_addr == start_addr)
{
end_addr++;
}
phy_start_addr = start_addr * part->geometry.bytes_per_sector;
phy_size = (end_addr - start_addr) * part->geometry.bytes_per_sector;
if (fal_partition_erase(part->fal_part, phy_start_addr, phy_size) < 0)
{
return -RT_ERROR;
}
}
return RT_EOK;
}
static rt_size_t blk_dev_read(rt_device_t dev, rt_off_t pos, void* buffer, rt_size_t size)
{
int ret = 0;
struct fal_blk_device *part = (struct fal_blk_device*) dev;
assert(part != RT_NULL);
ret = fal_partition_read(part->fal_part, pos * part->geometry.block_size, buffer, size * part->geometry.block_size);
if (ret != (int)(size * part->geometry.block_size))
{
ret = 0;
}
else
{
ret = size;
}
return ret;
}
static rt_size_t blk_dev_write(rt_device_t dev, rt_off_t pos, const void* buffer, rt_size_t size)
{
int ret = 0;
struct fal_blk_device *part;
rt_off_t phy_pos;
rt_size_t phy_size;
part = (struct fal_blk_device*) dev;
assert(part != RT_NULL);
/* change the block device's logic address to physical address */
phy_pos = pos * part->geometry.bytes_per_sector;
phy_size = size * part->geometry.bytes_per_sector;
ret = fal_partition_erase(part->fal_part, phy_pos, phy_size);
if (ret == (int) phy_size)
{
ret = fal_partition_write(part->fal_part, phy_pos, buffer, phy_size);
}
if (ret != (int) phy_size)
{
ret = 0;
}
else
{
ret = size;
}
return ret;
}
#ifdef RT_USING_DEVICE_OPS
const static struct rt_device_ops blk_dev_ops =
{
RT_NULL,
RT_NULL,
RT_NULL,
blk_dev_read,
blk_dev_write,
blk_dev_control
};
#endif
/**
* create RT-Thread block device by specified partition
*
* @param parition_name partition name
*
* @return != NULL: created block device
* NULL: created failed
*/
struct rt_device *fal_blk_device_create(const char *parition_name)
{
struct fal_blk_device *blk_dev;
const struct fal_partition *fal_part = fal_partition_find(parition_name);
const struct fal_flash_dev *fal_flash = NULL;
if (!fal_part)
{
log_e("Error: the partition name (%s) is not found.", parition_name);
return NULL;
}
if ((fal_flash = fal_flash_device_find(fal_part->flash_name)) == NULL)
{
log_e("Error: the flash device name (%s) is not found.", fal_part->flash_name);
return NULL;
}
blk_dev = (struct fal_blk_device*) rt_malloc(sizeof(struct fal_blk_device));
if (blk_dev)
{
blk_dev->fal_part = fal_part;
blk_dev->geometry.bytes_per_sector = fal_flash->blk_size;
blk_dev->geometry.block_size = fal_flash->blk_size;
blk_dev->geometry.sector_count = fal_part->len / fal_flash->blk_size;
/* register device */
blk_dev->parent.type = RT_Device_Class_Block;
#ifdef RT_USING_DEVICE_OPS
blk_dev->parent.ops = &blk_dev_ops;
#else
blk_dev->parent.init = NULL;
blk_dev->parent.open = NULL;
blk_dev->parent.close = NULL;
blk_dev->parent.read = blk_dev_read;
blk_dev->parent.write = blk_dev_write;
blk_dev->parent.control = blk_dev_control;
#endif
/* no private */
blk_dev->parent.user_data = RT_NULL;
log_i("The FAL block device (%s) created successfully", fal_part->name);
rt_device_register(RT_DEVICE(blk_dev), fal_part->name, RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_STANDALONE);
}
else
{
log_e("Error: no memory for create FAL block device");
}
return RT_DEVICE(blk_dev);
}
/* ========================== MTD nor device ======================== */
#if defined(RT_USING_MTD_NOR)
struct fal_mtd_nor_device
{
struct rt_mtd_nor_device parent;
const struct fal_partition *fal_part;
};
static rt_size_t mtd_nor_dev_read(struct rt_mtd_nor_device* device, rt_off_t offset, rt_uint8_t* data, rt_uint32_t length)
{
int ret = 0;
struct fal_mtd_nor_device *part = (struct fal_mtd_nor_device*) device;
assert(part != RT_NULL);
ret = fal_partition_read(part->fal_part, offset, data, length);
if (ret != (int)length)
{
ret = 0;
}
else
{
ret = length;
}
return ret;
}
static rt_size_t mtd_nor_dev_write(struct rt_mtd_nor_device* device, rt_off_t offset, const rt_uint8_t* data, rt_uint32_t length)
{
int ret = 0;
struct fal_mtd_nor_device *part;
part = (struct fal_mtd_nor_device*) device;
assert(part != RT_NULL);
ret = fal_partition_write(part->fal_part, offset, data, length);
if (ret != (int) length)
{
ret = 0;
}
else
{
ret = length;
}
return ret;
}
static rt_err_t mtd_nor_dev_erase(struct rt_mtd_nor_device* device, rt_off_t offset, rt_uint32_t length)
{
int ret = 0;
struct fal_mtd_nor_device *part;
part = (struct fal_mtd_nor_device*) device;
assert(part != RT_NULL);
ret = fal_partition_erase(part->fal_part, offset, length);
if (ret != length)
{
return -RT_ERROR;
}
else
{
return RT_EOK;
}
}
static const struct rt_mtd_nor_driver_ops _ops =
{
RT_NULL,
mtd_nor_dev_read,
mtd_nor_dev_write,
mtd_nor_dev_erase,
};
/**
* create RT-Thread MTD NOR device by specified partition
*
* @param parition_name partition name
*
* @return != NULL: created MTD NOR device
* NULL: created failed
*/
struct rt_device *fal_mtd_nor_device_create(const char *parition_name)
{
struct fal_mtd_nor_device *mtd_nor_dev;
const struct fal_partition *fal_part = fal_partition_find(parition_name);
const struct fal_flash_dev *fal_flash = NULL;
if (!fal_part)
{
log_e("Error: the partition name (%s) is not found.", parition_name);
return NULL;
}
if ((fal_flash = fal_flash_device_find(fal_part->flash_name)) == NULL)
{
log_e("Error: the flash device name (%s) is not found.", fal_part->flash_name);
return NULL;
}
mtd_nor_dev = (struct fal_mtd_nor_device*) rt_malloc(sizeof(struct fal_mtd_nor_device));
if (mtd_nor_dev)
{
mtd_nor_dev->fal_part = fal_part;
mtd_nor_dev->parent.block_start = 0;
mtd_nor_dev->parent.block_end = fal_part->len / fal_flash->blk_size;
mtd_nor_dev->parent.block_size = fal_flash->blk_size;
/* set ops */
mtd_nor_dev->parent.ops = &_ops;
log_i("The FAL MTD NOR device (%s) created successfully", fal_part->name);
rt_mtd_nor_register_device(fal_part->name, &mtd_nor_dev->parent);
}
else
{
log_e("Error: no memory for create FAL MTD NOR device");
}
return RT_DEVICE(&mtd_nor_dev->parent);
}
#endif /* defined(RT_USING_MTD_NOR) */
/* ========================== char device ======================== */
struct fal_char_device
{
struct rt_device parent;
const struct fal_partition *fal_part;
};
/* RT-Thread device interface */
static rt_size_t char_dev_read(rt_device_t dev, rt_off_t pos, void *buffer, rt_size_t size)
{
int ret = 0;
struct fal_char_device *part = (struct fal_char_device *) dev;
assert(part != RT_NULL);
if (pos + size > part->fal_part->len)
size = part->fal_part->len - pos;
ret = fal_partition_read(part->fal_part, pos, buffer, size);
if (ret != (int)(size))
ret = 0;
return ret;
}
static rt_size_t char_dev_write(rt_device_t dev, rt_off_t pos, const void *buffer, rt_size_t size)
{
int ret = 0;
struct fal_char_device *part;
part = (struct fal_char_device *) dev;
assert(part != RT_NULL);
if (pos == 0)
{
fal_partition_erase_all(part->fal_part);
}
else if (pos + size > part->fal_part->len)
{
size = part->fal_part->len - pos;
}
ret = fal_partition_write(part->fal_part, pos, buffer, size);
if (ret != (int) size)
ret = 0;
return ret;
}
#ifdef RT_USING_DEVICE_OPS
const static struct rt_device_ops char_dev_ops =
{
RT_NULL,
RT_NULL,
RT_NULL,
char_dev_read,
char_dev_write,
RT_NULL
};
#endif
#ifdef RT_USING_POSIX
#include <dfs_posix.h>
/* RT-Thread device filesystem interface */
static int char_dev_fopen(struct dfs_fd *fd)
{
struct fal_char_device *part = (struct fal_char_device *) fd->data;
assert(part != RT_NULL);
switch (fd->flags & O_ACCMODE)
{
case O_RDONLY:
break;
case O_WRONLY:
case O_RDWR:
/* erase partition when device file open */
fal_partition_erase_all(part->fal_part);
break;
default:
break;
}
fd->pos = 0;
return RT_EOK;
}
static int char_dev_fread(struct dfs_fd *fd, void *buf, size_t count)
{
int ret = 0;
struct fal_char_device *part = (struct fal_char_device *) fd->data;
assert(part != RT_NULL);
if (fd->pos + count > part->fal_part->len)
count = part->fal_part->len - fd->pos;
ret = fal_partition_read(part->fal_part, fd->pos, buf, count);
if (ret != (int)(count))
return 0;
fd->pos += ret;
return ret;
}
static int char_dev_fwrite(struct dfs_fd *fd, const void *buf, size_t count)
{
int ret = 0;
struct fal_char_device *part = (struct fal_char_device *) fd->data;
assert(part != RT_NULL);
if (fd->pos + count > part->fal_part->len)
count = part->fal_part->len - fd->pos;
ret = fal_partition_write(part->fal_part, fd->pos, buf, count);
if (ret != (int) count)
return 0;
fd->pos += ret;
return ret;
}
static const struct dfs_file_ops char_dev_fops =
{
char_dev_fopen,
RT_NULL,
RT_NULL,
char_dev_fread,
char_dev_fwrite,
RT_NULL, /* flush */
RT_NULL, /* lseek */
RT_NULL, /* getdents */
RT_NULL,
};
#endif /* defined(RT_USING_POSIX) */
/**
* create RT-Thread char device by specified partition
*
* @param parition_name partition name
*
* @return != NULL: created char device
* NULL: created failed
*/
struct rt_device *fal_char_device_create(const char *parition_name)
{
struct fal_char_device *char_dev;
const struct fal_partition *fal_part = fal_partition_find(parition_name);
if (!fal_part)
{
log_e("Error: the partition name (%s) is not found.", parition_name);
return NULL;
}
if ((fal_flash_device_find(fal_part->flash_name)) == NULL)
{
log_e("Error: the flash device name (%s) is not found.", fal_part->flash_name);
return NULL;
}
char_dev = (struct fal_char_device *) rt_malloc(sizeof(struct fal_char_device));
if (char_dev)
{
char_dev->fal_part = fal_part;
/* register device */
char_dev->parent.type = RT_Device_Class_Char;
#ifdef RT_USING_DEVICE_OPS
char_dev->parent.ops = &char_dev_ops;
#else
char_dev->parent.init = NULL;
char_dev->parent.open = NULL;
char_dev->parent.close = NULL;
char_dev->parent.read = char_dev_read;
char_dev->parent.write = char_dev_write;
char_dev->parent.control = NULL;
/* no private */
char_dev->parent.user_data = NULL;
#endif
rt_device_register(RT_DEVICE(char_dev), fal_part->name, RT_DEVICE_FLAG_RDWR);
log_i("The FAL char device (%s) created successfully", fal_part->name);
#ifdef RT_USING_POSIX
/* set fops */
char_dev->parent.fops = &char_dev_fops;
#endif
}
else
{
log_e("Error: no memory for create FAL char device");
}
return RT_DEVICE(char_dev);
}
#if defined(RT_USING_FINSH) && defined(FINSH_USING_MSH)
#include <finsh.h>
extern int fal_init_check(void);
static void fal(uint8_t argc, char **argv) {
#define __is_print(ch) ((unsigned int)((ch) - ' ') < 127u - ' ')
#define HEXDUMP_WIDTH 16
#define CMD_PROBE_INDEX 0
#define CMD_READ_INDEX 1
#define CMD_WRITE_INDEX 2
#define CMD_ERASE_INDEX 3
#define CMD_BENCH_INDEX 4
int result;
static const struct fal_flash_dev *flash_dev = NULL;
static const struct fal_partition *part_dev = NULL;
size_t i = 0, j = 0;
const char* help_info[] =
{
[CMD_PROBE_INDEX] = "fal probe [dev_name|part_name] - probe flash device or partition by given name",
[CMD_READ_INDEX] = "fal read addr size - read 'size' bytes starting at 'addr'",
[CMD_WRITE_INDEX] = "fal write addr data1 ... dataN - write some bytes 'data' starting at 'addr'",
[CMD_ERASE_INDEX] = "fal erase addr size - erase 'size' bytes starting at 'addr'",
[CMD_BENCH_INDEX] = "fal bench <blk_size> - benchmark test with per block size",
};
if (fal_init_check() != 1)
{
rt_kprintf("\n[Warning] FAL is not initialized or failed to initialize!\n\n");
return;
}
if (argc < 2)
{
rt_kprintf("Usage:\n");
for (i = 0; i < sizeof(help_info) / sizeof(char*); i++)
{
rt_kprintf("%s\n", help_info[i]);
}
rt_kprintf("\n");
}
else
{
const char *operator = argv[1];
uint32_t addr, size;
if (!strcmp(operator, "probe"))
{
if (argc >= 3)
{
char *dev_name = argv[2];
if ((flash_dev = fal_flash_device_find(dev_name)) != NULL)
{
part_dev = NULL;
}
else if ((part_dev = fal_partition_find(dev_name)) != NULL)
{
flash_dev = NULL;
}
else
{
rt_kprintf("Device %s NOT found. Probe failed.\n", dev_name);
flash_dev = NULL;
part_dev = NULL;
}
}
if (flash_dev)
{
rt_kprintf("Probed a flash device | %s | addr: %ld | len: %d |.\n", flash_dev->name,
flash_dev->addr, flash_dev->len);
}
else if (part_dev)
{
rt_kprintf("Probed a flash partition | %s | flash_dev: %s | offset: %ld | len: %d |.\n",
part_dev->name, part_dev->flash_name, part_dev->offset, part_dev->len);
}
else
{
rt_kprintf("No flash device or partition was probed.\n");
rt_kprintf("Usage: %s.\n", help_info[CMD_PROBE_INDEX]);
fal_show_part_table();
}
}
else
{
if (!flash_dev && !part_dev)
{
rt_kprintf("No flash device or partition was probed. Please run 'fal probe'.\n");
return;
}
if (!rt_strcmp(operator, "read"))
{
if (argc < 4)
{
rt_kprintf("Usage: %s.\n", help_info[CMD_READ_INDEX]);
return;
}
else
{
addr = strtol(argv[2], NULL, 0);
size = strtol(argv[3], NULL, 0);
uint8_t *data = rt_malloc(size);
if (data)
{
if (flash_dev)
{
result = flash_dev->ops.read(addr, data, size);
}
else if (part_dev)
{
result = fal_partition_read(part_dev, addr, data, size);
}
if (result >= 0)
{
rt_kprintf("Read data success. Start from 0x%08X, size is %ld. The data is:\n", addr,
size);
rt_kprintf("Offset (h) 00 01 02 03 04 05 06 07 08 09 0A 0B 0C 0D 0E 0F\n");
for (i = 0; i < size; i += HEXDUMP_WIDTH)
{
rt_kprintf("[%08X] ", addr + i);
/* dump hex */
for (j = 0; j < HEXDUMP_WIDTH; j++)
{
if (i + j < size)
{
rt_kprintf("%02X ", data[i + j]);
}
else
{
rt_kprintf(" ");
}
}
/* dump char for hex */
for (j = 0; j < HEXDUMP_WIDTH; j++)
{
if (i + j < size)
{
rt_kprintf("%c", __is_print(data[i + j]) ? data[i + j] : '.');
}
}
rt_kprintf("\n");
}
rt_kprintf("\n");
}
rt_free(data);
}
else
{
rt_kprintf("Low memory!\n");
}
}
}
else if (!strcmp(operator, "write"))
{
if (argc < 4)
{
rt_kprintf("Usage: %s.\n", help_info[CMD_WRITE_INDEX]);
return;
}
else
{
addr = strtol(argv[2], NULL, 0);
size = argc - 3;
uint8_t *data = rt_malloc(size);
if (data)
{
for (i = 0; i < size; i++)
{
data[i] = strtol(argv[3 + i], NULL, 0);
}
if (flash_dev)
{
result = flash_dev->ops.write(addr, data, size);
}
else if (part_dev)
{
result = fal_partition_write(part_dev, addr, data, size);
}
if (result >= 0)
{
rt_kprintf("Write data success. Start from 0x%08X, size is %ld.\n", addr, size);
rt_kprintf("Write data: ");
for (i = 0; i < size; i++)
{
rt_kprintf("%d ", data[i]);
}
rt_kprintf(".\n");
}
rt_free(data);
}
else
{
rt_kprintf("Low memory!\n");
}
}
}
else if (!rt_strcmp(operator, "erase"))
{
if (argc < 4)
{
rt_kprintf("Usage: %s.\n", help_info[CMD_ERASE_INDEX]);
return;
}
else
{
addr = strtol(argv[2], NULL, 0);
size = strtol(argv[3], NULL, 0);
if (flash_dev)
{
result = flash_dev->ops.erase(addr, size);
}
else if (part_dev)
{
result = fal_partition_erase(part_dev, addr, size);
}
if (result >= 0)
{
rt_kprintf("Erase data success. Start from 0x%08X, size is %ld.\n", addr, size);
}
}
}
else if (!strcmp(operator, "bench"))
{
if (argc < 3)
{
rt_kprintf("Usage: %s.\n", help_info[CMD_BENCH_INDEX]);
return;
}
else if ((argc > 3 && strcmp(argv[3], "yes")) || argc < 4)
{
rt_kprintf("DANGER: It will erase full chip or partition! Please run 'fal bench %d yes'.\n", strtol(argv[2], NULL, 0));
return;
}
/* full chip benchmark test */
uint32_t start_time, time_cast;
size_t write_size = strtol(argv[2], NULL, 0), read_size = strtol(argv[2], NULL, 0), cur_op_size;
uint8_t *write_data = (uint8_t *)rt_malloc(write_size), *read_data = (uint8_t *)rt_malloc(read_size);
if (write_data && read_data)
{
for (i = 0; i < write_size; i ++) {
write_data[i] = i & 0xFF;
}
if (flash_dev)
{
size = flash_dev->len;
}
else if (part_dev)
{
size = part_dev->len;
}
/* benchmark testing */
rt_kprintf("Erasing %ld bytes data, waiting...\n", size);
start_time = rt_tick_get();
if (flash_dev)
{
result = flash_dev->ops.erase(0, size);
}
else if (part_dev)
{
result = fal_partition_erase(part_dev, 0, size);
}
if (result >= 0)
{
time_cast = rt_tick_get() - start_time;
rt_kprintf("Erase benchmark success, total time: %d.%03dS.\n", time_cast / RT_TICK_PER_SECOND,
time_cast % RT_TICK_PER_SECOND / ((RT_TICK_PER_SECOND * 1 + 999) / 1000));
}
else
{
rt_kprintf("Erase benchmark has an error. Error code: %d.\n", result);
}
/* write test */
rt_kprintf("Writing %ld bytes data, waiting...\n", size);
start_time = rt_tick_get();
for (i = 0; i < size; i += write_size)
{
if (i + write_size <= size)
{
cur_op_size = write_size;
}
else
{
cur_op_size = size - i;
}
if (flash_dev)
{
result = flash_dev->ops.write(i, write_data, cur_op_size);
}
else if (part_dev)
{
result = fal_partition_write(part_dev, i, write_data, cur_op_size);
}
if (result < 0)
{
break;
}
}
if (result >= 0)
{
time_cast = rt_tick_get() - start_time;
rt_kprintf("Write benchmark success, total time: %d.%03dS.\n", time_cast / RT_TICK_PER_SECOND,
time_cast % RT_TICK_PER_SECOND / ((RT_TICK_PER_SECOND * 1 + 999) / 1000));
}
else
{
rt_kprintf("Write benchmark has an error. Error code: %d.\n", result);
}
/* read test */
rt_kprintf("Reading %ld bytes data, waiting...\n", size);
start_time = rt_tick_get();
for (i = 0; i < size; i += read_size)
{
if (i + read_size <= size)
{
cur_op_size = read_size;
}
else
{
cur_op_size = size - i;
}
if (flash_dev)
{
result = flash_dev->ops.read(i, read_data, cur_op_size);
}
else if (part_dev)
{
result = fal_partition_read(part_dev, i, read_data, cur_op_size);
}
/* data check */
for (int index = 0; index < cur_op_size; index ++)
{
if (write_data[index] != read_data[index])
{
rt_kprintf("%d %d %02x %02x.\n", i, index, write_data[index], read_data[index]);
}
}
if (memcmp(write_data, read_data, cur_op_size))
{
result = -RT_ERROR;
rt_kprintf("Data check ERROR! Please check you flash by other command.\n");
}
/* has an error */
if (result < 0)
{
break;
}
}
if (result >= 0)
{
time_cast = rt_tick_get() - start_time;
rt_kprintf("Read benchmark success, total time: %d.%03dS.\n", time_cast / RT_TICK_PER_SECOND,
time_cast % RT_TICK_PER_SECOND / ((RT_TICK_PER_SECOND * 1 + 999) / 1000));
}
else
{
rt_kprintf("Read benchmark has an error. Error code: %d.\n", result);
}
}
else
{
rt_kprintf("Low memory!\n");
}
rt_free(write_data);
rt_free(read_data);
}
else
{
rt_kprintf("Usage:\n");
for (i = 0; i < sizeof(help_info) / sizeof(char*); i++)
{
rt_kprintf("%s\n", help_info[i]);
}
rt_kprintf("\n");
return;
}
if (result < 0) {
rt_kprintf("This operate has an error. Error code: %d.\n", result);
}
}
}
}
MSH_CMD_EXPORT(fal, FAL (Flash Abstraction Layer) operate.);
#endif /* defined(RT_USING_FINSH) && defined(FINSH_USING_MSH) */
#endif /* RT_VER_NUM */

View File

@ -0,0 +1,69 @@
/*
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2018-01-26 armink the first version
*/
#include "eeprom_fm24.h"
#include <fal.h>
static int init(void);
static int erase(long offset, size_t size);
static int read(long offset, uint8_t *buf, size_t size);
static int write(long offset, const uint8_t *buf, size_t size);
// 1.定义 flash 设备
struct fal_flash_dev eeprom_fm24 =
{
.name = EEPROM_FM24_DEV_NAME,
.addr = 0,
.len = FM24_PAGE_SIZE,
.blk_size = EEPROM_FM24_BLOCK_SIZE,
.ops = {init, read, write, erase},
.write_gran = 1};
static int init(void)
{
return 1;
}
static int erase(long offset, size_t size)
{
// uint8_t erase_size = size > FAL_ERASE_SIZE ? FAL_ERASE_SIZE : size;
// uint8_t buf[FAL_ERASE_SIZE];
// osel_memset(buf, 0xFF, FAL_ERASE_SIZE);
// for (uint8_t i = 0; i < (size / FM24_PAGE_SIZE); i++)
// {
// uint32_t addr = eeprom_fm24.addr + offset + i * FM24_PAGE_SIZE;
// eeprom_fm24_write(addr, (uint8_t *)buf, erase_size);
// }
return size;
}
static int read(long offset, uint8_t *buf, size_t size)
{
/* You can add your code under here. */
if (size == 0)
{
return 0;
}
uint32_t addr = eeprom_fm24.addr + offset;
BOOL res = eeprom_fm24_read(addr, buf, size);
return res == TRUE ? size : 0;
}
static int write(long offset, const uint8_t *buf, size_t size)
{
if (size == 0)
{
return 0;
}
uint32_t addr = eeprom_fm24.addr + offset;
BOOL res = eeprom_fm24_write(addr, (uint8_t *)buf, size);
return res == TRUE ? (int)size : -1;
}

View File

@ -0,0 +1,87 @@
/*
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2018-01-26 armink the first version
*/
#include "eeprom_m95.h"
#include <fal.h>
static int init(void);
static int erase(long offset, size_t size);
static int read1(long offset, uint8_t *buf, size_t size);
static int read2(long offset, uint8_t *buf, size_t size);
static int write1(long offset, const uint8_t *buf, size_t size);
static int write2(long offset, const uint8_t *buf, size_t size);
// 1.定义 flash 设备
struct fal_flash_dev eeprom_m95_1 =
{
.name = EEPROM_M95_1_DEV_NAME,
.addr = 10 * M95_PAGE_SIZE_256,
.len = EEPROM_M95_1_SIZE - 10 * M95_PAGE_SIZE_256,
.blk_size = EEPROM_M95_1_BLOCK_SIZE,
.ops = {init, read1, write1, erase},
.write_gran = 1}; // 设置写粒度,单位 bitEPPROM写粒度为1bit
struct fal_flash_dev eeprom_m95_2 =
{
.name = EEPROM_M95_2_DEV_NAME,
.addr = 0x000000,
.len = EEPROM_M95_2_SIZE,
.blk_size = EEPROM_M95_2_BLOCK_SIZE,
.ops = {init, read2, write2, erase},
.write_gran = 1};
static int init(void)
{
return 1;
}
static int erase(long offset, size_t size)
{
// uint8_t erase_size = size > FAL_ERASE_SIZE ? FAL_ERASE_SIZE : size;
// uint8_t buf[FAL_ERASE_SIZE];
// osel_memset(buf, 0xFF, FAL_ERASE_SIZE);
// for (uint8_t i = 0; i < (size / M95_PAGE_SIZE_256); i++)
// {
// uint32_t addr = eeprom_m95_1.addr + offset + i * M95_PAGE_SIZE_256;
// eeprom_m95_write(M95_1, addr, (uint8_t *)buf, erase_size);
// }
return size;
}
static int read1(long offset, uint8_t *buf, size_t size)
{
/* You can add your code under here. */
uint32_t addr = eeprom_m95_1.addr + offset;
BOOL res = eeprom_m95_read(M95_1, addr, buf, size);
return res == TRUE ? size : 0;
}
static int write1(long offset, const uint8_t *buf, size_t size)
{
uint32_t addr = eeprom_m95_1.addr + offset;
BOOL res = eeprom_m95_write(M95_1, addr, (uint8_t *)buf, size);
return res == TRUE ? (int)size : -1;
}
static int read2(long offset, uint8_t *buf, size_t size)
{
/* You can add your code under here. */
uint32_t addr = eeprom_m95_2.addr + offset;
BOOL res = eeprom_m95_read(M95_2, addr, buf, size);
return res == TRUE ? size : 0;
}
static int write2(long offset, const uint8_t *buf, size_t size)
{
uint32_t addr = eeprom_m95_2.addr + offset;
BOOL res = eeprom_m95_write(M95_2, addr, (uint8_t *)buf, size);
return res == TRUE ? (int)size : -1;
}

157
lib/flashdb/fdb.c Normal file
View File

@ -0,0 +1,157 @@
/*
* Copyright (c) 2020, Armink, <armink.ztl@gmail.com>
*
* SPDX-License-Identifier: Apache-2.0
*/
/**
* @file
* @brief Initialize interface.
*
* Some initialize interface for this library.
*/
#include <flashdb.h>
#include <fdb_low_lvl.h>
#include <string.h>
#include <inttypes.h>
#ifdef FDB_USING_FILE_POSIX_MODE
#if !defined(_MSC_VER)
#include <unistd.h>
#endif
#endif /* FDB_USING_FILE_POSIX_MODE */
#define FDB_LOG_TAG ""
#if !defined(FDB_USING_FAL_MODE) && !defined(FDB_USING_FILE_MODE)
#error "Please defined the FDB_USING_FAL_MODE or FDB_USING_FILE_MODE macro"
#endif
fdb_err_t _fdb_init_ex(fdb_db_t db, const char *name, const char *path, fdb_db_type type, void *user_data)
{
FDB_ASSERT(db);
FDB_ASSERT(name);
FDB_ASSERT(path);
if (db->init_ok) {
return FDB_NO_ERR;
}
db->name = name;
db->type = type;
db->user_data = user_data;
if (db->file_mode) {
#ifdef FDB_USING_FILE_MODE
memset(db->cur_file_sec, FDB_FAILED_ADDR, FDB_FILE_CACHE_TABLE_SIZE * sizeof(db->cur_file_sec[0]));
/* must set when using file mode */
FDB_ASSERT(db->sec_size != 0);
FDB_ASSERT(db->max_size != 0);
#ifdef FDB_USING_FILE_POSIX_MODE
memset(db->cur_file, -1, FDB_FILE_CACHE_TABLE_SIZE * sizeof(db->cur_file[0]));
#else
memset(db->cur_file, 0, FDB_FILE_CACHE_TABLE_SIZE * sizeof(db->cur_file[0]));
#endif
db->storage.dir = path;
FDB_ASSERT(strlen(path) != 0)
#endif
} else {
#ifdef FDB_USING_FAL_MODE
size_t block_size;
/* FAL (Flash Abstraction Layer) initialization */
fal_init();
/* check the flash partition */
if ((db->storage.part = fal_partition_find(path)) == NULL) {
FDB_INFO("Error: Partition (%s) not found.\n", path);
return FDB_PART_NOT_FOUND;
}
block_size = fal_flash_device_find(db->storage.part->flash_name)->blk_size;
if (db->sec_size == 0) {
db->sec_size = block_size;
} else {
/* must be aligned with block size */
if (db->sec_size % block_size != 0) {
FDB_INFO("Error: db sector size (%" PRIu32 ") MUST align with block size (%zu).\n", db->sec_size, block_size);
return FDB_INIT_FAILED;
}
}
db->max_size = db->storage.part->len;
#endif /* FDB_USING_FAL_MODE */
}
/* the block size MUST to be the Nth power of 2 */
FDB_ASSERT((db->sec_size & (db->sec_size - 1)) == 0);
/* must align with sector size */
if (db->max_size % db->sec_size != 0) {
FDB_INFO("Error: db total size (%" PRIu32 ") MUST align with sector size (%" PRIu32 ").\n", db->max_size, db->sec_size);
return FDB_INIT_FAILED;
}
/* must has more than or equal 2 sectors */
if (db->max_size / db->sec_size < 2) {
FDB_INFO("Error: db MUST has more than or equal 2 sectors, current has %" PRIu32 " sector(s)\n", db->max_size / db->sec_size);
return FDB_INIT_FAILED;
}
return FDB_NO_ERR;
}
void _fdb_init_finish(fdb_db_t db, fdb_err_t result)
{
static bool log_is_show = false;
if (result == FDB_NO_ERR) {
db->init_ok = true;
if (!log_is_show) {
FDB_INFO("FlashDB V%s is initialize success.\n", FDB_SW_VERSION);
FDB_INFO("You can get the latest version on https://github.com/armink/FlashDB .\n");
log_is_show = true;
}
} else if (!db->not_formatable) {
FDB_INFO("Error: %s (%s@%s) is initialize fail (%d).\n", db->type == FDB_DB_TYPE_KV ? "KVDB" : "TSDB",
db->name, _fdb_db_path(db), (int)result);
}
}
void _fdb_deinit(fdb_db_t db)
{
FDB_ASSERT(db);
if (db->init_ok) {
#ifdef FDB_USING_FILE_MODE
for (int i = 0; i < FDB_FILE_CACHE_TABLE_SIZE; i++) {
#ifdef FDB_USING_FILE_POSIX_MODE
if (db->cur_file[i] > 0) {
close(db->cur_file[i]);
}
#else
if (db->cur_file[i] != 0) {
fclose(db->cur_file[i]);
}
#endif /* FDB_USING_FILE_POSIX_MODE */
}
#endif /* FDB_USING_FILE_MODE */
}
db->init_ok = false;
}
const char *_fdb_db_path(fdb_db_t db)
{
if (db->file_mode) {
#ifdef FDB_USING_FILE_MODE
return db->storage.dir;
#else
return NULL;
#endif
}
else {
#ifdef FDB_USING_FAL_MODE
return db->storage.part->name;
#else
return NULL;
#endif
}
}

50
lib/flashdb/fdb_cfg.h Normal file
View File

@ -0,0 +1,50 @@
/*
* Copyright (c) 2020, Armink, <armink.ztl@gmail.com>
*
* SPDX-License-Identifier: Apache-2.0
*/
/**
* @file
* @brief configuration file
*/
#ifndef _FDB_CFG_H_
#define _FDB_CFG_H_
/* using KVDB feature */
#define FDB_USING_KVDB
#ifdef FDB_USING_KVDB
/* Auto update KV to latest default when current KVDB version number is changed. @see fdb_kvdb.ver_num */
#define FDB_KV_AUTO_UPDATE
#endif
/* using TSDB (Time series database) feature */
#define FDB_USING_TSDB
/* Using FAL storage mode */
#define FDB_USING_FAL_MODE
#ifdef FDB_USING_FAL_MODE
/* the flash write granularity, unit: bit
* only support 1(nor flash)/ 8(stm32f2/f4)/ 32(stm32f1)/ 64(stm32f7)/ 128(stm32h5) */
#define FDB_WRITE_GRAN 1 /* @note you must define it for a value */
#endif
/* Using file storage mode by LIBC file API, like fopen/fread/fwrte/fclose */
/* #define FDB_USING_FILE_LIBC_MODE */
/* Using file storage mode by POSIX file API, like open/read/write/close */
/* #define FDB_USING_FILE_POSIX_MODE */
/* MCU Endian Configuration, default is Little Endian Order. */
/* #define FDB_BIG_ENDIAN */
/* log print macro. default EF_PRINT macro is printf() */
/* #define FDB_PRINT(...) my_printf(__VA_ARGS__) */
/* print debug information */
// #define FDB_DEBUG_ENABLE
#endif /* _FDB_CFG_H_ */

385
lib/flashdb/fdb_def.h Normal file
View File

@ -0,0 +1,385 @@
/*
* Copyright (c) 2020-2023, Armink, <armink.ztl@gmail.com>
*
* SPDX-License-Identifier: Apache-2.0
*/
/**
* @file
* @brief Public definition.
*/
#ifndef _FDB_DEF_H_
#define _FDB_DEF_H_
#ifdef FDB_USING_NATIVE_ASSERT
#include <assert.h>
#endif
#ifdef __cplusplus
extern "C"
{
#endif
/* software version number */
#define FDB_SW_VERSION "2.1.1"
#define FDB_SW_VERSION_NUM 0x20101
/* the KV max name length must less then it */
#ifndef FDB_KV_NAME_MAX
#define FDB_KV_NAME_MAX 64
#endif
/* the KV cache table size, it will improve KV search speed when using cache */
#ifndef FDB_KV_CACHE_TABLE_SIZE
#define FDB_KV_CACHE_TABLE_SIZE 64
#endif
/* the sector cache table size, it will improve KV save speed when using cache */
#ifndef FDB_SECTOR_CACHE_TABLE_SIZE
#define FDB_SECTOR_CACHE_TABLE_SIZE 8
#endif
#if (FDB_KV_CACHE_TABLE_SIZE > 0) && (FDB_SECTOR_CACHE_TABLE_SIZE > 0)
#define FDB_KV_USING_CACHE
#endif
#if defined(FDB_USING_FILE_LIBC_MODE) || defined(FDB_USING_FILE_POSIX_MODE)
#define FDB_USING_FILE_MODE
#endif
/* the file cache table size, it will improve GC speed in file mode when using cache */
#ifndef FDB_FILE_CACHE_TABLE_SIZE
#define FDB_FILE_CACHE_TABLE_SIZE 4
#endif
#ifndef FDB_WRITE_GRAN
#define FDB_WRITE_GRAN 1
#endif
/* log function. default FDB_PRINT macro is printf() */
// #ifndef FDB_PRINT
// #define FDB_PRINT(...) printf(__VA_ARGS__)
// #endif
#ifndef FDB_PRINT
#define FDB_PRINT(...)
#endif
#define FDB_LOG_PREFIX1() FDB_PRINT("[FlashDB]" FDB_LOG_TAG)
#define FDB_LOG_PREFIX2() FDB_PRINT(" ")
#define FDB_LOG_PREFIX() \
FDB_LOG_PREFIX1(); \
FDB_LOG_PREFIX2()
#ifdef FDB_DEBUG_ENABLE
#define FDB_DEBUG(...) \
FDB_LOG_PREFIX(); \
FDB_PRINT("(%s:%d) ", __FILE__, __LINE__); \
FDB_PRINT(__VA_ARGS__)
#else
#define FDB_DEBUG(...)
#endif
/* routine print function. Must be implement by user. */
#define FDB_INFO(...) \
FDB_LOG_PREFIX(); \
FDB_PRINT(__VA_ARGS__)
/* assert for developer. */
#ifdef FDB_USING_NATIVE_ASSERT
#define FDB_ASSERT(EXPR) assert(EXPR);
#else
#ifndef FDB_ASSERT
#define FDB_ASSERT(EXPR) \
if (!(EXPR)) \
{ \
FDB_INFO("(%s) has assert failed at %s.\n", #EXPR, __func__); \
while (1) \
; \
}
#endif /* FDB_ASSERT */
#endif /* FDB_USING_NATIVE_ASSERT */
#define FDB_KVDB_CTRL_SET_SEC_SIZE 0x00 /**< set sector size control command, this change MUST before database initialization */
#define FDB_KVDB_CTRL_GET_SEC_SIZE 0x01 /**< get sector size control command */
#define FDB_KVDB_CTRL_SET_LOCK 0x02 /**< set lock function control command */
#define FDB_KVDB_CTRL_SET_UNLOCK 0x03 /**< set unlock function control command */
#define FDB_KVDB_CTRL_SET_FILE_MODE 0x09 /**< set file mode control command, this change MUST before database initialization */
#define FDB_KVDB_CTRL_SET_MAX_SIZE 0x0A /**< set database max size in file mode control command, this change MUST before database initialization */
#define FDB_KVDB_CTRL_SET_NOT_FORMAT 0x0B /**< set database NOT format mode control command, this change MUST before database initialization */
#define FDB_TSDB_CTRL_SET_SEC_SIZE 0x00 /**< set sector size control command, this change MUST before database initialization */
#define FDB_TSDB_CTRL_GET_SEC_SIZE 0x01 /**< get sector size control command */
#define FDB_TSDB_CTRL_SET_LOCK 0x02 /**< set lock function control command */
#define FDB_TSDB_CTRL_SET_UNLOCK 0x03 /**< set unlock function control command */
#define FDB_TSDB_CTRL_SET_ROLLOVER 0x04 /**< set rollover control command, this change MUST after database initialization */
#define FDB_TSDB_CTRL_GET_ROLLOVER 0x05 /**< get rollover control command */
#define FDB_TSDB_CTRL_GET_LAST_TIME 0x06 /**< get last save time control command */
#define FDB_TSDB_CTRL_SET_FILE_MODE 0x09 /**< set file mode control command, this change MUST before database initialization */
#define FDB_TSDB_CTRL_SET_MAX_SIZE 0x0A /**< set database max size in file mode control command, this change MUST before database initialization */
#define FDB_TSDB_CTRL_SET_NOT_FORMAT 0x0B /**< set database NOT formatable mode control command, this change MUST before database initialization */
#ifdef FDB_USING_TIMESTAMP_64BIT
typedef int64_t fdb_time_t;
#else
typedef int32_t fdb_time_t;
#endif /* FDB_USING_TIMESTAMP_64BIT */
typedef fdb_time_t (*fdb_get_time)(void);
struct fdb_default_kv_node
{
char *key;
void *value;
size_t value_len;
};
struct fdb_default_kv
{
struct fdb_default_kv_node *kvs;
size_t num;
};
/* error code */
typedef enum
{
FDB_NO_ERR,
FDB_ERASE_ERR,
FDB_READ_ERR,
FDB_WRITE_ERR,
FDB_PART_NOT_FOUND,
FDB_KV_NAME_ERR,
FDB_KV_NAME_EXIST,
FDB_SAVED_FULL,
FDB_INIT_FAILED,
} fdb_err_t;
enum fdb_kv_status
{
FDB_KV_UNUSED,
FDB_KV_PRE_WRITE,
FDB_KV_WRITE,
FDB_KV_PRE_DELETE,
FDB_KV_DELETED,
FDB_KV_ERR_HDR,
#define FDB_KV_STATUS_NUM 6
};
typedef enum fdb_kv_status fdb_kv_status_t;
enum fdb_tsl_status
{
FDB_TSL_UNUSED,
FDB_TSL_PRE_WRITE,
FDB_TSL_WRITE,
FDB_TSL_USER_STATUS1,
FDB_TSL_DELETED,
FDB_TSL_USER_STATUS2,
#define FDB_TSL_STATUS_NUM 6
};
typedef enum fdb_tsl_status fdb_tsl_status_t;
/* key-value node object */
struct fdb_kv
{
fdb_kv_status_t status; /**< node status, @see fdb_kv_status_t */
bool crc_is_ok; /**< node CRC32 check is OK */
uint8_t name_len; /**< name length */
uint32_t magic; /**< magic word(`K`, `V`, `4`, `0`) */
uint32_t len; /**< node total length (header + name + value), must align by FDB_WRITE_GRAN */
uint32_t value_len; /**< value length */
char name[FDB_KV_NAME_MAX]; /**< name */
struct
{
uint32_t start; /**< node start address */
uint32_t value; /**< value start address */
} addr;
};
typedef struct fdb_kv *fdb_kv_t;
struct fdb_kv_iterator
{
struct fdb_kv curr_kv; /**< Current KV we get from the iterator */
uint32_t iterated_cnt; /**< How many KVs have we iterated already */
size_t iterated_obj_bytes; /**< Total storage size of KVs we have iterated. */
size_t iterated_value_bytes; /**< Total value size of KVs we have iterated. */
uint32_t sector_addr; /**< Current sector address we're iterating. DO NOT touch it. */
uint32_t traversed_len; /**< Traversed sector total length. */
};
typedef struct fdb_kv_iterator *fdb_kv_iterator_t;
/* time series log node object */
struct fdb_tsl
{
fdb_tsl_status_t status; /**< node status, @see fdb_log_status_t */
fdb_time_t time; /**< node timestamp */
uint32_t log_len; /**< log length, must align by FDB_WRITE_GRAN */
struct
{
uint32_t index; /**< node index address */
uint32_t log; /**< log data address */
} addr;
};
typedef struct fdb_tsl *fdb_tsl_t;
typedef bool (*fdb_tsl_cb)(fdb_tsl_t tsl, void *arg);
typedef enum
{
FDB_DB_TYPE_KV,
FDB_DB_TYPE_TS,
} fdb_db_type;
/* the flash sector store status */
enum fdb_sector_store_status
{
FDB_SECTOR_STORE_UNUSED,
FDB_SECTOR_STORE_EMPTY,
FDB_SECTOR_STORE_USING,
FDB_SECTOR_STORE_FULL,
#define FDB_SECTOR_STORE_STATUS_NUM 4
};
typedef enum fdb_sector_store_status fdb_sector_store_status_t;
/* the flash sector dirty status */
enum fdb_sector_dirty_status
{
FDB_SECTOR_DIRTY_UNUSED,
FDB_SECTOR_DIRTY_FALSE,
FDB_SECTOR_DIRTY_TRUE,
FDB_SECTOR_DIRTY_GC,
#define FDB_SECTOR_DIRTY_STATUS_NUM 4
};
typedef enum fdb_sector_dirty_status fdb_sector_dirty_status_t;
/* KVDB section information */
struct kvdb_sec_info
{
bool check_ok; /**< sector header check is OK */
struct
{
fdb_sector_store_status_t store; /**< sector store status @see fdb_sector_store_status_t */
fdb_sector_dirty_status_t dirty; /**< sector dirty status @see sector_dirty_status_t */
} status;
uint32_t addr; /**< sector start address */
uint32_t magic; /**< magic word(`E`, `F`, `4`, `0`) */
uint32_t combined; /**< the combined next sector number, 0xFFFFFFFF: not combined */
size_t remain; /**< remain size */
uint32_t empty_kv; /**< the next empty KV node start address */
};
typedef struct kvdb_sec_info *kv_sec_info_t;
/* TSDB section information */
struct tsdb_sec_info
{
bool check_ok; /**< sector header check is OK */
fdb_sector_store_status_t status; /**< sector store status @see fdb_sector_store_status_t */
uint32_t addr; /**< sector start address */
uint32_t magic; /**< magic word(`T`, `S`, `L`, `0`) */
fdb_time_t start_time; /**< the first start node's timestamp, 0xFFFFFFFF: unused */
fdb_time_t end_time; /**< the last end node's timestamp, 0xFFFFFFFF: unused */
uint32_t end_idx; /**< the last end node's index, 0xFFFFFFFF: unused */
fdb_tsl_status_t end_info_stat[2]; /**< the last end node's info status */
size_t remain; /**< remain size */
uint32_t empty_idx; /**< the next empty node index address */
uint32_t empty_data; /**< the next empty node's data end address */
};
typedef struct tsdb_sec_info *tsdb_sec_info_t;
struct kv_cache_node
{
uint16_t name_crc; /**< KV name's CRC32 low 16bit value */
uint16_t active; /**< KV node access active degree */
uint32_t addr; /**< KV node address */
};
typedef struct kv_cache_node *kv_cache_node_t;
/* database structure */
typedef struct fdb_db *fdb_db_t;
struct fdb_db
{
const char *name; /**< database name */
fdb_db_type type; /**< database type */
union
{
#ifdef FDB_USING_FAL_MODE
const struct fal_partition *part; /**< flash partition for saving database */
#endif
#ifdef FDB_USING_FILE_MODE
const char *dir; /**< directory path for saving database */
#endif
} storage;
uint32_t sec_size; /**< flash section size. It's a multiple of block size */
uint32_t max_size; /**< database max size. It's a multiple of section size */
uint32_t oldest_addr; /**< the oldest sector start address */
bool init_ok; /**< initialized successfully */
bool file_mode; /**< is file mode, default is false */
bool not_formatable; /**< is can NOT be formated mode, default is false */
#ifdef FDB_USING_FILE_MODE
uint32_t cur_file_sec[FDB_FILE_CACHE_TABLE_SIZE]; /**< last operate sector address */
#if defined(FDB_USING_FILE_POSIX_MODE)
int cur_file[FDB_FILE_CACHE_TABLE_SIZE]; /**< current file object */
#elif defined(FDB_USING_FILE_LIBC_MODE)
FILE *cur_file[FDB_FILE_CACHE_TABLE_SIZE]; /**< current file object */
#endif /* FDB_USING_FILE_MODE */
uint32_t cur_sec; /**< current operate sector address */
#endif
void (*lock)(fdb_db_t db); /**< lock the database operate */
void (*unlock)(fdb_db_t db); /**< unlock the database operate */
void *user_data;
};
/* KVDB structure */
struct fdb_kvdb
{
struct fdb_db parent; /**< inherit from fdb_db */
struct fdb_default_kv default_kvs; /**< default KV */
bool gc_request; /**< request a GC check */
bool in_recovery_check; /**< is in recovery check status when first reboot */
struct fdb_kv cur_kv;
struct kvdb_sec_info cur_sector;
bool last_is_complete_del;
#ifdef FDB_KV_USING_CACHE
/* KV cache table */
struct kv_cache_node kv_cache_table[FDB_KV_CACHE_TABLE_SIZE];
/* sector cache table, it caching the sector info which status is current using */
struct kvdb_sec_info sector_cache_table[FDB_SECTOR_CACHE_TABLE_SIZE];
#endif /* FDB_KV_USING_CACHE */
#ifdef FDB_KV_AUTO_UPDATE
uint32_t ver_num; /**< setting version number for update */
#endif
void *user_data;
};
typedef struct fdb_kvdb *fdb_kvdb_t;
/* TSDB structure */
struct fdb_tsdb
{
struct fdb_db parent; /**< inherit from fdb_db */
struct tsdb_sec_info cur_sec; /**< current using sector */
fdb_time_t last_time; /**< last TSL timestamp */
fdb_get_time get_time; /**< the current timestamp get function */
size_t max_len; /**< the maximum length of each log */
bool rollover; /**< the oldest data will rollover by newest data, default is true */
void *user_data;
};
typedef struct fdb_tsdb *fdb_tsdb_t;
/* blob structure */
struct fdb_blob
{
void *buf; /**< blob data buffer */
size_t size; /**< blob data buffer size */
struct
{
uint32_t meta_addr; /**< saved KV or TSL index address */
uint32_t addr; /**< blob data saved address */
size_t len; /**< blob data saved length */
} saved;
};
typedef struct fdb_blob *fdb_blob_t;
#ifdef __cplusplus
}
#endif
#endif /* _FDB_DEF_H_ */

318
lib/flashdb/fdb_file.c Normal file
View File

@ -0,0 +1,318 @@
/*
* Copyright (c) 2020, Armink, <armink.ztl@gmail.com>
* Copyright (c) 2020, enkiller, <462747508@qq.com>
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <stdio.h>
#include <string.h>
#include <flashdb.h>
#include <fdb_low_lvl.h>
#define FDB_LOG_TAG "[file]"
#ifdef FDB_USING_FILE_MODE
#define DB_PATH_MAX 256
static void get_db_file_path(fdb_db_t db, uint32_t addr, char *path, size_t size)
{
#define DB_NAME_MAX 8
/* from db_name.fdb.0 to db_name.fdb.n */
char file_name[DB_NAME_MAX + 4 + 10];
uint32_t sec_addr = FDB_ALIGN_DOWN(addr, db->sec_size);
int index = sec_addr / db->sec_size;
snprintf(file_name, sizeof(file_name), "%.*s.fdb.%d", DB_NAME_MAX, db->name, index);
if (strlen(db->storage.dir) + 1 + strlen(file_name) >= size) {
/* path is too long */
FDB_INFO("Error: db (%s) file path (%s) is too log.\n", file_name, db->storage.dir);
FDB_ASSERT(0)
}
snprintf(path, size, "%s/%s", db->storage.dir, file_name);
}
#if defined(FDB_USING_FILE_POSIX_MODE)
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#if !defined(_MSC_VER)
#include <unistd.h>
#endif
static int get_file_from_cache(fdb_db_t db, uint32_t sec_addr)
{
for (int i = 0; i < FDB_FILE_CACHE_TABLE_SIZE; i++) {
if (db->cur_file_sec[i] == sec_addr)
return db->cur_file[i];
}
return -1;
}
static void update_file_cache(fdb_db_t db, uint32_t sec_addr, int fd)
{
int free_index = FDB_FILE_CACHE_TABLE_SIZE;
for (int i = 0; i < FDB_FILE_CACHE_TABLE_SIZE; i++) {
if (db->cur_file_sec[i] == sec_addr) {
db->cur_file[i] = fd;
return;
} else if (db->cur_file[i] == -1) {
free_index = i;
}
}
if (fd > 0) {
if (free_index < FDB_FILE_CACHE_TABLE_SIZE) {
db->cur_file[free_index] = fd;
db->cur_file_sec[free_index] = sec_addr;
} else {
/* cache is full, move to end */
for (int i = FDB_FILE_CACHE_TABLE_SIZE - 1; i > 0; i--) {
close(db->cur_file[i]);
memcpy(&db->cur_file[i], &db->cur_file[i - 1], sizeof(db->cur_file[0]));
memcpy(&db->cur_file_sec[i], &db->cur_file_sec[i - 1], sizeof(db->cur_file_sec[0]));
}
/* add to head */
db->cur_file[0] = fd;
db->cur_file_sec[0] = sec_addr;
}
}
}
static int open_db_file(fdb_db_t db, uint32_t addr, bool clean)
{
uint32_t sec_addr = FDB_ALIGN_DOWN(addr, db->sec_size);
int fd = get_file_from_cache(db, sec_addr);
char path[DB_PATH_MAX];
if (fd <= 0 || clean) {
get_db_file_path(db, addr, path, DB_PATH_MAX);
if (fd > 0) {
close(fd);
fd = -1;
update_file_cache(db, sec_addr, fd);
}
if (clean) {
/* clean the old file */
int clean_fd = open(path, O_RDWR | O_CREAT | O_TRUNC, 0777);
if (clean_fd <= 0) {
FDB_INFO("Error: open (%s) file failed.\n", path);
}
else {
close(clean_fd);
clean_fd = -1;
}
}
if (get_file_from_cache(db, sec_addr) < 0) {
/* open the database file */
fd = open(path, O_RDWR, 0777);
update_file_cache(db, sec_addr, fd);
}
db->cur_sec = sec_addr;
}
return fd;
}
fdb_err_t _fdb_file_read(fdb_db_t db, uint32_t addr, void *buf, size_t size)
{
fdb_err_t result = FDB_NO_ERR;
int fd = open_db_file(db, addr, false);
if (fd > 0) {
/* get the offset address is relative to the start of the current file */
addr = addr % db->sec_size;
if ((lseek(fd, addr, SEEK_SET) != (int32_t)addr) || (read(fd, buf, size) != (ssize_t)size))
result = FDB_READ_ERR;
} else {
result = FDB_READ_ERR;
}
return result;
}
fdb_err_t _fdb_file_write(fdb_db_t db, uint32_t addr, const void *buf, size_t size, bool sync)
{
fdb_err_t result = FDB_NO_ERR;
int fd = open_db_file(db, addr, false);
if (fd > 0) {
/* get the offset address is relative to the start of the current file */
addr = addr % db->sec_size;
if ((lseek(fd, addr, SEEK_SET) != (int32_t)addr) || (write(fd, buf, size) != (ssize_t)size))
result = FDB_WRITE_ERR;
if(sync) {
fsync(fd);
}
} else {
result = FDB_WRITE_ERR;
}
return result;
}
fdb_err_t _fdb_file_erase(fdb_db_t db, uint32_t addr, size_t size)
{
fdb_err_t result = FDB_NO_ERR;
int fd = open_db_file(db, addr, true);
if (fd > 0) {
#define BUF_SIZE 32
uint8_t buf[BUF_SIZE];
size_t i;
lseek(fd, 0, SEEK_SET);
for (i = 0; i * BUF_SIZE < size; i++)
{
memset(buf, 0xFF, BUF_SIZE);
write(fd, buf, BUF_SIZE);
}
memset(buf, 0xFF, BUF_SIZE);
write(fd, buf, size - i * BUF_SIZE);
fsync(fd);
} else {
result = FDB_ERASE_ERR;
}
return result;
}
#elif defined(FDB_USING_FILE_LIBC_MODE)
static FILE *get_file_from_cache(fdb_db_t db, uint32_t sec_addr)
{
for (int i = 0; i < FDB_FILE_CACHE_TABLE_SIZE; i++) {
if (db->cur_file_sec[i] == sec_addr)
return db->cur_file[i];
}
return NULL;
}
static void update_file_cache(fdb_db_t db, uint32_t sec_addr, FILE *fd)
{
int free_index = FDB_FILE_CACHE_TABLE_SIZE;
for (int i = 0; i < FDB_FILE_CACHE_TABLE_SIZE; i++) {
if (db->cur_file_sec[i] == sec_addr) {
db->cur_file[i] = fd;
return;
}
else if (db->cur_file[i] == 0) {
free_index = i;
}
}
if (fd) {
if (free_index < FDB_FILE_CACHE_TABLE_SIZE) {
db->cur_file[free_index] = fd;
db->cur_file_sec[free_index] = sec_addr;
}
else {
/* cache is full, move to end */
for (int i = FDB_FILE_CACHE_TABLE_SIZE - 1; i > 0; i--) {
fclose(db->cur_file[i]);
memcpy(&db->cur_file[i], &db->cur_file[i - 1], sizeof(db->cur_file[0]));
memcpy(&db->cur_file_sec[i], &db->cur_file_sec[i - 1], sizeof(db->cur_file_sec[0]));
}
/* add to head */
db->cur_file[0] = fd;
db->cur_file_sec[0] = sec_addr;
}
}
}
static FILE *open_db_file(fdb_db_t db, uint32_t addr, bool clean)
{
uint32_t sec_addr = FDB_ALIGN_DOWN(addr, db->sec_size);
FILE *fd = get_file_from_cache(db, sec_addr);
char path[DB_PATH_MAX];
if (fd == NULL || clean) {
get_db_file_path(db, addr, path, DB_PATH_MAX);
if (fd) {
fclose(fd);
fd = NULL;
update_file_cache(db, sec_addr, fd);
}
if (clean) {
/* clean the old file */
FILE *clean_fd = fopen(path, "wb+");
if (clean_fd == NULL) {
FDB_INFO("Error: open (%s) file failed.\n", path);
} else {
fclose(clean_fd);
clean_fd = NULL;
}
}
if (get_file_from_cache(db, sec_addr) == NULL) {
/* open the database file */
fd = fopen(path, "rb+");
update_file_cache(db, sec_addr, fd);
}
db->cur_sec = sec_addr;
}
return fd;
}
fdb_err_t _fdb_file_read(fdb_db_t db, uint32_t addr, void *buf, size_t size)
{
fdb_err_t result = FDB_NO_ERR;
FILE *fp = open_db_file(db, addr, false);
if (fp) {
addr = addr % db->sec_size;
if ((fseek(fp, addr, SEEK_SET) != 0) || (fread(buf, size, 1, fp) != size))
result = FDB_READ_ERR;
} else {
result = FDB_READ_ERR;
}
return result;
}
fdb_err_t _fdb_file_write(fdb_db_t db, uint32_t addr, const void *buf, size_t size, bool sync)
{
fdb_err_t result = FDB_NO_ERR;
FILE *fp = open_db_file(db, addr, false);
if (fp) {
addr = addr % db->sec_size;
if ((fseek(fp, addr, SEEK_SET) != 0) || (fwrite(buf, size, 1, fp) != size))
result = FDB_READ_ERR;
if(sync) {
fflush(fp);
}
} else {
result = FDB_READ_ERR;
}
return result;
}
fdb_err_t _fdb_file_erase(fdb_db_t db, uint32_t addr, size_t size)
{
fdb_err_t result = FDB_NO_ERR;
FILE *fp = open_db_file(db, addr, true);
if (fp != NULL) {
#define BUF_SIZE 32
uint8_t buf[BUF_SIZE];
size_t i;
fseek(fp, 0, SEEK_SET);
for (i = 0; i * BUF_SIZE < size; i++)
{
memset(buf, 0xFF, BUF_SIZE);
fwrite(buf, BUF_SIZE, 1, fp);
}
memset(buf, 0xFF, BUF_SIZE);
fwrite(buf, size - i * BUF_SIZE, 1, fp);
fflush(fp);
} else {
result = FDB_ERASE_ERR;
}
return result;
}
#endif /* defined(FDB_USING_FILE_LIBC_MODE) */
#endif /* FDB_USING_FILE_MODE */

1967
lib/flashdb/fdb_kvdb.c Normal file

File diff suppressed because it is too large Load Diff

69
lib/flashdb/fdb_low_lvl.h Normal file
View File

@ -0,0 +1,69 @@
/*
* Copyright (c) 2020, Armink, <armink.ztl@gmail.com>
*
* SPDX-License-Identifier: Apache-2.0
*/
/**
* @file
* @brief low level API and definition
*/
#ifndef _FDB_LOW_LVL_H_
#define _FDB_LOW_LVL_H_
#include <fdb_cfg.h>
#include <fdb_def.h>
#if (FDB_WRITE_GRAN == 1)
#define FDB_STATUS_TABLE_SIZE(status_number) ((status_number * FDB_WRITE_GRAN + 7)/8)
#else
#define FDB_STATUS_TABLE_SIZE(status_number) (((status_number - 1) * FDB_WRITE_GRAN + 7)/8)
#endif
/* the data is erased */
#define FDB_BYTE_ERASED 0xFF
/* the data is written */
#define FDB_BYTE_WRITTEN 0x00
/* Return the most contiguous size aligned at specified width. RT_ALIGN(13, 4)
* would return 16.
*/
#define FDB_ALIGN(size, align) (((size) + (align) - 1) - (((size) + (align) -1) % (align)))
/* align by write granularity */
#define FDB_WG_ALIGN(size) (FDB_ALIGN(size, ((FDB_WRITE_GRAN + 7)/8)))
/**
* Return the down number of aligned at specified width. RT_ALIGN_DOWN(13, 4)
* would return 12.
*/
#define FDB_ALIGN_DOWN(size, align) (((size) / (align)) * (align))
/* align down by write granularity */
#define FDB_WG_ALIGN_DOWN(size) (FDB_ALIGN_DOWN(size, (FDB_WRITE_GRAN + 7)/8))
#define FDB_STORE_STATUS_TABLE_SIZE FDB_STATUS_TABLE_SIZE(FDB_SECTOR_STORE_STATUS_NUM)
#define FDB_DIRTY_STATUS_TABLE_SIZE FDB_STATUS_TABLE_SIZE(FDB_SECTOR_DIRTY_STATUS_NUM)
/* the data is unused */
#if (FDB_BYTE_ERASED == 0xFF)
#define FDB_DATA_UNUSED 0xFFFFFFFF
#else
#define FDB_DATA_UNUSED 0x00000000
#endif
/* invalid address */
#define FDB_FAILED_ADDR 0xFFFFFFFF
size_t _fdb_set_status(uint8_t status_table[], size_t status_num, size_t status_index);
size_t _fdb_get_status(uint8_t status_table[], size_t status_num);
uint32_t _fdb_continue_ff_addr(fdb_db_t db, uint32_t start, uint32_t end);
fdb_err_t _fdb_init_ex(fdb_db_t db, const char *name, const char *part_name, fdb_db_type type, void *user_data);
void _fdb_init_finish(fdb_db_t db, fdb_err_t result);
void _fdb_deinit(fdb_db_t db);
const char *_fdb_db_path(fdb_db_t db);
fdb_err_t _fdb_write_status(fdb_db_t db, uint32_t addr, uint8_t status_table[], size_t status_num, size_t status_index, bool sync);
size_t _fdb_read_status(fdb_db_t db, uint32_t addr, uint8_t status_table[], size_t total_num);
fdb_err_t _fdb_flash_read(fdb_db_t db, uint32_t addr, void *buf, size_t size);
fdb_err_t _fdb_flash_erase(fdb_db_t db, uint32_t addr, size_t size);
fdb_err_t _fdb_flash_write(fdb_db_t db, uint32_t addr, const void *buf, size_t size, bool sync);
#endif /* _FDB_LOW_LVL_H_ */

1024
lib/flashdb/fdb_tsdb.c Normal file

File diff suppressed because it is too large Load Diff

320
lib/flashdb/fdb_utils.c Normal file
View File

@ -0,0 +1,320 @@
/*
* Copyright (c) 2020, Armink, <armink.ztl@gmail.com>
*
* SPDX-License-Identifier: Apache-2.0
*/
/**
* @file
* @brief utils
*
* Some utils for this library.
*/
#include <stdio.h>
#include <string.h>
#include <flashdb.h>
#include <fdb_low_lvl.h>
#define FDB_LOG_TAG "[utils]"
static const uint32_t crc32_table[] =
{
0x00000000, 0x77073096, 0xee0e612c, 0x990951ba, 0x076dc419, 0x706af48f,
0xe963a535, 0x9e6495a3, 0x0edb8832, 0x79dcb8a4, 0xe0d5e91e, 0x97d2d988,
0x09b64c2b, 0x7eb17cbd, 0xe7b82d07, 0x90bf1d91, 0x1db71064, 0x6ab020f2,
0xf3b97148, 0x84be41de, 0x1adad47d, 0x6ddde4eb, 0xf4d4b551, 0x83d385c7,
0x136c9856, 0x646ba8c0, 0xfd62f97a, 0x8a65c9ec, 0x14015c4f, 0x63066cd9,
0xfa0f3d63, 0x8d080df5, 0x3b6e20c8, 0x4c69105e, 0xd56041e4, 0xa2677172,
0x3c03e4d1, 0x4b04d447, 0xd20d85fd, 0xa50ab56b, 0x35b5a8fa, 0x42b2986c,
0xdbbbc9d6, 0xacbcf940, 0x32d86ce3, 0x45df5c75, 0xdcd60dcf, 0xabd13d59,
0x26d930ac, 0x51de003a, 0xc8d75180, 0xbfd06116, 0x21b4f4b5, 0x56b3c423,
0xcfba9599, 0xb8bda50f, 0x2802b89e, 0x5f058808, 0xc60cd9b2, 0xb10be924,
0x2f6f7c87, 0x58684c11, 0xc1611dab, 0xb6662d3d, 0x76dc4190, 0x01db7106,
0x98d220bc, 0xefd5102a, 0x71b18589, 0x06b6b51f, 0x9fbfe4a5, 0xe8b8d433,
0x7807c9a2, 0x0f00f934, 0x9609a88e, 0xe10e9818, 0x7f6a0dbb, 0x086d3d2d,
0x91646c97, 0xe6635c01, 0x6b6b51f4, 0x1c6c6162, 0x856530d8, 0xf262004e,
0x6c0695ed, 0x1b01a57b, 0x8208f4c1, 0xf50fc457, 0x65b0d9c6, 0x12b7e950,
0x8bbeb8ea, 0xfcb9887c, 0x62dd1ddf, 0x15da2d49, 0x8cd37cf3, 0xfbd44c65,
0x4db26158, 0x3ab551ce, 0xa3bc0074, 0xd4bb30e2, 0x4adfa541, 0x3dd895d7,
0xa4d1c46d, 0xd3d6f4fb, 0x4369e96a, 0x346ed9fc, 0xad678846, 0xda60b8d0,
0x44042d73, 0x33031de5, 0xaa0a4c5f, 0xdd0d7cc9, 0x5005713c, 0x270241aa,
0xbe0b1010, 0xc90c2086, 0x5768b525, 0x206f85b3, 0xb966d409, 0xce61e49f,
0x5edef90e, 0x29d9c998, 0xb0d09822, 0xc7d7a8b4, 0x59b33d17, 0x2eb40d81,
0xb7bd5c3b, 0xc0ba6cad, 0xedb88320, 0x9abfb3b6, 0x03b6e20c, 0x74b1d29a,
0xead54739, 0x9dd277af, 0x04db2615, 0x73dc1683, 0xe3630b12, 0x94643b84,
0x0d6d6a3e, 0x7a6a5aa8, 0xe40ecf0b, 0x9309ff9d, 0x0a00ae27, 0x7d079eb1,
0xf00f9344, 0x8708a3d2, 0x1e01f268, 0x6906c2fe, 0xf762575d, 0x806567cb,
0x196c3671, 0x6e6b06e7, 0xfed41b76, 0x89d32be0, 0x10da7a5a, 0x67dd4acc,
0xf9b9df6f, 0x8ebeeff9, 0x17b7be43, 0x60b08ed5, 0xd6d6a3e8, 0xa1d1937e,
0x38d8c2c4, 0x4fdff252, 0xd1bb67f1, 0xa6bc5767, 0x3fb506dd, 0x48b2364b,
0xd80d2bda, 0xaf0a1b4c, 0x36034af6, 0x41047a60, 0xdf60efc3, 0xa867df55,
0x316e8eef, 0x4669be79, 0xcb61b38c, 0xbc66831a, 0x256fd2a0, 0x5268e236,
0xcc0c7795, 0xbb0b4703, 0x220216b9, 0x5505262f, 0xc5ba3bbe, 0xb2bd0b28,
0x2bb45a92, 0x5cb36a04, 0xc2d7ffa7, 0xb5d0cf31, 0x2cd99e8b, 0x5bdeae1d,
0x9b64c2b0, 0xec63f226, 0x756aa39c, 0x026d930a, 0x9c0906a9, 0xeb0e363f,
0x72076785, 0x05005713, 0x95bf4a82, 0xe2b87a14, 0x7bb12bae, 0x0cb61b38,
0x92d28e9b, 0xe5d5be0d, 0x7cdcefb7, 0x0bdbdf21, 0x86d3d2d4, 0xf1d4e242,
0x68ddb3f8, 0x1fda836e, 0x81be16cd, 0xf6b9265b, 0x6fb077e1, 0x18b74777,
0x88085ae6, 0xff0f6a70, 0x66063bca, 0x11010b5c, 0x8f659eff, 0xf862ae69,
0x616bffd3, 0x166ccf45, 0xa00ae278, 0xd70dd2ee, 0x4e048354, 0x3903b3c2,
0xa7672661, 0xd06016f7, 0x4969474d, 0x3e6e77db, 0xaed16a4a, 0xd9d65adc,
0x40df0b66, 0x37d83bf0, 0xa9bcae53, 0xdebb9ec5, 0x47b2cf7f, 0x30b5ffe9,
0xbdbdf21c, 0xcabac28a, 0x53b39330, 0x24b4a3a6, 0xbad03605, 0xcdd70693,
0x54de5729, 0x23d967bf, 0xb3667a2e, 0xc4614ab8, 0x5d681b02, 0x2a6f2b94,
0xb40bbe37, 0xc30c8ea1, 0x5a05df1b, 0x2d02ef8d
};
/**
* Calculate the CRC32 value of a memory buffer.
*
* @param crc accumulated CRC32 value, must be 0 on first call
* @param buf buffer to calculate CRC32 value for
* @param size bytes in buffer
*
* @return calculated CRC32 value
*/
uint32_t fdb_calc_crc32(uint32_t crc, const void *buf, size_t size)
{
const uint8_t *p;
p = (const uint8_t *)buf;
crc = crc ^ ~0U;
while (size--) {
crc = crc32_table[(crc ^ *p++) & 0xFF] ^ (crc >> 8);
}
return crc ^ ~0U;
}
size_t _fdb_set_status(uint8_t status_table[], size_t status_num, size_t status_index)
{
size_t byte_index = SIZE_MAX;
/*
* | write garn | status0 | status1 | status2 | status3 |
* ------------------------------------------------------------------------------------------------------
* | 1bit | 0xFF | 0x7F | 0x3F | 0x1F
* ------------------------------------------------------------------------------------------------------
* | 8bit | 0xFF FF FF | 0x00 FF FF | 0x00 00 FF | 0x00 00 00
* ------------------------------------------------------------------------------------------------------
* | 32bit | 0xFFFFFFFF FFFFFFFF | 0x00FFFFFF FFFFFFFF | 0x00FFFFFF 00FFFFFF | 0x00FFFFFF 00FFFFFF
* | | 0xFFFFFFFF | 0xFFFFFFFF | 0xFFFFFFFF | 0x00FFFFFF
* ------------------------------------------------------------------------------------------------------
* | | 0xFFFFFFFF FFFFFFFF | 0x00FFFFFF FFFFFFFF | 0x00FFFFFF FFFFFFFF | 0x00FFFFFF FFFFFFFF
* | 64bit | 0xFFFFFFFF FFFFFFFF | 0xFFFFFFFF FFFFFFFF | 0x00FFFFFF FFFFFFFF | 0x00FFFFFF FFFFFFFF
* | | 0xFFFFFFFF FFFFFFFF | 0xFFFFFFFF FFFFFFFF | 0xFFFFFFFF FFFFFFFF | 0x00FFFFFF FFFFFFFF
*/
memset(status_table, FDB_BYTE_ERASED, FDB_STATUS_TABLE_SIZE(status_num));
if (status_index > 0) {
#if (FDB_WRITE_GRAN == 1)
byte_index = (status_index - 1) / 8;
#if (FDB_BYTE_ERASED == 0xFF)
status_table[byte_index] &= (0x00ff >> (status_index % 8));
#else
status_table[byte_index] |= (0x00ff >> (status_index % 8));
#endif
#else
byte_index = (status_index - 1) * (FDB_WRITE_GRAN / 8);
status_table[byte_index] = FDB_BYTE_WRITTEN;
#endif /* FDB_WRITE_GRAN == 1 */
}
return byte_index;
}
size_t _fdb_get_status(uint8_t status_table[], size_t status_num)
{
size_t i = 0, status_num_bak = --status_num;
while (status_num --) {
/* get the first 0 position from end address to start address */
#if (FDB_WRITE_GRAN == 1)
if ((status_table[status_num / 8] & (0x80 >> (status_num % 8))) == 0x00) {
break;
}
#else /* (FDB_WRITE_GRAN == 8) || (FDB_WRITE_GRAN == 32) || (FDB_WRITE_GRAN == 64) */
if (status_table[status_num * FDB_WRITE_GRAN / 8] == FDB_BYTE_WRITTEN) {
break;
}
#endif /* FDB_WRITE_GRAN == 1 */
i++;
}
return status_num_bak - i;
}
fdb_err_t _fdb_write_status(fdb_db_t db, uint32_t addr, uint8_t status_table[], size_t status_num, size_t status_index, bool sync)
{
fdb_err_t result = FDB_NO_ERR;
size_t byte_index;
FDB_ASSERT(status_index < status_num);
FDB_ASSERT(status_table);
/* set the status first */
byte_index = _fdb_set_status(status_table, status_num, status_index);
/* the first status table value is all 1, so no need to write flash */
if (byte_index == SIZE_MAX) {
return FDB_NO_ERR;
}
#if (FDB_WRITE_GRAN == 1)
result = _fdb_flash_write(db, addr + byte_index, (uint32_t *)&status_table[byte_index], 1, sync);
#else /* (FDB_WRITE_GRAN == 8) || (FDB_WRITE_GRAN == 32) || (FDB_WRITE_GRAN == 64) */
/* write the status by write granularity
* some flash (like stm32 onchip) NOT supported repeated write before erase */
result = _fdb_flash_write(db, addr + byte_index, (uint32_t *) &status_table[byte_index], FDB_WRITE_GRAN / 8, sync);
#endif /* FDB_WRITE_GRAN == 1 */
return result;
}
size_t _fdb_read_status(fdb_db_t db, uint32_t addr, uint8_t status_table[], size_t total_num)
{
FDB_ASSERT(status_table);
_fdb_flash_read(db, addr, (uint32_t *) status_table, FDB_STATUS_TABLE_SIZE(total_num));
return _fdb_get_status(status_table, total_num);
}
/*
* find the continue 0xFF flash address to end address
*/
uint32_t _fdb_continue_ff_addr(fdb_db_t db, uint32_t start, uint32_t end)
{
uint8_t buf[32], last_data = FDB_BYTE_WRITTEN;
size_t i, addr = start, read_size;
for (; start < end; start += sizeof(buf)) {
if (start + sizeof(buf) < end) {
read_size = sizeof(buf);
} else {
read_size = end - start;
}
_fdb_flash_read(db, start, (uint32_t *) buf, read_size);
for (i = 0; i < read_size; i++) {
if (last_data != FDB_BYTE_ERASED && buf[i] == FDB_BYTE_ERASED) {
addr = start + i;
}
last_data = buf[i];
}
}
if (last_data == FDB_BYTE_ERASED) {
return FDB_WG_ALIGN(addr);
} else {
return end;
}
}
/**
* Make a blob object.
*
* @param blob blob object
* @param value_buf value buffer
* @param buf_len buffer length
*
* @return new blob object
*/
fdb_blob_t fdb_blob_make(fdb_blob_t blob, const void *value_buf, size_t buf_len)
{
blob->buf = (void *)value_buf;
blob->size = buf_len;
return blob;
}
/**
* Read the blob object in database.
*
* @param db database object
* @param blob blob object
*
* @return read length
*/
size_t fdb_blob_read(fdb_db_t db, fdb_blob_t blob)
{
size_t read_len = blob->size;
if (read_len > blob->saved.len) {
read_len = blob->saved.len;
}
if (_fdb_flash_read(db, blob->saved.addr, blob->buf, read_len) != FDB_NO_ERR) {
read_len = 0;
}
return read_len;
}
#ifdef FDB_USING_FILE_MODE
extern fdb_err_t _fdb_file_read(fdb_db_t db, uint32_t addr, void *buf, size_t size);
extern fdb_err_t _fdb_file_write(fdb_db_t db, uint32_t addr, const void *buf, size_t size, bool sync);
extern fdb_err_t _fdb_file_erase(fdb_db_t db, uint32_t addr, size_t size);
#endif /* FDB_USING_FILE_LIBC */
fdb_err_t _fdb_flash_read(fdb_db_t db, uint32_t addr, void *buf, size_t size)
{
fdb_err_t result = FDB_NO_ERR;
if (db->file_mode) {
#ifdef FDB_USING_FILE_MODE
return _fdb_file_read(db, addr, buf, size);
#else
return FDB_READ_ERR;
#endif
} else {
#ifdef FDB_USING_FAL_MODE
if (fal_partition_read(db->storage.part, addr, (uint8_t *) buf, size) < 0) {
result = FDB_READ_ERR;
}
#endif
}
return result;
}
fdb_err_t _fdb_flash_erase(fdb_db_t db, uint32_t addr, size_t size)
{
fdb_err_t result = FDB_NO_ERR;
if (db->file_mode) {
#ifdef FDB_USING_FILE_MODE
return _fdb_file_erase(db, addr, size);
#else
return FDB_ERASE_ERR;
#endif /* FDB_USING_FILE_MODE */
} else {
#ifdef FDB_USING_FAL_MODE
if (fal_partition_erase(db->storage.part, addr, size) < 0) {
result = FDB_ERASE_ERR;
}
#endif
}
return result;
}
fdb_err_t _fdb_flash_write(fdb_db_t db, uint32_t addr, const void *buf, size_t size, bool sync)
{
fdb_err_t result = FDB_NO_ERR;
if (db->file_mode) {
#ifdef FDB_USING_FILE_MODE
return _fdb_file_write(db, addr, buf, size, sync);
#else
return FDB_WRITE_ERR;
#endif /* FDB_USING_FILE_MODE */
} else {
#ifdef FDB_USING_FAL_MODE
if (fal_partition_write(db->storage.part, addr, (uint8_t *)buf, size) < 0)
{
result = FDB_WRITE_ERR;
}
#endif
}
return result;
}

79
lib/flashdb/flashdb.h Normal file
View File

@ -0,0 +1,79 @@
/*
* Copyright (c) 2020, Armink, <armink.ztl@gmail.com>
*
* SPDX-License-Identifier: Apache-2.0
*/
/**
* @file
* @brief Public APIs.
*/
#ifndef _FLASHDB_H_
#define _FLASHDB_H_
#include <stdint.h>
#include <stddef.h>
#include <stdbool.h>
#include <stdio.h>
#include <time.h>
#include <fdb_cfg.h>
#ifdef FDB_USING_FAL_MODE
#include <fal.h>
#endif
#include <fdb_def.h>
#ifdef __cplusplus
extern "C" {
#endif
/* FlashDB database API */
fdb_err_t fdb_kvdb_init (fdb_kvdb_t db, const char *name, const char *path, struct fdb_default_kv *default_kv,
void *user_data);
void fdb_kvdb_control(fdb_kvdb_t db, int cmd, void *arg);
fdb_err_t fdb_kvdb_check(fdb_kvdb_t db);
fdb_err_t fdb_kvdb_deinit(fdb_kvdb_t db);
fdb_err_t fdb_tsdb_init (fdb_tsdb_t db, const char *name, const char *path, fdb_get_time get_time, size_t max_len,
void *user_data);
void fdb_tsdb_control(fdb_tsdb_t db, int cmd, void *arg);
fdb_err_t fdb_tsdb_deinit(fdb_tsdb_t db);
/* blob API */
fdb_blob_t fdb_blob_make (fdb_blob_t blob, const void *value_buf, size_t buf_len);
size_t fdb_blob_read (fdb_db_t db, fdb_blob_t blob);
/* Key-Value API like a KV DB */
fdb_err_t fdb_kv_set (fdb_kvdb_t db, const char *key, const char *value);
char *fdb_kv_get (fdb_kvdb_t db, const char *key);
fdb_err_t fdb_kv_set_blob (fdb_kvdb_t db, const char *key, fdb_blob_t blob);
size_t fdb_kv_get_blob (fdb_kvdb_t db, const char *key, fdb_blob_t blob);
fdb_err_t fdb_kv_del (fdb_kvdb_t db, const char *key);
fdb_kv_t fdb_kv_get_obj (fdb_kvdb_t db, const char *key, fdb_kv_t kv);
fdb_blob_t fdb_kv_to_blob (fdb_kv_t kv, fdb_blob_t blob);
fdb_err_t fdb_kv_set_default (fdb_kvdb_t db);
void fdb_kv_print (fdb_kvdb_t db);
fdb_kv_iterator_t fdb_kv_iterator_init(fdb_kvdb_t db, fdb_kv_iterator_t itr);
bool fdb_kv_iterate (fdb_kvdb_t db, fdb_kv_iterator_t itr);
/* Time series log API like a TSDB */
fdb_err_t fdb_tsl_append (fdb_tsdb_t db, fdb_blob_t blob);
fdb_err_t fdb_tsl_append_with_ts(fdb_tsdb_t db, fdb_blob_t blob, fdb_time_t timestamp);
void fdb_tsl_iter (fdb_tsdb_t db, fdb_tsl_cb cb, void *cb_arg);
void fdb_tsl_iter_reverse(fdb_tsdb_t db, fdb_tsl_cb cb, void *cb_arg);
void fdb_tsl_iter_by_time(fdb_tsdb_t db, fdb_time_t from, fdb_time_t to, fdb_tsl_cb cb, void *cb_arg);
size_t fdb_tsl_query_count (fdb_tsdb_t db, fdb_time_t from, fdb_time_t to, fdb_tsl_status_t status);
fdb_err_t fdb_tsl_set_status (fdb_tsdb_t db, fdb_tsl_t tsl, fdb_tsl_status_t status);
void fdb_tsl_clean (fdb_tsdb_t db);
fdb_blob_t fdb_tsl_to_blob (fdb_tsl_t tsl, fdb_blob_t blob);
/* fdb_utils.c */
uint32_t fdb_calc_crc32(uint32_t crc, const void *buf, size_t size);
#ifdef __cplusplus
}
#endif
#endif /* _FLASHDB_H_ */

38
lib/flashdb/readme.md Normal file
View File

@ -0,0 +1,38 @@
# 移植说明
## 简介
[FlashDB](http://armink.gitee.io/flashdb/#/zh-cn/) 是一款超轻量级的嵌入式数据库专注于提供嵌入式产品的数据存储方案。FlashDB 不仅支持传统的基于文件系统的数据库模式,而且结合了 Flash 的特性,具有较强的性能及可靠性。并在保证极低的资源占用前提下,尽可能延长 Flash 使用寿命。
## 使用场景
如今物联网产品种类越来越多运行时产生的数据种类及总量及也在不断变大。FlashDB 提供了多样化的数据存储方案,不仅资源占用小,并且存储容量大,非常适合用于物联网产品。下面是主要应用场景:
* **键值数据库**
* 产品参数存储
* 用户配置信息存储
* 小文件管理
* **时序数据库**
* 存储动态产生的结构化数据:如 温湿度传感器采集的环境监测信息,智能手环实时记录的人体健康信息等
* 记录运行日志:存储产品历史的运行日志,异常告警的记录等
本项目使用3块EPPROM
## 文件移植
项目地址 https://github.com/armink/FlashDB
引入目录中的文件
.\FlashDB\src
.\FlashDB\inc
.\FlashDB\port\fal\src
.\FlashDB\port\fal\inc
> fal_cfg.h 这个文件为用户自定义升级的时候不要覆盖

View File

@ -1,18 +0,0 @@
{
"configurations": [
{
"name": "windows-gcc-x64",
"includePath": [
"${workspaceFolder}/**"
],
"compilerPath": "C:/TDM-GCC-64/bin/gcc.exe",
"cStandard": "${default}",
"cppStandard": "${default}",
"intelliSenseMode": "windows-gcc-x64",
"compilerArgs": [
""
]
}
],
"version": 4
}

View File

@ -1,24 +0,0 @@
{
"version": "0.2.0",
"configurations": [
{
"name": "C/C++ Runner: Debug Session",
"type": "cppdbg",
"request": "launch",
"args": [],
"stopAtEntry": false,
"externalConsole": true,
"cwd": "e:/work/stm32/epm/User/lib/flow",
"program": "e:/work/stm32/epm/User/lib/flow/build/Debug/outDebug",
"MIMode": "gdb",
"miDebuggerPath": "gdb",
"setupCommands": [
{
"description": "Enable pretty-printing for gdb",
"text": "-enable-pretty-printing",
"ignoreFailures": true
}
]
}
]
}

View File

@ -1,58 +0,0 @@
{
"C_Cpp_Runner.cCompilerPath": "gcc",
"C_Cpp_Runner.cppCompilerPath": "g++",
"C_Cpp_Runner.debuggerPath": "gdb",
"C_Cpp_Runner.cStandard": "",
"C_Cpp_Runner.cppStandard": "",
"C_Cpp_Runner.msvcBatchPath": "C:/Program Files/Microsoft Visual Studio/2022/Community/VC/Auxiliary/Build/vcvarsall.bat",
"C_Cpp_Runner.useMsvc": false,
"C_Cpp_Runner.warnings": [
"-Wall",
"-Wextra",
"-Wpedantic",
"-Wshadow",
"-Wformat=2",
"-Wcast-align",
"-Wconversion",
"-Wsign-conversion",
"-Wnull-dereference"
],
"C_Cpp_Runner.msvcWarnings": [
"/W4",
"/permissive-",
"/w14242",
"/w14287",
"/w14296",
"/w14311",
"/w14826",
"/w44062",
"/w44242",
"/w14905",
"/w14906",
"/w14263",
"/w44265",
"/w14928"
],
"C_Cpp_Runner.enableWarnings": true,
"C_Cpp_Runner.warningsAsError": false,
"C_Cpp_Runner.compilerArgs": [],
"C_Cpp_Runner.linkerArgs": [],
"C_Cpp_Runner.includePaths": [],
"C_Cpp_Runner.includeSearch": [
"*",
"**/*"
],
"C_Cpp_Runner.excludeSearch": [
"**/build",
"**/build/**",
"**/.*",
"**/.*/**",
"**/.vscode",
"**/.vscode/**"
],
"C_Cpp_Runner.useAddressSanitizer": false,
"C_Cpp_Runner.useUndefinedSanitizer": false,
"C_Cpp_Runner.useLeakSanitizer": false,
"C_Cpp_Runner.showCompilationTime": false,
"C_Cpp_Runner.useLinkTimeOptimization": false
}

View File

@ -88,6 +88,16 @@ typedef struct
float32 b;
} linear_func_param_t;
#define S_CURVE_POINTS 70
typedef struct
{
float32 start;
float32 end;
float32 current;
float32 t[S_CURVE_POINTS];
uint16_t index;
} s_curve_generator_t;
extern void assic_to_str(uint8_t *assic, uint8_t len, uint8_t *str); // ASCII码转字符串
extern void get_cpu_id(uint32_t *id); // 获取CPU ID
extern uint32_t cpu_encrypt(void); // CPU加密
@ -124,4 +134,7 @@ extern void add_commas(uint32_t num, char *result);
extern linear_func_param_t calculate_linear_regression(const point_t *points, int32_t count); // 计算线性回归
extern float32 get_linearity_value(const point_t *points, int32_t count, linear_func_param_t param); // 获取线性度
#endif //__LIB_H
void s_curve_generator_init(s_curve_generator_t *gen, float32 start);
float32 s_curve_generate_point(s_curve_generator_t *gen, float32 target);
#endif //__LIB_H

View File

@ -15,12 +15,12 @@
// mem1内存参数设定.mem1完全处于内部SRAM里面.(设置内部SARM的内存池和内存表的参数)
#define MEM1_BLOCK_SIZE 8 // 一个内存块大小为32字节
#define MEM1_MAX_SIZE 8 * 1024 // 最大管理内存 1K (我们这个内存管理系统的内部SRAM可控制的内存大小)
#define MEM1_MAX_SIZE 25 * 1024 // 最大管理内存 1K (我们这个内存管理系统的内部SRAM可控制的内存大小)
#define MEM1_ALLOC_TABLE_SIZE MEM1_MAX_SIZE / MEM1_BLOCK_SIZE // 内存表大小(有多少块内存块)
// mem2内存参数设定.mem2的内存池处于外部SRAM里面
#define MEM2_BLOCK_SIZE 8 // 一个内存块大小为32字节
#define MEM2_MAX_SIZE 0 * 1024 // 因为精英版没有外扩内存,故这里设置一个最小值
#define MEM2_MAX_SIZE 20 * 1024 // 因为精英版没有外扩内存,故这里设置一个最小值
#define MEM2_ALLOC_TABLE_SIZE MEM2_MAX_SIZE / MEM2_BLOCK_SIZE // 内存表大小
// 内存管理控制器结构体

View File

@ -14,7 +14,7 @@
#include "lib.h"
#define hal_int_state_t char
#ifdef STM32
#include "main.h"
#include "stm32l4xx.h"
#define HAL_ENTER_CRITICAL(__HANDLE__) \
do \
{ \

9511
lib/lcd/font/HZ16x16.c Normal file

File diff suppressed because it is too large Load Diff

374
lib/lcd/font/HZ18x18.c Normal file
View File

@ -0,0 +1,374 @@
/*
**********************************************************************
* UcGUI Font
* Chinese GB2312 library
* (c) Copyright 19xx-20xx, company name
*
*
* ucGUI字体生成器v9.0 :(qq:602426967)
*
**********************************************************************
*/
#include "GUI.H"
/* char: code:0x0031 */
static GUI_CONST_STORAGE unsigned char ac0031[54] = {
_____XX_,_____X__,________,
_____XX_,___XXXXX,________,
_XXX_XX_,__XX___X,X_______,
__XX____,_XX_____,X_______,
___X____,XX______,XX______,
XXX_____,X_______,X_______,
XXX_____,_______X,X_______,
________,______XX,________,
____XX__,_____XX_,________,
___XX___,____XX__,________,
__XX____,________,________,
_XX_____,_______X,XX______,
XX______,_X_____X,XX______,
XX______,XX____X_,________,
XX_____X,X_____XX,________,
_XX___XX,___XX_XX,X_______,
__XXXXX_,___XX___,________,
___XXX__,___XX___,________
};
/* char: code:0x0032 */
static GUI_CONST_STORAGE unsigned char ac0032[54] = {
________,____XXX_,________,
________,___XXXXX,________,
________,__XX___X,X_______,
________,_XX_____,XX______,
_______X,XX______,XX______,
_______X,X_______,XX______,
______XX,______XX,X_______,
______XX,_XX__XXX,________,
____X_XX,_XXXXXX_,________,
___XXXXX,X_XX_X__,________,
__XXX__X,X_XX____,________,
_XXX____,__XX____,________,
XX______,_XX_____,________,
XX______,XXX_____,________,
XX_____X,X_______,________,
_XX___XX,________,________,
__XXXXX_,________,________,
___XXX__,________,________
};
/* char: code:0x0033 */
static GUI_CONST_STORAGE unsigned char ac0033[54] = {
________,___XXXX_,________,
________,__XXXXXX,X_______,
________,_XXX__XX,XX______,
________,_XXX____,XX______,
________,_XX_____,XX______,
________,_XX_____,XX______,
________,_XX_____,XX______,
________,________,________,
XXXXXXXX,XXXXX___,________,
XXXXXXXX,XXXXX___,________,
XXXXXXXX,XXXXX___,________,
XXXXXXXX,XXXXX___,________,
XXXXXXXX,XXXXX___,________,
XXXXXXXX,XXXXX___,________,
XXXXXXXX,XXXXX___,________,
XXXXXXXX,XXXXX___,________,
_XXXXXXX,XXXX____,________,
________,________,________
};
/* char: code:0x0034 */
static GUI_CONST_STORAGE unsigned char ac0034[54] = {
_______X,XXX_____,________,
______XX,XXXX____,________,
_____XXX,__XXX___,________,
_____XX_,___XX___,________,
____XXX_,___XX___,________,
____XXX_,___XX___,________,
____XXX_,___XX___,________,
________,________,________,
__XXXXXX,XXXXXXXX,________,
__XXXXXX,XXXXXXXX,________,
__XXXXXX,XXXXXXXX,________,
__XXXXXX,XXXXXXXX,________,
__XXXXXX,XXXXXXXX,________,
__XXXXXX,XXXXXXXX,________,
__XXXXXX,XXXXXXXX,________,
__XXXXXX,XXXXXXXX,________,
___XXXXX,XXXXXXX_,________,
________,________,________
};
/* char: code:0x0035 */
static GUI_CONST_STORAGE unsigned char ac0035[54] = {
________,________,________,
________,________,________,
_____XXX,XXXXX___,________,
____XX__,____XX__,________,
___XX___,____XXX_,________,
__XX____,___XX_XX,________,
__X_____,__XXX__X,________,
__X_____,_XXX___X,________,
__X_____,XXX____X,________,
__X____X,XX_____X,________,
__X___XX,X______X,________,
__X__XXX,_______X,________,
___XXXX_,______XX,________,
___XX___,_____XX_,________,
____XX__,____XX__,________,
______XX,XXXXX___,________,
________,________,________,
________,________,________
};
/* char: code:0x0036 */
static GUI_CONST_STORAGE unsigned char ac0036[54] = {
________,XX______,________,
________,XXX_____,________,
________,XXXX____,________,
________,XXXXX___,________,
____XX__,XX_XXX__,________,
_____XX_,XX_XXX__,________,
_____XXX,XXXXX___,________,
______XX,XXXX____,________,
________,XXX_____,________,
________,XXX_____,________,
_______X,XXXX____,________,
_____XXX,XX_XX___,________,
_____XX_,XX__XX__,________,
____XX__,XX_XXX__,________,
________,XXXXX___,________,
________,XXXX____,________,
________,XXX_____,________,
________,XX______,________
};
/* char: code:0x0037 */
static GUI_CONST_STORAGE unsigned char ac0037[54] = {
________,_______X,________,
________,______XX,________,
________,____XXXX,________,
________,__XXXXXX,________,
________,_XXXXXXX,________,
_______X,XXXXXXXX,________,
______XX,XXXXXXXX,________,
____XXXX,XXXXXXXX,________,
___XXXXX,XXXXXXXX,________,
___XXXXX,XXXXXXXX,________,
_____XXX,XXXXXXXX,________,
______XX,XXXXXXXX,________,
_______X,XXXXXXXX,________,
________,_XXXXXXX,________,
________,___XXXXX,________,
________,____XXXX,________,
________,______XX,________,
________,_______X,________
};
/* char: code:0x0061 */
static GUI_CONST_STORAGE unsigned char ac0061[54] = {
________,________,________,
_______X,XXX_____,________,
______XX,XXX_____,________,
______XX,XXXX____,________,
______XX,_XXX____,________,
_____XXX,__XX____,________,
_____XXX,__XXX___,________,
____XXX_,__XXX___,________,
____XXX_,___XXX__,________,
____XX__,___XXX__,________,
___XXX__,____XX__,________,
___XXXXX,XXXXXXX_,________,
__XXXXXX,XXXXXXX_,________,
__XXX___,_____XX_,________,
__XXX___,_____XXX,________,
_XXX____,_____XXX,________,
_XXX____,______XX,X_______,
________,________,________
};
/* char: code:0x0066 */
static GUI_CONST_STORAGE unsigned char ac0066[54] = {
________,________,________,
__XXXXXX,XXXXXXXX,X_______,
__XXXXXX,XXXXXXXX,X_______,
__XXXX__,________,________,
__XXXX__,________,________,
__XXXX__,________,________,
__XXXX__,________,________,
__XXXX__,________,________,
__XXXXXX,XXXXXXXX,________,
__XXXXXX,XXXXXXXX,________,
__XXXX__,________,________,
__XXXX__,________,________,
__XXXX__,________,________,
__XXXX__,________,________,
__XXXX__,________,________,
__XXXX__,________,________,
__XXXX__,________,________,
________,________,________
};
/* char: code:0x006D */
static GUI_CONST_STORAGE unsigned char ac006D[54] = {
________,________,________,
_XXXX___,______XX,X_______,
_XXXX___,_____XXX,X_______,
_XXXXX__,_____XXX,X_______,
_XX_XX__,____XXXX,X_______,
_XXXXX__,____XX_X,X_______,
_XXXXXX_,____XX_X,X_______,
_XXX_XX_,___XX__X,X_______,
_XXX_XX_,___XX__X,X_______,
_XXX__XX,___XX__X,X_______,
_XXX__XX,__XX___X,X_______,
_XXX__XX,__XX___X,X_______,
_XXX___X,X_XX___X,X_______,
_XXX___X,XXX____X,X_______,
_XXX___X,XXX____X,X_______,
_XXX____,XXX____X,X_______,
_XXX____,XX_____X,X_______,
________,________,________
};
/* char: code:0x0073 */
static GUI_CONST_STORAGE unsigned char ac0073[54] = {
________,________,________,
_____XXX,XXXXX___,________,
___XXXXX,XXXXXXX_,________,
__XXXX__,___XXXXX,________,
__XXXX__,____XXXX,________,
__XXXX__,________,________,
__XXXX__,________,________,
___XXXXX,X_______,________,
____XXXX,XXXXX___,________,
_______X,XXXXXXX_,________,
________,___XXXXX,________,
________,_____XXX,X_______,
____X___,_____XXX,X_______,
_XXXX___,_____XXX,X_______,
__XXXX__,____XXXX,________,
___XXXXX,XXXXXXX_,________,
_____XXX,XXXXX___,________,
________,________,________
};
/* char: code:0x0074 */
static GUI_CONST_STORAGE unsigned char ac0074[54] = {
________,________,________,
_XXXXXXX,XXXXXXXX,X_______,
_XXXXXXX,XXXXXXXX,X_______,
_______X,XXX_____,________,
_______X,XXX_____,________,
_______X,XXX_____,________,
_______X,XXX_____,________,
_______X,XXX_____,________,
_______X,XXX_____,________,
_______X,XXX_____,________,
_______X,XXX_____,________,
_______X,XXX_____,________,
_______X,XXX_____,________,
_______X,XXX_____,________,
_______X,XXX_____,________,
_______X,XXX_____,________,
_______X,XXX_____,________,
________,________,________
};
/* char: code:0x0077 */
static GUI_CONST_STORAGE unsigned char ac0077[54] = {
________,________,________,
_XX_____,XX_____X,X_______,
_XX_____,XX_____X,X_______,
_XX____X,XX_____X,X_______,
_XX____X,XXX___XX,X_______,
_XX____X,XXX___XX,________,
__XX___X,_XX___XX,________,
__XX__XX,__X___XX,________,
__XX__XX,__X___XX,________,
__XX__XX,__XX__XX,________,
__XX__XX,__XX_XX_,________,
___XX_X_,__XX_XX_,________,
___XXXX_,___X_XX_,________,
___XXXX_,___X_XX_,________,
___XXXX_,___XXX__,________,
___XXX__,___XXX__,________,
____XX__,___XXX__,________,
________,________,________
};
static GUI_CONST_STORAGE GUI_CHARINFO Cinfo[13] = {
{ 18, 18, 3, (unsigned char *)&ac0031 }, /*0: */
{ 18, 18, 3, (unsigned char *)&ac0032 }, /*1: */
{ 18, 18, 3, (unsigned char *)&ac0033 }, /*2: */
{ 16, 16, 3, (unsigned char *)&ac0034 }, /*3: */
{ 16, 16, 3, (unsigned char *)&ac0035 }, /*4: */
{ 14, 14, 3, (unsigned char *)&ac0036 }, /*5: */
{ 16, 16, 3, (unsigned char *)&ac0037 }, /*6: */
{ 17, 17, 3, (unsigned char *)&ac0061 }, /*7: */
{ 17, 17, 3, (unsigned char *)&ac0066 }, /*8: */
{ 17, 17, 3, (unsigned char *)&ac006D }, /*9: */
{ 17, 17, 3, (unsigned char *)&ac0073 }, /*10: */
{ 17, 17, 3, (unsigned char *)&ac0074 }, /*11: */
{ 17, 17, 3, (unsigned char *)&ac0077 }, /*12: */
};
static GUI_CONST_STORAGE GUI_FONT_PROP Prop6 = {
0x0077, /*start :*/
0x0077, /*end :, len=1*/
&Cinfo[ 12 ],
(void*)0
};
static GUI_CONST_STORAGE GUI_FONT_PROP Prop5 = {
0x0073, /*start :*/
0x0074, /*end :, len=2*/
&Cinfo[ 10 ],
&Prop6
};
static GUI_CONST_STORAGE GUI_FONT_PROP Prop4 = {
0x006D, /*start :*/
0x006D, /*end :, len=1*/
&Cinfo[ 9 ],
&Prop5
};
static GUI_CONST_STORAGE GUI_FONT_PROP Prop3 = {
0x0066, /*start :*/
0x0066, /*end :, len=1*/
&Cinfo[ 8 ],
&Prop4
};
static GUI_CONST_STORAGE GUI_FONT_PROP Prop2 = {
0x0061, /*start :*/
0x0061, /*end :, len=1*/
&Cinfo[ 7 ],
&Prop3
};
static GUI_CONST_STORAGE GUI_FONT_PROP Prop1 = {
0x0031, /*start :*/
0x0037, /*end :, len=7*/
&Cinfo[ 0 ],
&Prop2
};
GUI_CONST_STORAGE GUI_FONT GUI_FontHZ18x18 = {
GUI_FONTTYPE_PROP_SJIS,
18, /* height of font */
18, /* space of font y */
1,
1,
&Prop1
};

198
lib/lcd/font/HZ20x20.c Normal file
View File

@ -0,0 +1,198 @@
/*
**********************************************************************
* UcGUI Font
* Chinese GB2312 library
* (c) Copyright 19xx-20xx, company name
*
*
* ucGUI字体生成器v9.0 :(qq:602426967)
*
**********************************************************************
*/
#include "GUI.H"
/* char: code:0x0030 */
static GUI_CONST_STORAGE unsigned char ac0030[60] = {
________, ________, ________,
_______X, XXXXX___, ________,
_____XXX, ____XXX_, ________,
____XX__, ______XX, ________,
___XX___, _______X, X_______,
__XX__X_, _____X__, XX______,
__X__XXX, ____XXX_, _X______,
_XX___XX, X__XXX__, _XX_____,
_X_____X, XXXXX___, _XX_____,
_X______, XXXX____, __X_____,
_X______, XXXX____, __X_____,
_X_____X, XXXXX___, _XX_____,
_XX___XX, X__XXX__, _XX_____,
__X__XXX, ____XXX_, _X______,
__XX__X_, _____X__, XX______,
___XX___, _______X, X_______,
____XX__, ______XX, ________,
_____XXX, X__XXXX_, ________,
_______X, XXXXX___, ________,
________, ________, ________};
/* char: code:0x0031 */
static GUI_CONST_STORAGE unsigned char ac0031[60] = {
_______X, XXXXX___, ________,
_____XXX, XXXXXXX_, ________,
___XXX__, ______XX, X_______,
__XXX___, _______X, XX______,
__XX____, ________, XX______,
_XX____X, XXXXX___, _XX_____,
_X_____X, X__XX___, __X_____,
XX____XX, ____XX__, __XX____,
XX______, ____XX__, __XX____,
XX______, ___XX___, __XX____,
XX______, __XX____, __XX____,
XX______, _XX_____, __XX____,
XX______, _XX_____, __XX____,
_X______, ________, _XX_____,
_XX_____, _XX_____, _XX_____,
__XX____, _XX_____, XX______,
__XXX___, _X_____X, X_______,
___XXX__, ______XX, ________,
_____XXX, XXXXXXX_, ________,
_______X, XXXXX___, ________};
/* char: code:0x0032 */
static GUI_CONST_STORAGE unsigned char ac0032[60] = {
_____XXX, XX______, ________,
____XXXX, XXX_____, ________,
_____XX_, __XX____, ________,
______XX, ___XX___, ________,
_X_____X, ____XX__, ________,
XXX____X, X___XX__, ________,
XXXX___X, X____X__, ________,
XX_XXXXX, _____X__, ________,
XX___X__, ____XX__, ________,
XX______, ____XX__, ________,
_XX_____, _____XX_, ________,
__XX____, ______XX, ________,
___XXX__, XX_____X, X_______,
____XXXX, XXX_____, XX______,
________, __XX____, _XX_____,
________, ___XX___, __XX____,
________, ____XX__, __XX____,
________, _____XX_, __XX____,
________, ______XX, XXX_____,
________, _______X, XX______};
/* char: code:0x0033 */
static GUI_CONST_STORAGE unsigned char ac0033[60] = {
________, ________, ________,
________, ________, ________,
________, ________, ________,
________, ________, ________,
________, ________, XX______,
________, _______X, XXX_____,
________, ______XX, XX______,
________, _____XXX, X_______,
__XX____, ____XXXX, ________,
__XXX___, ___XXXX_, ________,
___XXX__, __XXXX__, ________,
____XXX_, _XXXX___, ________,
_____XXX, XXXX____, ________,
______XX, XXX_____, ________,
_______X, XX______, ________,
________, X_______, ________,
________, ________, ________,
________, ________, ________,
________, ________, ________,
________, ________, ________};
/* char: code:0x0034 */
static GUI_CONST_STORAGE unsigned char ac0034[60] = {
________, ________, ________,
________, ________, ________,
________, ________, ________,
________, ________, ________,
________, ________, ________,
________, ________, ________,
________, ________, ________,
________, _______X, ________,
___X____, _X____X_, X_______,
__X_X___, X_X__X__, ________,
___X____, _X____X_, X_______,
________, _______X, ________,
________, ________, ________,
________, ________, ________,
________, ________, ________,
________, ________, ________,
________, ________, ________,
________, ________, ________,
________, ________, ________,
________, ________, ________};
/* char: code:0x0035 */
static GUI_CONST_STORAGE unsigned char ac0035[60] = {
________, ________, ________,
________, ________, ________,
________, ________, ________,
________, ________, ________,
________, ________, ________,
________, ________, ________,
________, ________, ________,
___X____, ________, ________,
__X_XX__, _X_____X, ________,
_____X__, X_X___X_, X_______,
__X_XX__, _X_____X, ________,
___X____, ________, ________,
________, ________, ________,
________, ________, ________,
________, ________, ________,
________, ________, ________,
________, ________, ________,
________, ________, ________,
________, ________, ________,
________, ________, ________};
/* char: code:0x0036 */
static GUI_CONST_STORAGE unsigned char ac0036[60] = {
________, ________, ________,
________, ________, ________,
________, ________, ________,
________, ________, ________,
________, ________, ________,
________, ________, ________,
________, ________, ________,
________, _X______, ________,
___X____, X_X____X, ________,
__X_X__X, ___X__X_, X_______,
___X____, X_X____X, ________,
________, _X______, ________,
________, ________, ________,
________, ________, ________,
________, ________, ________,
________, ________, ________,
________, ________, ________,
________, ________, ________,
________, ________, ________,
________, ________, ________};
static GUI_CONST_STORAGE GUI_CHARINFO Cinfo[7] = {
{19, 19, 3, (unsigned char *)&ac0030}, /*0: */
{20, 20, 3, (unsigned char *)&ac0031}, /*1: */
{20, 20, 3, (unsigned char *)&ac0032}, /*2: */
{19, 19, 3, (unsigned char *)&ac0033}, /*3: */
{17, 17, 3, (unsigned char *)&ac0034}, /*4: */
{17, 17, 3, (unsigned char *)&ac0035}, /*5: */
{17, 17, 3, (unsigned char *)&ac0036}, /*6: */
};
static GUI_CONST_STORAGE GUI_FONT_PROP Prop1 = {
0x0030, /*start :*/
0x0036, /*end :, len=7*/
&Cinfo[0],
(void *)0};
GUI_CONST_STORAGE GUI_FONT GUI_FontHZ20x20 = {
GUI_FONTTYPE_PROP_SJIS,
20, /* height of font */
20, /* space of font y */
1,
1,
&Prop1};

8317
lib/lcd/font/HZ24x24.c Normal file

File diff suppressed because it is too large Load Diff

3765
lib/lcd/font/HZ32x32.c Normal file

File diff suppressed because it is too large Load Diff

10040
lib/lcd/font/LOGO.c Normal file

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,13 @@
@ECHO OFF
ECHO CCGUIAntiAlias.BAT: Compiling GUI\AntiAlias
CALL CC GUIAAArc
CALL CC GUIAAChar
CALL CC GUIAAChar2
CALL CC GUIAAChar4
CALL CC GUIAACircle
CALL CC GUIAALib
CALL CC GUIAALine
CALL CC GUIAAPoly
CALL CC GUIAAPolyOut

View File

@ -0,0 +1,87 @@
/*
*********************************************************************************************************
* uC/GUI
* Universal graphic software for embedded applications
*
* (c) Copyright 2002, Micrium Inc., Weston, FL
* (c) Copyright 2002, SEGGER Microcontroller Systeme GmbH
*
* µC/GUI is protected by international copyright laws. Knowledge of the
* source code may not be used to write a similar product. This file may
* only be used in accordance with a license and should not be redistributed
* in any way. We appreciate your understanding and fairness.
*
----------------------------------------------------------------------
File : GUIArcAA.C
Purpose : Draw Arc routines with Antialiasing
---------------------------END-OF-HEADER------------------------------
*/
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <math.h>
#include "GUI_Protected.h"
#if GUI_SUPPORT_AA
/*********************************************************************
*
* Static code
*
**********************************************************************
*/
/*********************************************************************
*
* _DrawArcAA
*/
static void _DrawArcAA(int x0, int y0, int rx, int ry, int a0, int a1) {
int PenSizePrev = GUI_GetPenSize();
int PenSize_AA;
int Factor;
Factor = GUI_Context.AA_HiResEnable ? 1 : GUI_Context.AA_Factor;
/* Convert into Hires coordinates (if not already done) */
x0 *= Factor;
y0 *= Factor;
rx *= Factor;
ry *= Factor;
PenSize_AA = PenSizePrev * GUI_Context.AA_Factor;
GUI_AA_Init_HiRes(x0 - rx - PenSize_AA, x0 + rx + PenSize_AA);
GUI_SetPenSize(PenSize_AA);
GL_DrawArc(x0, y0, rx, ry,a0,a1);
GUI_SetPenSize(PenSizePrev); /* restore former pen size */
/* Cleanup */
GUI_AA_Exit();
}
/*********************************************************************
*
* Public code
*
**********************************************************************
*/
/*********************************************************************
*
* GUI_AA_DrawArc
*/
void GUI_AA_DrawArc(int x0, int y0, int rx, int ry, int a0, int a1) {
GUI_LOCK();
#if (GUI_WINSUPPORT)
WM_ADDORG_AA(x0,y0);
WM_ITERATE_START(NULL) {
#endif
_DrawArcAA( x0, y0, rx, ry, a0, a1);
#if (GUI_WINSUPPORT)
} WM_ITERATE_END();
#endif
GUI_UNLOCK();
}
#else /* Avoid problems with empty object modules */
void GUIAAArc_C(void);
void GUIAAArc_C(void) {}
#endif /* GUI_SUPPORT_AA */
/*************************** End of file ****************************/

View File

@ -0,0 +1,167 @@
/*
*********************************************************************************************************
* uC/GUI
* Universal graphic software for embedded applications
*
* (c) Copyright 2002, Micrium Inc., Weston, FL
* (c) Copyright 2002, SEGGER Microcontroller Systeme GmbH
*
* µC/GUI is protected by international copyright laws. Knowledge of the
* source code may not be used to write a similar product. This file may
* only be used in accordance with a license and should not be redistributed
* in any way. We appreciate your understanding and fairness.
*
----------------------------------------------------------------------
File : GUICharAA.C
Purpose : Display antialiased
---------------------------END-OF-HEADER------------------------------
*/
#include "GUI_Private.h"
#if GUI_SUPPORT_AA
#include <stdio.h>
#include <string.h>
/*********************************************************************
*
* Types
*
**********************************************************************
*/
typedef void tSetPixelAA(int x, int y, U8 Intens);
/*********************************************************************
*
* Static data
*
**********************************************************************
*/
static const U8 Bit2Mask0[] = {1<<7, 1<<5, 1<<3, 1<<1};
static const U8 Bit2Mask1[] = {1<<6, 1<<4, 1<<2, 1<<0};
/*********************************************************************
*
* Static code
*
**********************************************************************
*/
/*********************************************************************
*
* Draw
*/
static void Draw(int x0, int y0, int XSize, int YSize, int BytesPerLine, const U8*pData) {
int x, y;
tSetPixelAA* pfSetPixelAA;
pfSetPixelAA = (GUI_Context.TextMode & GUI_TM_TRANS)
? LCD_SetPixelAA : LCD_SetPixelAA_NoTrans;
for (y=0; y<YSize; y++) {
const U8* pData0 = pData;
const U8* pData1 = pData+BytesPerLine;
for (x=0; x<XSize; x++) {
int PixelCnt=0;
int Mask0 = Bit2Mask0[x&3];
int Mask1 = Bit2Mask1[x&3];
if ((*pData0) & Mask0)
PixelCnt++;
if ((*pData0) & Mask1)
PixelCnt++;
if ((*pData1) & Mask0)
PixelCnt++;
if ((*pData1) & Mask1)
PixelCnt++;
if ((x&3) ==3) {
pData0++;
pData1++;
}
switch (PixelCnt) {
case 4: LCD_HL_DrawPixel(x0+x,y0+y); break;
case 3: (*pfSetPixelAA) (x0+x,y0+y, 12); break;
case 2: (*pfSetPixelAA) (x0+x,y0+y, 8); break;
case 1: (*pfSetPixelAA) (x0+x,y0+y, 4); break;
}
}
pData+=2*BytesPerLine;
}
}
/*********************************************************************
*
* GUIPROP_FindChar
*/
static const GUI_FONT_PROP* GUIPROP_FindChar(const GUI_FONT_PROP* pProp, U16P c) {
for (pProp = GUI_Context.pAFont->p.pProp; pProp; pProp=(const GUI_FONT_PROP*) pProp->pNext) {
if ((c>=pProp->First) && (c<=pProp->Last))
break;
}
return pProp;
}
/*********************************************************************
*
* Public code
*
**********************************************************************
*/
/*********************************************************************
*
* GUIPROPAA_DispChar
*/
void GUIPROPAA_DispChar(U16P c) {
int BytesPerLine;
GUI_DRAWMODE DrawMode = GUI_Context.TextMode;
const GUI_FONT_PROP* pProp = GUIPROP_FindChar(GUI_Context.pAFont->p.pProp, c);
if (pProp) {
GUI_DRAWMODE OldDrawMode;
const GUI_CHARINFO* pCharInfo = pProp->paCharInfo+(c-pProp->First);
BytesPerLine = pCharInfo->BytesPerLine;
OldDrawMode = LCD_SetDrawMode(DrawMode);
Draw ( GUI_Context.DispPosX, GUI_Context.DispPosY,
(pCharInfo->XSize+1)/2,
GUI_Context.pAFont->YSize,
BytesPerLine,
(U8 const*) pCharInfo->pData
);
LCD_SetDrawMode(OldDrawMode); /* Restore draw mode */
GUI_Context.DispPosX += (pCharInfo->XDist+1)/2;
}
}
/*********************************************************************
*
* GUIPROPAA_GetCharDistX
*/
int GUIPROPAA_GetCharDistX(U16P c) {
int r;
const GUI_FONT_PROP* pProp = GUIPROP_FindChar(GUI_Context.pAFont->p.pProp, c);
r = (pProp) ? (pProp->paCharInfo+(c-pProp->First))->XSize : 0;
return (r+1)/2;
}
/*********************************************************************
*
* GUIPROPAA_GetFontInfo
*/
void GUIPROPAA_GetFontInfo(const GUI_FONT * pFont, GUI_FONTINFO* pfi) {
GUI_USE_PARA(pFont);
pfi->Flags = GUI_FONTINFO_FLAG_PROP | GUI_FONTINFO_FLAG_AA;
}
/*********************************************************************
*
* GUIPROPAA_IsInFont
*/
char GUIPROPAA_IsInFont(const GUI_FONT * pFont, U16 c) {
const GUI_FONT_PROP* pProp = GUIPROP_FindChar(pFont->p.pProp, c);
return (pProp==NULL) ? 0 : 1;
}
#else /* Avoid problems with empty object modules */
void GUIAAChar_C(void);
void GUIAAChar_C(void) {}
#endif /* GUI_SUPPORT_AA */
/*************************** End of file ****************************/

View File

@ -0,0 +1,201 @@
/*
*********************************************************************************************************
* uC/GUI
* Universal graphic software for embedded applications
*
* (c) Copyright 2002, Micrium Inc., Weston, FL
* (c) Copyright 2002, SEGGER Microcontroller Systeme GmbH
*
* µC/GUI is protected by international copyright laws. Knowledge of the
* source code may not be used to write a similar product. This file may
* only be used in accordance with a license and should not be redistributed
* in any way. We appreciate your understanding and fairness.
*
----------------------------------------------------------------------
File : GUICharAA2.C
Purpose : Display antialiased 2bpp
---------------------------END-OF-HEADER------------------------------
*/
#include "GUI_Private.h"
#if GUI_SUPPORT_AA
#include <stdio.h>
#include <string.h>
/*********************************************************************
*
* Defines
*
**********************************************************************
*/
#define MAX_CHAR_SIZE 100
/*********************************************************************
*
* Static data
*
**********************************************************************
*/
/* used by transparent characters */
static const int aConvTable[4] = {0, 5, 10, 15};
/* used by non transparent characters */
static LCD_COLOR aColor[4];
static LCD_PIXELINDEX OldColorIndex, OldBkColorIndex;
static GUI_LOGPALETTE Palette = {4, 0, &aColor[0]};
static GUI_BITMAP Bitmap = {0, 0, 0, 2, 0, &Palette, 0};
/*********************************************************************
*
* Static code
*
**********************************************************************
*/
/*********************************************************************
*
* DrawNoTrans
*/
static void DrawNoTrans(int x0, int y0, int XSize, int YSize, int BytesPerLine, const U8*pData) {
if ((OldColorIndex != LCD_COLORINDEX) ||
(OldBkColorIndex != LCD_BKCOLORINDEX)) {
int i;
LCD_PIXELINDEX BkColorIndex = LCD_BKCOLORINDEX;
LCD_PIXELINDEX ColorIndex = LCD_COLORINDEX;
LCD_COLOR BkColor = LCD_Index2Color(BkColorIndex);
LCD_COLOR Color = LCD_Index2Color(ColorIndex);
aColor[0] = BkColor;
for (i = 1; i < 3; i++) {
U8 Intens;
Intens = 5 * i;
aColor[i] = LCD_AA_MixColors(Color, BkColor, Intens);
}
aColor[3] = Color;
LCD_GetpPalConvTableUncached(&Palette);
OldColorIndex = ColorIndex;
OldBkColorIndex = BkColorIndex;
}
Bitmap.XSize = XSize;
Bitmap.YSize = YSize;
Bitmap.BytesPerLine = BytesPerLine;
Bitmap.pData = pData;
GL_DrawBitmap(&Bitmap, x0, y0);
}
/*********************************************************************
*
* DrawTrans
*/
static void DrawTrans(int x0, int y0, int XSize, int YSize, int BytesPerLine, const U8*pData) {
int x, y;
for (y = 0; y < YSize; y++) {
const U8 *pData0 = pData;
U8 Rem = XSize & 3;
for (x = 0; x < XSize - 1; x += 4) {
LCD_SetPixelAA(x + x0 , y0 + y, aConvTable[((*pData0 ) >> 6) ]);
LCD_SetPixelAA(x + x0 + 1, y0 + y, aConvTable[((*pData0 ) >> 4) & 0x03]);
LCD_SetPixelAA(x + x0 + 2, y0 + y, aConvTable[((*pData0 ) >> 2) & 0x03]);
LCD_SetPixelAA(x + x0 + 3, y0 + y, aConvTable[((*pData0++) ) & 0x03]);
}
if (Rem) {
LCD_SetPixelAA(x + x0 , y0 + y, aConvTable[((*pData0 ) >> 6) ]);
if (Rem > 1) {
LCD_SetPixelAA(x + x0 + 1, y0 + y, aConvTable[((*pData0 ) >> 4) & 0x03]);
if (Rem > 2) {
LCD_SetPixelAA(x + x0 + 2, y0 + y, aConvTable[((*pData0 ) >> 2) & 0x03]);
}
}
}
pData += BytesPerLine;
}
}
/*********************************************************************
*
* GUIPROP_FindChar
*/
static const GUI_FONT_PROP* GUIPROP_FindChar(const GUI_FONT_PROP* pProp, U16P c) {
for (pProp = GUI_Context.pAFont->p.pProp; pProp; pProp=(const GUI_FONT_PROP*) pProp->pNext) {
if ((c>=pProp->First) && (c<=pProp->Last))
break;
}
return pProp;
}
/*********************************************************************
*
* Public code
*
**********************************************************************
*/
/*********************************************************************
*
* GUIPROP_AA2_DispChar
*/
void GUIPROP_AA2_DispChar(U16P c) {
int BytesPerLine;
GUI_DRAWMODE DrawMode = GUI_Context.TextMode;
const GUI_FONT_PROP* pProp = GUIPROP_FindChar(GUI_Context.pAFont->p.pProp, c);
if (pProp) {
GUI_DRAWMODE OldDrawMode;
const GUI_CHARINFO* pCharInfo = pProp->paCharInfo+(c-pProp->First);
BytesPerLine = pCharInfo->BytesPerLine;
OldDrawMode = LCD_SetDrawMode(DrawMode);
if (DrawMode & GUI_TM_TRANS) {
DrawTrans(GUI_Context.DispPosX,
GUI_Context.DispPosY,
pCharInfo->XSize,
GUI_Context.pAFont->YSize,
BytesPerLine,
(U8 const*)pCharInfo->pData
);
} else {
DrawNoTrans(GUI_Context.DispPosX,
GUI_Context.DispPosY,
pCharInfo->XSize,
GUI_Context.pAFont->YSize,
BytesPerLine,
(U8 const*)pCharInfo->pData
);
}
LCD_SetDrawMode(OldDrawMode); /* Restore draw mode */
GUI_Context.DispPosX += pCharInfo->XDist;
}
}
/*********************************************************************
*
* GUIPROP_AA2_GetCharDistX
*/
int GUIPROP_AA2_GetCharDistX(U16P c) {
const GUI_FONT_PROP* pProp = GUIPROP_FindChar(GUI_Context.pAFont->p.pProp, c);
return (pProp) ? (pProp->paCharInfo+(c-pProp->First))->XSize : 0;
}
/*********************************************************************
*
* GUIPROP_AA2_GetFontInfo
*/
void GUIPROP_AA2_GetFontInfo(const GUI_FONT * pFont, GUI_FONTINFO* pfi) {
GUI_USE_PARA(pFont);
pfi->Flags = GUI_FONTINFO_FLAG_PROP | GUI_FONTINFO_FLAG_AA2;
}
/*********************************************************************
*
* GUIPROP_AA2_IsInFont
*/
char GUIPROP_AA2_IsInFont(const GUI_FONT * pFont, U16 c) {
const GUI_FONT_PROP* pProp = GUIPROP_FindChar(pFont->p.pProp, c);
return (pProp==NULL) ? 0 : 1;
}
#else /* Avoid problems with empty object modules */
void GUIAAChar2_C(void);
void GUIAAChar2_C(void) {}
#endif /* GUI_SUPPORT_AA */
/*************************** End of file ****************************/

View File

@ -0,0 +1,129 @@
/*
*********************************************************************************************************
* uC/GUI
* Universal graphic software for embedded applications
*
* (c) Copyright 2002, Micrium Inc., Weston, FL
* (c) Copyright 2002, SEGGER Microcontroller Systeme GmbH
*
* µC/GUI is protected by international copyright laws. Knowledge of the
* source code may not be used to write a similar product. This file may
* only be used in accordance with a license and should not be redistributed
* in any way. We appreciate your understanding and fairness.
*
----------------------------------------------------------------------
File : GUICharAA.C
Purpose : Display antialiased
---------------------------END-OF-HEADER------------------------------
*/
#include "GUI_Private.h"
#if GUI_SUPPORT_AA
#include <stdio.h>
#include <string.h>
/*********************************************************************
*
* Static code
*
**********************************************************************
*/
/*********************************************************************
*
* Draw
*/
static void Draw(int x0, int y0, int XSize, int YSize, int BytesPerLine, const U8*pData) {
int x, y;
tLCD_SetPixelAA* pfSetPixelAA;
pfSetPixelAA = (GUI_Context.TextMode && GUI_TM_TRANS) ?
LCD_SetPixelAA : LCD_SetPixelAA_NoTrans;
for (y=0; y<YSize; y++) {
const U8*pData0 = pData;
for (x=0; x<XSize-1; x+=2) {
(*pfSetPixelAA)(x+x0,y0+y, (*pData0)>>4); /* x0+x changed -> x+x0 to avoid problems with IAR's ICCMC80 */
(*pfSetPixelAA)(x0+x+1,y0+y, (*pData0++)&15);
}
if (XSize&1) {
(*pfSetPixelAA)(x0+x,y0+y, (*pData0)&15);
}
pData+=BytesPerLine;
}
}
/*********************************************************************
*
* GUIPROP_FindChar
*/
static const GUI_FONT_PROP* GUIPROP_FindChar(const GUI_FONT_PROP* pProp, U16P c) {
for (pProp = GUI_Context.pAFont->p.pProp; pProp; pProp=(const GUI_FONT_PROP*) pProp->pNext) {
if ((c>=pProp->First) && (c<=pProp->Last))
break;
}
return pProp;
}
/*********************************************************************
*
* Public code
*
**********************************************************************
*/
/*********************************************************************
*
* GUIPROP_AA4_DispChar
*/
void GUIPROP_AA4_DispChar(U16P c) {
int BytesPerLine;
GUI_DRAWMODE DrawMode = GUI_Context.TextMode;
const GUI_FONT_PROP* pProp = GUIPROP_FindChar(GUI_Context.pAFont->p.pProp, c);
if (pProp) {
GUI_DRAWMODE OldDrawMode;
const GUI_CHARINFO* pCharInfo = pProp->paCharInfo+(c-pProp->First);
BytesPerLine = pCharInfo->BytesPerLine;
OldDrawMode = LCD_SetDrawMode(DrawMode);
Draw ( GUI_Context.DispPosX, GUI_Context.DispPosY,
pCharInfo->XSize,
GUI_Context.pAFont->YSize,
BytesPerLine,
(U8 const*)pCharInfo->pData
);
LCD_SetDrawMode(OldDrawMode); /* Restore draw mode */
GUI_Context.DispPosX += pCharInfo->XDist;
}
}
/*********************************************************************
*
* GUIPROP_AA4_GetCharDistX
*/
int GUIPROP_AA4_GetCharDistX(U16P c) {
const GUI_FONT_PROP* pProp = GUIPROP_FindChar(GUI_Context.pAFont->p.pProp, c);
return (pProp) ? (pProp->paCharInfo+(c-pProp->First))->XSize : 0;
}
/*********************************************************************
*
* GUIPROP_AA4_GetFontInfo
*/
void GUIPROP_AA4_GetFontInfo(const GUI_FONT * pFont, GUI_FONTINFO* pfi) {
GUI_USE_PARA(pFont);
pfi->Flags = GUI_FONTINFO_FLAG_PROP | GUI_FONTINFO_FLAG_AA4;
}
/*********************************************************************
*
* GUIPROP_AA4_IsInFont
*/
char GUIPROP_AA4_IsInFont(const GUI_FONT * pFont, U16 c) {
const GUI_FONT_PROP* pProp = GUIPROP_FindChar(pFont->p.pProp, c);
return (pProp==NULL) ? 0 : 1;
}
#else /* Avoid problems with empty object modules */
void GUIAAChar4_C(void);
void GUIAAChar4_C(void) {}
#endif /* GUI_SUPPORT_AA */
/*************************** End of file ****************************/

View File

@ -0,0 +1,133 @@
/*
*********************************************************************************************************
* uC/GUI
* Universal graphic software for embedded applications
*
* (c) Copyright 2002, Micrium Inc., Weston, FL
* (c) Copyright 2002, SEGGER Microcontroller Systeme GmbH
*
* µC/GUI is protected by international copyright laws. Knowledge of the
* source code may not be used to write a similar product. This file may
* only be used in accordance with a license and should not be redistributed
* in any way. We appreciate your understanding and fairness.
*
----------------------------------------------------------------------
File : GUICirleAA.C
Purpose : Draw Circle routines with Antialiasing
TBD: Circle needs to be calculated from top to bottom in order
to avoid AA problems at certain positions.
---------------------------END-OF-HEADER------------------------------
*/
#include "GUI_Protected.h"
#include <stdio.h>
#include <string.h>
#include <math.h>
#if GUI_SUPPORT_AA
/*********************************************************************
*
* Static code
*
**********************************************************************
*/
/*********************************************************************
*
* FillCircle
*/
static void FillCircle(int x0, int y0, int r) {
int i, x;
int sqmax = r*r+r/2;
int yMin, yMax;
/* First step : find uppermost and lowermost coordinates */
yMin = y0 - r;
yMax = y0 + r;
/* Use Clipping rect to reduce calculation (if possible) */
if (GUI_Context.pClipRect_HL) {
if (yMax > GUI_Context.pClipRect_HL->y1)
yMax = GUI_Context.pClipRect_HL->y1;
if (yMin < GUI_Context.pClipRect_HL->y0)
yMin = GUI_Context.pClipRect_HL->y0;
}
/* Draw top half */
for (i=0, x=r; i<r; i++) {
int y = y0-i;
if ((y >= yMin) && (y <= yMax)) {
/* calc proper x-value */
while ((i*i+x*x) >sqmax)
--x;
LCD_HL_DrawHLine (x0-x, y, x0+x);
}
}
/* Draw bottom half */
for (i=0, x=r; i<r; i++) {
int y = y0 + i;
if ((y >= yMin) && (y <= yMax)) {
/* calc proper x-value */
while ((i*i+x*x) >sqmax)
--x;
LCD_HL_DrawHLine (x0-x, y, x0+x);
}
}
}
/*********************************************************************
*
* Public code
*
**********************************************************************
*/
/*********************************************************************
*
* GL_FillCircleAA_HiRes
*/
void GL_FillCircleAA_HiRes(int x0, int y0, int r) {
/* Init AA Subsystem, pass horizontal limits */
GUI_AA_Init_HiRes(x0-r, x0+r);
/* Do the actual drawing */
FillCircle(x0, y0, r);
/* Cleanup */
GUI_AA_Exit();
}
/*********************************************************************
*
* GUI_AA_FillCircle
*/
void GUI_AA_FillCircle(int x0, int y0, int r) {
#if (GUI_WINSUPPORT)
GUI_RECT Rect;
#endif
GUI_LOCK();
#if (GUI_WINSUPPORT)
WM_ADDORG_AA(x0,y0);
#endif
if (!GUI_Context.AA_HiResEnable) {
x0 *= GUI_Context.AA_Factor;
y0 *= GUI_Context.AA_Factor;
r *= GUI_Context.AA_Factor;
}
#if (GUI_WINSUPPORT)
Rect.x0 = GUI_AA_HiRes2Pixel(x0 - r);
Rect.x1 = GUI_AA_HiRes2Pixel(x0 + r);
Rect.y0 = GUI_AA_HiRes2Pixel(y0 - r);
Rect.y1 = GUI_AA_HiRes2Pixel(y0 + r);
WM_ITERATE_START(&Rect); {
#endif
GL_FillCircleAA_HiRes(x0, y0, r);
#if (GUI_WINSUPPORT)
} WM_ITERATE_END();
#endif
GUI_UNLOCK();
}
#else /* Avoid problems with empty object modules */
void GUIAACircle_C(void);
void GUIAACircle_C(void) {}
#endif /* GUI_SUPPORT_AA */
/*************************** End of file ****************************/

View File

@ -0,0 +1,280 @@
/*
*********************************************************************************************************
* uC/GUI
* Universal graphic software for embedded applications
*
* (c) Copyright 2002, Micrium Inc., Weston, FL
* (c) Copyright 2002, SEGGER Microcontroller Systeme GmbH
*
* µC/GUI is protected by international copyright laws. Knowledge of the
* source code may not be used to write a similar product. This file may
* only be used in accordance with a license and should not be redistributed
* in any way. We appreciate your understanding and fairness.
*
----------------------------------------------------------------------
File : GUIAALib.C
Purpose : Antialiasing library
---------------------------END-OF-HEADER------------------------------
*/
#include "GUI_Private.h"
#include "LCD_ConfDefaults.h" /* Required in order to know max. XSize so we do not waste memory */
#if GUI_SUPPORT_AA
#include <stdio.h>
#include <string.h>
/*********************************************************************
*
* Defines, config defaults
*
**********************************************************************
*/
#ifndef GUI_AA_LINEBUFFER_SIZE
#define GUI_AA_LINEBUFFER_SIZE LCD_XSIZE
#endif
/*********************************************************************
*
* Static data
*
**********************************************************************
*/
static U8 abAABuffer[GUI_AA_LINEBUFFER_SIZE]; /* This could be changed to dynamic memory ... */
static U8* pabAABuffer;
static int _x0, _x1, _y, _x0_InUse, _x1_InUse;
static GUI_RECT ClipRect_HL;
static tLCD_HL_APIList DrawAPICopy; /* Copy of device function ptr list */
static const tLCD_HL_APIList* pLCD_HLPrev; /* Copy of device function ptr list */
/*********************************************************************
*
* Static code
*
**********************************************************************
*/
/*********************************************************************
*
* _CleanLine
*/
static void _CleanLine(void) {
GUI_MEMSET(pabAABuffer,0, _x1 - _x0+1);
_y = -16383; /* Invalidate */
_x0_InUse = 16383;
_x1_InUse = -16383;
}
/*********************************************************************
*
* _FlushLine
*/
static void _FlushLine(void) {
int i;
int iEnd = _x1_InUse-_x0;
int IMax = GUI_Context.AA_Factor * GUI_Context.AA_Factor;
for (i =_x0_InUse-_x0; i<=iEnd; i++) {
int Intens = *(pabAABuffer+i);
if (Intens) {
/* Check we can use line draw */
if (Intens == IMax) {
int j;
for (j=i; j<iEnd; ) {
if (*(pabAABuffer+j+1) != IMax) {
break;
}
j++;
}
/* Draw the full pixel(s) */
if (j!=i) {
pLCD_HLPrev->pfDrawHLine(_x0+i, _y, _x0+j);
i = j; /*xxx*/
} else {
LCD_HL_DrawPixel (_x0+i,_y);
}
} else {
LCD_SetPixelAA(_x0+i,_y, (15*Intens+IMax/2)/IMax);
}
}
}
_CleanLine();
}
/*********************************************************************
*
* _DrawHLine
*
* Purpose:
* This is the redirected DrawHLine routine which is called
* instead of the default output routine. Its job is to do
* antialiasing and then perform the drawing operations.
*/
static void _DrawHLine (int x0, int y, int x1) {
int x0Real, x1Real;
/* Make sure there is something to do */
if (x1<x0)
return;
/* Flush line if we are in an other pixel (real) line */
if (y/GUI_Context.AA_Factor != _y) {
_FlushLine();
_y = y/GUI_Context.AA_Factor;
}
x0Real = x0/GUI_Context.AA_Factor;
x1Real = x1/GUI_Context.AA_Factor;
/* Handle used area (speed optimization for drawing) */
if (x0Real < _x0_InUse)
_x0_InUse = x0Real;
if (x1Real > _x1_InUse)
_x1_InUse = x1Real;
/* Clip (should not be necessary ... Just to be on the safe side ! */
if (x0Real < _x0) {
x0 = _x0 * GUI_Context.AA_Factor;
}
if (x1Real > _x1) {
x1 = (_x1+1)*GUI_Context.AA_Factor-1;
}
/* Make sure there is still something to do (after clipping) */
if (x1<x0)
return;
/* Inc. hit counters in buffer */
{
int x0_Off = x0/GUI_Context.AA_Factor-_x0;
int x1_Off = x1/GUI_Context.AA_Factor-_x0;
int iRem = x1_Off-x0_Off+1;
U8 *pDest = pabAABuffer+x0_Off;
if (iRem ==1) {
*(pDest) += x1-x0+1;
} else {
/* First Pixel */
*pDest++ += ((x0_Off+_x0+1)*GUI_Context.AA_Factor-x0);
/* Middle Pixels */
for (;--iRem>1; ) {
*pDest++ +=GUI_Context.AA_Factor;
}
/* Last Pixel */
*pDest += (1+x1- (x1_Off+_x0) *GUI_Context.AA_Factor);
}
}
}
/*********************************************************************
*
* CalcClipRectHL
*/
static void CalcClipRectHL(void) {
ClipRect_HL.x0 = GUI_Context.ClipRect.x0 * GUI_Context.AA_Factor;
ClipRect_HL.y0 = GUI_Context.ClipRect.y0 * GUI_Context.AA_Factor;
ClipRect_HL.x1 = (GUI_Context.ClipRect.x1+1) * GUI_Context.AA_Factor -1;
ClipRect_HL.y1 = (GUI_Context.ClipRect.y1+1) * GUI_Context.AA_Factor -1;
}
/*********************************************************************
*
* Public code
*
**********************************************************************
*/
/*********************************************************************
*
* GUI_AA_Init
*/
int GUI_AA_Init(int x0, int x1) {
int r =0;
/* Bounds checking:
Make sure x0, x1 are in legal range ...
(The important point is that they span no more than configured as
buffer size)
*/
if (x0<0)
x0 =0;
if (x1-x0 > GUI_AA_LINEBUFFER_SIZE-1)
x1 = x0+GUI_AA_LINEBUFFER_SIZE-1;
/* Is there anything to do at all ??? */
if (x1 < x0) {
x1 = x0; /* Not really ... */
r =1;
}
DrawAPICopy = *GUI_Context.pLCD_HL; /* Copy API table */
pLCD_HLPrev = GUI_Context.pLCD_HL; /* Remember list ptr (for restore) */
DrawAPICopy.pfDrawHLine = _DrawHLine; /* modify function ptr. for hline */
GUI_Context.pLCD_HL = &DrawAPICopy; /* Use copy of fp-list */
pabAABuffer = abAABuffer;
_x0 = x0;
_x1 = x1;
_CleanLine();
CalcClipRectHL();
GUI_Context.pClipRect_HL = &ClipRect_HL;
return r;
}
/*********************************************************************
*
* GUI_AA_Init_HiRes
*/
int GUI_AA_Init_HiRes(int x0, int x1) {
x0 /= GUI_Context.AA_Factor;
x1 /= GUI_Context.AA_Factor;
return GUI_AA_Init(x0, x1);
}
/*********************************************************************
*
* GUI_AA_SetFactor
*/
void GUI_AA_SetFactor(int Factor) {
GUI_Context.AA_Factor = Factor;
CalcClipRectHL(); /* High level clipping depends on quality factor */
}
/*********************************************************************
*
* GUI_AA_GetFactor
*/
int GUI_AA_GetFactor(void) {
return GUI_Context.AA_Factor;
}
/*********************************************************************
*
* GUI_AA_DisableHiRes
*/
void GUI_AA_DisableHiRes(void) {
GUI_Context.AA_HiResEnable = 0;
}
/*********************************************************************
*
* GUI_AA_EnableHiRes
*/
void GUI_AA_EnableHiRes(void) {
GUI_Context.AA_HiResEnable =1;
}
/*********************************************************************
*
* GUI_AA_HiRes2Pixel
*/
I16 GUI_AA_HiRes2Pixel(int HiRes) {
return GUI_Context.AA_Factor ? (HiRes / GUI_Context.AA_Factor) : HiRes;
}
/*********************************************************************
*
* GUI_AA_Exit
*/
void GUI_AA_Exit(void) {
_FlushLine();
/* restore previous settings */
GUI_Context.pLCD_HL = pLCD_HLPrev;
GUI_Context.pClipRect_HL = &GUI_Context.ClipRect;
}
#else /* Avoid problems with empty object modules */
void GUIAALib_C(void);
void GUIAALib_C(void) {}
#endif /* GUI_SUPPORT_AA */
/*************************** End of file ****************************/

View File

@ -0,0 +1,109 @@
/*
*********************************************************************************************************
* uC/GUI
* Universal graphic software for embedded applications
*
* (c) Copyright 2002, Micrium Inc., Weston, FL
* (c) Copyright 2002, SEGGER Microcontroller Systeme GmbH
*
* ľC/GUI is protected by international copyright laws. Knowledge of the
* source code may not be used to write a similar product. This file may
* only be used in accordance with a license and should not be redistributed
* in any way. We appreciate your understanding and fairness.
*
----------------------------------------------------------------------
File : GUIAALine.C
Purpose : Drawing lines with antialiasing
---------------------------END-OF-HEADER------------------------------
*/
#include "GUI_Protected.h"
#include <stddef.h>
#if GUI_SUPPORT_AA
/*********************************************************************
*
* Static code
*
**********************************************************************
*/
/*********************************************************************
*
* _AA_DrawLine
*/
static void _AA_DrawLine(int x0, int y0, int x1, int y1) {
int xMin, xMax;
U8 PenSizeOld = GUI_GetPenSize();
U8 PenSizeHR = PenSizeOld * GUI_Context.AA_Factor;
U8 OldPenShape = GUI_SetPenShape(GUI_PS_FLAT);
/* Calculate left and right borders for AA module */
if (x0 < x1) {
xMin = x0;
xMax = x1;
} else {
xMin = x1;
xMax = x0;
}
if (GUI_Context.AA_HiResEnable) {
xMin -= PenSizeHR;
xMax += PenSizeHR;
xMin /= GUI_Context.AA_Factor;
xMax /= GUI_Context.AA_Factor;
} else {
xMin -= PenSizeOld;
xMax += PenSizeOld;
x0 *= GUI_Context.AA_Factor;
x1 *= GUI_Context.AA_Factor;
y0 *= GUI_Context.AA_Factor;
y1 *= GUI_Context.AA_Factor;
}
/* Do the actual drawing */
GUI_AA_Init(xMin, xMax);
GUI_SetPenSize(PenSizeHR);
GL_DrawLine(x0 , y0 , x1 , y1 );
GUI_AA_Exit();
/* Draw end points (can be optimized away in future, TBD*/
switch (OldPenShape) {
case GUI_PS_ROUND:
{
int r = GUI_Context.AA_Factor * PenSizeOld / 2;
GL_FillCircleAA_HiRes(x0 , y0 , r);
GL_FillCircleAA_HiRes(x1 , y1 , r);
}
break;
}
GUI_SetPenSize(PenSizeOld);
GUI_SetPenShape(OldPenShape);
}
/*********************************************************************
*
* Public code
*
**********************************************************************
*/
/*********************************************************************
*
* GUI_AA_DrawLine
*/
void GUI_AA_DrawLine(int x0, int y0, int x1, int y1) {
GUI_LOCK();
#if (GUI_WINSUPPORT)
WM_ADDORG_AA(x0,y0);
WM_ADDORG_AA(x1,y1);
WM_ITERATE_START(NULL); {
#endif
_AA_DrawLine(x0, y0, x1, y1);
#if (GUI_WINSUPPORT)
} WM_ITERATE_END();
#endif
GUI_UNLOCK();
}
#else /* Avoid problems with empty object modules */
void GUIAALine_C(void);
void GUIAALine_C(void) {}
#endif /* GUI_SUPPORT_AA */
/*************************** End of file ****************************/

View File

@ -0,0 +1,112 @@
/*
*********************************************************************************************************
* uC/GUI
* Universal graphic software for embedded applications
*
* (c) Copyright 2002, Micrium Inc., Weston, FL
* (c) Copyright 2002, SEGGER Microcontroller Systeme GmbH
*
* µC/GUI is protected by international copyright laws. Knowledge of the
* source code may not be used to write a similar product. This file may
* only be used in accordance with a license and should not be redistributed
* in any way. We appreciate your understanding and fairness.
*
----------------------------------------------------------------------
File : GUIPolyAA.C
Purpose : Draw Polygon routines with Antialiasing
---------------------------END-OF-HEADER------------------------------
*/
#include "GUI_Private.h"
#include <stdio.h>
#include <string.h>
#include <math.h>
#if GUI_SUPPORT_AA
/*********************************************************************
*
* Static code
*
**********************************************************************
*/
/*********************************************************************
*
* _FillPolygonAA
*/
static void _FillPolygonAA(GUI_POINT* paPoint, int NumPoints, int x, int y) {
int i;
int Stat;
int x0,x1;
int PosFactor = GUI_Context.AA_HiResEnable ? 1 : GUI_Context.AA_Factor;
/* Calc horizontal limits and init GUI_AA */
x0 = x1 = paPoint[0].x;
for (i=1; i< NumPoints; i++) {
int x = paPoint[i].x;
if (x<x0)
x0 = x;
if (x>x1)
x1 = x;
}
if (!GUI_Context.AA_HiResEnable) {
Stat = GUI_AA_Init(x0+x,x1+x);
} else {
Stat = GUI_AA_Init((x0+x)/GUI_Context.AA_Factor,(x1+x)/GUI_Context.AA_Factor);
}
if (Stat ==0) {
/* Modify pointlist */
if (!GUI_Context.AA_HiResEnable) {
for (i=0; i< NumPoints; i++) {
paPoint[i].x *= GUI_Context.AA_Factor;
paPoint[i].y *= GUI_Context.AA_Factor;
}
}
GL_FillPolygon(paPoint, NumPoints, x * PosFactor, y * PosFactor);
/* Restore pointlist */
if (!GUI_Context.AA_HiResEnable) {
for (i=0; i< NumPoints; i++) {
paPoint[i].x /= GUI_Context.AA_Factor;
paPoint[i].y /= GUI_Context.AA_Factor;
}
}
/* Cleanup */
}
GUI_AA_Exit();
}
/*********************************************************************
*
* Public code
*
**********************************************************************
*/
/*********************************************************************
*
* GUI_AA_FillPolygon
*/
void GUI_AA_FillPolygon(/*const*/ GUI_POINT* pPoints, int NumPoints, int x0, int y0) {
GUI_LOCK();
#if (GUI_WINSUPPORT)
WM_ADDORG_AA(x0,y0);
WM_ITERATE_START(NULL); {
#endif
/* Variables in MEMDEV module (with memory devices only) */
#if GUI_SUPPORT_MEMDEV
if (GUI_Context.pDeviceAPI->pfFillPolygonAA)
GUI_Context.pDeviceAPI->pfFillPolygonAA(pPoints, NumPoints, x0, y0);
else
#endif
_FillPolygonAA (pPoints, NumPoints, x0, y0);
#if (GUI_WINSUPPORT)
} WM_ITERATE_END();
#endif
GUI_UNLOCK();
}
#else /* Avoid problems with empty object modules */
void GUIAAPoly_C(void);
void GUIAAPoly_C(void) {}
#endif /* GUI_SUPPORT_AA */
/*************************** End of file ****************************/

View File

@ -0,0 +1,54 @@
/*
*********************************************************************************************************
* uC/GUI
* Universal graphic software for embedded applications
*
* (c) Copyright 2002, Micrium Inc., Weston, FL
* (c) Copyright 2002, SEGGER Microcontroller Systeme GmbH
*
* µC/GUI is protected by international copyright laws. Knowledge of the
* source code may not be used to write a similar product. This file may
* only be used in accordance with a license and should not be redistributed
* in any way. We appreciate your understanding and fairness.
*
----------------------------------------------------------------------
File : GUIPolyOutAA.C
Purpose : Draw Polygon outline routines with Antialiasing
---------------------------END-OF-HEADER------------------------------
*/
#include <stdio.h>
#include <string.h>
#include "GUI.h"
#if GUI_SUPPORT_AA
/*********************************************************************
*
* Public code
*
**********************************************************************
*/
/*********************************************************************
*
* GUI_AA_DrawPolyOutline
*/
void GUI_AA_DrawPolyOutline(const GUI_POINT* pSrc, int NumPoints, int Thickness, int x, int y) {
U8 PrevDraw;
GUI_POINT aiTemp[10];
GUI_EnlargePolygon(&aiTemp[0], pSrc, NumPoints, Thickness);
GUI_AA_FillPolygon( &aiTemp[0], NumPoints, x, y );
PrevDraw = LCD_SetDrawMode(GUI_DRAWMODE_REV);
/* Copy points due to const qualifier */
memcpy(aiTemp, pSrc, NumPoints*2*sizeof(GUI_POINT));
GUI_AA_FillPolygon( aiTemp, NumPoints, x, y );
LCD_SetDrawMode(PrevDraw);
}
#else /* Avoid problems with empty object modules */
void GUIAAPolyOut_C(void);
void GUIAAPolyOut_C(void) {}
#endif /* GUI_SUPPORT_AA */
/*************************** End of file ****************************/

Binary file not shown.

View File

@ -0,0 +1,39 @@
/*
*********************************************************************************************************
* uC/GUI
* Universal graphic software for embedded applications
*
* (c) Copyright 2002, Micrium Inc., Weston, FL
* (c) Copyright 2002, SEGGER Microcontroller Systeme GmbH
*
* <EFBFBD>C/GUI is protected by international copyright laws. Knowledge of the
* source code may not be used to write a similar product. This file may
* only be used in accordance with a license and should not be redistributed
* in any way. We appreciate your understanding and fairness.
*
----------------------------------------------------------------------
File : GUIConf.h
Purpose : Configures abilities, fonts etc.
----------------------------------------------------------------------
*/
#ifndef GUICONF_H
#define GUICONF_H
#define GUI_OS (0) /* Compile with multitasking support */
#define GUI_SUPPORT_TOUCH (0) /* Support a touch screen (req. win-manager) */
#define GUI_SUPPORT_UNICODE (1) /* Support mixed ASCII/UNICODE strings */
#define GUI_DEFAULT_FONT &GUI_FontHZ16x16
#define GUI_ALLOC_SIZE 5000 /* Size of dynamic memory ... For WM and memory devices*/
/*********************************************************************
*
* Configuration of available packages
*/
#define GUI_WINSUPPORT 0 /* Window manager package available */
#define GUI_SUPPORT_MEMDEV 0 /* Memory devices available */
#define GUI_SUPPORT_AA 1 /* Anti aliasing available */
#endif /* Avoid multiple inclusion */

View File

@ -0,0 +1,31 @@
/*
*********************************************************************************************************
* uC/GUI
* Universal graphic software for embedded applications
*
* (c) Copyright 2002, Micrium Inc., Weston, FL
* (c) Copyright 2002, SEGGER Microcontroller Systeme GmbH
*
* µC/GUI is protected by international copyright laws. Knowledge of the
* source code may not be used to write a similar product. This file may
* only be used in accordance with a license and should not be redistributed
* in any way. We appreciate your understanding and fairness.
*
----------------------------------------------------------------------
File : GUITouch.Conf.h
Purpose : Configures touch screen module
----------------------------------------------------------------------
*/
#ifndef GUITOUCH_CONF_H
#define GUITOUCH_CONF_H
#define GUI_TOUCH_AD_LEFT 20
#define GUI_TOUCH_AD_RIGHT 240
#define GUI_TOUCH_SWAP_XY 1
#define GUI_TOUCH_MIRROR_X 0
#define GUI_TOUCH_MIRROR_Y 1
#endif /* GUITOUCH_CONF_H */

View File

@ -0,0 +1,90 @@
/*
*********************************************************************************************************
* uC/GUI
* Universal graphic software for embedded applications
*
* (c) Copyright 2002, Micrium Inc., Weston, FL
* (c) Copyright 2002, SEGGER Microcontroller Systeme GmbH
*
* µC/GUI is protected by international copyright laws. Knowledge of the
* source code may not be used to write a similar product. This file may
* only be used in accordance with a license and should not be redistributed
* in any way. We appreciate your understanding and fairness.
*
----------------------------------------------------------------------
File : GUI_X.C
Purpose : Config / System dependent externals for GUI
---------------------------END-OF-HEADER------------------------------
*/
#include "GUI.h"
#include "GUI_X.h"
/*********************************************************************
*
* Global data
*/
volatile int OS_TimeMS;
/*********************************************************************
*
* Timing:
* GUI_X_GetTime()
* GUI_X_Delay(int)
Some timing dependent routines require a GetTime
and delay function. Default time unit (tick), normally is
1 ms.
*/
int GUI_X_GetTime(void)
{
return OS_TimeMS;
}
void GUI_X_Delay(int ms)
{
int tEnd = OS_TimeMS + ms;
while ((tEnd - OS_TimeMS) > 0)
;
}
/*********************************************************************
*
* GUI_X_Init()
*
* Note:
* GUI_X_Init() is called from GUI_Init is a possibility to init
* some hardware which needs to be up and running before the GUI.
* If not required, leave this routine blank.
*/
void GUI_X_Init(void) {}
/*********************************************************************
*
* GUI_X_ExecIdle
*
* Note:
* Called if WM is in idle state
*/
void GUI_X_ExecIdle(void) {}
/*********************************************************************
*
* Logging: OS dependent
Note:
Logging is used in higher debug levels only. The typical target
build does not use logging and does therefor not require any of
the logging routines below. For a release build without logging
the routines below may be eliminated to save some space.
(If the linker is not function aware and eliminates unreferenced
functions automatically)
*/
void GUI_X_Log(const char *s) { GUI_USE_PARA(s); }
void GUI_X_Warn(const char *s) { GUI_USE_PARA(s); }
void GUI_X_ErrorOut(const char *s) { GUI_USE_PARA(s); }

View File

@ -0,0 +1,40 @@
/*
*********************************************************************************************************
* uC/GUI
* Universal graphic software for embedded applications
*
* (c) Copyright 2002, Micrium Inc., Weston, FL
* (c) Copyright 2002, SEGGER Microcontroller Systeme GmbH
*
* <EFBFBD>C/GUI is protected by international copyright laws. Knowledge of the
* source code may not be used to write a similar product. This file may
* only be used in accordance with a license and should not be redistributed
* in any way. We appreciate your understanding and fairness.
*
----------------------------------------------------------------------
File : LCDConf_1375_C8_C320x240.h
Purpose : Sample configuration file
----------------------------------------------------------------------
*/
#ifndef LCDCONF_H
#define LCDCONF_H
#include "board.h" // user defined
/*********************************************************************
*
* General configuration of LCD
*
**********************************************************************
*/
#define LCD_XSIZE (400) /* X-resolution of LCD, Logical coor. */
#define LCD_YSIZE (240) /* Y-resolution of LCD, Logical coor. */
#define LCD_BITSPERPIXEL (8)
#define LCD_CONTROLLER (-1)
#define LCD_INIT_CONTROLLER() lcd_init();
#endif /* LCDCONF_H */

Binary file not shown.

View File

@ -0,0 +1,25 @@
@ECHO OFF
ECHO CCConvertColor.bat: Compiling GUI\ConvertColor
CALL CC LCDP111
CALL CC LCDP222
CALL CC LCDP233
CALL CC LCDP323
CALL CC LCDP332
CALL CC LCDP444_12
CALL CC LCDP444_12_1
CALL CC LCDP444_16
CALL CC LCDP555
CALL CC LCDP556
CALL CC LCDP565
CALL CC LCDP655
CALL CC LCDP8666
CALL CC LCDP8666_1
CALL CC LCDPM233
CALL CC LCDPM323
CALL CC LCDPM332
CALL CC LCDPM444_12
CALL CC LCDPM444_16
CALL CC LCDPM555
CALL CC LCDPM556
CALL CC LCDPM565
CALL CC LCDPM655

View File

@ -0,0 +1,98 @@
/*
*********************************************************************************************************
* uC/GUI
* Universal graphic software for embedded applications
*
* (c) Copyright 2002, Micrium Inc., Weston, FL
* (c) Copyright 2002, SEGGER Microcontroller Systeme GmbH
*
* µC/GUI is protected by international copyright laws. Knowledge of the
* source code may not be used to write a similar product. This file may
* only be used in accordance with a license and should not be redistributed
* in any way. We appreciate your understanding and fairness.
*
----------------------------------------------------------------------
File : LCD111.C
Purpose : Color conversion routines for 111 color mode
---------------------------END-OF-HEADER------------------------------
*/
#include "LCD_Protected.h" /* inter modul definitions */
/*********************************************************************
*
* Public code, LCD_FIXEDPALETTE == 111, 8 basic colors
*
**********************************************************************
*/
/*********************************************************************
*
* LCD_Color2Index_111
*/
unsigned LCD_Color2Index_111(LCD_COLOR Color) {
int r,g,b;
r = (Color>>(0+7)) &1;
g = (Color>>(8+7)) &1;
b = (Color>>(16+7)) &1;
return r+(g<<1)+(b<<2);
}
/*********************************************************************
*
* LCD_Index2Color_111
*/
LCD_COLOR LCD_Index2Color_111(int Index) {
U16 r,g,b;
r = (((Index>>0)&1)*0xff);
g = (((Index>>1)&1)*0xff);
b = (Index>>2) *0xff;
return r | (g<<8) | ((U32)b<<16);
}
/*********************************************************************
*
* LCD_GetIndexMask_111
*/
unsigned LCD_GetIndexMask_111(void) {
return 0x0007;
}
/*********************************************************************
*
* Public code, LCD_FIXEDPALETTE == 111, 8 basic colors, SWAP_RB
*
**********************************************************************
*/
/*********************************************************************
*
* LCD_Color2Index_M111
*/
unsigned LCD_Color2Index_M111(LCD_COLOR Color) {
int r,g,b;
r = (Color>>(0+7)) &1;
g = (Color>>(8+7)) &1;
b = (Color>>(16+7)) &1;
return b+(g<<1)+(r<<2);
}
/*********************************************************************
*
* LCD_Index2Color_M111
*/
LCD_COLOR LCD_Index2Color_M111(int Index) {
U16 r,g,b;
r = (((Index>>0)&1)*0xff);
g = (((Index>>1)&1)*0xff);
b = (Index>>2) *0xff;
return b | (g<<8) | ((U32)r<<16);
}
/*********************************************************************
*
* LCD_GetIndexMask_M111
*/
unsigned LCD_GetIndexMask_M111(void) {
return 0x0007;
}
/*************************** End of file ****************************/

Some files were not shown because too many files have changed in this diff Show More