Compare commits

...

4 Commits

20 changed files with 138 additions and 242 deletions

View File

@ -32,6 +32,7 @@ endif
COMPONENTS_$(TARGET) = \
$(TOP_DIR)/app/libuser$(LIB_EXT) \
$(TOP_DIR)/app/app_drivers/libappdrivers$(LIB_EXT) \
$(TOP_DIR)/app/persistency/libpersistency$(LIB_EXT) \
$(TOP_DIR)/lvgl/liblvgl$(LIB_EXT)
ifeq ($(USE_LIB), 0)

View File

@ -32,7 +32,7 @@
*
*/
#define I2C_SCL WM_IO_PA_01
#define I2C_SDA WM_IO_PA_04
#define I2C_SDA WM_IO_PB_19
/**
* @brief lcd display
@ -57,6 +57,6 @@
* @brief debug uart
*
*/
#define DEBUG_UART_TX WM_IO_PB_02
// DEBUG_UART_TX WM_IO_PB_02
#endif //APPCONFIG_H

View File

@ -325,7 +325,6 @@ void lcd_init(LCDConfig_t * const LCDConfig)
// Init MMC SDIO peripheral
mmc_sdio_driver_periph_init(LCDConfig->drawFinishedCb, LCDConfig->cbArg);
#if 1
#if DISPLAY_CONTROLLER == 0
const u8 *cmd = ili9341_init_seq;
#elif DISPLAY_CONTROLLER == 1
@ -342,61 +341,6 @@ void lcd_init(LCDConfig_t * const LCDConfig)
tls_os_time_delay(*(cmd + 1));
cmd += *cmd + 2;
}
#else
lcd_set_data_command(LCDConfig, LCD_COMMAND);
lcd_set_cs(LCDConfig, LCD_SELECTED);
mmc_sdio_driver_write_one(0x00);
mmc_sdio_driver_write_one(0x80);
lcd_set_cs(LCDConfig, LCD_RELEASED);
tls_os_time_delay(4);
lcd_set_cs(LCDConfig, LCD_SELECTED);
mmc_sdio_driver_write_one(0x08);
mmc_sdio_driver_write_one(0x80);
lcd_set_cs(LCDConfig, LCD_RELEASED);
tls_os_time_delay(4);
lcd_set_cs(LCDConfig, LCD_SELECTED);
mmc_sdio_driver_write_one(0x09);
mmc_sdio_driver_write_one(0x80);
lcd_set_cs(LCDConfig, LCD_RELEASED);
tls_os_time_delay(4);
lcd_set_cs(LCDConfig, LCD_SELECTED);
mmc_sdio_driver_write_one(0x14);
mmc_sdio_driver_write_one(0x80);
tls_os_time_delay(4);
lcd_set_cs(LCDConfig, LCD_RELEASED);
/*
spi_write_9_bit(LCDConfig, false, 0x01);
tls_os_time_delay(2);
spi_write_9_bit(LCDConfig, false, 0x11);
tls_os_time_delay(2);
spi_write_9_bit(LCDConfig, false, 0x3A);spi_write_9_bit(LCDConfig, true, 0x05);
tls_os_time_delay(2);
spi_write_9_bit(LCDConfig, false, 0x36);spi_write_9_bit(LCDConfig, true, 0x00);
tls_os_time_delay(2);
spi_write_9_bit(LCDConfig, false, 0x2A);spi_write_9_bit(LCDConfig, true, 0x00);spi_write_9_bit(LCDConfig, true, 0x00);spi_write_9_bit(LCDConfig, true, 0x00);spi_write_9_bit(LCDConfig, true, 0xF0);
tls_os_time_delay(2);
spi_write_9_bit(LCDConfig, false, 0x2B);spi_write_9_bit(LCDConfig, true, 0x00);spi_write_9_bit(LCDConfig, true, 0x00);spi_write_9_bit(LCDConfig, true, 0x01);spi_write_9_bit(LCDConfig, true, 0x40);
tls_os_time_delay(2);
spi_write_9_bit(LCDConfig, false, 0x21);tls_os_time_delay(2);
spi_write_9_bit(LCDConfig, false, 0x13);tls_os_time_delay(2);
spi_write_9_bit(LCDConfig, false, 0x29);
*/
#endif
lcd_set_backlight(LCDConfig, 255);
}
void lcd_draw_rect_frame(LCDConfig_t * const LCDConfig, uint16_t x, uint16_t y, uint16_t width, uint16_t height, uint8_t *data)
@ -422,14 +366,14 @@ void lcd_set_backlight(LCDConfig_t * const LCDConfig, uint8_t brightness)
// Backlight is controlled using PWM
wm_pwm4_config(LCDConfig->LCDPWMBacklightPin);
// Set pwm to 10kHz
tls_pwm_init(4, 10000, 0, 0);
tls_pwm_init(LCD_PWM_CHANNEL, 10000, 0, 0);
// Set brightness
tls_pwm_duty_set(4, brightness);
tls_pwm_duty_set(LCD_PWM_CHANNEL, brightness);
}
else
{
// We stop the pwm
tls_pwm_stop(4);
tls_pwm_stop(LCD_PWM_CHANNEL);
tls_gpio_cfg(LCDConfig->LCDPWMBacklightPin, WM_GPIO_DIR_OUTPUT, WM_GPIO_ATTR_FLOATING);
tls_gpio_write(LCDConfig->LCDPWMBacklightPin, 0);
}

