prettyprint

2024年9月21日 星期六

STM32 HAL || Large 7-Segment LED with WS2812 || Rotary Encoder || STM32F103C8T6

 本文章介紹利用WS2812燈條來製作一個大型的七段式顯示器,用來顯示SHT40的溫濕度。利用Rotary encoder來設定七段式顯示器的顏色。MCU 使用STM32F103C8T6。


WS2812每個0或1的編碼方式與時序。

STM32F103C8T6使用SPI介面來輸出波形。
RCC Clock 設定40MHz

SPI baud rate:

SPI GPIO:



Rotary Encoder Timer設定:

成果展示:



程式碼:

main.c
/* USER CODE BEGIN Header */
/**
  ******************************************************************************
  * @file           : main.c
  * @brief          : Main program body
  ******************************************************************************
  * @attention
  *
  * Copyright (c) 2024 STMicroelectronics.
  * All rights reserved.
  *
  * This software is licensed under terms that can be found in the LICENSE file
  * in the root directory of this software component.
  * If no LICENSE file comes with this software, it is provided AS-IS.
  *
  ******************************************************************************
  */
/* USER CODE END Header */
/* Includes ------------------------------------------------------------------*/
#include "main.h"

/* Private includes ----------------------------------------------------------*/
/* USER CODE BEGIN Includes */
#include "ws2812.h"
#include "sht40.h"
#include "math.h"
/* USER CODE END Includes */

/* Private typedef -----------------------------------------------------------*/
/* USER CODE BEGIN PTD */

/* USER CODE END PTD */

/* Private define ------------------------------------------------------------*/
/* USER CODE BEGIN PD */

/* USER CODE END PD */

/* Private macro -------------------------------------------------------------*/
/* USER CODE BEGIN PM */

/* USER CODE END PM */

/* Private variables ---------------------------------------------------------*/
I2C_HandleTypeDef hi2c1;

SPI_HandleTypeDef hspi1;
DMA_HandleTypeDef hdma_spi1_tx;

TIM_HandleTypeDef htim2;
TIM_HandleTypeDef htim3;

/* USER CODE BEGIN PV */
// 7-segment digit
uint8_t digit[13][7] = {
    {1,1,1,1,1,1,0}, //0
    {1,0,0,0,0,1,0}, //1
    {0,1,1,0,1,1,1}, //2
    {1,1,0,0,1,1,1}, //3
    {1,0,0,1,0,1,1}, //4
    {1,1,0,1,1,0,1}, //5
    {1,1,1,1,1,0,1}, //6
    {1,0,0,0,1,1,0}, //7
    {1,1,1,1,1,1,1}, //8
    {1,0,0,1,1,1,1}, //9
	{0,0,0,1,1,1,1}, // degree
	{0,1,1,1,1,0,0}, // C
	{1,1,1,0,0,0,1}, // low%
};
uint8_t rgb_color[3] = {128,128,128};
enum {
	SET_RED=0,
	SET_GREEN=1,
	SET_BLUE=2,
	SET_COUNT=3,
};
uint8_t rgb_set_index=SET_RED;
int16_t rgb_set_start_counter=0;

uint8_t sw_state=1;
uint8_t set_color_mode=0;
uint8_t long_press_count=0;
int16_t counter=0;

ws2812_pixel_color_t pixels_color;

/* USER CODE END PV */

/* Private function prototypes -----------------------------------------------*/
void SystemClock_Config(void);
static void MX_GPIO_Init(void);
static void MX_DMA_Init(void);
static void MX_SPI1_Init(void);
static void MX_I2C1_Init(void);
static void MX_TIM2_Init(void);
static void MX_TIM3_Init(void);
/* USER CODE BEGIN PFP */

/* USER CODE END PFP */

/* Private user code ---------------------------------------------------------*/
/* USER CODE BEGIN 0 */
void display_digit(uint8_t number) {

    for (int i=0; i < 7; i++) {
        if (digit[number][i] == 1) {
        	for (int k=0; k < 3;k++) ws2812_display_pixel(&pixels_color,1);
        }
        else {
        	for (int k=0; k < 3;k++) ws2812_display_pixel(&pixels_color,0);
        }
    }
}

void HAL_TIM_IC_CaptureCallback(TIM_HandleTypeDef* htim) {
	if (set_color_mode) {
		counter = (int16_t)__HAL_TIM_GET_COUNTER(htim);
		rgb_color[rgb_set_index] += (counter - rgb_set_start_counter);
		rgb_set_start_counter = counter;
		ws2812_set_pixel_color(&pixels_color,0,0,rgb_color[SET_BLUE]);
		display_digit(1);
		ws2812_set_pixel_color(&pixels_color,0,rgb_color[SET_GREEN],0);
		display_digit(1);
		ws2812_set_pixel_color(&pixels_color,rgb_color[SET_RED],0,0);
		display_digit(1);
		ws2812_set_pixel_color(&pixels_color,rgb_color[SET_RED],rgb_color[SET_GREEN],rgb_color[SET_BLUE]);
		display_digit(1);
	}
}


void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim){
	if (HAL_GPIO_ReadPin(RT_SW_GPIO_Port, RT_SW_Pin) == GPIO_PIN_SET) {
		HAL_TIM_Base_Stop_IT(&htim2);
		if (long_press_count > 20) {
			set_color_mode = !set_color_mode;
		}
		long_press_count=0;
		sw_state = 1;

		rgb_set_index = (rgb_set_index+1) % SET_COUNT;
		rgb_set_start_counter = (int16_t)__HAL_TIM_GET_COUNTER(&htim3);

		if (set_color_mode){
			ws2812_set_pixel_color(&pixels_color,0,0,rgb_color[SET_BLUE]);
			display_digit(1);
			ws2812_set_pixel_color(&pixels_color,0,rgb_color[SET_GREEN],0);
			display_digit(1);
			ws2812_set_pixel_color(&pixels_color,rgb_color[SET_RED],0,0);
			display_digit(1);
			ws2812_set_pixel_color(&pixels_color,rgb_color[SET_RED],rgb_color[SET_GREEN],rgb_color[SET_BLUE]);
			display_digit(1);
		}
	} else {
		long_press_count++;
	}

}


void HAL_GPIO_EXTI_Callback(uint16_t gpio) {
	if (gpio == RT_SW_Pin && sw_state) {
		sw_state=0;
		HAL_TIM_Base_Start_IT(&htim2);
	}
}
/* USER CODE END 0 */

/**
  * @brief  The application entry point.
  * @retval int
  */
int main(void)
{

  /* USER CODE BEGIN 1 */

  /* USER CODE END 1 */

  /* MCU Configuration--------------------------------------------------------*/

  /* Reset of all peripherals, Initializes the Flash interface and the Systick. */
  HAL_Init();

  /* USER CODE BEGIN Init */

  /* USER CODE END Init */

  /* Configure the system clock */
  SystemClock_Config();

  /* USER CODE BEGIN SysInit */

  /* USER CODE END SysInit */

  /* Initialize all configured peripherals */
  MX_GPIO_Init();
  MX_DMA_Init();
  MX_SPI1_Init();
  MX_I2C1_Init();
  MX_TIM2_Init();
  MX_TIM3_Init();
  /* USER CODE BEGIN 2 */

  HAL_TIM_Encoder_Start_IT(&htim3, TIM_CHANNEL_ALL);
  /* USER CODE END 2 */

  /* Infinite loop */
  /* USER CODE BEGIN WHILE */
  ws2812_set_pixel_color(&pixels_color,rgb_color[SET_RED],rgb_color[SET_GREEN],rgb_color[SET_BLUE]);


 uint8_t temp, digit0, digit1;
 float sht40_temp, sht40_humi;
 while (1)
 {
	sht40_get_th_data(&sht40_temp, &sht40_humi);
	temp = (uint8_t) round(sht40_temp);
	digit0 = temp%10;
	digit1 = temp/10;
	if(!set_color_mode) {
	  display_digit(11);
	  display_digit(10);
	  display_digit(digit0);
	  display_digit(digit1);
	  HAL_Delay(2000);
	}

	temp = (uint8_t) round(sht40_humi);
	digit0 = temp%10;
	digit1 = temp/10;
	if(!set_color_mode) {
	  display_digit(12);
	  display_digit(10);
	  display_digit(digit0);
	  display_digit(digit1);
	  HAL_Delay(2000);
	}

    /* USER CODE END WHILE */

    /* USER CODE BEGIN 3 */
  }
  /* USER CODE END 3 */
}

/**
  * @brief System Clock Configuration
  * @retval None
  */
void SystemClock_Config(void)
{
  RCC_OscInitTypeDef RCC_OscInitStruct = {0};
  RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};

  /** Initializes the RCC Oscillators according to the specified parameters
  * in the RCC_OscInitTypeDef structure.
  */
  RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
  RCC_OscInitStruct.HSEState = RCC_HSE_ON;
  RCC_OscInitStruct.HSEPredivValue = RCC_HSE_PREDIV_DIV1;
  RCC_OscInitStruct.HSIState = RCC_HSI_ON;
  RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON;
  RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
  RCC_OscInitStruct.PLL.PLLMUL = RCC_PLL_MUL5;
  if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
  {
    Error_Handler();
  }

  /** Initializes the CPU, AHB and APB buses clocks
  */
  RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
                              |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;
  RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK;
  RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
  RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2;
  RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;

  if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_1) != HAL_OK)
  {
    Error_Handler();
  }
}

/**
  * @brief I2C1 Initialization Function
  * @param None
  * @retval None
  */
