add get touch coordinate function to xidatong-riscv64.

This commit is contained in:
TXuian 2022-07-15 01:08:18 -07:00
commit 1818e23744
11 changed files with 864 additions and 217 deletions

View File

@ -24,7 +24,7 @@ int main(void)
#ifdef APPLICATION_OTA
ApplicationOtaTaskInit();
#endif
return 0;
return 0;
}
// int cppmain(void);

View File

@ -13,26 +13,26 @@
* limitations under the License.
*/
/**
* @file board.c
* @brief support kd233-board init configure and start-up
* @version 1.0
* @author AIIT XUOS Lab
* @date 2022-07-25
*/
/**
* @file board.c
* @brief support kd233-board init configure and start-up
* @version 1.0
* @author AIIT XUOS Lab
* @date 2022-07-25
*/
/*************************************************
File name: board.c
Description: support xidatong-riscv64-board init configure and driver/task/... init
Others: https://canaan-creative.com/developer
History:
1. Date: 2022-07-25
Author: AIIT XUOS Lab
Modification:
1. support xidatong-riscv64-board InitBoardHardware
2. support xidatong-riscv64-board Kd233Start
3. support xidatong-riscv64-board shell cmd, include reboot, shutdown
*************************************************/
/*************************************************
File name: board.c
Description: support xidatong-riscv64-board init configure and driver/task/... init
Others: https://canaan-creative.com/developer
History:
1. Date: 2022-07-25
Author: AIIT XUOS Lab
Modification:
1. support xidatong-riscv64-board InitBoardHardware
2. support xidatong-riscv64-board Kd233Start
3. support xidatong-riscv64-board shell cmd, include reboot, shutdown
*************************************************/
#include <xizi.h>
#include <clint.h>
@ -60,12 +60,13 @@ extern int HwI2cInit(void);
extern int HwRtcInit(void);
extern int HwWdtInit(void);
extern int HwLcdInit(void);
extern int HwTouchInit(void);
extern int HwTimerInit(void);
#if defined(FS_VFS) && defined (MOUNT_SDCARD)
#include <iot-vfs.h>
#include <sd_spi.h>
extern SpiSdDeviceType SpiSdInit(struct Bus *bus, const char *dev_name, const char *drv_name, const char *sd_name);
extern SpiSdDeviceType SpiSdInit(struct Bus* bus, const char* dev_name, const char* drv_name, const char* sd_name);
/**
* @description: Mount SD card
@ -73,14 +74,14 @@ extern SpiSdDeviceType SpiSdInit(struct Bus *bus, const char *dev_name, const ch
*/
int MountSDCard(void)
{
struct Bus *spi_bus;
struct Bus* spi_bus;
spi_bus = BusFind(SPI_BUS_NAME_1);
if (NONE == SpiSdInit(spi_bus, SPI_1_DEVICE_NAME_0, SPI_1_DRV_NAME, SPI_SD_NAME)) {
KPrintf("MountSDCard SpiSdInit error!\n");
return 0;
}
if (EOK == MountFilesystem(SPI_BUS_NAME_1, SPI_SD_NAME, SPI_1_DRV_NAME, FSTYPE_FATFS, "/"))
KPrintf("SPI SD card fatfs mounted\n");
@ -90,37 +91,37 @@ int MountSDCard(void)
void InitBss(void)
{
unsigned int *dst;
unsigned int* dst;
dst = &__bss_start;
while (dst < &__bss_end){
while (dst < &__bss_end) {
*dst++ = 0;
}
}
void Kd233Start(uint32_t mhartid)
{
switch(mhartid) {
case CPU0:
InitBss();
switch (mhartid) {
case CPU0:
InitBss();
/*kernel start entry*/
entry();
break;
case CPU1:
while(0x2018050420191010 != cpu2_boot_flag) { ///< waiting for boot flag ,then start cpu1 core
/*kernel start entry*/
entry();
break;
case CPU1:
while (0x2018050420191010 != cpu2_boot_flag) { ///< waiting for boot flag ,then start cpu1 core
#ifndef ARCH_SMP
asm volatile("wfi");
asm volatile("wfi");
#endif
}
}
#ifdef ARCH_SMP
SecondaryCpuCStart();
SecondaryCpuCStart();
#endif
break;
break;
default:
break;
}
default:
break;
}
}
int Freq(void)
@ -149,26 +150,26 @@ int Freq(void)
return 0;
}
SHELL_EXPORT_CMD(SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_CMD_FUNC)|SHELL_CMD_PARAM_NUM(0),Freq, Freq, show frequency information );
SHELL_EXPORT_CMD(SHELL_CMD_PERMISSION(0) | SHELL_CMD_TYPE(SHELL_TYPE_CMD_FUNC) | SHELL_CMD_PARAM_NUM(0), Freq, Freq, show frequency information);
#ifdef ARCH_SMP
extern int EnableHwclintIpi(void);
#endif
struct InitSequenceDesc _board_init[] =
struct InitSequenceDesc _board_init[] =
{
#ifdef BSP_USING_GPIO
{ "hw_pin", HwGpioInit },
{ "io_config", IoConfigInit },
{ "io_config", IoConfigInit },
#endif
#ifdef BSP_USING_SPI
{ "hw_spi", HwSpiInit },
{ "hw_spi", HwSpiInit },
#endif
#ifdef BSP_USING_I2C
{ "hw_i2c", HwI2cInit },
#endif
#ifdef BSP_USING_LCD
{ "hw_lcd", HwLcdInit },
{ "hw_lcd", HwLcdInit },
#endif
#ifdef BSP_USING_HWTIMER
{ "hw_timer" , HwTimerInit },
@ -179,14 +180,17 @@ struct InitSequenceDesc _board_init[] =
#ifdef BSP_USING_RTC
{"hw_rtc", HwRtcInit },
#endif
{ " NONE ",NONE },
#ifdef BSP_USING_TOUCH
{"touch", HwTouchInit },
#endif
{ " NONE ",NONE },
};
void InitBoardHardware(void)
{
int i = 0;
int ret = 0;
int i = 0;
int ret = 0;
SysctlPllSetFreq(SYSCTL_PLL0, 800000000UL);
SysctlPllSetFreq(SYSCTL_PLL1, 400000000UL);
#ifdef BSP_USING_GPIO
@ -204,12 +208,12 @@ void InitBoardHardware(void)
#endif
/* initialize memory system */
InitBoardMemory(MEMORY_START_ADDRESS, MEMORY_END_ADDRESS);
InitBoardMemory(MEMORY_START_ADDRESS, MEMORY_END_ADDRESS);
#ifdef KERNEL_CONSOLE
/* set console device */
InstallConsole(KERNEL_CONSOLE_BUS_NAME, KERNEL_CONSOLE_DRV_NAME, KERNEL_CONSOLE_DEVICE_NAME);
KPrintf("\nconsole init completed.\n");
KPrintf("\nconsole init completed.\n");
KPrintf("board initialization......\n");
#endif /* KERNEL_CONSOLE */
@ -220,21 +224,21 @@ void InitBoardHardware(void)
#endif
#ifdef KERNEL_COMPONENTS_INIT
for(i = 0; _board_init[i].fn != NONE; i++) {
ret = _board_init[i].fn();
KPrintf("initialize %s %s\n",_board_init[i].fn_name, ret == 0 ? "success" : "failed");
}
for (i = 0; _board_init[i].fn != NONE; i++) {
ret = _board_init[i].fn();
KPrintf("initialize %s %s\n", _board_init[i].fn_name, ret == 0 ? "success" : "failed");
}
#endif
KPrintf("board init done.\n");
KPrintf("start kernel...\n");
KPrintf("board init done.\n");
KPrintf("start kernel...\n");
}
void HwCpuReset(void)
{
sysctl->soft_reset.soft_reset = 1;
while(RET_TRUE);
while (RET_TRUE);
}
SHELL_EXPORT_CMD(SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_CMD_FUNC)|SHELL_CMD_PARAM_NUM(0),Reboot, HwCpuReset, reset machine );
SHELL_EXPORT_CMD(SHELL_CMD_PERMISSION(0) | SHELL_CMD_TYPE(SHELL_TYPE_CMD_FUNC) | SHELL_CMD_PARAM_NUM(0), Reboot, HwCpuReset, reset machine);

