未验证 提交 db16cada 编写于 作者: B Bernard Xiong 提交者: GitHub

Merge pull request #1864 from xuzhuoyi/stm32f429-disco

STM32F429-DISCO 添加 I2C 和触摸屏支持
......@@ -117,18 +117,24 @@ CONFIG_RT_USING_SERIAL=y
# CONFIG_RT_USING_CAN is not set
# CONFIG_RT_USING_HWTIMER is not set
# CONFIG_RT_USING_CPUTIME is not set
# CONFIG_RT_USING_I2C is not set
CONFIG_RT_USING_I2C=y
CONFIG_RT_USING_I2C_BITOPS=y
CONFIG_RT_USING_PIN=y
# CONFIG_RT_USING_PWM is not set
# CONFIG_RT_USING_MTD_NOR is not set
# CONFIG_RT_USING_MTD_NAND is not set
# CONFIG_RT_USING_MTD is not set
# CONFIG_RT_USING_RTC is not set
# CONFIG_RT_USING_SDIO is not set
# CONFIG_RT_USING_SPI is not set
# CONFIG_RT_USING_WDT is not set
# CONFIG_RT_USING_WIFI is not set
# CONFIG_RT_USING_AUDIO is not set
#
# Using WiFi
#
# CONFIG_RT_USING_WIFI is not set
#
# Using USB
#
......@@ -138,8 +144,13 @@ CONFIG_RT_USING_PIN=y
#
# POSIX layer and C standard library
#
# CONFIG_RT_USING_LIBC is not set
CONFIG_RT_USING_LIBC=y
# CONFIG_RT_USING_PTHREADS is not set
CONFIG_RT_USING_POSIX=y
# CONFIG_RT_USING_POSIX_MMAP is not set
# CONFIG_RT_USING_POSIX_TERMIOS is not set
# CONFIG_RT_USING_POSIX_AIO is not set
# CONFIG_RT_USING_MODULE is not set
#
# Network
......@@ -210,6 +221,7 @@ CONFIG_RT_USING_PIN=y
# CONFIG_PKG_USING_NOPOLL is not set
# CONFIG_PKG_USING_NETUTILS is not set
# CONFIG_PKG_USING_AT_DEVICE is not set
# CONFIG_PKG_USING_WIZNET is not set
#
# IoT Cloud
......@@ -246,13 +258,12 @@ CONFIG_RT_USING_PIN=y
# CONFIG_PKG_USING_EASYFLASH is not set
# CONFIG_PKG_USING_EASYLOGGER is not set
# CONFIG_PKG_USING_SYSTEMVIEW is not set
# CONFIG_PKG_USING_RDB is not set
#
# system packages
#
# CONFIG_PKG_USING_GUIENGINE is not set
# CONFIG_PKG_USING_GUIENGINE_V200 is not set
# CONFIG_PKG_USING_GUIENGINE_LATEST_VERSION is not set
# CONFIG_PKG_USING_CAIRO is not set
# CONFIG_PKG_USING_PIXMAN is not set
# CONFIG_PKG_USING_LWEXT4 is not set
......@@ -261,18 +272,27 @@ CONFIG_RT_USING_PIN=y
# CONFIG_PKG_USING_SQLITE is not set
# CONFIG_PKG_USING_RTI is not set
# CONFIG_PKG_USING_LITTLEVGL2RTT is not set
# CONFIG_PKG_USING_LITTLEVGL2RTT_V001 is not set
# CONFIG_PKG_USING_LITTLEVGL2RTT_LATEST_VERSION is not set
# CONFIG_LV_MEM_STATIC is not set
# CONFIG_LV_MEM_DYNAMIC is not set
# CONFIG_LV_COLOR_DEPTH_1 is not set
# CONFIG_LV_COLOR_DEPTH_8 is not set
# CONFIG_LV_COLOR_DEPTH_16 is not set
# CONFIG_LV_COLOR_DEPTH_24 is not set
# CONFIG_PKG_USING_CMSIS is not set
# CONFIG_PKG_USING_DFS_YAFFS is not set
#
# peripheral libraries and drivers
#
# CONFIG_PKG_USING_STM32F4_HAL is not set
# CONFIG_PKG_USING_STM32F4_DRIVERS is not set
# CONFIG_PKG_USING_REALTEK_AMEBA is not set
# CONFIG_PKG_USING_SHT2X is not set
# CONFIG_PKG_USING_AHT10 is not set
# CONFIG_PKG_USING_AP3216C is not set
# CONFIG_PKG_USING_STM32_SDIO is not set
# CONFIG_PKG_USING_ICM20608 is not set
# CONFIG_PKG_USING_U8G2 is not set
#
# miscellaneous packages
......@@ -303,8 +323,11 @@ CONFIG_RT_USING_PIN=y
# example package: hello
#
# CONFIG_PKG_USING_HELLO is not set
CONFIG_RT_USING_ILI9341_LCD=y
CONFIG_RT_USING_STMPE811_TOUCH=y
CONFIG_RT_USING_EXT_SDRAM=y
CONFIG_RT_USING_UART1=y
# CONFIG_RT_USING_UART2 is not set
# CONFIG_RT_USING_UART3 is not set
# CONFIG_RT_USING_SPI5 is not set
CONFIG_RT_USING_I2C3=y
/*
* File : application.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006, RT-Thread Development Team
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* The license and distribution terms for this file may be
* found in the file LICENSE in this distribution or at
* http://www.rt-thread.org/license/LICENSE
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
......@@ -32,8 +28,11 @@
#include <gdb_stub.h>
#endif
void rt_init_thread_entry(void* parameter)
{
rt_thread_t tid;
/* GDB STUB */
#ifdef RT_USING_GDB
gdb_set_device("uart6");
......@@ -57,7 +56,7 @@ void rt_init_thread_entry(void* parameter)
#endif
rt_components_init();
}
int rt_application_init()
......
/*
* File : startup.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006, RT-Thread Develop Team
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* The license and distribution terms for this file may be
* found in the file LICENSE in this distribution or at
* http://openlab.rt-thread.com/license/LICENSE
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
......
config RT_USING_ILI9341_LCD
bool "Enable LCD on the board"
default y
select RT_USING_EXT_SDRAM
config RT_USING_STMPE811_TOUCH
bool "Enable Touchscreen on the board"
default y
select RT_USING_I2C3
config RT_USING_EXT_SDRAM
bool "Enable SDRAM on the board"
default y
......@@ -16,4 +26,10 @@ config RT_USING_UART3
config RT_USING_SPI5
bool "Enable SPI5"
default n
default n
config RT_USING_I2C3
bool "Enable I2C3"
default y
select RT_USING_I2C
select RT_USING_I2C_BITOPS
......@@ -9,10 +9,20 @@ src = Split("""
board.c
stm32f4xx_it.c
usart.c
drv_sdram.c
drv_lcd.c
""")
if GetDepend(['RT_USING_EXT_SDRAM']):
src += ['drv_sdram.c']
if GetDepend(['RT_USING_I2C']):
src += ['drv_i2c.c']
if GetDepend(['RT_USING_ILI9341_LCD']):
src += ['drv_lcd.c']
if GetDepend(['RT_USING_STMPE811_TOUCH']):
src += ['drv_touch.c']
CPPPATH = [cwd]
group = DefineGroup('Drivers', src, depend = [''], CPPPATH = CPPPATH)
......
/*
* File : board.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2009 RT-Thread Develop Team
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* The license and distribution terms for this file may be
* found in the file LICENSE in this distribution or at
* http://www.rt-thread.org/license/LICENSE
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2009-01-05 Bernard first implementation
*/
#include <stdint.h>
#include <rthw.h>
#include <rtthread.h>
......
/*
* File : board.h
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2009, RT-Thread Development Team
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* The license and distribution terms for this file may be
* found in the file LICENSE in this distribution or at
* http://www.rt-thread.org/license/LICENSE
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
......
/*
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2017-06-05 tanek first implementation.
*/
#include "drv_i2c.h"
#include <board.h>
#include <finsh.h>
#include <rtdevice.h>
#include <rthw.h>
#define DEBUG
#ifdef DEBUG
#define DEBUG_PRINTF(...) rt_kprintf(__VA_ARGS__)
#else
#define DEBUG_PRINTF(...)
#endif
static void stm32f4_i2c_gpio_init()
{
GPIO_InitTypeDef GPIO_Initure;
__HAL_RCC_GPIOA_CLK_ENABLE();
__HAL_RCC_GPIOC_CLK_ENABLE();
GPIO_Initure.Pin = GPIO_PIN_8;
GPIO_Initure.Mode = GPIO_MODE_OUTPUT_OD;
GPIO_Initure.Pull = GPIO_PULLUP;
GPIO_Initure.Speed = GPIO_SPEED_FAST;
HAL_GPIO_Init(GPIOA, &GPIO_Initure);
GPIO_Initure.Pin = GPIO_PIN_9;
GPIO_Initure.Mode = GPIO_MODE_OUTPUT_OD;
GPIO_Initure.Pull = GPIO_PULLUP;
GPIO_Initure.Speed = GPIO_SPEED_FAST;
HAL_GPIO_Init(GPIOC, &GPIO_Initure);
HAL_GPIO_WritePin(GPIOA, GPIO_PIN_8, GPIO_PIN_SET);
HAL_GPIO_WritePin(GPIOC, GPIO_PIN_9, GPIO_PIN_SET);
}
static void stm32f4_set_sda(void *data, rt_int32_t state)
{
HAL_GPIO_WritePin(GPIOC, GPIO_PIN_9, (GPIO_PinState)state);
}
static void stm32f4_set_scl(void *data, rt_int32_t state)
{
HAL_GPIO_WritePin(GPIOA, GPIO_PIN_8, (GPIO_PinState)state);
}
static rt_int32_t stm32f4_get_sda(void *data)
{
return (rt_int32_t)HAL_GPIO_ReadPin(GPIOC, GPIO_PIN_9);
}
static rt_int32_t stm32f4_get_scl(void *data)
{
return (rt_int32_t)HAL_GPIO_ReadPin(GPIOA, GPIO_PIN_8);
}
static void stm32f4_udelay(rt_uint32_t us)
{
rt_int32_t i;
for (; us > 0; us--)
{
i = 50;
while (i > 0)
{
i--;
}
}
}
static const struct rt_i2c_bit_ops bit_ops = {
RT_NULL,
stm32f4_set_sda,
stm32f4_set_scl,
stm32f4_get_sda,
stm32f4_get_scl,
stm32f4_udelay,
5,
100
};
int stm32f4_i2c_init(void)
{
struct rt_i2c_bus_device *bus;
bus = rt_malloc(sizeof(struct rt_i2c_bus_device));
if (bus == RT_NULL)
{
rt_kprintf("rt_malloc failed\n");
return -RT_ENOMEM;
}
rt_memset((void *)bus, 0, sizeof(struct rt_i2c_bus_device));
bus->priv = (void *)&bit_ops;
stm32f4_i2c_gpio_init();
rt_i2c_bit_add_bus(bus, "i2c3");
return RT_EOK;
}
INIT_DEVICE_EXPORT(stm32f4_i2c_init);
/*
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
* Change Logs:
* Date Author Notes
* 2017-06-05 tanek first implementation.
*/
#ifndef STM32F4XX_IIC_INCLUDED
#define STM32F4XX_IIC_INCLUDED
#include <rtthread.h>
#include <drivers/spi.h>
#include "stm32f4xx_hal.h"
#endif // STM32F20X_40X_SPI_H_INCLUDED
/*
* File : drv_lcd.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2009 RT-Thread Develop Team
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* The license and distribution terms for this file may be
* found in the file LICENSE in this distribution or at
* http://www.rt-thread.org/license/LICENSE
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
......@@ -25,13 +21,13 @@
typedef struct
{
rt_uint16_t width; //LCD 宽度
rt_uint16_t height; //LCD 高度
rt_uint16_t id; //LCD ID
rt_uint8_t dir; //横屏还是竖屏控制:0,竖屏;1,横屏。
rt_uint16_t wramcmd; //开始写gram指令
rt_uint16_t setxcmd; //设置x坐标指令
rt_uint16_t setycmd; //设置y坐标指令
rt_uint16_t width;
rt_uint16_t height;
rt_uint16_t id;
rt_uint8_t dir; //Horizontal or vertical screen control: 0, vertical; 1, horizontal
rt_uint16_t wramcmd;
rt_uint16_t setxcmd;
rt_uint16_t setycmd;
} lcd_info_t;
typedef struct
......@@ -40,22 +36,20 @@ typedef struct
volatile rt_uint16_t ram;
} lcd_ili9341_t;
//使用NOR/SRAM的 Bank1.sector1,地址位HADDR[27,26]=00 A18作为数据命令区分线
//注意设置时STM32内部会右移一位对其!
#define LCD_ILI9341_BASE ((rt_uint32_t)(0x60000000 | 0x0007FFFE))
#define ili9341 ((lcd_ili9341_t *) LCD_ILI9341_BASE)
//////////////////////////////////////////////////////////////////////////////////
//扫描方向定义
#define L2R_U2D 0 //从左到右,从上到下
#define L2R_D2U 1 //从左到右,从下到上
#define R2L_U2D 2 //从右到左,从上到下
#define R2L_D2U 3 //从右到左,从下到上
#define U2D_L2R 4 //从上到下,从左到右
#define U2D_R2L 5 //从上到下,从右到左
#define D2U_L2R 6 //从下到上,从左到右
#define D2U_R2L 7 //从下到上,从右到左
#define DFT_SCAN_DIR L2R_U2D //默认的扫描方向
//Definition of scan direction
#define L2R_U2D 0
#define L2R_D2U 1
#define R2L_U2D 2
#define R2L_D2U 3
#define U2D_L2R 4
#define U2D_R2L 5
#define D2U_L2R 6
#define D2U_R2L 7
#define DFT_SCAN_DIR L2R_U2D
static lcd_info_t lcddev;
LTDC_HandleTypeDef LtdcHandler;
......@@ -734,108 +728,6 @@ rt_uint16_t ili9341_bgr2rgb(rt_uint16_t value)
return (blue << 11) + (green << 5) + (red << 0);
}
//static void ili9341_set_scan_direction(rt_uint8_t dir)
//{
// rt_uint16_t regval = 0;
// rt_uint16_t dirreg = 0;
// rt_uint16_t temp;
// switch (dir)
// {
// case L2R_U2D://从左到右,从上到下
// regval |= (0 << 7) | (0 << 6) | (0 << 5);
// break;
// case L2R_D2U://从左到右,从下到上
// regval |= (1 << 7) | (0 << 6) | (0 << 5);
// break;
// case R2L_U2D://从右到左,从上到下
// regval |= (0 << 7) | (1 << 6) | (0 << 5);
// break;
// case R2L_D2U://从右到左,从下到上
// regval |= (1 << 7) | (1 << 6) | (0 << 5);
// break;
// case U2D_L2R://从上到下,从左到右
// regval |= (0 << 7) | (0 << 6) | (1 << 5);
// break;
// case U2D_R2L://从上到下,从右到左
// regval |= (0 << 7) | (1 << 6) | (1 << 5);
// break;
// case D2U_L2R://从下到上,从左到右
// regval |= (1 << 7) | (0 << 6) | (1 << 5);
// break;
// case D2U_R2L://从下到上,从右到左
// regval |= (1 << 7) | (1 << 6) | (1 << 5);
// break;
// }
// dirreg = 0X36;
// ili9341_write_reg_with_value(dirreg, regval);
// if (regval & 0X20)
// {
// if (lcddev.width < lcddev.height)//交换X,Y
// {
// temp = lcddev.width;
// lcddev.width = lcddev.height;
// lcddev.height = temp;
// }
// }
// else
// {
// if (lcddev.width > lcddev.height)//交换X,Y
// {
// temp = lcddev.width;
// lcddev.width = lcddev.height;
// lcddev.height = temp;
// }
// }
//
// ili9341_write_reg(lcddev.setxcmd);
// ili9341_write_data(0);
// ili9341_write_data(0);
// ili9341_write_data((lcddev.width - 1) >> 8);
// ili9341_write_data((lcddev.width - 1) & 0XFF);
// ili9341_write_reg(lcddev.setycmd);
// ili9341_write_data(0);
// ili9341_write_data(0);
// ili9341_write_data((lcddev.height - 1) >> 8);
// ili9341_write_data((lcddev.height - 1) & 0XFF);
//}
//void ili9341_set_backlight(rt_uint8_t pwm)
//{
// ili9341_write_reg(0xBE);
// ili9341_write_data(0x05);
// ili9341_write_data(pwm*2.55);
// ili9341_write_data(0x01);
// ili9341_write_data(0xFF);
// ili9341_write_data(0x00);
// ili9341_write_data(0x00);
//}
//void ili9341_set_display_direction(rt_uint8_t dir)
//{
// lcddev.dir = dir;
// if (dir == 0)
// {
// lcddev.width = 240;
// lcddev.height = 320;
// }
// else
// {
// lcddev.width = 320;
// lcddev.height = 240;
// }
// lcddev.wramcmd = 0X2C;
// lcddev.setxcmd = 0X2A;
// lcddev.setycmd = 0X2B;
// ili9341_set_scan_direction(DFT_SCAN_DIR);
//}
void _lcd_low_level_init(void)
{
......@@ -906,7 +798,7 @@ static rt_err_t lcd_control(rt_device_t dev, int cmd, void *args)
info->bits_per_pixel = 16;
info->pixel_format = RTGRAPHIC_PIXEL_FORMAT_RGB565;
info->framebuffer = RT_NULL;
info->framebuffer = (rt_uint8_t *)LtdcHandler.LayerCfg[ActiveLayer].FBStartAdress;
info->width = 240;
info->height = 320;
}
......
/*
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2018-09-13 xuzhuoyi first implementation
*/
#ifndef __DRV_LCD_H__
#define __DRV_LCD_H__
......
/*
* File : drv_sdram.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2016, RT-Thread Development Team
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
......
/*
* File : drv_sdram.h
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2016 RT-Thread Develop Team
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* The license and distribution terms for this file may be
* found in the file LICENSE in this distribution or at
* http://www.rt-thread.org/license/LICENSE
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
......
/*
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2018-10-03 xuzhuoyi first implementation.
*/
#include "drv_touch.h"
#include "drivers/i2c.h"
#ifdef PKG_USING_LITTLEVGL2RTT
#include "littlevgl2rtt.h"
#endif
#define TSC_I2C_ADDR 0x41 /* 7-bit I2C address */
static struct rt_i2c_bus_device *stmpe811_i2c_bus;
/**
\fn int32_t touch_readRegister (uint8_t reg, uint8_t *val)
\brief Read register value from Touchscreen controller
\param[in] reg Register address
\param[out] val Pointer where data will be read from register
\returns
- \b 0: function succeeded
- \b -1: function failed
*/
static int32_t touch_read (uint8_t reg, uint8_t *val)
{
struct rt_i2c_msg msgs[2];
msgs[0].addr = TSC_I2C_ADDR;
msgs[0].flags = RT_I2C_WR;
msgs[0].buf = &reg;
msgs[0].len = 1;
msgs[1].addr = TSC_I2C_ADDR;
msgs[1].flags = RT_I2C_RD;
msgs[1].buf = val;
msgs[1].len = 1;
if (rt_i2c_transfer(stmpe811_i2c_bus, msgs, 2) == 2)
{
return RT_EOK;
}
else
{
return -RT_ERROR;
}
}
/**
\fn int32_t touch_writeData (uint8_t reg, const uint8_t *val)
\brief Write value to Touchscreen controller register
\param[in] reg Register address
\param[in] val Pointer with data to write to register
\returns
- \b 0: function succeeded
- \b -1: function failed
*/
static int32_t touch_write(uint8_t reg, uint8_t val)
{
struct rt_i2c_msg msgs;
rt_uint8_t buf[2] = {reg, val};
msgs.addr = TSC_I2C_ADDR;
msgs.flags = RT_I2C_WR;
msgs.buf = buf;
msgs.len = 2;
if (rt_i2c_transfer(stmpe811_i2c_bus, &msgs, 1) == 1)
{
return RT_EOK;
}
else
{
return -RT_ERROR;
}
}
/**
\fn int32_t Touch_Initialize (void)
\brief Initialize touchscreen
\returns
- \b 0: function succeeded
- \b -1: function failed
*/
static rt_err_t stmpe811_touch_init(rt_device_t dev)
{
stmpe811_i2c_bus = rt_i2c_bus_device_find("touch");
// ptrI2C->Initialize (NULL);
// ptrI2C->PowerControl(ARM_POWER_FULL);
// ptrI2C->Control (ARM_I2C_BUS_SPEED, ARM_I2C_BUS_SPEED_FAST);
// ptrI2C->Control (ARM_I2C_BUS_CLEAR, 0);
touch_write(STMPE811_SYS_CTRL1, 0x02); /* Reset Touch-screen controller */
rt_thread_mdelay(10); /* Wait 10ms */
touch_write(STMPE811_SYS_CTRL2, 0x0C); /* Enable TSC and ADC */
touch_write(STMPE811_ADC_CTRL1, 0x68); /* Set sample time , 12-bit mode */
rt_thread_mdelay(1); /* Wait 1ms */
touch_write(STMPE811_ADC_CTRL2, 0x01); /* ADC frequency 3.25 MHz */
touch_write(STMPE811_TSC_CFG, 0xC2); /* Detect delay 10us,
Settle time 500us */
touch_write(STMPE811_FIFO_TH, 0x01); /* Threshold for FIFO */
touch_write(STMPE811_FIFO_STA, 0x01); /* FIFO reset */
touch_write(STMPE811_FIFO_STA, 0x00); /* FIFO not reset */
touch_write(STMPE811_TSC_FRACTION_Z, 0x07); /* Fraction z */
touch_write(STMPE811_TSC_I_DRIVE, 0x01); /* Drive 50 mA typical */
touch_write(STMPE811_GPIO_AF, 0x00); /* Pins are used for touchscreen */
touch_write(STMPE811_TSC_CTRL, 0x01); /* Enable TSC */
return 0;
}
/**
\fn int32_t Touch_Uninitialize (void)
\brief De-initialize touchscreen
\returns
- \b 0: function succeeded
- \b -1: function failed
*/
int32_t touch_uninitialize (void) {
touch_write(STMPE811_SYS_CTRL1, 0x02); /* Reset Touch-screen controller */
return 0;
}
/**
\fn int32_t Touch_GetState (TOUCH_STATE *pState)
\brief Get touchscreen state
\param[out] pState pointer to TOUCH_STATE structure
\returns
- \b 0: function succeeded
- \b -1: function failed
*/
int32_t touch_get_state(struct touch_state *state)
{
uint8_t val;
uint8_t num;
uint8_t xyz[4];
int32_t res;
struct rt_i2c_msg msgs[2];
/* Read touch status */
res = touch_read(STMPE811_TSC_CTRL, &val);
if (res < 0) return -1;
state->pressed = (val & (1 << 7)) ? 1 : 0;
if (state->pressed)
{
val = STMPE811_TSC_DATA;
/* If FIFO overflow, discard all samples except the last one */
res = touch_read(STMPE811_FIFO_SIZE, &num);
if (res < 0 || num == 0) return -1;
while (num--)
{
msgs[0].addr = TSC_I2C_ADDR;
msgs[0].flags = RT_I2C_WR;
msgs[0].buf = &val;
msgs[0].len = 1;
//rt_i2c_transfer(stmpe811_i2c_bus, &msgs, 1);
//ptrI2C->MasterTransmit (TSC_I2C_ADDR, &val, 1, true);
//while (ptrI2C->GetStatus().busy);
msgs[1].addr = TSC_I2C_ADDR;
msgs[1].flags = RT_I2C_RD;
msgs[1].buf = xyz;
msgs[1].len = 4;
rt_i2c_transfer(stmpe811_i2c_bus, msgs, 2);
//ptrI2C->MasterReceive (TSC_I2C_ADDR, xyz, 4, false);
//while (ptrI2C->GetStatus().busy);
}
state->x = (int16_t)((xyz[0] << 4) | ((xyz[1] & 0xF0) >> 4));
state->y = (int16_t) (xyz[2] | ((xyz[1] & 0x0F) << 8));
}
else
{
/* Clear all data in FIFO */
touch_write(STMPE811_FIFO_STA, 0x1);
touch_write(STMPE811_FIFO_STA, 0x0);
}
return 0;
}
void touch_show_state()
{
int16_t x;
int16_t y;
struct touch_state ts;
touch_get_state(&ts);
x = (3706 - ts.x) / 14;
y = (-461 + ts.y) / 10.5;
rt_kprintf("[drv_touch] touch_show_state, x: %d, y: %d, pressed: %d, padding: %d\n", ts.x , ts.y, ts.pressed, ts.padding);
rt_kprintf("[drv_touch] touch_show_state, phy x: %d, phy y: %d\n", x , y);
}
MSH_CMD_EXPORT(touch_show_state, show screen coordinate in touching);
static int rt_hw_touch_init(void)
{
static struct rt_device touch;
/* init device structure */
touch.type = RT_Device_Class_Unknown;
touch.init = stmpe811_touch_init;
touch.user_data = RT_NULL;
/* register touch device to RT-Thread */
rt_device_register(&touch, "touch", RT_DEVICE_FLAG_RDWR);
return RT_EOK;
}
INIT_BOARD_EXPORT(rt_hw_touch_init);
/*
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2018-10-03 xuzhuoyi first implementation.
*/
#ifndef __DRV_TOUCH_H__
#define __DRV_TOUCH_H__
#include <stdint.h>
/* Register addresses */
#define STMPE811_CHIP_ID 0x00
#define STMPE811_ID_VER 0x02
#define STMPE811_SYS_CTRL1 0x03
#define STMPE811_SYS_CTRL2 0x04
#define STMPE811_SPI_CFG 0x08
#define STMPE811_INT_CTRL 0x09
#define STMPE811_INT_EN 0x0A
#define STMPE811_INT_STA 0x0B
#define STMPE811_GPIO_EN 0x0C
#define STMPE811_GPIO_INT_STA 0x0D
#define STMPE811_ADC_INT_EN 0x0E
#define STMPE811_ADC_INT_STA 0x0F
#define STMPE811_GPIO_SET_PIN 0x10
#define STMPE811_GPIO_CLR_PIN 0x11
#define STMPE811_GPIO_MP_STA 0x12
#define STMPE811_GPIO_DIR 0x13
#define STMPE811_GPIO_ED 0x14
#define STMPE811_GPIO_RE 0x15
#define STMPE811_GPIO_FE 0x16
#define STMPE811_GPIO_AF 0x17
#define STMPE811_ADC_CTRL1 0x20
#define STMPE811_ADC_CTRL2 0x21
#define STMPE811_ADC_CAPT 0x22
#define STMPE811_ADC_DATA_CH0 0x30
#define STMPE811_ADC_DATA_CH1 0x32
#define STMPE811_ADC_DATA_CH2 0x34
#define STMPE811_ADC_DATA_CH3 0x36
#define STMPE811_ADC_DATA_CH4 0x38
#define STMPE811_ADC_DATA_CH5 0x3A
#define STMPE811_ADC_DATA_CH6 0x3C
#define STMPE811_ADC_DATA_CH7 0x3E
#define STMPE811_TSC_CTRL 0x40
#define STMPE811_TSC_CFG 0x41
#define STMPE811_WDW_TR_X 0x42
#define STMPE811_WDW_TR_Y 0x44
#define STMPE811_WDW_BL_X 0x46
#define STMPE811_WDW_BL_Y 0x48
#define STMPE811_FIFO_TH 0x4A
#define STMPE811_FIFO_STA 0x4B
#define STMPE811_FIFO_SIZE 0x4C
#define STMPE811_TSC_DATA_X 0x4D
#define STMPE811_TSC_DATA_Y 0x4F
#define STMPE811_TSC_DATA_Z 0x51
#define STMPE811_TSC_FRACTION_Z 0x56
#define STMPE811_TSC_DATA_XYZ 0x57
#define STMPE811_TSC_DATA 0xD7
#define STMPE811_TSC_I_DRIVE 0x58
#define STMPE811_TSC_SHIELD 0x59
#define STMPE811_TEMP_CTRL 0x60
#define STMPE811_TEMP_DATA 0x61
#define STMPE811_TEMP_TH 0x62
/* Touch state */
struct touch_state {
int16_t x; ///< Position X
int16_t y; ///< Position Y
uint8_t pressed; ///< Pressed flag
uint8_t padding;
};
int32_t touch_get_state(struct touch_state *state);
#endif /* __DRV_TOUCH_H__ */
/*
* File : usart.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2009, RT-Thread Development Team
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* The license and distribution terms for this file may be
* found in the file LICENSE in this distribution or at
* http://www.rt-thread.org/license/LICENSE
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
......
/*
* File : usart.h
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2009, RT-Thread Development Team
* Copyright (c) 2006-2018, RT-Thread Development Team
*
* The license and distribution terms for this file may be
* found in the file LICENSE in this distribution or at
* http://www.rt-thread.org/license/LICENSE
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
......
此差异已折叠。
......@@ -20,6 +20,8 @@ STM32F429I-DISCOVERY 开发板使用高性能 MCU STM32F429,可以用于实现
|LED| 6 个 |
|按键| 2 个 |
本 BSP 已测试支持 RT-Thread GUIEngine 和 Littlevgl,可以使用 env 工具安装相应的 Package。
## 2. 编译说明
STM32F429-DISCO 板级包支持 MDK4﹑MDK5﹑IAR 开发环境和 GCC 编译器,以下是具体版本信息:
......@@ -61,13 +63,16 @@ finsh />
| 驱动 | 支持情况 | 备注 |
| ------ | ---- | :------: |
| USART | 支持 | USART1/2/3 |
| SPI | 支持 | |
| LCD | 支持 | 支持 FrameBuffer 模式 LCD 显示 |
| SPI | 支持 | SPI5 |
| IIC | 支持 | IIC3 |
| SDRAM | 支持 | |
| LCD | 支持 | 支持 FrameBuffer 模式 LCD 显示 |
| 触摸屏 | 支持 | IIC 接口 STMPE811 |
| USB OTG Host| 即将支持 | 预计 2018/11 |
| USB OTG Device| 未支持 | |
| GPIO | 未支持 | |
| IIC | 未支持 | |
| L3GD20 | 未支持 | |
| USB OTG | 未支持 | |
## 5. 联系人信息
......
......@@ -75,13 +75,20 @@
#define RT_USING_DEVICE_IPC
#define RT_PIPE_BUFSZ 512
#define RT_USING_SERIAL
#define RT_USING_I2C
#define RT_USING_I2C_BITOPS
#define RT_USING_PIN
/* Using WiFi */
/* Using USB */
/* POSIX layer and C standard library */
#define RT_USING_LIBC
#define RT_USING_POSIX
/* Network */
......@@ -147,7 +154,10 @@
/* example package: hello */
#define RT_USING_ILI9341_LCD
#define RT_USING_STMPE811_TOUCH
#define RT_USING_EXT_SDRAM
#define RT_USING_UART1
#define RT_USING_I2C3
#endif
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册