static void MX_I2C1_Init(void)
{

  /* USER CODE BEGIN I2C1_Init 0 */

  /* USER CODE END I2C1_Init 0 */

  /* USER CODE BEGIN I2C1_Init 1 */

  /* USER CODE END I2C1_Init 1 */
  hi2c1.Instance = I2C1;
  hi2c1.Init.ClockSpeed = 100000;
  hi2c1.Init.DutyCycle = I2C_DUTYCYCLE_2;
  hi2c1.Init.OwnAddress1 = 0;
  hi2c1.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT;
  hi2c1.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE;
  hi2c1.Init.OwnAddress2 = 0;
  hi2c1.Init.GeneralCallMode = I2C_GENERALCALL_DISABLE;
  hi2c1.Init.NoStretchMode = I2C_NOSTRETCH_DISABLE;
  if (HAL_I2C_Init(&hi2c1) != HAL_OK)
  {
    Error_Handler();
  }
  /* USER CODE BEGIN I2C1_Init 2 */

  /* USER CODE END I2C1_Init 2 */

}

/**
  * @brief SPI1 Initialization Function
  * @param None
  * @retval None
  */
static void MX_SPI1_Init(void)
{

  /* USER CODE BEGIN SPI1_Init 0 */

  /* USER CODE END SPI1_Init 0 */

  /* USER CODE BEGIN SPI1_Init 1 */

  /* USER CODE END SPI1_Init 1 */
  /* SPI1 parameter configuration*/
  hspi1.Instance = SPI1;
  hspi1.Init.Mode = SPI_MODE_MASTER;
  hspi1.Init.Direction = SPI_DIRECTION_1LINE;
  hspi1.Init.DataSize = SPI_DATASIZE_8BIT;
  hspi1.Init.CLKPolarity = SPI_POLARITY_LOW;
  hspi1.Init.CLKPhase = SPI_PHASE_1EDGE;
  hspi1.Init.NSS = SPI_NSS_SOFT;
  hspi1.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_16;
  hspi1.Init.FirstBit = SPI_FIRSTBIT_MSB;
  hspi1.Init.TIMode = SPI_TIMODE_DISABLE;
  hspi1.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLE;
  hspi1.Init.CRCPolynomial = 10;
  if (HAL_SPI_Init(&hspi1) != HAL_OK)
  {
    Error_Handler();
  }
  /* USER CODE BEGIN SPI1_Init 2 */

  /* USER CODE END SPI1_Init 2 */

}

/**
  * @brief TIM2 Initialization Function
  * @param None
  * @retval None
  */
static void MX_TIM2_Init(void)
{

  /* USER CODE BEGIN TIM2_Init 0 */

  /* USER CODE END TIM2_Init 0 */

  TIM_ClockConfigTypeDef sClockSourceConfig = {0};
  TIM_MasterConfigTypeDef sMasterConfig = {0};

  /* USER CODE BEGIN TIM2_Init 1 */

  /* USER CODE END TIM2_Init 1 */
  htim2.Instance = TIM2;
  htim2.Init.Prescaler = 2000-1;
  htim2.Init.CounterMode = TIM_COUNTERMODE_UP;
  htim2.Init.Period = 1000-1;
  htim2.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
  htim2.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
  if (HAL_TIM_Base_Init(&htim2) != HAL_OK)
  {
    Error_Handler();
  }
  sClockSourceConfig.ClockSource = TIM_CLOCKSOURCE_INTERNAL;
  if (HAL_TIM_ConfigClockSource(&htim2, &sClockSourceConfig) != HAL_OK)
  {
    Error_Handler();
  }
  sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
  sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
  if (HAL_TIMEx_MasterConfigSynchronization(&htim2, &sMasterConfig) != HAL_OK)
  {
    Error_Handler();
  }
  /* USER CODE BEGIN TIM2_Init 2 */

  /* USER CODE END TIM2_Init 2 */

}

/**
  * @brief TIM3 Initialization Function
  * @param None
  * @retval None
  */
static void MX_TIM3_Init(void)
{

  /* USER CODE BEGIN TIM3_Init 0 */

  /* USER CODE END TIM3_Init 0 */

  TIM_Encoder_InitTypeDef sConfig = {0};
  TIM_MasterConfigTypeDef sMasterConfig = {0};

  /* USER CODE BEGIN TIM3_Init 1 */

  /* USER CODE END TIM3_Init 1 */
  htim3.Instance = TIM3;
  htim3.Init.Prescaler = 0;
  htim3.Init.CounterMode = TIM_COUNTERMODE_UP;
  htim3.Init.Period = 65535;
  htim3.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
  htim3.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE;
  sConfig.EncoderMode = TIM_ENCODERMODE_TI12;
  sConfig.IC1Polarity = TIM_ICPOLARITY_FALLING;
  sConfig.IC1Selection = TIM_ICSELECTION_DIRECTTI;
  sConfig.IC1Prescaler = TIM_ICPSC_DIV1;
  sConfig.IC1Filter = 0;
  sConfig.IC2Polarity = TIM_ICPOLARITY_FALLING;
  sConfig.IC2Selection = TIM_ICSELECTION_DIRECTTI;
  sConfig.IC2Prescaler = TIM_ICPSC_DIV1;
  sConfig.IC2Filter = 0;
  if (HAL_TIM_Encoder_Init(&htim3, &sConfig) != HAL_OK)
  {
    Error_Handler();
  }
  sMasterConfig.MasterOutputTrigger = TIM_TRGO_RESET;
  sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE;
  if (HAL_TIMEx_MasterConfigSynchronization(&htim3, &sMasterConfig) != HAL_OK)
  {
    Error_Handler();
  }
  /* USER CODE BEGIN TIM3_Init 2 */

  /* USER CODE END TIM3_Init 2 */

}

/**
  * Enable DMA controller clock
  */
static void MX_DMA_Init(void)
{

  /* DMA controller clock enable */
  __HAL_RCC_DMA1_CLK_ENABLE();

  /* DMA interrupt init */
  /* DMA1_Channel3_IRQn interrupt configuration */
  HAL_NVIC_SetPriority(DMA1_Channel3_IRQn, 0, 0);
  HAL_NVIC_EnableIRQ(DMA1_Channel3_IRQn);

}

/**
  * @brief GPIO Initialization Function
  * @param None
  * @retval None
  */
static void MX_GPIO_Init(void)
{
  GPIO_InitTypeDef GPIO_InitStruct = {0};
/* USER CODE BEGIN MX_GPIO_Init_1 */
/* USER CODE END MX_GPIO_Init_1 */

  /* GPIO Ports Clock Enable */
  __HAL_RCC_GPIOD_CLK_ENABLE();
  __HAL_RCC_GPIOA_CLK_ENABLE();
  __HAL_RCC_GPIOB_CLK_ENABLE();

  /*Configure GPIO pin : RT_SW_Pin */
  GPIO_InitStruct.Pin = RT_SW_Pin;
  GPIO_InitStruct.Mode = GPIO_MODE_IT_FALLING;
  GPIO_InitStruct.Pull = GPIO_PULLUP;
  HAL_GPIO_Init(RT_SW_GPIO_Port, &GPIO_InitStruct);

  /* EXTI interrupt init*/
  HAL_NVIC_SetPriority(EXTI3_IRQn, 0, 0);
  HAL_NVIC_EnableIRQ(EXTI3_IRQn);

/* USER CODE BEGIN MX_GPIO_Init_2 */
/* USER CODE END MX_GPIO_Init_2 */
}

/* USER CODE BEGIN 4 */

/* USER CODE END 4 */

/**
  * @brief  This function is executed in case of error occurrence.
  * @retval None
  */
void Error_Handler(void)
{
  /* USER CODE BEGIN Error_Handler_Debug */
  /* User can add his own implementation to report the HAL error return state */
  __disable_irq();
  while (1)
  {
  }
  /* USER CODE END Error_Handler_Debug */
}

#ifdef  USE_FULL_ASSERT
/**
  * @brief  Reports the name of the source file and the source line number
  *         where the assert_param error has occurred.
  * @param  file: pointer to the source file name
  * @param  line: assert_param error line source number
  * @retval None
  */
void assert_failed(uint8_t *file, uint32_t line)
{
  /* USER CODE BEGIN 6 */
  /* User can add his own implementation to report the file name and line number,
     ex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
  /* USER CODE END 6 */
}
#endif /* USE_FULL_ASSERT */

ws2812.c

#include "main.h"
#include "ws2812.h"
#include "string.h"

extern SPI_HandleTypeDef hspi1;
extern DMA_HandleTypeDef hdma_spi1_tx;