View File

@ -21,6 +21,15 @@ if BSP_USING_I2C
source "$BSP_DIR/third_party_driver/i2c/Kconfig"
endif
menuconfig BSP_USING_TOUCH
bool "Using TOUCH device"
default n
select RESOURCES_TOUCH
select BSP_USING_I2C
if BSP_USING_TOUCH
source "$BSP_DIR/third_party_driver/touch/Kconfig"
endif
menuconfig BSP_USING_PLIC
bool "Using PLIC device"
default y

View File

@ -20,6 +20,10 @@ ifeq ($(CONFIG_BSP_USING_I2C),y)
SRC_DIR += i2c
endif
ifeq ($(CONFIG_BSP_USING_TOUCH),y)
SRC_DIR += touch
endif
ifeq ($(CONFIG_BSP_USING_I2S),y)
SRC_DIR += i2s
endif

View File

@ -8,24 +8,24 @@
* 2019-03-19 ZYH first version
*/
/**
* @file drv_io_config.c
* @brief support xidatong-riscv64-board io configure
* @version 1.0
* @author AIIT XUOS Lab
* @date 2022-07-25
*/
/**
* @file drv_io_config.c
* @brief support xidatong-riscv64-board io configure
* @version 1.0
* @author AIIT XUOS Lab
* @date 2022-07-25
*/
/*************************************************
File name: drv_io_config.c
Description: support kd233-board io configure
Others: take RT-Thread v4.0.2/bsp/k210/driver/drv_io_config.c for references
https://github.com/RT-Thread/rt-thread/tree/v4.0.2
History:
1. Date: 2022-07-25
Author: AIIT XUOS Lab
Modification: support kd233-board io configure
*************************************************/
/*************************************************
File name: drv_io_config.c
Description: support kd233-board io configure
Others: take RT-Thread v4.0.2/bsp/k210/driver/drv_io_config.c for references
https://github.com/RT-Thread/rt-thread/tree/v4.0.2
History:
1. Date: 2022-07-25
Author: AIIT XUOS Lab
Modification: support kd233-board io configure
*************************************************/
#include <xizi.h>
#include <fpioa.h>
@ -40,13 +40,13 @@ static struct io_config
{
int io_num;
fpioa_function_t func;
const char * FuncName;
} io_config[] =
const char* FuncName;
} io_config[] =
{
#ifdef BSP_USING_LCD
IOCONFIG(BSP_LCD_CS_PIN, FUNC_SPI0_SS0),
IOCONFIG(BSP_LCD_WR_PIN, FUNC_SPI0_SCLK),
IOCONFIG(BSP_LCD_DC_PIN, HS_GPIO(LCD_DC_PIN)),
IOCONFIG(BSP_LCD_CS_PIN, FUNC_SPI0_SS0),
IOCONFIG(BSP_LCD_WR_PIN, FUNC_SPI0_SCLK),
IOCONFIG(BSP_LCD_DC_PIN, HS_GPIO(LCD_DC_PIN)),
#endif
#ifdef BSP_USING_SPI1
@ -78,7 +78,9 @@ static struct io_config
IOCONFIG(BSP_I2C_SDA, FUNC_GPIO3),
IOCONFIG(BSP_I2C_SCL, FUNC_GPIO4),
#endif
#ifdef BSP_USING_TOUCH
IOCONFIG(BSP_TOUCH_TP_INT, HS_GPIO(FPIOA_TOUCH_TP_INT))
#endif
};
static int PrintIoConfig()
@ -88,7 +90,7 @@ static int PrintIoConfig()
KPrintf("┌───────┬────────────────────────┐\n");
KPrintf("│Pin │Function │\n");
KPrintf("├───────┼────────────────────────┤\n");
for(i = 0; i < sizeof io_config / sizeof io_config[0]; i++)
for (i = 0; i < sizeof io_config / sizeof io_config[0]; i++)
{
KPrintf("│%-2d │%-24.24s│\n", io_config[i].io_num, io_config[i].FuncName);
}
@ -98,8 +100,8 @@ static int PrintIoConfig()
SHELL_EXPORT_CMD(SHELL_CMD_PERMISSION(0)|SHELL_CMD_TYPE(SHELL_TYPE_CMD_FUNC)|SHELL_CMD_PARAM_NUM(0),
io,PrintIoConfig,print io config);
SHELL_EXPORT_CMD(SHELL_CMD_PERMISSION(0) | SHELL_CMD_TYPE(SHELL_TYPE_CMD_FUNC) | SHELL_CMD_PARAM_NUM(0),
io, PrintIoConfig, print io config);
int IoConfigInit(void)
@ -120,10 +122,10 @@ int IoConfigInit(void)
sysctl_set_power_mode(SYSCTL_POWER_BANK3, SYSCTL_POWER_V33);
#endif
for(i = 0; i < count; i++)
for (i = 0; i < count; i++)
{
ret = FpioaSetFunction(io_config[i].io_num, io_config[i].func);
if(ret != 0)
if (ret != 0)
return ret;
}

View File