View File

@ -1,5 +1,7 @@
#include "app_common.h"
#include "lvgl.h"
#include "lv_port_disp.h"
#include "lv_port_indev.h"
#include "FreeRTOS.h"
#include "wm_include.h"
#include "lcd.h"
@ -11,27 +13,7 @@
#include "QMC5883L.h"
#include "BMP280.h"
#include "bma456w.h"
#include "lv_port_indev.h"
#define LVGL_GFX_BUFFER_SIZE (LCD_PIXEL_WIDTH * LCD_PIXEL_HEIGHT / 2)
static lv_color_t lvgl_draw_buffer[LVGL_GFX_BUFFER_SIZE];
static lv_disp_draw_buf_t lvgl_draw_buffer_dsc;
static lv_disp_drv_t display_driver;
static LCDConfig_t LCDConfig;
static void lvgl_display_flush_cb(lv_disp_drv_t *disp_drv, const lv_area_t *area, lv_color_t *color_p)
{
lcd_draw_rect_frame(&LCDConfig, area->x1, area->y1, area->x2 - area->x1 + 1, area->y2 - area->y1 + 1, (uint8_t *)color_p);
/* lv_disp_flush_ready is called in the LCD driver registered callback */
}
static void lcd_draw_finished_cb(void *arg)
{
lv_disp_flush_ready((lv_disp_drv_t *)arg);
}
#include "watch_settings.h"
static void date_time_cb(struct tm * const dateTime)
{
@ -51,9 +33,17 @@ struct bma456w_wrist_wear_wakeup_params setting;
struct bma4_int_pin_config pin_config;
uint16_t int_status;
static void setBrightness(uint8_t brightness)
{
extern LCDConfig_t LCDConfig;
lcd_set_backlight(&LCDConfig, brightness);
}
static void setBrightnessCb(uint8_t brightness)
{
lcd_set_backlight(&LCDConfig, brightness);
persistency_get_settings()->display.brightness = brightness;
setBrightness(brightness);
}
static void setTimeCb(uint8_t hour, uint8_t minute, uint8_t second, uint8_t day, uint8_t month, uint8_t year)
@ -119,19 +109,6 @@ static void delay_us(uint32_t period, void *intf_ptr)
tls_os_time_delay(pdMS_TO_TICKS(period / 1000));
}
/*uint16_t x = 0, y = 0, action = 0;
static void touch_screen_isr(void *arg)
{
tls_clr_gpio_irq_status(WM_IO_PB_00);
uint8_t tc_data[9];
i2c_read(0x15, 0x00, tc_data, sizeof tc_data);
x = ((tc_data[3] & 0x0f) << 8) | tc_data[4];
y = ((tc_data[5] & 0x0f) << 8) | tc_data[6];
action = tc_data[3] >> 6;
}*/
void gfx_task(void *param)
{
APP_LOG_TRACE("starting");
@ -139,45 +116,7 @@ void gfx_task(void *param)
/* Initialize the lvgl library*/
lv_init();
/* Create, initialize and register the display driver*/
lv_disp_drv_init(&display_driver);
display_driver.hor_res = LCD_PIXEL_WIDTH;
display_driver.ver_res = LCD_PIXEL_HEIGHT;
display_driver.rotated = LV_DISP_ROT_NONE;
lv_disp_draw_buf_init(&lvgl_draw_buffer_dsc, lvgl_draw_buffer, NULL, LVGL_GFX_BUFFER_SIZE);
display_driver.draw_buf = &lvgl_draw_buffer_dsc;
display_driver.flush_cb = &(lvgl_display_flush_cb);
/* Initialize the LCD display */
lcd_config_init(&LCDConfig);
lcd_register_draw_finished_cb(&LCDConfig, &(lcd_draw_finished_cb), &display_driver);
#if defined(W800)
LCDConfig.LCDPWMBacklightPin = WM_IO_PA_07;
LCDConfig.LCDClockPin = WM_IO_PB_06;
LCDConfig.LCDDataPin = WM_IO_PB_07;
LCDConfig.LCDChipSelectPin = WM_IO_PB_10;
LCDConfig.LCDDataCommandPin = WM_IO_PB_08;
LCDConfig.LCDResetPin = WM_IO_PB_09;
#elif defined(W801)
LCDConfig.LCDPWMBacklightPin = WM_IO_PA_08;
LCDConfig.LCDClockPin = WM_IO_PA_09;
LCDConfig.LCDDataPin = WM_IO_PA_10;
LCDConfig.LCDChipSelectPin = WM_IO_PA_13;
LCDConfig.LCDDataCommandPin = WM_IO_PA_11;
LCDConfig.LCDResetPin = WM_IO_PA_12;
#endif
lcd_init(&LCDConfig);
if(!lv_disp_drv_register(&display_driver))
{
APP_LOG_ERROR("Failed to register display driver");
}
lv_port_disp_init();
lv_port_indev_init();
watch_face_init(&watchFace);
@ -192,7 +131,7 @@ void gfx_task(void *param)
lv_scr_load(watchFace.display);
/* Let's init the I2C interface */
i2c_init(WM_IO_PA_04, WM_IO_PA_01, 100000);
i2c_init(I2C_SDA, I2C_SCL, 100000);
uint8_t aliveCounter = 0;
@ -294,9 +233,9 @@ void gfx_task(void *param)
else
APP_LOG_INFO("BMA456 set pin conf failed");
/*tls_gpio_cfg(WM_IO_PB_00, WM_GPIO_DIR_INPUT, WM_GPIO_ATTR_PULLHIGH);
tls_gpio_isr_register(WM_IO_PB_00, &(touch_screen_isr), NULL);
tls_gpio_irq_enable(WM_IO_PB_00, WM_GPIO_IRQ_TRIG_FALLING_EDGE);*/
/* Once we are done with the initializing steps we
don't forget to turn the backlight on ! */
setBrightness(persistency_get_settings()->display.brightness);
for(;;)
{
@ -305,46 +244,44 @@ void gfx_task(void *param)
if(compass_screen_is_in_use(&compassScreen) && QMC5883L_is_data_available())
{
/*__disable_irq();
/*
QMC5883L_MData_t MDataRaw = QMC5883L_get_MFields_raw();
APP_LOG_TRACE("X %d Y %d Z %d", MDataRaw.MFieldX, MDataRaw.MFieldY, MDataRaw.MFieldZ);
__enable_irq();*/
*/
QMC5883L_MData_calibrated_t MData = QMC5883L_get_MFields_calibrated();
compass_screen_set_azimuth(&compassScreen, angle_with_offset(QMC5883L_get_azimuth(MData), 180));
}
/*uint8_t rslt = bma456w_read_int_status(&int_status, &bma);
uint8_t rslt = bma456w_read_int_status(&int_status, &bma);
if(rslt != BMA4_OK)
APP_LOG_DEBUG("Failed to read int status");
if((BMA4_OK == rslt) && (int_status & BMA456W_WRIST_WEAR_WAKEUP_INT))
{
APP_LOG_DEBUG("Wrist tilt");
}*/
}
if(++aliveCounter % 200 == 0)
{
float temp = BMP280_get_temperature();
BMP280_trigger_measurement();
APP_LOG_DEBUG("GFX thread, temp : %0.2f", temp);
//APP_LOG_DEBUG("------------ x %d y %d, action : %d", x, y, action);
aliveCounter = 0;
}
/* Handle inactivity periods : */
/*if(lv_disp_get_inactive_time(NULL) > 10000)
if(lv_disp_get_inactive_time(NULL) > 10000)
{
// First, we disable the display backlight and we set all the peripherals in their low power mode
lcd_set_backlight(&LCDConfig, 0);
setBrightness(0);
// Let's sleep
tls_pmu_sleep_start();
// On wake up, we force the watch face to sync up with the rtc /!\ RTC update delay WTF ?
tls_os_time_delay(1);
watch_face_force_sync(&watchFace);
lv_disp_trig_activity(NULL);
lcd_set_backlight(&LCDConfig, 255);
}*/
setBrightness(persistency_get_settings()->display.brightness);
}
}
}