void ws2812_set_pixel_color(ws2812_pixel_color_t *ws2812_pixels_color, uint8_t red, uint8_t green, uint8_t blue) {
	ws2812_pixels_color->green.bit0 = green >> 0 & 0x01 ? WS2812_BIT_1:WS2812_BIT_0;
	ws2812_pixels_color->green.bit1 = green >> 1 & 0x01 ? WS2812_BIT_1:WS2812_BIT_0;
	ws2812_pixels_color->green.bit2 = green >> 2 & 0x01 ? WS2812_BIT_1:WS2812_BIT_0;
	ws2812_pixels_color->green.bit3 = green >> 3 & 0x01 ? WS2812_BIT_1:WS2812_BIT_0;
	ws2812_pixels_color->green.bit4 = green >> 4 & 0x01 ? WS2812_BIT_1:WS2812_BIT_0;
	ws2812_pixels_color->green.bit5 = green >> 5 & 0x01 ? WS2812_BIT_1:WS2812_BIT_0;
	ws2812_pixels_color->green.bit6 = green >> 6 & 0x01 ? WS2812_BIT_1:WS2812_BIT_0;
	ws2812_pixels_color->green.bit7 = green >> 7 & 0x01 ? WS2812_BIT_1:WS2812_BIT_0;

	ws2812_pixels_color->red.bit0 = red >> 0 & 0x01 ? WS2812_BIT_1:WS2812_BIT_0;
	ws2812_pixels_color->red.bit1 = red >> 1 & 0x01 ? WS2812_BIT_1:WS2812_BIT_0;
	ws2812_pixels_color->red.bit2 = red >> 2 & 0x01 ? WS2812_BIT_1:WS2812_BIT_0;
	ws2812_pixels_color->red.bit3 = red >> 3 & 0x01 ? WS2812_BIT_1:WS2812_BIT_0;
	ws2812_pixels_color->red.bit4 = red >> 4 & 0x01 ? WS2812_BIT_1:WS2812_BIT_0;
	ws2812_pixels_color->red.bit5 = red >> 5 & 0x01 ? WS2812_BIT_1:WS2812_BIT_0;
	ws2812_pixels_color->red.bit6 = red >> 6 & 0x01 ? WS2812_BIT_1:WS2812_BIT_0;
	ws2812_pixels_color->red.bit7 = red >> 7 & 0x01 ? WS2812_BIT_1:WS2812_BIT_0;

	ws2812_pixels_color->blue.bit0 = blue >> 0 & 0x01 ? WS2812_BIT_1:WS2812_BIT_0;
	ws2812_pixels_color->blue.bit1 = blue >> 1 & 0x01 ? WS2812_BIT_1:WS2812_BIT_0;
	ws2812_pixels_color->blue.bit2 = blue >> 2 & 0x01 ? WS2812_BIT_1:WS2812_BIT_0;
	ws2812_pixels_color->blue.bit3 = blue >> 3 & 0x01 ? WS2812_BIT_1:WS2812_BIT_0;
	ws2812_pixels_color->blue.bit4 = blue >> 4 & 0x01 ? WS2812_BIT_1:WS2812_BIT_0;
	ws2812_pixels_color->blue.bit5 = blue >> 5 & 0x01 ? WS2812_BIT_1:WS2812_BIT_0;
	ws2812_pixels_color->blue.bit6 = blue >> 6 & 0x01 ? WS2812_BIT_1:WS2812_BIT_0;
	ws2812_pixels_color->blue.bit7 = blue >> 7 & 0x01 ? WS2812_BIT_1:WS2812_BIT_0;
}

void ws2812_display_pixel(ws2812_pixel_color_t *ws2812_pixels_color,uint8_t show) {
	if (show) {
		HAL_SPI_Transmit(&hspi1, (uint8_t*)ws2812_pixels_color, WS2812_PIXEL_BYTES, 1000);
	} else {
		ws2812_pixel_color_t black;
		ws2812_set_pixel_color(&black, 0, 0, 0);
		HAL_SPI_Transmit(&hspi1, (uint8_t*)&black  , WS2812_PIXEL_BYTES, 1000);
	}
}



ws2812.h

#ifndef INC_WS2812_H_
#define INC_WS2812_H_

#define WS2812_BIT_1 0b110
#define WS2812_BIT_0 0b100

#define WS2812_PIXEL_BYTES	12 // 3*4, 4 bytes for red, green or blue

typedef	struct {
	uint8_t bit6:4;  //low nibble
	uint8_t bit7:4;  //high nibble for byte one
	uint8_t bit4:4;
	uint8_t bit5:4;
	uint8_t bit2:4;
	uint8_t bit3:4;
	uint8_t bit0:4;
	uint8_t bit1:4;
} ws2812_color_bits_t;

typedef struct {
	ws2812_color_bits_t green;
	ws2812_color_bits_t red;
	ws2812_color_bits_t blue;
}ws2812_pixel_color_t;


void ws2812_display_pixel(ws2812_pixel_color_t *ws2812_pixels_color,uint8_t show);
void ws2812_set_pixel_color(ws2812_pixel_color_t *ws2812_pixels_color, uint8_t red, uint8_t green, uint8_t blue);


#endif /* INC_WS2812_H_ */

sht40.c

#include "sht40.h"


void sht40_get_th_data(float *temp, float *humi) {
        uint8_t buff[8];

        float t_ticks, rh_ticks, t_degC, rh_pRH;
        buff[0] = 0xFD;
        //ret = i2c_write_blocking(I2C_SHT40_PORT, 0x44, buff,1,false);
        HAL_I2C_Master_Transmit(&hi2c1, 0x44<<1, buff, 1, 1000);
        HAL_Delay(10);
        //ret = i2c_read_blocking(I2C_SHT40_PORT, 0x44, buff, 6, false);
        HAL_I2C_Master_Receive(&hi2c1, 0x44<<1, buff, 6,1000);
        t_ticks = buff[0] * 256 + buff[1];
        //checksum_t = rx_bytes[2]
        rh_ticks = buff[3] * 256 + buff[4];
        //checksum_rh = rx_bytes[5]
        t_degC = -45 + 175 * t_ticks/65535;
        rh_pRH = -6 + 125 * rh_ticks/65535;
        if (rh_pRH > 100)
            rh_pRH = 100;
        if (rh_pRH < 0)
            rh_pRH = 0;

        *temp = t_degC;
        *humi = rh_pRH;
        //printf("temp:%f, himidity:%f\n", t_degC, rh_pRH);
}



sht40.h

#ifndef __SHT40_H__
#define __SHT40_H__
#include "main.h"
extern I2C_HandleTypeDef hi2c1;


void sht40_get_th_data(float* temp, float* humi);

#endif

WS2812_F103.ioc

#MicroXplorer Configuration settings - do not modify
CAD.formats=
CAD.pinconfig=
CAD.provider=
Dma.Request0=SPI1_TX
Dma.RequestsNb=1
Dma.SPI1_TX.0.Direction=DMA_MEMORY_TO_PERIPH
Dma.SPI1_TX.0.Instance=DMA1_Channel3
Dma.SPI1_TX.0.MemDataAlignment=DMA_MDATAALIGN_BYTE
Dma.SPI1_TX.0.MemInc=DMA_MINC_ENABLE
Dma.SPI1_TX.0.Mode=DMA_NORMAL
Dma.SPI1_TX.0.PeriphDataAlignment=DMA_PDATAALIGN_BYTE
Dma.SPI1_TX.0.PeriphInc=DMA_PINC_DISABLE
Dma.SPI1_TX.0.Priority=DMA_PRIORITY_LOW
Dma.SPI1_TX.0.RequestParameters=Instance,Direction,PeriphInc,MemInc,PeriphDataAlignment,MemDataAlignment,Mode,Priority
File.Version=6
GPIO.groupedBy=Group By Peripherals
KeepUserPlacement=false
Mcu.CPN=STM32F103C8T6
Mcu.Family=STM32F1
Mcu.IP0=DMA
Mcu.IP1=I2C1
Mcu.IP2=NVIC
Mcu.IP3=RCC
Mcu.IP4=SPI1
Mcu.IP5=SYS
Mcu.IP6=TIM2
Mcu.IP7=TIM3
Mcu.IPNb=8
Mcu.Name=STM32F103C(8-B)Tx
Mcu.Package=LQFP48
Mcu.Pin0=PD0-OSC_IN
Mcu.Pin1=PD1-OSC_OUT
Mcu.Pin10=PB7
Mcu.Pin11=VP_SYS_VS_Systick
Mcu.Pin12=VP_TIM2_VS_ClockSourceINT
Mcu.Pin2=PA5
Mcu.Pin3=PA7
Mcu.Pin4=PA13
Mcu.Pin5=PA14
Mcu.Pin6=PB3
Mcu.Pin7=PB4
Mcu.Pin8=PB5
Mcu.Pin9=PB6
Mcu.PinsNb=13
Mcu.ThirdPartyNb=0
Mcu.UserConstants=
Mcu.UserName=STM32F103C8Tx
MxCube.Version=6.12.0
MxDb.Version=DB.6.0.120
NVIC.BusFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.DMA1_Channel3_IRQn=true\:0\:0\:false\:false\:true\:false\:true\:true
NVIC.DebugMonitor_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.EXTI3_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true
NVIC.ForceEnableDMAVector=true
NVIC.HardFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.MemoryManagement_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.NonMaskableInt_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.PendSV_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.PriorityGroup=NVIC_PRIORITYGROUP_4
NVIC.SVCall_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
NVIC.SysTick_IRQn=true\:15\:0\:false\:false\:true\:false\:true\:false
NVIC.TIM2_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true
NVIC.TIM3_IRQn=true\:0\:0\:false\:false\:true\:true\:true\:true
NVIC.UsageFault_IRQn=true\:0\:0\:false\:false\:true\:false\:false\:false
PA13.Mode=Serial_Wire
PA13.Signal=SYS_JTMS-SWDIO
PA14.Mode=Serial_Wire
PA14.Signal=SYS_JTCK-SWCLK
PA5.Mode=Simplex_Bidirectional_Master
PA5.Signal=SPI1_SCK
PA7.Mode=Simplex_Bidirectional_Master
PA7.Signal=SPI1_MOSI
PB3.GPIOParameters=GPIO_PuPd,GPIO_Label,GPIO_ModeDefaultEXTI
PB3.GPIO_Label=RT_SW
PB3.GPIO_ModeDefaultEXTI=GPIO_MODE_IT_FALLING
PB3.GPIO_PuPd=GPIO_PULLUP
PB3.Locked=true
PB3.Signal=GPXTI3
PB4.Signal=S_TIM3_CH1
PB5.Signal=S_TIM3_CH2
PB6.Mode=I2C
PB6.Signal=I2C1_SCL
PB7.Mode=I2C
PB7.Signal=I2C1_SDA
PD0-OSC_IN.Mode=HSE-External-Oscillator
PD0-OSC_IN.Signal=RCC_OSC_IN
PD1-OSC_OUT.Mode=HSE-External-Oscillator
PD1-OSC_OUT.Signal=RCC_OSC_OUT
PinOutPanel.RotationAngle=0
ProjectManager.AskForMigrate=true
ProjectManager.BackupPrevious=false
ProjectManager.CompilerOptimize=6
ProjectManager.ComputerToolchain=false
ProjectManager.CoupleFile=false
ProjectManager.CustomerFirmwarePackage=
ProjectManager.DefaultFWLocation=true
ProjectManager.DeletePrevious=true
ProjectManager.DeviceId=STM32F103C8Tx
ProjectManager.FirmwarePackage=STM32Cube FW_F1 V1.8.6
ProjectManager.FreePins=false
ProjectManager.HalAssertFull=false
ProjectManager.HeapSize=0x200
ProjectManager.KeepUserCode=true
ProjectManager.LastFirmware=true
ProjectManager.LibraryCopy=1
ProjectManager.MainLocation=Core/Src
ProjectManager.NoMain=false
ProjectManager.PreviousToolchain=
ProjectManager.ProjectBuild=false
ProjectManager.ProjectFileName=WS2812_F103.ioc
ProjectManager.ProjectName=WS2812_F103
ProjectManager.ProjectStructure=
ProjectManager.RegisterCallBack=
ProjectManager.StackSize=0x400
ProjectManager.TargetToolchain=STM32CubeIDE
ProjectManager.ToolChainLocation=
ProjectManager.UAScriptAfterPath=
ProjectManager.UAScriptBeforePath=
ProjectManager.UnderRoot=true
ProjectManager.functionlistsort=1-SystemClock_Config-RCC-false-HAL-false,2-MX_GPIO_Init-GPIO-false-HAL-true,3-MX_DMA_Init-DMA-false-HAL-true,4-MX_SPI1_Init-SPI1-false-HAL-true,5-MX_I2C1_Init-I2C1-false-HAL-true,6-MX_TIM2_Init-TIM2-false-HAL-true,7-MX_TIM3_Init-TIM3-false-HAL-true
RCC.ADCFreqValue=20000000
RCC.AHBFreq_Value=40000000
RCC.APB1CLKDivider=RCC_HCLK_DIV2
RCC.APB1Freq_Value=20000000
RCC.APB1TimFreq_Value=40000000
RCC.APB2Freq_Value=40000000
RCC.APB2TimFreq_Value=40000000
RCC.FCLKCortexFreq_Value=40000000
RCC.FamilyName=M
RCC.HCLKFreq_Value=40000000
RCC.IPParameters=ADCFreqValue,AHBFreq_Value,APB1CLKDivider,APB1Freq_Value,APB1TimFreq_Value,APB2Freq_Value,APB2TimFreq_Value,FCLKCortexFreq_Value,FamilyName,HCLKFreq_Value,MCOFreq_Value,PLLCLKFreq_Value,PLLMCOFreq_Value,PLLMUL,PLLSourceVirtual,SYSCLKFreq_VALUE,SYSCLKSource,TimSysFreq_Value,USBFreq_Value,VCOOutput2Freq_Value
RCC.MCOFreq_Value=40000000
RCC.PLLCLKFreq_Value=40000000
RCC.PLLMCOFreq_Value=20000000
RCC.PLLMUL=RCC_PLL_MUL5
RCC.PLLSourceVirtual=RCC_PLLSOURCE_HSE
RCC.SYSCLKFreq_VALUE=40000000
RCC.SYSCLKSource=RCC_SYSCLKSOURCE_PLLCLK
RCC.TimSysFreq_Value=40000000
RCC.USBFreq_Value=40000000
RCC.VCOOutput2Freq_Value=8000000
SH.GPXTI3.0=GPIO_EXTI3
SH.GPXTI3.ConfNb=1
SH.S_TIM3_CH1.0=TIM3_CH1,Encoder_Interface
SH.S_TIM3_CH1.ConfNb=1
SH.S_TIM3_CH2.0=TIM3_CH2,Encoder_Interface
SH.S_TIM3_CH2.ConfNb=1
SPI1.BaudRatePrescaler=SPI_BAUDRATEPRESCALER_16
SPI1.CalculateBaudRate=2.5 MBits/s
SPI1.Direction=SPI_DIRECTION_1LINE
SPI1.IPParameters=VirtualType,Mode,Direction,BaudRatePrescaler,CalculateBaudRate
SPI1.Mode=SPI_MODE_MASTER
SPI1.VirtualType=VM_MASTER
TIM2.IPParameters=Prescaler,Period
TIM2.Period=1000-1
TIM2.Prescaler=2000-1
TIM3.EncoderMode=TIM_ENCODERMODE_TI12
TIM3.IC1Polarity=TIM_ICPOLARITY_FALLING
TIM3.IC2Polarity=TIM_ICPOLARITY_FALLING
TIM3.IPParameters=EncoderMode,IC1Polarity,IC2Polarity
VP_SYS_VS_Systick.Mode=SysTick
VP_SYS_VS_Systick.Signal=SYS_VS_Systick
VP_TIM2_VS_ClockSourceINT.Mode=Internal
VP_TIM2_VS_ClockSourceINT.Signal=TIM2_VS_ClockSourceINT
board=custom
isbadioc=false