@ -8,30 +8,30 @@
* 2012-04-25 weety first version
*/
/**
* @file connect_i2c.c
* @brief support kd233-board i2c function and register to bus framework
* @version 1.0
* @author AIIT XUOS Lab
* @date 2022-07-25
*/
/**
* @file connect_i2c.c
* @brief support kd233-board i2c function and register to bus framework
* @version 1.0
* @author AIIT XUOS Lab
* @date 2022-07-25
*/
/*************************************************
File name: connect_i2c.c
Description: support xidatong-riscv64-board i2c configure and i2c bus register function
Others: take RT-Thread v4.0.2/components/drivers/i2c/i2c-bit-ops.c for references
https://github.com/RT-Thread/rt-thread/tree/v4.0.2
History:
1. Date: 2022-07-25
Author: AIIT XUOS Lab
Modification:
1. support xidatong-riscv64-board i2c bit configure, write and read
2. support xidatong-riscv64-board i2c bus device and driver register
*************************************************/
/*************************************************
File name: connect_i2c.c
Description: support xidatong-riscv64-board i2c configure and i2c bus register function
Others: take RT-Thread v4.0.2/components/drivers/i2c/i2c-bit-ops.c for references
https://github.com/RT-Thread/rt-thread/tree/v4.0.2
History:
1. Date: 2022-07-25
Author: AIIT XUOS Lab
Modification:
1. support xidatong-riscv64-board i2c bit configure, write and read
2. support xidatong-riscv64-board i2c bus device and driver register
*************************************************/
#include <board.h>
#include "gpio_common.h"
#include"fpioa.h"
#include "gpio_common.h"
#include"fpioa.h"
#include "connect_i2c.h"
#include <sleep.h>
#include "sysctl.h"
@ -58,52 +58,54 @@ static I2cBusParam i2c_bus_param =
#define SdaHigh(done) SET_SDA(done, 1)
#define SclLow(done) SET_SCL(done, 0)
void I2cGpioInit(const I2cBusParam *bus_param)
void I2cGpioInit(const I2cBusParam* bus_param)
{
gpio_init ();
FpioaSetFunction(BSP_I2C_SDA , FUNC_GPIO3 );//RISC-V FPIOA CFG
FpioaSetFunction(BSP_I2C_SCL , FUNC_GPIO4 );//RISC-V FPIOA CFG
gpio_set_drive_mode(bus_param->i2c_sda_pin , GPIO_DM_OUTPUT );
gpio_set_drive_mode(bus_param->i2c_scl_pin, GPIO_DM_OUTPUT );
gpio_set_pin(bus_param->i2c_sda_pin , GPIO_PV_HIGH );
gpio_set_pin(bus_param->i2c_scl_pin , GPIO_PV_HIGH );
gpio_init();
FpioaSetFunction(BSP_I2C_SDA, FUNC_GPIO3);//RISC-V FPIOA CFG
FpioaSetFunction(BSP_I2C_SCL, FUNC_GPIO4);//RISC-V FPIOA CFG
gpio_set_drive_mode(bus_param->i2c_sda_pin, GPIO_DM_OUTPUT);
gpio_set_drive_mode(bus_param->i2c_scl_pin, GPIO_DM_OUTPUT);
gpio_set_pin(bus_param->i2c_sda_pin, GPIO_PV_HIGH);
gpio_set_pin(bus_param->i2c_scl_pin, GPIO_PV_HIGH);
}
static void SetSdaState(void *data, uint8 sda_state)
static void SetSdaState(void* data, uint8 sda_state)
{
I2cBusParam *bus_param = (I2cBusParam *)data;
I2cBusParam* bus_param = (I2cBusParam*)data;
if (sda_state) {
gpio_set_drive_mode(bus_param->i2c_sda_pin, GPIO_DM_OUTPUT );
gpio_set_pin(bus_param->i2c_sda_pin , GPIO_PV_HIGH );
} else {
gpio_set_drive_mode(bus_param->i2c_sda_pin, GPIO_DM_OUTPUT );
gpio_set_pin(bus_param->i2c_sda_pin , GPIO_PV_LOW );
gpio_set_drive_mode(bus_param->i2c_sda_pin, GPIO_DM_OUTPUT);
gpio_set_pin(bus_param->i2c_sda_pin, GPIO_PV_HIGH);
}
else {
gpio_set_drive_mode(bus_param->i2c_sda_pin, GPIO_DM_OUTPUT);
gpio_set_pin(bus_param->i2c_sda_pin, GPIO_PV_LOW);
}
}
static void SetSclState(void *data, uint8 scl_state)
static void SetSclState(void* data, uint8 scl_state)
{
I2cBusParam *bus_param = (I2cBusParam *)data;
I2cBusParam* bus_param = (I2cBusParam*)data;
if (scl_state) {
gpio_set_drive_mode(bus_param->i2c_scl_pin, GPIO_DM_OUTPUT );
gpio_set_pin(bus_param->i2c_scl_pin , GPIO_PV_HIGH );
} else {
gpio_set_drive_mode(bus_param->i2c_scl_pin, GPIO_DM_OUTPUT );
gpio_set_pin(bus_param->i2c_scl_pin , GPIO_PV_LOW );
gpio_set_drive_mode(bus_param->i2c_scl_pin, GPIO_DM_OUTPUT);
gpio_set_pin(bus_param->i2c_scl_pin, GPIO_PV_HIGH);
}
else {
gpio_set_drive_mode(bus_param->i2c_scl_pin, GPIO_DM_OUTPUT);
gpio_set_pin(bus_param->i2c_scl_pin, GPIO_PV_LOW);
}
}
static uint8 GetSdaState(void *data)
static uint8 GetSdaState(void* data)
{
I2cBusParam *bus_param = (I2cBusParam *)data;
gpio_set_drive_mode (bus_param->i2c_sda_pin, GPIO_DM_INPUT_PULL_UP );
I2cBusParam* bus_param = (I2cBusParam*)data;
gpio_set_drive_mode(bus_param->i2c_sda_pin, GPIO_DM_INPUT_PULL_UP);
return gpio_get_pin(bus_param->i2c_sda_pin);
}
static uint8 GetSclState(void *data)
static uint8 GetSclState(void* data)
{
I2cBusParam *bus_param = (I2cBusParam *)data;
gpio_set_drive_mode (bus_param->i2c_scl_pin, GPIO_DM_INPUT_PULL_UP );
I2cBusParam* bus_param = (I2cBusParam*)data;
gpio_set_drive_mode(bus_param->i2c_scl_pin, GPIO_DM_INPUT_PULL_UP);
return gpio_get_pin(bus_param->i2c_scl_pin);
}
@ -119,37 +121,37 @@ static const struct I2cHalDrvDone I2cDrvDone =
.timeout = 100
};
static x_err_t I2cBusReset(const I2cBusParam *bus_param)
static x_err_t I2cBusReset(const I2cBusParam* bus_param)
{
int32 i = 0;
gpio_set_drive_mode(bus_param->i2c_sda_pin, GPIO_DM_INPUT_PULL_UP );
gpio_set_drive_mode(bus_param->i2c_sda_pin, GPIO_DM_INPUT_PULL_UP);
if (GPIO_LOW == gpio_get_pin(bus_param->i2c_sda_pin)) {
while (i++ < 9) {
gpio_set_drive_mode(bus_param->i2c_scl_pin, GPIO_DM_OUTPUT );
gpio_set_pin(bus_param->i2c_scl_pin , GPIO_PV_HIGH );
gpio_set_drive_mode(bus_param->i2c_scl_pin, GPIO_DM_OUTPUT);
gpio_set_pin(bus_param->i2c_scl_pin, GPIO_PV_HIGH);
usleep(100);
gpio_set_pin(bus_param->i2c_scl_pin , GPIO_PV_LOW );
gpio_set_pin(bus_param->i2c_scl_pin, GPIO_PV_LOW);
usleep(100);
}
}
gpio_set_drive_mode(bus_param->i2c_sda_pin, GPIO_DM_INPUT_PULL_UP );
gpio_set_drive_mode(bus_param->i2c_sda_pin, GPIO_DM_INPUT_PULL_UP);
if (GPIO_LOW == gpio_get_pin(bus_param->i2c_sda_pin)) {
return -ERROR;
}
return EOK;
}
static __inline void I2cDelay(struct I2cHalDrvDone *done)
static __inline void I2cDelay(struct I2cHalDrvDone* done)
{
done->udelay((done->delay_us + 1) >> 1);
}
static __inline void I2cDelay2(struct I2cHalDrvDone *done)
static __inline void I2cDelay2(struct I2cHalDrvDone* done)
{
done->udelay(done->delay_us);
}
static x_err_t SclHigh(struct I2cHalDrvDone *done)
static x_err_t SclHigh(struct I2cHalDrvDone* done)
{
x_ticks_t start;
@ -171,14 +173,14 @@ done:
return EOK;
}
static void I2cStart(struct I2cHalDrvDone *done)
static void I2cStart(struct I2cHalDrvDone* done)
{
SdaLow(done);
I2cDelay(done);
SclLow(done);
}
static void I2cRestart(struct I2cHalDrvDone *done)
static void I2cRestart(struct I2cHalDrvDone* done)
{
SdaHigh(done);
SclHigh(done);
@ -188,7 +190,7 @@ static void I2cRestart(struct I2cHalDrvDone *done)
SclLow(done);
}
static void I2cStop(struct I2cHalDrvDone *done)
static void I2cStop(struct I2cHalDrvDone* done)
{
SdaLow(done);
I2cDelay(done);
@ -198,12 +200,12 @@ static void I2cStop(struct I2cHalDrvDone *done)
I2cDelay2(done);
}
static __inline x_bool I2cWaitack(struct I2cHalDrvDone *done)
static __inline x_bool I2cWaitack(struct I2cHalDrvDone* done)
{
x_bool ack;
SdaHigh(done);
GET_SDA(done);
GET_SDA(done);
I2cDelay(done);
if (SclHigh(done) < 0) {
@ -218,12 +220,12 @@ static __inline x_bool I2cWaitack(struct I2cHalDrvDone *done)
return ack;
}
static int32 I2cWriteb(struct I2cBus *bus, uint8 data)
static int32 I2cWriteb(struct I2cBus* bus, uint8 data)
{
int32 i;
uint8 bit;
struct I2cHalDrvDone *done = (struct I2cHalDrvDone *)bus->private_data;
struct I2cHalDrvDone* done = (struct I2cHalDrvDone*)bus->private_data;
for (i = 7; i >= 0; i--) {
SclLow(done);
@ -232,8 +234,8 @@ static int32 I2cWriteb(struct I2cBus *bus, uint8 data)
I2cDelay(done);
if (SclHigh(done) < 0) {
KPrintf("I2cWriteb: 0x%02x, "
"wait scl pin high timeout at bit %d",
data, i);
"wait scl pin high timeout at bit %d",
data, i);
return -ETIMEOUT;
}
@ -244,11 +246,11 @@ static int32 I2cWriteb(struct I2cBus *bus, uint8 data)
return I2cWaitack(done);
}
static int32 I2cReadb(struct I2cBus *bus)
static int32 I2cReadb(struct I2cBus* bus)
{
uint8 i;
uint8 data = 0;
struct I2cHalDrvDone *done = (struct I2cHalDrvDone *)bus->private_data;
struct I2cHalDrvDone* done = (struct I2cHalDrvDone*)bus->private_data;
SdaHigh(done);
GET_SDA(done);
@ -258,7 +260,7 @@ static int32 I2cReadb(struct I2cBus *bus)
if (SclHigh(done) < 0) {
KPrintf("I2cReadb: wait scl pin high "
"timeout at bit %d", 7 - i);
"timeout at bit %d", 7 - i);
return -ETIMEOUT;
}
@ -272,11 +274,11 @@ static int32 I2cReadb(struct I2cBus *bus)
return data;
}
static x_size_t I2cSendBytes(struct I2cBus *bus, struct I2cDataStandard *msg)
static x_size_t I2cSendBytes(struct I2cBus* bus, struct I2cDataStandard* msg)
{
int32 ret;
x_size_t bytes = 0;
const uint8 *ptr = msg->buf;
const uint8* ptr = msg->buf;
int32 count = msg->len;
uint16 ignore_nack = msg->flags & I2C_IGNORE_NACK;
@ -284,12 +286,14 @@ static x_size_t I2cSendBytes(struct I2cBus *bus, struct I2cDataStandard *msg)
ret = I2cWriteb(bus, *ptr);
if ((ret > 0) || (ignore_nack && (ret == 0))) {
count --;
ptr ++;
bytes ++;
} else if (ret == 0) {
count--;
ptr++;
bytes++;
}
else if (ret == 0) {
return 0;
} else {
}
else {
KPrintf("send bytes: error %d", ret);
return ret;
@ -299,9 +303,9 @@ static x_size_t I2cSendBytes(struct I2cBus *bus, struct I2cDataStandard *msg)
return bytes;
}
static x_err_t I2cSendAckOrNack(struct I2cBus *bus, int ack)
static x_err_t I2cSendAckOrNack(struct I2cBus* bus, int ack)
{
struct I2cHalDrvDone *done = (struct I2cHalDrvDone *)bus->private_data;
struct I2cHalDrvDone* done = (struct I2cHalDrvDone*)bus->private_data;
if (ack)
SET_SDA(done, 0);
@ -316,11 +320,11 @@ static x_err_t I2cSendAckOrNack(struct I2cBus *bus, int ack)
return EOK;
}
static x_size_t I2cRecvBytes(struct I2cBus *bus, struct I2cDataStandard *msg)
static x_size_t I2cRecvBytes(struct I2cBus* bus, struct I2cDataStandard* msg)
{
int32 val;
int32 bytes = 0;
uint8 *ptr = msg->buf;
uint8* ptr = msg->buf;
int32 count = msg->len;
const uint32 flags = msg->flags;
@ -328,13 +332,14 @@ static x_size_t I2cRecvBytes(struct I2cBus *bus, struct I2cDataStandard *msg)
val = I2cReadb(bus);
if (val >= 0) {
*ptr = val;
bytes ++;
} else {
bytes++;
}
else {
break;
}
ptr ++;
count --;
ptr++;
count--;
if (!(flags & I2C_NO_READ_ACK)) {
val = I2cSendAckOrNack(bus, count);
@ -346,9 +351,9 @@ static x_size_t I2cRecvBytes(struct I2cBus *bus, struct I2cDataStandard *msg)
return bytes;
}
static int32 I2cSendAddress(struct I2cBus *bus, uint8 addr, int32 retries)
static int32 I2cSendAddress(struct I2cBus* bus, uint8 addr, int32 retries)
{
struct I2cHalDrvDone *done = (struct I2cHalDrvDone *)bus->private_data;
struct I2cHalDrvDone* done = (struct I2cHalDrvDone*)bus->private_data;
int32 i;
x_err_t ret = 0;
@ -364,11 +369,11 @@ static int32 I2cSendAddress(struct I2cBus *bus, uint8 addr, int32 retries)
return ret;
}
static x_err_t I2cBitSendAddress(struct I2cBus *bus, struct I2cDataStandard *msg)
static x_err_t I2cBitSendAddress(struct I2cBus* bus, struct I2cDataStandard* msg)
{
uint16 flags = msg->flags;
uint16 ignore_nack = msg->flags & I2C_IGNORE_NACK;
struct I2cHalDrvDone *done = (struct I2cHalDrvDone *)bus->private_data;
struct I2cHalDrvDone* done = (struct I2cHalDrvDone*)bus->private_data;
uint8 addr1, addr2;
int32 retries;
@ -401,7 +406,8 @@ static x_err_t I2cBitSendAddress(struct I2cBus *bus, struct I2cDataStandard *msg
return -EPIO;
}
}
} else {
}
else {
addr1 = msg->addr << 1;
if (flags & I2C_RD)
addr1 |= 1;
@ -413,11 +419,11 @@ static x_err_t I2cBitSendAddress(struct I2cBus *bus, struct I2cDataStandard *msg
return EOK;
}
static uint32 I2cWriteData(struct I2cHardwareDevice *i2c_dev, struct I2cDataStandard *msg)
static uint32 I2cWriteData(struct I2cHardwareDevice* i2c_dev, struct I2cDataStandard* msg)
{
struct I2cBus *bus = (struct I2cBus *)i2c_dev->haldev.owner_bus;
struct I2cBus* bus = (struct I2cBus*)i2c_dev->haldev.owner_bus;
bus->private_data = i2c_dev->haldev.owner_bus->private_data;
struct I2cHalDrvDone *done = (struct I2cHalDrvDone *)bus->private_data;
struct I2cHalDrvDone* done = (struct I2cHalDrvDone*)bus->private_data;
int32 ret;
int32 i = 0;
uint16 ignore_nack;
@ -435,15 +441,15 @@ static uint32 I2cWriteData(struct I2cHardwareDevice *i2c_dev, struct I2cDataStan
}
}
if (msg->flags & I2C_WR) {
if (msg->flags == I2C_WR) {
ret = I2cSendBytes(bus, msg);
if (ret >= 1)
//KPrintf("write %d byte%s", ret, ret == 1 ? "" : "s");
if (ret < msg->len) {
if (ret >= 0)
ret = -ERROR;
goto out;
}
if (ret < msg->len) {
if (ret >= 0)
ret = -ERROR;
goto out;
}
}
msg = msg->next;
i++;
@ -456,11 +462,11 @@ out:
return ret;
}
static uint32 I2cReadData(struct I2cHardwareDevice *i2c_dev, struct I2cDataStandard *msg)
static uint32 I2cReadData(struct I2cHardwareDevice* i2c_dev, struct I2cDataStandard* msg)
{
struct I2cBus *bus = (struct I2cBus *)i2c_dev->haldev.owner_bus;
struct I2cBus* bus = (struct I2cBus*)i2c_dev->haldev.owner_bus;
bus->private_data = i2c_dev->haldev.owner_bus->private_data;
struct I2cHalDrvDone *done = (struct I2cHalDrvDone *)bus->private_data;
struct I2cHalDrvDone* done = (struct I2cHalDrvDone*)bus->private_data;
int32 ret;
int32 i = 0;
uint16 ignore_nack;
@ -483,11 +489,11 @@ static uint32 I2cReadData(struct I2cHardwareDevice *i2c_dev, struct I2cDataStand
ret = I2cRecvBytes(bus, msg);
if (ret >= 1)
//KPrintf("read %d byte%s", ret, ret == 1 ? "" : "s");
if (ret < msg->len) {
if (ret >= 0)
ret = -EPIO;
goto out;
}
if (ret < msg->len) {
if (ret >= 0)
ret = -EPIO;
goto out;
}
}
msg = msg->next;
i++;
@ -500,36 +506,36 @@ out:
return ret;
}
static uint32 I2cInit(struct I2cDriver *i2c_drv, struct BusConfigureInfo *configure_info)
static uint32 I2cInit(struct I2cDriver* i2c_drv, struct BusConfigureInfo* configure_info)
{
NULL_PARAM_CHECK(i2c_drv);
struct I2cHardwareDevice *i2c_dev = (struct I2cHardwareDevice *)i2c_drv->driver.owner_bus->owner_haldev;
struct I2cHardwareDevice* i2c_dev = (struct I2cHardwareDevice*)i2c_drv->driver.owner_bus->owner_haldev;
if (configure_info->private_data) {
i2c_dev->i2c_dev_addr = *((uint16 *)configure_info->private_data);
i2c_dev->i2c_dev_addr = *((uint16*)configure_info->private_data);
return EOK;
}
KPrintf("I2cInit need set i2c dev addr\n");
return ERROR;
}
static uint32 I2cDrvConfigure(void *drv, struct BusConfigureInfo *configure_info)
static uint32 I2cDrvConfigure(void* drv, struct BusConfigureInfo* configure_info)
{
NULL_PARAM_CHECK(drv);
NULL_PARAM_CHECK(configure_info);
x_err_t ret = EOK;
struct I2cDriver *i2c_drv = (struct I2cDriver *)drv;
struct I2cDriver* i2c_drv = (struct I2cDriver*)drv;
switch (configure_info->configure_cmd)
{
case OPE_INT:
ret = I2cInit(i2c_drv, configure_info);
break;
default:
break;
case OPE_INT:
ret = I2cInit(i2c_drv, configure_info);
break;
default:
break;
}
return ret;
@ -545,12 +551,12 @@ static const struct I2cDevDone i2c_dev_done =
};
/*Init i2c bus*/
static int BoardI2cBusInit(struct I2cBus *i2c_bus, struct I2cDriver *i2c_driver)
static int BoardI2cBusInit(struct I2cBus* i2c_bus, struct I2cDriver* i2c_driver)
{
x_err_t ret = EOK;
/*Init the i2c bus */
i2c_bus->private_data = (void *)&I2cDrvDone;
i2c_bus->private_data = (void*)&I2cDrvDone;
ret = I2cBusInit(i2c_bus, I2C_BUS_NAME_1);
if (EOK != ret) {
KPrintf("board_i2c_init I2cBusInit error %d\n", ret);
@ -558,7 +564,7 @@ static int BoardI2cBusInit(struct I2cBus *i2c_bus, struct I2cDriver *i2c_driver)
}
/*Init the i2c driver*/
i2c_driver->private_data = (void *)&I2cDrvDone;
i2c_driver->private_data = (void*)&I2cDrvDone;
ret = I2cDriverInit(i2c_driver, I2C_DRV_NAME_1);
if (EOK != ret) {
KPrintf("board_i2c_init I2cDriverInit error %d\n", ret);
@ -570,7 +576,7 @@ static int BoardI2cBusInit(struct I2cBus *i2c_bus, struct I2cDriver *i2c_driver)
if (EOK != ret) {
KPrintf("board_i2c_init I2cDriverAttachToBus error %d\n", ret);
return ERROR;
}
}
return ret;
}
@ -588,13 +594,13 @@ static int BoardI2cDevBend(void)
if (EOK != ret) {
KPrintf("board_i2c_init I2cDeviceInit device %s error %d\n", I2C_1_DEVICE_NAME_0, ret);
return ERROR;
}
}
ret = I2cDeviceAttachToBus(I2C_1_DEVICE_NAME_0, I2C_BUS_NAME_1);
if (EOK != ret) {
KPrintf("board_i2c_init I2cDeviceAttachToBus device %s error %d\n", I2C_1_DEVICE_NAME_0, ret);
return ERROR;
}
}
return ret;
}
@ -624,7 +630,7 @@ int HwI2cInit(void)
if (EOK != ret) {
KPrintf("board_i2c_Init error ret %u\n", ret);
return ERROR;
}
}
I2cBusReset(&i2c_bus_param);
#endif