View File

@ -90,7 +90,7 @@ static void brightness_slider_cb(lv_event_t * e)
lv_obj_t * slider = lv_event_get_target(e);
uint8_t brightness = (float)lv_slider_get_value(slider) * 2.55;
if(brightness > 5)
if(brightness > 0)
settingsScreen->settingsScreenAPIInterface.setBrightnessSettingsCb(brightness);
}

View File

@ -17,10 +17,10 @@
#include "app_common.h"
#include "lvgl.h"
#include "gfx_task.h"
#include "wm_gpio_afsel.h"
void user_task_main(void *param)
{
/* Creating the gfx task */
if(tls_os_task_create(&gfx_task_handle, "gfx_task", &(gfx_task), NULL, gfx_task_stack, GFX_STACK_SIZE_IN_BYTES, GFX_STACK_PRIORITY, 0 /*not used anyway*/) != TLS_OS_SUCCESS)
{

View File

@ -0,0 +1,13 @@
#include "watch_settings.h"
/* WatchSetting object with default values */
static WatchSettings_t watchSettings =
{
.timeAndDate = {.config = 0},
.display = {.brightness = 255, .sleep_timeout = 10,},
};
WatchSettings_t *persistency_get_settings(void)
{
return &watchSettings;
}

View File

@ -41,4 +41,10 @@ typedef struct WatchSettings
LanguageAndUI_t languageAndUI;
} WatchSettings_t;
WatchSettings_t *persistency_get_settings(void);
bool persistency_save_settings(void);
bool persistency_load_settings(void);
#endif //WATCH_SETTINGS_H

View File

@ -16,8 +16,8 @@
#define WM_CONFIG_DEBUG_UART1 CFG_OFF/*PRINTF PORT USE UART1*/
/**Driver Support**/
#define TLS_CONFIG_HS_SPI CFG_ON /*High Speed SPI*/
#define TLS_CONFIG_LS_SPI CFG_ON /*Low Speed SPI*/
#define TLS_CONFIG_HS_SPI CFG_OFF /*High Speed SPI*/
#define TLS_CONFIG_LS_SPI CFG_OFF /*Low Speed SPI*/
#define TLS_CONFIG_UART CFG_ON /*UART*/
/**Only Factory Test At Command**/

View File

@ -90,6 +90,11 @@ typedef int int32;
#endif
typedef unsigned int uint32;
#ifdef uint32_t
#undef uint32_t
#endif
typedef unsigned int uint32_t;
#ifdef int16
#undef int16
#endif
@ -130,7 +135,6 @@ typedef unsigned short uint16_t;
#endif
typedef unsigned int u32_t;
#ifdef s8_t
#undef s8_t
#endif

View File

@ -63,12 +63,12 @@ void lv_port_disp_init(void)
lcd_register_draw_finished_cb(&LCDConfig, &(lcd_draw_finished_cb), &display_driver);
#if defined(W800)
LCDConfig.LCDPWMBacklightPin = WM_IO_PA_07;
LCDConfig.LCDClockPin = WM_IO_PB_06;
LCDConfig.LCDDataPin = WM_IO_PB_07;
LCDConfig.LCDChipSelectPin = WM_IO_PB_10;
LCDConfig.LCDDataCommandPin = WM_IO_PB_08;
LCDConfig.LCDResetPin = WM_IO_PB_09;
LCDConfig.LCDPWMBacklightPin = LCD_PWM_BACKLIGHT;
LCDConfig.LCDClockPin = LCD_CLOCK_CLOCK;
LCDConfig.LCDDataPin = LCD_DATA_LINE;
LCDConfig.LCDChipSelectPin = LCD_CHIP_SELECT;
LCDConfig.LCDDataCommandPin = LCD_DATA_COMMAND;
LCDConfig.LCDResetPin = LCD_RESET;
#elif defined(W801)
LCDConfig.LCDPWMBacklightPin = WM_IO_PA_08;
LCDConfig.LCDClockPin = WM_IO_PA_09;

View File

@ -1,5 +1,5 @@
/**
* @file lv_port_indev_templ.c
* @file lv_port_indev.c
*
*/

View File

@ -11,7 +11,6 @@
*********************/
#include "lv_port_indev.h"
#include "touchpad.h"
#include "i2c.h"
/*********************
* DEFINES
@ -68,18 +67,6 @@ lv_indev_t * indev_touchpad;
* GLOBAL FUNCTIONS
**********************/
uint16_t x = 0, y = 0, action = 0;
static void touch_screen_isr(void *arg)
{
tls_clr_gpio_irq_status(WM_IO_PB_00);
uint8_t tc_data[9];
i2c_read(0x15, 0x00, tc_data, sizeof tc_data);
x = ((tc_data[3] & 0x0f) << 8) | tc_data[4];
y = ((tc_data[5] & 0x0f) << 8) | tc_data[6];
action = tc_data[3] >> 6;
}
void lv_port_indev_init(void)
{
/**
@ -101,10 +88,7 @@ void lv_port_indev_init(void)
* -----------------*/
/*Initialize your touchpad if you have*/
//touchpad_init();
tls_gpio_cfg(WM_IO_PB_00, WM_GPIO_DIR_INPUT, WM_GPIO_ATTR_PULLHIGH);
tls_gpio_isr_register(WM_IO_PB_00, &(touch_screen_isr), NULL);
tls_gpio_irq_enable(WM_IO_PB_00, WM_GPIO_IRQ_TRIG_FALLING_EDGE);
touchpad_init();
/*Register a touchpad input device*/
lv_indev_drv_init(&indev_drv);
@ -203,7 +187,7 @@ static void touchpad_init(void)
}
/*Will be called by the library to read the touchpad*/
/*static void touchpad_read(lv_indev_drv_t * indev_drv, lv_indev_data_t * data)
static void touchpad_read(lv_indev_drv_t * indev_drv, lv_indev_data_t * data)
{
static lv_coord_t last_x = 0;
static lv_coord_t last_y = 0;
@ -220,40 +204,15 @@ static void touchpad_init(void)
// Set the last pressed coordinates
data->point.x = 240-last_y;
data->point.y = last_x;
}*/
static void touchpad_read(lv_indev_drv_t * indev_drv, lv_indev_data_t * data)
{
static lv_coord_t last_x = 0;
static lv_coord_t last_y = 0;
// Save the pressed coordinates and the state
if(touchpad_is_pressed()) {
last_x = x;
last_y = y;
data->state = LV_INDEV_STATE_PR;
}
else {
data->state = LV_INDEV_STATE_REL;
}
// Set the last pressed coordinates
data->point.x = 239-last_x;
data->point.y = 239-last_y;
}
/*Return true is the touchpad is pressed*/
/*static bool touchpad_is_pressed(void)
static bool touchpad_is_pressed(void)
{
// Your code comes here
bool val = bsp_touchpad_is_pressed();
// printf("---> %d\n",val);
return val;
}*/
static bool touchpad_is_pressed(void)
{
return action == 2;
}
/*Get the x and y coordinates if the touchpad is pressed*/
@ -266,11 +225,6 @@ static void touchpad_get_xy(lv_coord_t * x, lv_coord_t * y)
// printf("---> x:%d y:%d\n", (*x), (*y));
}
/*static void touchpad_get_xy(lv_coord_t * x, lv_coord_t * y)
{
}*/
// /*------------------
// * Mouse
// * -----------------*/