2024年9月12日 星期四

[Raspberry Pi Pico W] Bluetooth on-screen mouse using LVGL and Btstack libraries

 本篇文章介紹HID over Gatt(HOG) bluetooth mouse. 使用Btstack library. 使用者介面為觸控螢幕並使用LVGL graphic library。


 軟體部份:

有關hog mouse主要修改自Btstack example hog_mouse_demo.c程式,詳細內容參閱文末的hog_mouse.h檔案。

HID report 


LVGL library移植至Raspberry Pi Pico程式碼如前篇文章所示:

[Raspberry Pi Pico (c-sdk)] LVGL Graphics Library & Pico PIO TFT display driver(Serial or Parallel)


在本文章中修改部份程式碼,附於文末。

成果展示:




程式碼:

  • pico_tft.c
#include "stdio.h"
#include "stdlib.h"
#include "pico/stdlib.h"
#include "hardware/clocks.h"
#include "string.h"

#include "registers.h"
#include "pico_tft.pio.h"
#include "pico_tft.h"
#include "hardware/dma.h"

#define MAX_BYTE_TRANS (TFT_WIDTH*TFT_HEIGHT*2)

#define PICO_TFT_SERIAL
#define PICO_TFT_DMA

// MADCTL register: 			MY,MX,MV,ML,BGR,MH,x,x
static uint8_t TFT_MADCTL_PORTRAIT  		=	0b01001000;
static uint8_t TFT_MADCTL_LANDSCAPE  		=	0b00101000;
static uint8_t TFT_MADCTL_PORTRAIT_MIRROR  =	0b10001000;
static uint8_t TFT_MADCTL_LANDSCAPE_MIRROR = 	0b11101000;
static uint16_t tft_width;
static uint16_t tft_height;
static uint8_t tft_orientation;

PIO tft_pio = pio1;
uint tft_sm=0;
uint in_out_base_pin=4;
uint set_base_pin=12;
uint sideset_base_pin=16; 
uint s_in_out_base_pin=19; 

int tft_dma_channel;

void tft_cmd(uint32_t cmd, uint32_t count, uint8_t *param)
{
    pio_sm_restart(tft_pio, tft_sm);
    #ifdef PICO_TFT_SERIAL
    pio_sm_put_blocking(tft_pio, tft_sm, cmd << 24);
    #endif
    #ifdef PICO_TFT_PARALLEL
    pio_sm_put_blocking(tft_pio, tft_sm, cmd);
    #endif
    
    pio_sm_put_blocking(tft_pio, tft_sm, count);
    for (int i = 0; i < count; i++)
    {
        #ifdef PICO_TFT_SERIAL
        pio_sm_put_blocking(tft_pio, tft_sm, param[i]<<24);
        #endif
        #ifdef PICO_TFT_PARALLEL
        pio_sm_put_blocking(tft_pio, tft_sm, param[i]);
        #endif
    }
}
//#ifdef PICO_TFT_DMA
void tft_cmd_dma(uint32_t cmd, uint32_t count, uint8_t *param)
{
    #ifdef PICO_TFT_SERIAL
    tft_cmd(cmd, count, param);
    return;
    #endif 
    pio_sm_restart(tft_pio, tft_sm);
    pio_sm_put_blocking(tft_pio, tft_sm, cmd);
    pio_sm_put_blocking(tft_pio, tft_sm, count);
    dma_channel_set_trans_count(tft_dma_channel, count >> DMA_SIZE_8, false);
    dma_channel_set_read_addr(tft_dma_channel, param, false);
    dma_channel_start(tft_dma_channel);
    dma_channel_wait_for_finish_blocking(tft_dma_channel);
    
}
//#endif
void tft_pio_cmd_init(PIO pio, uint sm, uint in_out_base,  uint set_sideset, uint32_t freq) {
    uint offset=0;
    pio_sm_config c;
    #ifdef PICO_TFT_PARALLEL
    offset = pio_add_program(pio, &tft_pio_parallel_program);
    c = tft_pio_parallel_program_get_default_config(offset);
    for (int i=0; i < 8; i++) pio_gpio_init(pio, in_out_base+i);
    for (int i=0; i < 4; i++) pio_gpio_init(pio, set_sideset+i);
    pio_sm_set_consecutive_pindirs(pio, sm, in_out_base, 8, true);
    pio_sm_set_consecutive_pindirs(pio, sm, set_base, 4, true);
    sm_config_set_in_pins(&c, in_out_base);
    sm_config_set_out_pins(&c, in_out_base, 8);
    sm_config_set_set_pins(&c, set_sideset, 4);
    sm_config_set_out_shift(&c, true, false, 8);
    sm_config_set_in_shift(&c, false, false, 8);
    #endif
    #ifdef PICO_TFT_SERIAL
    offset = pio_add_program(pio, &tft_pio_serial_program);
    c = tft_pio_serial_program_get_default_config(offset);
    pio_gpio_init(pio, in_out_base);
    for (int i=0; i < 3; i++) pio_gpio_init(pio, set_sideset+i);
    pio_sm_set_consecutive_pindirs(pio, sm, in_out_base, 1, true);
    pio_sm_set_consecutive_pindirs(pio, sm, set_sideset, 3, true);
    sm_config_set_in_pins(&c, in_out_base);
    sm_config_set_out_pins(&c, in_out_base, 1);
    sm_config_set_sideset_pins(&c, set_sideset);
    sm_config_set_out_shift(&c, false, false, 8);
    sm_config_set_in_shift(&c, true, false, 8);
    #endif
       
    //sm_config_set_fifo_join(&c, PIO_FIFO_JOIN_TX);
    
    float div = clock_get_hz(clk_sys)/freq;
    sm_config_set_clkdiv(&c, div);
    //sm_config_set_clkdiv(&c, 1.25);
    
    #ifdef PICO_TFT_DMA
    /*   DMA  */
    tft_dma_channel = dma_claim_unused_channel(true);
    dma_channel_config dc = dma_channel_get_default_config(tft_dma_channel);
    channel_config_set_write_increment(&dc, false);
    channel_config_set_read_increment(&dc, true);
    channel_config_set_dreq(&dc, pio_get_dreq(pio, sm, true));
    channel_config_set_transfer_data_size(&dc, DMA_SIZE_8); //DMA_SIZE_8,16,32
    
    dma_channel_configure(tft_dma_channel, &dc, (void*) (PIO1_BASE+PIO_TXF0_OFFSET), 
             NULL, MAX_BYTE_TRANS>> DMA_SIZE_8, false); //DMA_SIZE_8 or 16 or 32
    /*  DMA */
    #endif 
    pio_sm_init(pio, sm, offset, &c);
    pio_sm_set_enabled(pio, sm, true);
}