View File

@ -0,0 +1,60 @@
/**
* @file connect_touch.h
* @brief support xidatong-riscv64 touch function and register to bus framework
* @version 1.0
* @author AIIT XiUOS Lab
* @date 2022-04-25
*/
#ifndef CONNECT_TOUCH_H
#define CONNECT_TOUCH_H
#include <device.h>
/* 表示读数据 */
#define I2C_M_RD 0x0001
struct i2c_msg {
uint16_t flags; /*控制标志 */
uint16_t len; /*读写数据的长度 */
uint8_t *buf; /*存储读写数据的指针 */
};
typedef struct
{
int X;
int Y;
} POINT;
typedef enum _touch_event
{
kTouch_Down = 0, /*!< The state changed to touched. */
kTouch_Up = 1, /*!< The state changed to not touched. */
kTouch_Contact = 2, /*!< There is a continuous touch being detected. */
kTouch_Reserved = 3 /*!< No touch information available. */
} touch_event_t;
/*设定使用的电容屏IIC设备地址*/
#define GTP_ADDRESS 0xBA
#define GTP_MAX_HEIGHT 272
#define GTP_MAX_WIDTH 480
#define GTP_INT_TRIGGER 0
#define GTP_MAX_TOUCH 5
#define GTP_CONFIG_MAX_LENGTH 240
#define GTP_ADDR_LENGTH 2
// Registers define
#define GTP_READ_COOR_ADDR 0x814E
#define GTP_REG_SLEEP 0x8040
#define GTP_REG_SENSOR_ID 0x814A
#define GTP_REG_CONFIG_DATA 0x8047
#define GTP_REG_VERSION 0x8140
#define CFG_GROUP_LEN(p_cfg_grp) (sizeof(p_cfg_grp) / sizeof(p_cfg_grp[0]))
int HwTouchInit(void);
#endif