View File

@ -1,6 +1,6 @@
/**
* @file lv_port_indev_templ.h
* @file lv_port_indev.h
*
*/

View File

@ -48,8 +48,25 @@ static void uart0Init (int bandrate)
tls_reg_write32(HR_UART0_DMA_CTRL, 0x00); /* Disable DMA */
tls_reg_write32(HR_UART0_FIFO_CTRL, 0x00); /* one byte TX/RX */
// tls_reg_write32(HR_UART0_INT_MASK, 0x00); /* Disable INT */
}
static void uart2Init(int bandrate)
{
unsigned int bd;
NVIC_DisableIRQ(UART24_IRQn);
NVIC_ClearPendingIRQ(UART24_IRQn);
bd = (APB_CLK/(16*bandrate) - 1)|(((APB_CLK%(bandrate*16))*16/(bandrate*16))<<16);
tls_reg_write32(HR_UART2_BAUD_RATE_CTRL, bd);
tls_reg_write32(HR_UART2_LINE_CTRL, UART_BITSTOP_VAL | UART_TXEN_BIT | UART_RXEN_BIT);
tls_reg_write32(HR_UART2_FLOW_CTRL, 0x00); /* Disable afc */
tls_reg_write32(HR_UART2_DMA_CTRL, 0x00); /* Disable DMA */
tls_reg_write32(HR_UART2_FIFO_CTRL, 0x00); /* one byte TX/RX */
// tls_reg_write32(HR_UART2_INT_MASK, 0x00); /* Disable INT */
}
#if 0
static void uart1_io_init(void)
{
@ -97,7 +114,8 @@ void board_init(void)
#if USE_UART0_PRINT
/* use uart0 as log output io */
uart0Init(115200);
//uart0Init(115200);
uart2Init(115200);
set_printf_port(0);
#else
uart1_io_init();

View File

@ -82,10 +82,23 @@ int sendchar(int ch)
return ch;
}
int sendchar_debug_uart(int ch)
{
if (ch == '\n')
{
while (tls_reg_read32(HR_UART2_FIFO_STATUS) & 0x3F);
tls_reg_write32(HR_UART2_TX_WIN, '\r');
}
while (tls_reg_read32(HR_UART2_FIFO_STATUS) & 0x3F);
tls_reg_write32(HR_UART2_TX_WIN, (char)ch);
return ch;
}
int fputc(int ch, FILE *stream)
{
(void)stream;
sendchar(ch);
//sendchar(ch);
sendchar_debug_uart(ch);
return 0;
}