/* tft draw functions*/
uint16_t tft_color_565RGB(uint8_t R, uint8_t G, uint8_t B) {
    uint16_t c;
    c = (((uint16_t)R)>>3)<<11 | (((uint16_t)G)>>2) << 5 | ((uint16_t)B)>>3;
    return c;
}
void tft_memory_write_window(uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2)
{
	uint8_t addr[4];
    addr[0]=(uint8_t)(x1 >> 8);
    addr[1]= (uint8_t)(x1 & 0xff);
    addr[2]= (uint8_t)(x2 >> 8);
    addr[3]= (uint8_t)(x2 & 0xff);
    tft_cmd(TFT_COLADDRSET, 4,   addr);

    addr[0]=(uint8_t)(y1 >> 8);
    addr[1]= (uint8_t)(y1 & 0xff);
    addr[2]= (uint8_t)(y2 >> 8);
    addr[3]= (uint8_t)(y2 & 0xff);
	tft_cmd(TFT_PAGEADDRSET, 4,   addr );

    tft_cmd(TFT_MEMORYWRITE, 0, NULL);
}

void tft_set_address_window(uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2)
{
	uint8_t addr[4];
    addr[0]=(uint8_t)(x1 >> 8);
    addr[1]= (uint8_t)(x1 & 0xff);
    addr[2]= (uint8_t)(x2 >> 8);
    addr[3]= (uint8_t)(x2 & 0xff);
    tft_cmd(TFT_COLADDRSET, 4,  addr);

    addr[0]=(uint8_t)(y1 >> 8);
    addr[1]= (uint8_t)(y1 & 0xff);
    addr[2]= (uint8_t)(y2 >> 8);
    addr[3]= (uint8_t)(y2 & 0xff);
	tft_cmd(TFT_PAGEADDRSET, 4,  addr );
}

/* put color at point*/
void tft_draw_pixel(uint16_t x, uint16_t y, uint16_t color)
{
    if ( x < 0 || x > TFT_WIDTH-1 || y < 0 || y > TFT_HEIGHT-1) {
        printf("over range,x,y\n");
        return;
    }
	tft_set_address_window(x,y,x,y);
    tft_cmd(TFT_MEMORYWRITE, 2,  (uint8_t[2]){(uint8_t)(color >> 8), (uint8_t)color});
}

uint16_t tft_get_width() {
    return tft_width;
}

uint16_t tft_get_height() {
    return tft_height;
}

uint8_t tft_get_orientation() {
    return tft_orientation;
}
void tft_set_orientation(uint8_t orientation) {
    tft_orientation = orientation;
    switch (orientation) {
        case TFT_ORIENTATION_PORTRAIT:
            tft_cmd(TFT_MADCTL, 1,  (uint8_t[1]){TFT_MADCTL_PORTRAIT});
            tft_width = TFT_WIDTH;
            tft_height = TFT_HEIGHT;
        break;
        case TFT_ORIENTATION_PORTRAIT_MIRROR:
            tft_cmd(TFT_MADCTL, 1,  (uint8_t[1]){TFT_MADCTL_PORTRAIT_MIRROR});
            tft_width = TFT_WIDTH;
            tft_height = TFT_HEIGHT;
        break;
        case TFT_ORIENTATION_LANDSCAPE:
            tft_cmd(TFT_MADCTL, 1,  (uint8_t[1]){TFT_MADCTL_LANDSCAPE});
            tft_width = TFT_HEIGHT;
            tft_height = TFT_WIDTH;
        break;
        case TFT_ORIENTATION_LANDSCAPE_MIRROR:
            tft_cmd(TFT_MADCTL, 1,  (uint8_t[1]){TFT_MADCTL_LANDSCAPE_MIRROR});
            tft_width = TFT_HEIGHT;
            tft_height = TFT_WIDTH;
        break;
    }

}
void tft_init_config() {
	tft_cmd(TFT_SOFTRESET, 1,  NULL);
    sleep_ms(120);
    tft_cmd(TFT_SLEEPOUT, 0,  NULL);
    sleep_ms(120);

    tft_cmd(TFT_COMMANDSET, 1,  (uint8_t[1]){0xC3}); //enable part 1
    tft_cmd(TFT_COMMANDSET, 1,  (uint8_t[1]){0x96}); //enable part 2
    //tft_cmd(TFT_MADCTL, 1,  (uint8_t[1]){0x88}); //MY,MX,MV,ML,BRG,MH,0,0(24), 0:RGB
    tft_set_orientation(TFT_ORIENTATION_PORTRAIT);
    tft_cmd(TFT_PIXELFORMAT, 1,  (uint8_t[1]){0x05}); //0x05:RGB565, 0x06 RGB666
    tft_cmd(TFT_DSIPLAY_INVER, 1,  (uint8_t[1]){0x01}); // 1-dot
    //tft_cmd(TFT_DISPLAYFUNC, 3,  (uint8_t[3]){0x0A, 0x82, 0x27});  // ILI9342
    tft_cmd(TFT_DISPLAYFUNC, 3,  (uint8_t[3]){0x80, 0x02, 0x3B}); // ST7796
    tft_cmd(TFT_DISP_OUTPUT_CTRL_ADJUST, 8,  (uint8_t[8])
                {0x40,
                 0x8A,
                 0x00,
                 0x00,
                 0x29,  //Source eqaulizing period time= 22.5 us
                 0x19,  //Timing for "Gate start"=25 (Tclk)
                 0xA5,  //Timing for "Gate End"=37 (Tclk), Gate driver EQ function ON
                 0x33}); // ST7796

    tft_cmd(TFT_POWERCONTROL2, 1,  (uint8_t[1]){0x06}); // 0x05 :3.3V
    tft_cmd(TFT_POWERCONTROL3, 1,  (uint8_t[1]){0xA7});
    tft_cmd(TFT_VCOMCONTROL1, 1,  (uint8_t[1]){0x18});
    sleep_ms(120);
    tft_cmd(TFT_PGAMCOR, 14, (uint8_t[14]){ 0xf0, 0x09, 0x0b, 0x06, 0x04, 0x15, 0x2f, 0x54, 0x42, 0x3c, 0x17, 0x14, 0x18, 0x1b});
    tft_cmd(TFT_NGAMCOR, 14, (uint8_t[14]){ 0xe0, 0x09, 0x0b, 0x06, 0x04, 0x03, 0x2b, 0x43, 0x42, 0x3b, 0x16, 0x14, 0x17, 0x1b}); 
    sleep_ms(120);
    tft_cmd(TFT_COMMANDSET, 1,  (uint8_t[1]){0x3C}); // disable part 1
    tft_cmd(TFT_COMMANDSET, 1,  (uint8_t[1]){0x69}); // disable part 2

    tft_cmd(TFT_DISPLAYOFF, 0,  NULL);
    sleep_ms(120);    
    tft_cmd(TFT_DISPLAYON, 0,  NULL);
    sleep_ms(500);
    
}
void tft_init(PIO pio, uint sm, uint din_base, uint csx_dcx_sck_side_base_pin) {
    tft_pio = pio;
    tft_sm = sm;
    #ifdef PICO_TFT_PARALLEL
        in_out_base_pin = din_base;
        set_base_pin = csx_dcx_sck_side_base_pin;
        tft_pio_cmd_init(tft_pio, tft_sm, in_out_base_pin, set_base_pin, 70000000);  //pio freq
    #endif
    #ifdef PICO_TFT_SERIAL
        s_in_out_base_pin = din_base;
        sideset_base_pin = csx_dcx_sck_side_base_pin;
        tft_pio_cmd_init(tft_pio, tft_sm, s_in_out_base_pin, sideset_base_pin, 90000000/* 62.5M baud rate for SPI*/);  //pio freq  
    #endif 
    tft_init_config();
    
}

  
  • pico_tft.h
#ifndef  _TFT_H_
#define _TFT_H_

#define TFT_WIDTH   320
#define TFT_HEIGHT  480

enum {
    TFT_ORIENTATION_PORTRAIT=0,
    TFT_ORIENTATION_LANDSCAPE,
    TFT_ORIENTATION_PORTRAIT_MIRROR,
    TFT_ORIENTATION_LANDSCAPE_MIRROR,
};     

#include "pico/stdlib.h"

#include "hardware/pio.h"
#include "pico_tft_lvgl.h"