View File

@ -0,0 +1,17 @@
if BSP_USING_TOUCH
config TOUCH_BUS_NAME
string "touch bus name"
default "touch"
config TOUCH_DRV_NAME
string "touch bus driver name"
default "touch_drv"
config TOUCH_DEVICE_NAME
string "touch bus device name"
default "touch_dev"
config BSP_TOUCH_TP_INT
int "touch int pin"
default 36
config FPIOA_TOUCH_TP_INT
int "fpioa touch int pin"
default 12
endif

View File

@ -0,0 +1,4 @@
SRC_FILES := connect_touch.c
include $(KERNEL_ROOT)/compiler.mk

View File

@ -0,0 +1,541 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiUOS is licensed under Mulan PSL v2.
* You can use this software according to the terms and conditions of the Mulan PSL v2.
* You may obtain a copy of Mulan PSL v2 at:
* http://license.coscl.org.cn/MulanPSL2
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
* See the Mulan PSL v2 for more details.
*/
/**
* @file connect_touch.c
* @brief support xidatong-riscv64 touch function and register to bus framework
* @version 1.0
* @author AIIT XiUOS Lab
* @date 2022-05-15
*/
#include <stdbool.h>
#include <board.h>
#include <connect_touch.h>
#include <bus.h>
#include <gpiohs.h>
#include <fpioa.h>
// #define LCD_HEIGHT BSP_LCD_X_MAX
// #define LCD_WIDTH BSP_LCD_Y_MAX
#define DEFAULT_NUM 0x0D
volatile bool SemReleaseFlag = 0;
static struct Bus* i2c_bus = NONE;
static struct Bus* pin_bus = NONE;
int touch_sem = 0;
POINT Pre_Touch_Point;
/* HERE WE IMPLEMENT I2C READING AND WRITING FROM SENSOR */
/* write sensor register data */
static x_err_t WriteReg(struct HardwareDev* dev, uint8 len, uint8* buf)
{
struct BusBlockWriteParam write_param;
write_param.pos = 0;
write_param.size = len;
write_param.buffer = (void*)buf;
/* use I2C device API transfer data */
return BusDevWriteData(dev, &write_param);
}
/* read sensor register data */
static x_err_t ReadRegs(struct HardwareDev* dev, uint8 len, uint8* buf)
{
struct BusBlockReadParam read_param;
read_param.pos = 0;
read_param.buffer = (void*)buf;
read_param.read_length = len;
read_param.size = len;
/* use I2C device API transfer data */
return BusDevReadData(dev, &read_param);
}
/**
* i2c_transfer - execute a single I2C message
* @msgs: One or more messages to execute before STOP is issued to
* terminate the operation; each message begins with a START.
*/
int I2C_Transfer(struct i2c_msg* msg)
{
int16 ret = 0;
if (msg->flags & I2C_M_RD) //根据flag判断是读数据还是写数据
{
ret = ReadRegs(i2c_bus->owner_haldev, msg->len, msg->buf); //IIC读取数据
}
else
{
ret = WriteReg(i2c_bus->owner_haldev, msg->len, msg->buf); //IIC写入数据
} //正常完成的传输结构个数
return ret;
}
static int32_t GtpI2cWrite(uint8_t* buf, int32_t len)
{
struct i2c_msg msg;
int32_t ret = -1;
int32_t retries = 0;
msg.flags = !I2C_M_RD;
msg.len = len;
msg.buf = buf;
//msg.scl_rate = 300 * 1000; // for Rockchip, etc
while (retries < 5)
{
ret = I2C_Transfer(&msg);
if (ret == 1) { break; }
retries++;
}
if (retries >= 5)
{
KPrintf("I2C Write: 0x%04X, %d bytes failed, errcode: %d! Process reset.", (((uint16_t)(buf[0] << 8)) | buf[1]), len - 2, ret);
ret = -1;
}
return ret;
}
static int32_t GtpI2cRead(uint8_t* buf, int32_t len)
{
struct i2c_msg msgs[2];
int32_t ret = -1;
int32_t retries = 0;
// write reading addr.
msgs[0].flags = !I2C_M_RD;
msgs[0].len = GTP_ADDR_LENGTH;
msgs[0].buf = buf;
// read data at addr sended.
msgs[1].flags = I2C_M_RD;
msgs[1].len = len - GTP_ADDR_LENGTH;
msgs[1].buf = &buf[GTP_ADDR_LENGTH];
while (retries < 5)
{
ret = I2C_Transfer(&msgs[0]);
ret += I2C_Transfer(&msgs[1]);
if (ret == 2)break;
retries++;
}
if (retries >= 5)
{
KPrintf("I2C Read: 0x%04X, %d bytes %d times failed, errcode: %d! Process reset.\n", (((uint16_t)(buf[0] << 8)) | buf[1]), len - 2, retries, ret);
ret = -1;
}
return ret;
}
/* HERE WE IMPLEMENT TOUCH INIT */
int32_t GtpReadVersion(void)
{
int32_t ret = -1;
uint8_t buf[8] = { GTP_REG_VERSION >> 8, GTP_REG_VERSION & 0xff };
ret = GtpI2cRead(buf, sizeof(buf));
if (ret < 0)
{
KPrintf("GTP read version failed.\n");
return ret;
}
if (buf[5] == 0x00)
{
KPrintf("IC1 Version: %c%c%c_%02x%02x\n", buf[2], buf[3], buf[4], buf[7], buf[6]);
}
else
{
KPrintf("IC2 Version: %c%c%c%c_%02x%02x\n", buf[2], buf[3], buf[4], buf[5], buf[7], buf[6]);
}
return ret;
}
static int32_t GtpGetInfo(void)
{
uint8_t end_cmd[3] = { GTP_READ_COOR_ADDR >> 8, GTP_READ_COOR_ADDR & 0xFF, 0 };
uint8_t opr_buf[6] = { 0 };
int32_t ret = 0;
uint16_t abs_x_max = GTP_MAX_WIDTH;
uint16_t abs_y_max = GTP_MAX_HEIGHT;
uint8_t int_trigger_type = GTP_INT_TRIGGER;
opr_buf[0] = (uint8_t)((GTP_REG_CONFIG_DATA + 1) >> 8);
opr_buf[1] = (uint8_t)((GTP_REG_CONFIG_DATA + 1) & 0xFF);
if (GtpI2cRead(opr_buf, 6) < 0)
{
return -1;
}
abs_x_max = (opr_buf[3] << 8) + opr_buf[2];
abs_y_max = (opr_buf[5] << 8) + opr_buf[4];
opr_buf[0] = (uint8_t)((GTP_REG_CONFIG_DATA + 6) >> 8);
opr_buf[1] = (uint8_t)((GTP_REG_CONFIG_DATA + 6) & 0xFF);
if (GtpI2cRead(opr_buf, 3) < 0)
{
return 0;
}
int_trigger_type = opr_buf[2] & 0x03;
KPrintf("X_MAX = %d, Y_MAX = %d, TRIGGER = 0x%02x\n",
abs_x_max, abs_y_max, int_trigger_type);
if (GtpI2cWrite(end_cmd, 3) < 0)
{
KPrintf("I2C write end_cmd error!\n");
ret = 0;
}
return 0; ;
}
// not used in polling mode
static void GT9xx_PEN_IRQHandler(void* arg)
{
KPrintf("int hdr working.\n");
if (!SemReleaseFlag)
{
KSemaphoreAbandon(touch_sem);
SemReleaseFlag = true;
}
}
int32_t GT9xx_INT_INIT() {
int32_t ret = -ERROR;
pin_bus = PinBusInitGet();
struct PinParam pin_param;
struct BusConfigureInfo pin_configure_info;
pin_configure_info.configure_cmd = OPE_CFG;
pin_configure_info.private_data = (void*)&pin_param;
pin_param.cmd = GPIO_CONFIG_MODE;
pin_param.pin = BSP_TOUCH_TP_INT;
pin_param.mode = GPIO_CFG_INPUT_PULLUP;
ret = BusDrvConfigure(pin_bus->owner_driver, &pin_configure_info);
if (ret != EOK) {
KPrintf("config pin_param %d input failed!\n", pin_param.pin);
return -ERROR;
}
pin_param.cmd = GPIO_IRQ_REGISTER;
pin_param.pin = BSP_TOUCH_TP_INT;
pin_param.irq_set.irq_mode = GPIO_IRQ_EDGE_FALLING;
pin_param.irq_set.hdr = GT9xx_PEN_IRQHandler;
pin_param.irq_set.args = NONE;
ret = BusDrvConfigure(pin_bus->owner_driver, &pin_configure_info);
if (ret != EOK) {
KPrintf("register pin_param %d irq failed!\n", pin_param.pin);
return -ERROR;
}
pin_param.cmd = GPIO_IRQ_DISABLE;
pin_param.pin = BSP_TOUCH_TP_INT;
ret = BusDrvConfigure(pin_bus->owner_driver, &pin_configure_info);
if (ret != EOK) {
KPrintf("disable pin_param %d irq failed!\n", pin_param.pin);
return -ERROR;
}
// 4. enable interuption
pin_param.cmd = GPIO_IRQ_ENABLE;
pin_param.pin = BSP_TOUCH_TP_INT;
ret = BusDrvConfigure(pin_bus->owner_driver, &pin_configure_info);
if (ret != EOK) {
KPrintf("enable pin_param %d irq failed!\n", pin_param.pin);
return -ERROR;
}
return EOK;
}
int32_t I2C_Touch_Init() {
// using static bus information
int32_t ret = -1;
/* find I2C device and get I2C handle */
i2c_bus = BusFind(I2C_BUS_NAME_1);
if (NONE == i2c_bus) {
KPrintf("MCU can't find %s bus!\n", I2C_BUS_NAME_1);
return -ERROR;
}
else {
KPrintf("MCU find %s bus!\n", I2C_BUS_NAME_1);
}
i2c_bus->owner_haldev = BusFindDevice(i2c_bus, I2C_1_DEVICE_NAME_0);
i2c_bus->owner_driver = BusFindDriver(i2c_bus, I2C_DRV_NAME_1);
if (i2c_bus->match(i2c_bus->owner_driver, i2c_bus->owner_haldev)) {
KPrintf("i2c match drv %s %p dev %s %p error\n",
I2C_DRV_NAME_1, i2c_bus->owner_driver,
I2C_1_DEVICE_NAME_0, i2c_bus->owner_haldev);
return -ERROR;
}
else {
KPrintf("MCU successfully! write %p read %p\n",
i2c_bus->owner_haldev->dev_done->write,
i2c_bus->owner_haldev->dev_done->read);
}
struct BusConfigureInfo i2c_configure_info;
// memset(&i2c_configure_info, 0, sizeof(struct BusConfigureInfo));
i2c_configure_info.configure_cmd = OPE_INT;
uint16 i2c_address = GTP_ADDRESS >> 1;
i2c_configure_info.private_data = (void*)&i2c_address;
BusDrvConfigure(i2c_bus->owner_driver, &i2c_configure_info);
// 3. init interruption
return GT9xx_INT_INIT();
}
/* HERE WE IMPLEMENT GET COORDINATE FUNCTION */
/**
* @brief
* @param
* @retval
*/
bool GetTouchEvent(POINT* touch_point, touch_event_t* touch_event)
{
uint8_t end_cmd[3] = { GTP_READ_COOR_ADDR >> 8, GTP_READ_COOR_ADDR & 0xFF, 0 };
uint8_t point_data[2 + 1 + 8 * GTP_MAX_TOUCH + 1] = { GTP_READ_COOR_ADDR >> 8, GTP_READ_COOR_ADDR & 0xFF };
uint8_t touch_num = 0;
uint8_t finger = 0;
static uint16_t pre_touch = 0;
uint8_t* coor_data = NULL;
int32_t input_x = 0;
int32_t input_y = 0;
int32_t input_w = 0;
int32_t ret = -1;
ret = GtpI2cRead(point_data, 12);//10字节寄存器加2字节地址
if (ret < 0)
{
KPrintf("I2C transfer error. errno:%d\n ", ret);
return 0;
}
finger = point_data[GTP_ADDR_LENGTH];//状态寄存器数据
if (finger == 0x00) //没有数据,退出
{
ret = 0;
goto exit_work_func;
}
if ((finger & 0x80) == 0)//判断buffer status位
{
ret = 0;
goto exit_work_func;//坐标未就绪,数据无效
}
touch_num = finger & 0x0f;//坐标点数
if (touch_num > GTP_MAX_TOUCH)
{
ret = 0;
goto exit_work_func;//大于最大支持点数,错误退出
}
if (touch_num)
{
coor_data = &point_data[0 * 8 + 3];
input_x = coor_data[1] | (coor_data[2] << 8); //x坐标
input_y = coor_data[3] | (coor_data[4] << 8); //y坐标
input_w = coor_data[5] | (coor_data[6] << 8); //size
touch_point->X = input_x;
touch_point->Y = input_y;
*touch_event = kTouch_Down;
Pre_Touch_Point = *touch_point;
}
else if (pre_touch) //touch_ num=0 且pre_touch=0
{
*touch_point = Pre_Touch_Point;
*touch_event = kTouch_Up;
Pre_Touch_Point.X = -1;
Pre_Touch_Point.Y = -1;
}
pre_touch = touch_num;
exit_work_func:
{
ret = GtpI2cWrite(end_cmd, 3);
if (ret < 0)
{
KPrintf("I2C write end_cmd error!\n");
ret = 0;
}
}
return ret;
}
static uint32 TouchOpen(void* dev)
{
int32_t ret = -1;
I2C_Touch_Init();
ret = GtpReadVersion();
if (ret < 0)
{
KPrintf("gtp read version error\n");
return ret;
}
ret = GtpGetInfo();
if (ret < 0)
{
KPrintf("gtp read info error\n");
return ret;
}
touch_sem = KSemaphoreCreate(0);
if (touch_sem < 0) {
KPrintf("touch create sem failed .\n");
return -1;
}
return ret;
}
static uint32 TouchClose(void* dev)
{
KSemaphoreDelete(touch_sem);
return 0;
}
static uint32 TouchRead(void* dev, struct BusBlockReadParam* read_param)
{
uint32 ret = -1;
x_err_t result;
POINT touch_point;
touch_point.X = -1;
touch_point.Y = -1;
touch_event_t touch_event;
struct TouchDataStandard* data = (struct TouchDataStandard*)read_param->buffer;
read_param->read_length = 0;
result = KSemaphoreObtain(touch_sem, 100);
if (GetTouchEvent(&touch_point, &touch_event))
{
data->x = touch_point.X;
data->y = touch_point.Y;
read_param->read_length = read_param->size;
ret = EOK;
}
SemReleaseFlag = 0;
return ret;
}
static uint32 TouchConfigure(void* drv, struct BusConfigureInfo* configure_info)
{
return 0;
}
struct TouchDevDone touch_dev_done =
{
.open = TouchOpen,
.close = TouchClose,
.write = NONE,
.read = TouchRead
};
/* BUS, DRIVER, DEVICE INIT */
// register bus and driver
static int BoardTouchBusInit(struct TouchBus* touch_bus, struct TouchDriver* touch_driver, const char* bus_name, const char* drv_name)
{
x_err_t ret = EOK;
/*Init the touch bus */
ret = TouchBusInit(touch_bus, bus_name);
if (EOK != ret) {
KPrintf("Board_touch_init touchBusInit error %d\n", ret);
return -ERROR;
}
/*Init the touch driver*/
ret = TouchDriverInit(touch_driver, drv_name);
if (EOK != ret) {
KPrintf("Board_touch_init touchDriverInit error %d\n", ret);
return -ERROR;
}
/*Attach the touch driver to the touch bus*/
ret = TouchDriverAttachToBus(drv_name, bus_name);
if (EOK != ret) {
KPrintf("Board_touch_init TouchDriverAttachToBus error %d\n", ret);
return -ERROR;
}
return ret;
}
/*Attach the touch device to the touch bus*/
static int BoardTouchDevBend(struct TouchHardwareDevice* touch_device, void* param, const char* bus_name, const char* dev_name)
{
x_err_t ret = EOK;
ret = TouchDeviceRegister(touch_device, param, dev_name);
if (EOK != ret) {
KPrintf("TouchDeviceRegister device %s error %d\n", dev_name, ret);
return -ERROR;
}
ret = TouchDeviceAttachToBus(dev_name, bus_name);
if (EOK != ret) {
KPrintf("TouchDeviceAttachToBus device %s error %d\n", dev_name, ret);
return -ERROR;
}
return ret;
}
// init bus, driver and device needed.
// stored in touch_bus, touch_driver and touch_dev
int HwTouchInit(void)
{
x_err_t ret = EOK;
static struct TouchBus touch_bus;
static struct TouchDriver touch_driver;
static struct TouchHardwareDevice touch_dev;
memset(&touch_bus, 0, sizeof(struct TouchBus));
memset(&touch_driver, 0, sizeof(struct TouchDriver));
memset(&touch_dev, 0, sizeof(struct TouchHardwareDevice));
touch_driver.configure = TouchConfigure;
ret = BoardTouchBusInit(&touch_bus, &touch_driver, TOUCH_BUS_NAME, TOUCH_DRV_NAME);
if (EOK != ret) {
return -ERROR;
}
touch_dev.dev_done = &touch_dev_done;
ret = BoardTouchDevBend(&touch_dev, NONE, TOUCH_BUS_NAME, TOUCH_DEVICE_NAME);
if (EOK != ret) {
KPrintf("board_touch_Init error ret %u\n", ret);
return -ERROR;
}
return EOK;
}