View File

@ -35,5 +35,6 @@ char * strdup(const char *s);
char * strndup(const char *s, size_t len);
int sendchar(int ch);
int sendchar_debug_uart(int ch);
#endif /* UTILS_H */

View File

@ -151,8 +151,11 @@ void wm_gpio_config()
/* must call first */
wm_gpio_af_disable();
wm_uart0_tx_config(WM_IO_PB_19);
wm_uart0_rx_config(WM_IO_PB_20);
/*wm_uart0_tx_config(WM_IO_PB_19);
wm_uart0_rx_config(WM_IO_PB_20);*/
/* used for the debug uart */
wm_uart2_tx_scio_config(WM_IO_PB_02);
/*Please Attention, only one IO's multiplex can be used at one times' configuration. */
@ -233,6 +236,7 @@ int main(void)
tls_reg_write32(HR_PMU_BK_REG, value);
value = tls_reg_read32(HR_PMU_PS_CR);
value &= ~(BIT(5));
value &= ~(BIT(6)); //Set wakeup pin to trigger immediatly by clearing pin 6, needed for the touch panel fast interrupt
tls_reg_write32(HR_PMU_PS_CR, value);
/*Close those not initialized clk except touchsensor/trng, uart0,sdadc,gpio,rfcfg*/

View File

@ -47,6 +47,7 @@ INCLUDES += -I $(TOP_DIR)/app/app_include
INCLUDES += -I $(TOP_DIR)/app/app_drivers/lcd
INCLUDES += -I $(TOP_DIR)/app/app_drivers/mmc_sdio
INCLUDES += -I $(TOP_DIR)/app/app_drivers/i2c
INCLUDES += -I $(TOP_DIR)/app/persistency
INCLUDES += -I $(TOP_DIR)/app/gfx
INCLUDES += -I $(TOP_DIR)/app