void tft_init(PIO pio, uint sm, uint din_base, uint csx_dcx_sck_side_base_pin);
void tft_init_config();
void tft_draw_pixel(uint16_t x, uint16_t y, uint16_t color);
void tft_set_address_window(uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2);
void tft_cmd(uint32_t cmd, uint32_t count,  uint8_t *param);
void tft_cmd_dma(uint32_t cmd, uint32_t count,  uint8_t *param);
uint16_t tft_color_565RGB(uint8_t R, uint8_t G, uint8_t B);
void tft_lv_draw_bitmap(uint16_t x, uint16_t y, uint16_t width, uint16_t height, uint8_t *bitmap);
void tft_pio_cmd_init(PIO pio, uint sm, uint out_base,  uint set_base, uint32_t freq);

uint16_t tft_get_width();
uint16_t tft_get_height();
uint8_t tft_get_orientation();
void tft_set_orientation(uint8_t orientation);

#endif
  
  • xpt2046.c
#include "stdio.h"
#include "stdlib.h"
#include "xpt2046.h"
#include "hardware/spi.h"
#include "hardware/gpio.h"
#include "pico/stdlib.h"
#include "pico_tft.h"

uint32_t xpt2046_event=0;
uint8_t READ_X = 0xD0;
uint8_t READ_Y = 0x90;
#define XPT_WIDTH  320
#define XPT_HEIGHT 480

bool xpt2046_getXY(uint16_t *x, uint16_t *y) {
   
    uint8_t temp[2];
    uint16_t raw_x, raw_y;
    uint16_t est_raw_x, est_raw_y;
    uint32_t avg_x = 0;
    uint32_t avg_y = 0;
     uint8_t nsamples = 0;
    uint8_t SAMPLES=10;

     gpio_put(XPT2046_CS, false);  
     if(gpio_get(XPT2046_IRQ_GPIO)) return false; 
     busy_wait_ms(10);
    //first pass
    SAMPLES=20; // get first average;
    for(uint8_t i = 0; i < SAMPLES; i++, nsamples++)
    {
        if(gpio_get(XPT2046_IRQ_GPIO)) {
            break;
        }
        spi_write_blocking(XPT2046_SPI, &READ_X, 1);
        spi_read_blocking(XPT2046_SPI, 0x00, temp, 2);
        raw_x = ((uint16_t)temp[0]) << 8 | (uint16_t)temp[1];

        spi_write_blocking(XPT2046_SPI, &READ_Y, 1);
        spi_read_blocking(XPT2046_SPI, 0x00, temp, 2);
        raw_y = ((uint16_t)temp[0]) << 8 | (uint16_t)temp[1];

        avg_x += raw_x;
        avg_y += raw_y;
    }  

    if(nsamples < SAMPLES)
        return false;

    gpio_put(XPT2046_CS, true);
    raw_x = (avg_x / SAMPLES);
    raw_y = (avg_y / SAMPLES);

    if(raw_x < XPT2046_MIN_RAW_X || raw_x > XPT2046_MAX_RAW_X) return false;
    if(raw_y < XPT2046_MIN_RAW_Y || raw_y > XPT2046_MAX_RAW_Y)  return false;  
    
    uint16_t tx,ty;
    tx = (raw_x - XPT2046_MIN_RAW_X) * XPT_WIDTH  / (XPT2046_MAX_RAW_X - XPT2046_MIN_RAW_X);
    ty = (raw_y - XPT2046_MIN_RAW_Y) * XPT_HEIGHT / (XPT2046_MAX_RAW_Y - XPT2046_MIN_RAW_Y);
   
    // adjust for TFT orientation
    uint8_t lot = tft_get_orientation();
		switch (lot)
		{
		case TFT_ORIENTATION_PORTRAIT:
			*x=tx;
			*y=TFT_HEIGHT-ty;
			break;
		case TFT_ORIENTATION_LANDSCAPE:
			*x=TFT_HEIGHT-ty;
			*y=TFT_WIDTH-tx;
					break;
		case TFT_ORIENTATION_PORTRAIT_MIRROR:
			*x=TFT_WIDTH-tx;
			*y=ty;
					break;
		case TFT_ORIENTATION_LANDSCAPE_MIRROR:
			*x=ty;
			*y=tx;
			break;
		}
    return true;   
}


bool xpt2046_TouchPressed()
{
    return !gpio_get(XPT2046_IRQ_GPIO);
}

void xpt2046_init() {
    gpio_init(XPT2046_IRQ_GPIO);
    gpio_init(XPT2046_MISO);
    gpio_init(XPT2046_MOSI);
    gpio_init(XPT2046_CLK);
    gpio_init(XPT2046_CS);
    gpio_set_dir(XPT2046_CS, GPIO_OUT);
    gpio_set_dir(XPT2046_IRQ_GPIO, GPIO_OUT);
    gpio_set_function(XPT2046_CLK,GPIO_FUNC_SPI);
    gpio_set_function(XPT2046_CS,GPIO_FUNC_SIO);
    gpio_set_function(XPT2046_MOSI,GPIO_FUNC_SPI);
    gpio_set_function(XPT2046_MISO,GPIO_FUNC_SPI);
    //spi_init(XPT2046_SPI,250000);
    spi_init(XPT2046_SPI,3125000); //3125000

}

extern lv_obj_t *mouse_cursor;
void xpt2046_lvgl_read_cb(struct _lv_indev_drv_t * indev, lv_indev_data_t* data) {
    uint16_t x,y;
    
    if (xpt2046_TouchPressed()) { 
        if (xpt2046_getXY(&x,&y)) {
            data->point.x = x;
            data->point.y = y;
            data->state = LV_INDEV_STATE_PRESSED; 
        } else {
            data->state = LV_INDEV_STATE_RELEASED;
        }          
    }  else {
        data->state = LV_INDEV_STATE_RELEASED;
    }
    
}
  
  • xpt2046.h
#ifndef _XPT2046_H_
#define _XPT2046_H_
#include "pico/stdlib.h"
#include "lvgl.h"

#define XPT2046_IRQ_GPIO    11 
#define XPT2046_MOSI        15 // 19
#define XPT2046_MISO        12 // 16
#define XPT2046_CS          13 // 17
#define XPT2046_CLK         14 // 18
#define XPT2046_SPI         spi1

#define XPT2046_MIN_RAW_X 1350  //2000
#define XPT2046_MAX_RAW_X 31000 //30000
#define XPT2046_MIN_RAW_Y 2050  //1500
#define XPT2046_MAX_RAW_Y 31500 //29000


void xpt2046_init();
bool xpt2046_getXY(uint16_t *x, uint16_t *y);
bool xpt2046_TouchPressed();
void xpt2046_lvgl_read_cb(struct _lv_indev_drv_t * indev, lv_indev_data_t* data);

#endif
  
  • hog_mouse.h
/* this file was modified from btstack example file:hog_mouse_demo.c*/
/*
 * Copyright (C) 2017 BlueKitchen GmbH
 *
 * Redistribution and use in source and binary forms, with or without
 * modification, are permitted provided that the following conditions
 * are met:
 *
 * 1. Redistributions of source code must retain the above copyright
 *    notice, this list of conditions and the following disclaimer.
 * 2. Redistributions in binary form must reproduce the above copyright
 *    notice, this list of conditions and the following disclaimer in the
 *    documentation and/or other materials provided with the distribution.
 * 3. Neither the name of the copyright holders nor the names of
 *    contributors may be used to endorse or promote products derived
 *    from this software without specific prior written permission.
 * 4. Any redistribution, use, or modification is done solely for
 *    personal benefit and not for any commercial purpose or for
 *    monetary gain.
 *
 * THIS SOFTWARE IS PROVIDED BY BLUEKITCHEN GMBH AND CONTRIBUTORS
 * ``AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL BLUEKITCHEN
 * GMBH OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
 * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
 * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF
 * THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
 * SUCH DAMAGE.
 *
 * Please inquire about commercial licensing options at
 * contact@bluekitchen-gmbh.com
 *
 */
#include "pico/cyw43_arch.h"
#include "btstack.h"
#include "ble/gatt-service/battery_service_server.h"
#include "ble/gatt-service/device_information_service_server.h"
#include "ble/gatt-service/hids_device.h"

#include "inttypes.h"

static struct {
    int dx;
    int dy;
    int wheel;
    uint8_t buttons;
} mouse_point;


static btstack_packet_callback_registration_t hci_event_callback_registration;
static btstack_packet_callback_registration_t l2cap_event_callback_registration;
static btstack_packet_callback_registration_t sm_event_callback_registration;
static uint8_t battery = 100;
static hci_con_handle_t con_handle = HCI_CON_HANDLE_INVALID;
static uint8_t protocol_mode = 1;
static void packet_handler (uint8_t packet_type, uint16_t channel, uint8_t *packet, uint16_t size);

const uint8_t adv_data[] = {
    // Flags general discoverable, BR/EDR not supported
    0x02, BLUETOOTH_DATA_TYPE_FLAGS, 0x06,
    // Name
    0x11, BLUETOOTH_DATA_TYPE_COMPLETE_LOCAL_NAME, 'P','i','c','o',' ','W',' ', 'H', 'I', 'D', ' ', 'M', 'o', 'u', 's', 'e',
    // 16-bit Service UUIDs
    0x03, BLUETOOTH_DATA_TYPE_COMPLETE_LIST_OF_16_BIT_SERVICE_CLASS_UUIDS, ORG_BLUETOOTH_SERVICE_HUMAN_INTERFACE_DEVICE & 0xff, ORG_BLUETOOTH_SERVICE_HUMAN_INTERFACE_DEVICE >> 8,
    // Appearance HID - Mouse (Category 15, Sub-Category 2)
    0x03, BLUETOOTH_DATA_TYPE_APPEARANCE, 0xC2, 0x03,
};
const uint8_t adv_data_len = sizeof(adv_data);