View File

@ -21,7 +21,7 @@ COMPILER:
$(MAKE) -C $$dir; \
done; \
fi
@echo -n $(OBJS) " " >> $(KERNEL_ROOT)/build/make.obj
@/bin/echo -n $(OBJS) " " >> $(KERNEL_ROOT)/build/make.obj
################################################
@ -33,7 +33,7 @@ $(eval OBJS += $(LOCALC)) \
$(if $(strip $(LOCALC)),$(eval $(LOCALC): $(1)
@if [ ! -d $$(@D) ]; then mkdir -p $$(@D); fi
@echo cc $$<
@echo -n $(dir $(LOCALC)) >>$(KERNEL_ROOT)/build/make.dep
@/bin/echo -n $(dir $(LOCALC)) >>$(KERNEL_ROOT)/build/make.dep
@$(CROSS_COMPILE)gcc -MM $$(CFLAGS) -c $$< >>$(KERNEL_ROOT)/build/make.dep
@$(CROSS_COMPILE)gcc $$(CFLAGS) -c $$< -o $$@))
endef
@ -46,7 +46,7 @@ $(eval OBJS += $(LOCALCPP)) \
$(if $(strip $(LOCALCPP)),$(eval $(LOCALCPP): $(1)
@if [ ! -d $$(@D) ]; then mkdir -p $$(@D); fi
@echo cc $$<
@echo -n $(dir $(LOCALCPP)) >>$(KERNEL_ROOT)/build/make.dep
@/bin/echo -n $(dir $(LOCALCPP)) >>$(KERNEL_ROOT)/build/make.dep
@$(CROSS_COMPILE)g++ -MM $$(CXXFLAGS) -c $$< >>$(KERNEL_ROOT)/build/make.dep
@$(CROSS_COMPILE)g++ $$(CXXFLAGS) -c $$< -o $$@))
endef
@ -59,7 +59,7 @@ $(eval OBJS += $(LOCALCPP)) \
$(if $(strip $(LOCALCPP)),$(eval $(LOCALCPP): $(1)
@if [ ! -d $$(@D) ]; then mkdir -p $$(@D); fi
@echo cc $$<
@echo -n $(dir $(LOCALCPP)) >>$(KERNEL_ROOT)/build/make.dep
@/bin/echo -n $(dir $(LOCALCPP)) >>$(KERNEL_ROOT)/build/make.dep
@$(CROSS_COMPILE)g++ -MM $$(CXXFLAGS) -c $$< >>$(KERNEL_ROOT)/build/make.dep
@$(CROSS_COMPILE)g++ $$(CXXFLAGS) -c $$< -o $$@))
endef
@ -72,7 +72,7 @@ $(eval OBJS += $(LOCALS)) \
$(if $(strip $(LOCALS)),$(eval $(LOCALS): $(1)
@if [ ! -d $$(@D) ]; then mkdir -p $$(@D); fi
@echo cc $$<
@echo -n $(dir $(LOCALC)) >>$(KERNEL_ROOT)/build/make.dep
@/bin/echo -n $(dir $(LOCALC)) >>$(KERNEL_ROOT)/build/make.dep
@$(CROSS_COMPILE)gcc -MM $$(CFLAGS) -c $$< >>$(KERNEL_ROOT)/build/make.dep
@$(CROSS_COMPILE)gcc $$(AFLAGS) -c $$< -o $$@))
endef