// USB HID Specification 1.1, Appendix B.2
const uint8_t hid_descriptor_mouse_boot_mode[] = {
    0x05, 0x01,                    // USAGE_PAGE (Generic Desktop)
    0x09, 0x02,                    // USAGE (Mouse)
    0xa1, 0x01,                    // COLLECTION (Application)

    0x85,  0x01,                    // Report ID 1

    0x09, 0x01,                    //   USAGE (Pointer)

    0xa1, 0x00,                    //   COLLECTION (Physical)

    0x05, 0x09,                    //     USAGE_PAGE (Button)
    0x19, 0x01,                    //     USAGE_MINIMUM (Button 1)
    0x29, 0x03,                    //     USAGE_MAXIMUM (Button 3)
    0x15, 0x00,                    //     LOGICAL_MINIMUM (0)
    0x25, 0x01,                    //     LOGICAL_MAXIMUM (1)
    0x95, 0x03,                    //     REPORT_COUNT (3)
    0x75, 0x01,                    //     REPORT_SIZE (1)
    0x81, 0x02,                    //     INPUT (Data,Var,Abs)
    0x95, 0x01,                    //     REPORT_COUNT (1)
    0x75, 0x05,                    //     REPORT_SIZE (5)
    0x81, 0x03,                    //     INPUT (Cnst,Var,Abs)

    0x05, 0x01,                    //     USAGE_PAGE (Generic Desktop)
    0x09, 0x30,                    //     USAGE (X)
    0x09, 0x31,                    //     USAGE (Y)
    0x09, 0x38,                    //     USAGE (WHEEL)
    0x15, 0x81,                    //     LOGICAL_MINIMUM (-127)
    0x25, 0x7f,                    //     LOGICAL_MAXIMUM (127)
    0x75, 0x08,                    //     REPORT_SIZE (8)
    0x95, 0x03,                    //     REPORT_COUNT (3)
    0x81, 0x06,                    //     INPUT (Data,Var,Rel)

    0xc0,                          //   END_COLLECTION
    0xc0                           // END_COLLECTION
};

static void hog_mouse_setup(void){

    // setup l2cap and
    l2cap_init();

    // setup SM: Display only
    sm_init();
    sm_set_io_capabilities(IO_CAPABILITY_DISPLAY_ONLY);
    // sm_set_authentication_requirements(SM_AUTHREQ_SECURE_CONNECTION | SM_AUTHREQ_BONDING);
    sm_set_authentication_requirements(SM_AUTHREQ_BONDING);

    // setup ATT server
    att_server_init(profile_data, NULL, NULL);

    // setup battery service
    battery_service_server_init(battery);

    // setup device information service
    device_information_service_server_init();

    // setup HID Device service
    hids_device_init(0, hid_descriptor_mouse_boot_mode, sizeof(hid_descriptor_mouse_boot_mode));

    // setup advertisements
    uint16_t adv_int_min = 0x0030;
    uint16_t adv_int_max = 0x0030;
    uint8_t adv_type = 0;
    bd_addr_t null_addr;
    memset(null_addr, 0, 6);
    gap_advertisements_set_params(adv_int_min, adv_int_max, adv_type, 0, null_addr, 0x07, 0x00);
    gap_advertisements_set_data(adv_data_len, (uint8_t*) adv_data);
    gap_advertisements_enable(1);

    // register for events
    hci_event_callback_registration.callback = &packet_handler;
    hci_add_event_handler(&hci_event_callback_registration);

    // register for connection parameter updates
    l2cap_event_callback_registration.callback = &packet_handler;
    l2cap_add_event_handler(&l2cap_event_callback_registration);

    sm_event_callback_registration.callback = &packet_handler;
    sm_add_event_handler(&sm_event_callback_registration);

    hids_device_register_packet_handler(packet_handler);

    hci_power_control(HCI_POWER_ON);
}

// HID Report sending
static void send_report(uint8_t buttons, int8_t dx, int8_t dy, int8_t wheel){
    uint8_t report[] = { buttons, (uint8_t) dx, (uint8_t) dy, (uint8_t) wheel};
    switch (protocol_mode){
        case 0:
            hids_device_send_boot_mouse_input_report(con_handle, report, sizeof(report));
            break;
        case 1:
            hids_device_send_input_report(con_handle, report, sizeof(report));
            break;
        default:
            break;
    }
}

static void mousing_can_send_now(void){
    send_report(mouse_point.buttons, mouse_point.dx, mouse_point.dy, mouse_point.wheel);
    // reset
    mouse_point.dx = 0;
    mouse_point.dy = 0;
    mouse_point.wheel=0;
    if (mouse_point.buttons){
        mouse_point.buttons = 0;
        hids_device_request_can_send_now_event(con_handle);
    }
}

static void packet_handler (uint8_t packet_type, uint16_t channel, uint8_t *packet, uint16_t size){
    UNUSED(channel);
    UNUSED(size);
    uint16_t conn_interval;

    if (packet_type != HCI_EVENT_PACKET) return;

    switch (hci_event_packet_get_type(packet)) {
        case HCI_EVENT_DISCONNECTION_COMPLETE:
            con_handle = HCI_CON_HANDLE_INVALID;
            break;
        case SM_EVENT_JUST_WORKS_REQUEST:
            sm_just_works_confirm(sm_event_just_works_request_get_handle(packet));
            break;
        case SM_EVENT_NUMERIC_COMPARISON_REQUEST:
            printf("Confirming numeric comparison: %"PRIu32"\n", sm_event_numeric_comparison_request_get_passkey(packet));
            sm_numeric_comparison_confirm(sm_event_passkey_display_number_get_handle(packet));
            break;
        case SM_EVENT_PASSKEY_DISPLAY_NUMBER:
            printf("Display Passkey: %"PRIu32"\n", sm_event_passkey_display_number_get_passkey(packet));
            break;
        case L2CAP_EVENT_CONNECTION_PARAMETER_UPDATE_RESPONSE:
            printf("L2CAP Connection Parameter Update Complete, response: %x\n", l2cap_event_connection_parameter_update_response_get_result(packet));
            break;
        case HCI_EVENT_LE_META:
            switch (hci_event_le_meta_get_subevent_code(packet)) {
                case HCI_SUBEVENT_LE_CONNECTION_COMPLETE:
                    // print connection parameters (without using float operations)
                    conn_interval = hci_subevent_le_connection_complete_get_conn_interval(packet);
                    printf("LE Connection Complete:\n");
                    printf("- Connection Interval: %u.%02u ms\n", conn_interval * 125 / 100, 25 * (conn_interval & 3));
                    printf("- Connection Latency: %u\n", hci_subevent_le_connection_complete_get_conn_latency(packet));
                    break;
                case HCI_SUBEVENT_LE_CONNECTION_UPDATE_COMPLETE:
                    // print connection parameters (without using float operations)
                    conn_interval = hci_subevent_le_connection_update_complete_get_conn_interval(packet);
                    printf("LE Connection Update:\n");
                    printf("- Connection Interval: %u.%02u ms\n", conn_interval * 125 / 100, 25 * (conn_interval & 3));
                    printf("- Connection Latency: %u\n", hci_subevent_le_connection_update_complete_get_conn_latency(packet));
                    break;
                default:
                    break;
            }
            break;  
        case HCI_EVENT_HIDS_META:
            switch (hci_event_hids_meta_get_subevent_code(packet)){
                case HIDS_SUBEVENT_INPUT_REPORT_ENABLE:
                    con_handle = hids_subevent_input_report_enable_get_con_handle(packet);
                    printf("Report Characteristic Subscribed %u\n", hids_subevent_input_report_enable_get_enable(packet));

                    // request connection param update via L2CAP following Apple Bluetooth Design Guidelines
                    // gap_request_connection_parameter_update(con_handle, 12, 12, 4, 100);    // 15 ms, 4, 1s

                    // directly update connection params via HCI following Apple Bluetooth Design Guidelines
                    // gap_update_connection_parameters(con_handle, 12, 12, 4, 100);    // 60-75 ms, 4, 1s

                    break;
                case HIDS_SUBEVENT_BOOT_KEYBOARD_INPUT_REPORT_ENABLE:
                    con_handle = hids_subevent_boot_keyboard_input_report_enable_get_con_handle(packet);
                    printf("Boot Keyboard Characteristic Subscribed %u\n", hids_subevent_boot_keyboard_input_report_enable_get_enable(packet));
                    break;
                case HIDS_SUBEVENT_BOOT_MOUSE_INPUT_REPORT_ENABLE:
                    con_handle = hids_subevent_boot_mouse_input_report_enable_get_con_handle(packet);
                    printf("Boot Mouse Characteristic Subscribed %u\n", hids_subevent_boot_mouse_input_report_enable_get_enable(packet));
                    break;
                case HIDS_SUBEVENT_PROTOCOL_MODE:
                    protocol_mode = hids_subevent_protocol_mode_get_protocol_mode(packet);
                    printf("Protocol Mode: %s mode\n", hids_subevent_protocol_mode_get_protocol_mode(packet) ? "Report" : "Boot");
                    break;
                case HIDS_SUBEVENT_CAN_SEND_NOW:
                    mousing_can_send_now();
                    break;
                default:
                    break;
            }
            break;
            
        default:
            break;
    }
}

  
  • pico_lvgl_ble_mouse.gatt
PRIMARY_SERVICE, GAP_SERVICE
CHARACTERISTIC, GAP_DEVICE_NAME, READ, "Pico W HID Mouse"

// add Battery Service
#import <battery_service.gatt>

// add Device ID Service
#import <device_information_service.gatt>

// add HID Service
#import <hids.gatt>

PRIMARY_SERVICE, GATT_SERVICE
CHARACTERISTIC, GATT_DATABASE_HASH, READ,

  
  • pico_lvbl_ble_mouse.c
#include <stdio.h>
#include "pico/stdlib.h"
#include "pico/cyw43_arch.h"

#include "picow_lvgl_ble_mouse.h"

#include "pico_lvgl.h"
#include "hog_mouse.h"

// TFT PIO setting
PIO TFT_PIO = pio0;
#define TFT_SM 0
#define TFT_SDI_GPIO 9
#define TFT_CSX_DCX_SCK_GPIO 6 // CSX=8, DCX=7, SCK=6, SIDE_SET


// mouse pad object
static lv_obj_t *mouse_cursor;
static lv_obj_t *right_button;
static lv_obj_t *left_button;
static lv_obj_t *wheel_up;
static lv_obj_t *wheel_down;

void button_press_cb(lv_event_t *e) {
    lv_event_code_t code =lv_event_get_code(e);
    lv_obj_t* obj = lv_event_get_target(e);
    if (code == LV_EVENT_PRESSED) {
        if (obj == left_button) {
            mouse_point.buttons |= 1;   // left button pressed
        }
        if (obj == right_button) {
            mouse_point.buttons |= 2;  // right button pressed
        }
        hids_device_request_can_send_now_event(con_handle);
    }
}

void rect_pad_cb(lv_event_t *e) {
    lv_event_code_t code =lv_event_get_code(e);
    static uint16_t x, y;
    static int16_t ox, oy;
    if (code == LV_EVENT_PRESSED) {
        if (!xpt2046_getXY(&ox, &oy)) {
            ox=-1; oy=-1;
        }
        mouse_point.dx=0;
        mouse_point.dy=0;

    }

    if (code == LV_EVENT_PRESSING && xpt2046_getXY(&x, &y)) {
        lv_obj_set_x(mouse_cursor, x-lv_obj_get_style_pad_left(mouse_cursor,0)-15);
        lv_obj_set_y(mouse_cursor, y-lv_obj_get_style_pad_top(mouse_cursor,0)-15);
        if (ox > 0 && oy > 0) {
            mouse_point.dx = (x-ox)*2; 
            mouse_point.dy = (y-oy)*2;
            ox=x;
            oy=y;
            hids_device_request_can_send_now_event(con_handle);
        } else {
            mouse_point.dx=0;
            mouse_point.dy=0;
        }
    }
}

void mouse_wheel_cb(lv_event_t *e) {
    lv_event_code_t code =lv_event_get_code(e);
    lv_obj_t* obj = lv_event_get_target(e);
    if (code == LV_EVENT_PRESSED || code == LV_EVENT_RELEASED) {
        mouse_point.wheel=0;
        hids_device_request_can_send_now_event(con_handle);
    }

    if (code == LV_EVENT_PRESSING) {
        if (obj == wheel_up) {
            mouse_point.wheel = 1;
        }
        if (obj == wheel_down) {
            mouse_point.wheel = -1;
        }
        hids_device_request_can_send_now_event(con_handle);
    } 
}

void mouse_pad_init() {
    left_button = lv_btn_create(lv_scr_act());
    right_button = lv_btn_create(lv_scr_act());
    lv_obj_t* rect_pad = lv_obj_create(lv_scr_act());
    lv_obj_t* wheel = lv_obj_create(lv_scr_act());

    lv_obj_set_style_pad_all(wheel, 1, 0);
    wheel_up = lv_btn_create(wheel);
    wheel_down = lv_btn_create(wheel);
    
    lv_obj_set_size(left_button, lv_pct(42)-5,lv_pct(15));
    lv_obj_set_size(right_button, lv_pct(42)-5,lv_pct(15)); 
    lv_obj_set_size(wheel, lv_pct(10),lv_pct(15));

    lv_obj_set_size(wheel_up, lv_pct(80),lv_pct(45));
    lv_obj_t *label = lv_label_create(wheel_up);
    lv_label_set_text(label, LV_SYMBOL_UP);
    lv_obj_center(label);
    lv_obj_set_size(wheel_down, lv_pct(80),lv_pct(45));
    label = lv_label_create(wheel_down);
    lv_obj_center(label);
    lv_label_set_text(label, LV_SYMBOL_DOWN);

    lv_obj_set_size(rect_pad, lv_pct(100), lv_pct(85)-4);

    lv_obj_add_event_cb(rect_pad, rect_pad_cb, LV_EVENT_ALL, NULL);
    lv_obj_set_scrollbar_mode(rect_pad, LV_SCROLLBAR_MODE_OFF);

    lv_obj_add_event_cb(left_button, button_press_cb, LV_EVENT_PRESSED, NULL);
    lv_obj_add_event_cb(right_button, button_press_cb, LV_EVENT_PRESSED, NULL);

    lv_obj_add_event_cb(wheel_up, mouse_wheel_cb, LV_EVENT_ALL, NULL);
    lv_obj_add_event_cb(wheel_down, mouse_wheel_cb, LV_EVENT_ALL, NULL);
   
    lv_obj_align(rect_pad, LV_ALIGN_TOP_MID, 0,0); 
    
    lv_obj_align(wheel, LV_ALIGN_BOTTOM_MID, 0, -10);
    lv_obj_align_to(left_button, wheel, LV_ALIGN_OUT_LEFT_TOP, -10, 0);
    lv_obj_align_to(right_button, wheel, LV_ALIGN_OUT_RIGHT_TOP, 10, 0);

    static lv_style_t button_style;
    lv_style_init(&button_style);
    lv_style_set_bg_color(&button_style, lv_color_hex(0xaaffff));
    lv_style_set_border_color(&button_style, lv_color_hex(0x0000ff));
    lv_style_set_border_width(&button_style, 2);
    lv_style_set_shadow_color(&button_style, lv_color_black());
    lv_style_set_shadow_ofs_x(&button_style, 2);
    lv_style_set_shadow_ofs_y(&button_style, 2);

    lv_obj_add_style(left_button, &button_style,0);
    lv_obj_add_style(right_button, &button_style,0);

    lv_obj_align(wheel_up, LV_ALIGN_TOP_MID, 0, 0);
    lv_obj_align(wheel_down, LV_ALIGN_BOTTOM_MID, 0, -2);
    
    mouse_cursor = lv_obj_create(rect_pad);
    lv_obj_set_style_bg_color(mouse_cursor, lv_color_hex(0xFF0000), 0);
    lv_obj_set_style_radius(mouse_cursor, LV_RADIUS_CIRCLE, 0);
    lv_obj_set_style_border_color(mouse_cursor, lv_color_hex(0xE08080), 0);
    lv_obj_set_style_border_width(mouse_cursor, 8, 0);
    lv_obj_set_size(mouse_cursor,30,30);
    lv_obj_set_pos(mouse_cursor, lv_pct(50),lv_pct(50));
    
}

int main()
{
    stdio_init_all();

    if (cyw43_arch_init()) {
        printf("cyw43_arch_init error\n");
        return 0;
    }

    pico_lvgl_tft_init(TFT_PIO, TFT_SM, TFT_SDI_GPIO, TFT_CSX_DCX_SCK_GPIO);
    tft_set_orientation(TFT_ORIENTATION_LANDSCAPE);
    
    pico_lvgl_display_init(5);
    pico_lvgl_xpt2046_init();

    mouse_pad_init();

    hog_mouse_setup();
    while (true) {
        lv_timer_handler();
        sleep_ms(5);
    }
}

  
  • CMakeLists.txt
# == DO NEVER EDIT THE NEXT LINES for Raspberry Pi Pico VS Code Extension to work ==
if(WIN32)
    set(USERHOME $ENV{USERPROFILE})
else()
    set(USERHOME $ENV{HOME})
endif()
set(sdkVersion 2.0.0)
set(toolchainVersion 13_2_Rel1)
set(picotoolVersion 2.0.0)
include(${USERHOME}/.pico-sdk/cmake/pico-vscode.cmake)
# ====================================================================================
# Generated Cmake Pico project file

cmake_minimum_required(VERSION 3.13)

set(CMAKE_C_STANDARD 11)
set(CMAKE_CXX_STANDARD 17)
set(CMAKE_EXPORT_COMPILE_COMMANDS ON)

# Initialise pico_sdk from installed location
# (note this can come from environment, CMake cache etc)

# == DO NEVER EDIT THE NEXT LINES for Raspberry Pi Pico VS Code Extension to work ==
if(WIN32)
    set(USERHOME $ENV{USERPROFILE})
else()
    set(USERHOME $ENV{HOME})
endif()
set(sdkVersion 2.0.0)
set(toolchainVersion 13_2_Rel1)
set(picotoolVersion 2.0.0)
include(${USERHOME}/.pico-sdk/cmake/pico-vscode.cmake)
# ====================================================================================
set(PICO_BOARD pico_w CACHE STRING "Board type")

# Pull in Raspberry Pi Pico SDK (must be before project)
include(pico_sdk_import.cmake)

project(picow_lvgl_ble_mouse C CXX ASM)

# Initialise the Raspberry Pi Pico SDK
pico_sdk_init()

# Add executable. Default name is the project name, version 0.1

add_executable(picow_lvgl_ble_mouse picow_lvgl_ble_mouse.c )

pico_set_program_name(picow_lvgl_ble_mouse "picow_lvgl_ble_mouse")
pico_set_program_version(picow_lvgl_ble_mouse "0.1")

# Modify the below lines to enable/disable output over UART/USB
pico_enable_stdio_uart(picow_lvgl_ble_mouse 1)
pico_enable_stdio_usb(picow_lvgl_ble_mouse 0)

# Add the standard library to the build
target_link_libraries(picow_lvgl_ble_mouse
        pico_stdlib
        pico_cyw43_arch_none
        pico_btstack_cyw43
        pico_btstack_ble
)

add_subdirectory(pico_lvgl)

target_link_libraries(picow_lvgl_ble_mouse
        pico_lvgl
)
pico_btstack_make_gatt_header(picow_lvgl_ble_mouse PRIVATE "${CMAKE_CURRENT_LIST_DIR}/picow_lvgl_ble_mouse.gatt")

# Add the standard include files to the build
target_include_directories(picow_lvgl_ble_mouse PRIVATE
  ${CMAKE_CURRENT_LIST_DIR}
  ${CMAKE_CURRENT_LIST_DIR}/.. # for our common lwipopts or any other standard includes, if required
)

pico_add_extra_outputs(picow_lvgl_ble_mouse)