add loransh/defconfig for edu-riscv64 on nuttx

This commit is contained in:
wgzAIIT 2022-11-29 11:13:08 +08:00
parent 4fd39c0dd7
commit 2757649473
9 changed files with 90 additions and 1667 deletions

View File

@ -39,128 +39,4 @@ menuconfig BSP_USING_TOUCH
bool "Using touch device"
default n
menuconfig BSP_USING_CAN
select K210_UART
select K210_UART1
bool "Using CAN device"
default n
menuconfig BSP_USING_CH438
bool "Using CH438 device"
default n
if BSP_USING_CH438
config CH438_EXTUART0
bool "Using Ch438 Port 0"
default n
menu "Ch438 Port 0 Configuration"
depends on CH438_EXTUART0
config CH438_EXTUART0_BAUD
int "Ch438 Port 0 Baud Rate."
default 115200
---help---
The configured BAUD of the CH438 EXTUART0.
endmenu
config CH438_EXTUART1
bool "Using Ch438 Port 1"
default n
menu "Ch438 Port 1 Configuration"
depends on CH438_EXTUART1
config CH438_EXTUART1_BAUD
int "Ch438 Port 1 Baud Rate."
default 115200
---help---
The configured BAUD of the CH438 EXTUART1.
endmenu
config CH438_EXTUART2
bool "Using Ch438 Port 2"
default n
menu "Ch438 Port 2 Configuration"
depends on CH438_EXTUART2
config CH438_EXTUART2_BAUD
int "Ch438 Port 2 Baud Rate."
default 115200
---help---
The configured BAUD of the CH438 EXTUART2.
endmenu
config CH438_EXTUART3
bool "Using Ch438 Port 3"
default n
menu "Ch438 Port 3 Configuration"
depends on CH438_EXTUART3
config CH438_EXTUART3_BAUD
int "Ch438 Port 3 Baud Rate."
default 115200
---help---
The configured BAUD of the CH438 EXTUART3.
endmenu
config CH438_EXTUART4
bool "Using Ch438 Port 4"
default n
menu "Ch438 Port 4 Configuration"
depends on CH438_EXTUART4
config CH438_EXTUART4_BAUD
int "Ch438 Port 4 Baud Rate."
default 115200
---help---
The configured BAUD of the CH438 EXTUART4.
endmenu
config CH438_EXTUART5
bool "Using Ch438 Port 5"
default n
menu "Ch438 Port 5 Configuration"
depends on CH438_EXTUART5
config CH438_EXTUART5_BAUD
int "Ch438 Port 5 Baud Rate."
default 115200
---help---
The configured BAUD of the CH438 EXTUART5.
endmenu
config CH438_EXTUART6
bool "Using Ch438 Port 6"
default n
menu "Ch438 Port 6 Configuration"
depends on CH438_EXTUART6
config CH438_EXTUART6_BAUD
int "Ch438 Port 6 Baud Rate."
default 115200
---help---
The configured BAUD of the CH438 EXTUART6.
endmenu
config CH438_EXTUART7
bool "Using Ch438 Port 7"
default n
menu "Ch438 Port 7 Configuration"
depends on CH438_EXTUART7
config CH438_EXTUART7_BAUD
int "Ch438 Port 7 Baud Rate."
default 115200
---help---
The configured BAUD of the CH438 EXTUART7.
endmenu
endif # BSP_USING_CH438
endif # ARCH_BOARD_EDU_RISCV64

View File

@ -0,0 +1,80 @@
#
# This file is autogenerated: PLEASE DO NOT EDIT IT.
#
# You can use "make menuconfig" to make any modifications to the installed .config file.
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
# modifications.
#
# CONFIG_NSH_DISABLE_LOSMART is not set
# CONFIG_STANDARD_SERIAL is not set
CONFIG_ADD_NUTTX_FETURES=y
CONFIG_ARCH="risc-v"
CONFIG_ARCH_BOARD="xidatong-riscv64"
CONFIG_ARCH_BOARD_XIDATONG_RISCV64=y
CONFIG_ARCH_CHIP="k210"
CONFIG_ARCH_CHIP_K210=y
CONFIG_ARCH_INTERRUPTSTACK=2048
CONFIG_ARCH_RISCV=y
CONFIG_ARCH_STACKDUMP=y
CONFIG_BINFMT_DISABLE=y
CONFIG_BOARD_LOOPSPERMSEC=46000
CONFIG_BUILTIN=y
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_SYMBOLS=y
CONFIG_EXAMPLES_HELLO=y
CONFIG_IDLETHREAD_STACKSIZE=2048
CONFIG_INIT_ENTRYPOINT="nsh_main"
CONFIG_INIT_STACKSIZE=3072
CONFIG_INTELHEX_BINARY=y
CONFIG_LIBC_PERROR_STDOUT=y
CONFIG_LIBC_STRERROR=y
CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_BUILTIN_APPS=y
CONFIG_NSH_DISABLE_IFUPDOWN=y
CONFIG_NSH_DISABLE_MKDIR=y
CONFIG_NSH_DISABLE_RM=y
CONFIG_NSH_DISABLE_RMDIR=y
CONFIG_NSH_DISABLE_UMOUNT=y
CONFIG_NSH_READLINE=y
CONFIG_NSH_STRERROR=y
CONFIG_PREALLOC_TIMERS=4
CONFIG_RAM_SIZE=2097152
CONFIG_RAM_START=0x80400000
CONFIG_RAW_BINARY=y
CONFIG_READLINE_CMD_HISTORY=y
CONFIG_READLINE_CMD_HISTORY_LEN=100
CONFIG_READLINE_CMD_HISTORY_LINELEN=120
CONFIG_RR_INTERVAL=200
CONFIG_SCHED_WAITPID=y
CONFIG_STACK_COLORATION=y
CONFIG_START_DAY=28
CONFIG_START_MONTH=12
CONFIG_START_YEAR=2019
CONFIG_SYSTEM_NSH=y
CONFIG_TASK_NAME_SIZE=20
CONFIG_TESTING_GETPRIME=y
CONFIG_UART0_SERIAL_CONSOLE=y
CONFIG_READLINE_TABCOMPLETION=y
CONFIG_SCHED_HPWORK=y
CONFIG_DEV_GPIO=y
CONFIG_BOARDCTL_RESET=y
CONFIG_K210_UART=y
CONFIG_K210_UART2=y
CONFIG_K210_UART2_BASE=0x50220000
CONFIG_K210_UART2_CLOCK=195000000
CONFIG_K210_UART2_IRQ=39
CONFIG_K210_UART2_BAUD=115200
CONFIG_K210_UART2_PARITY=0
CONFIG_K210_UART2_BITS=8
CONFIG_K210_UART2_2STOP=0
CONFIG_K210_UART2_RXBUFSIZE=128
CONFIG_K210_UART2_TXBUFSIZE=128
CONFIG_SUPPORT_CONNECTION_FRAMEWORK=y
CONFIG_CONNECTION_FRAMEWORK_DEBUG=y
CONFIG_CONNECTION_ADAPTER_LORA=y
CONFIG_ADAPTER_E220=y
CONFIG_ADAPTER_LORA_E220="e220"
CONFIG_ADAPTER_E220_DRIVER_EXTUART=n
CONFIG_ADAPTER_E220_DRIVER="/dev/ttyS2"
CONFIG_ADAPTER_E220_M0_PATH="/dev/gpio0"
CONFIG_ADAPTER_E220_M1_PATH="/dev/gpio1"

View File

@ -80,28 +80,12 @@ extern "C"
/*************************** GPIO define ***************************/
/* UART IO */
#define GPIO_WIFI_RXD 7
#define GPIO_WIFI_TXD 6
#define GPIO_EC200T_RXD 21
#define GPIO_EC200T_TXD 20
#define GPIO_CH376T_RXD 22
#define GPIO_CH376T_TXD 23
#define GPIO_CAN_RXD 18
#define GPIO_CAN_TXD 19
/* ch438 IO */
#define CH438_ALE_PIN 24
#define CH438_NWR_PIN 25
#define CH438_NRD_PIN 26
#define CH438_D0_PIN 27
#define CH438_D1_PIN 28
#define CH438_D2_PIN 29
#define CH438_D3_PIN 30
#define CH438_D4_PIN 31
#define CH438_D5_PIN 32
#define CH438_D6_PIN 33
#define CH438_D7_PIN 34
#define CH438_INT_PIN 35
#define GPIO_WIFI_RXD 7
#define GPIO_WIFI_TXD 6
#define GPIO_E220_RXD 21
#define GPIO_E220_TXD 20
#define GPIO_CH376T_RXD 22
#define GPIO_CH376T_TXD 23
/* w5500 IO */
#define BSP_ENET_SCLK 9
@ -124,8 +108,8 @@ extern "C"
#define BSP_IIC_SCL 17
/* other mode io */
#define GPIO_E220_M0 44
#define GPIO_E220_M1 45
#define GPIO_E220_M0 32
#define GPIO_E220_M1 33
#define GPIO_E18_MODE 46
#define GPIO_WIFI_EN 8
#define GPIO_CAN_CFG 43
@ -143,20 +127,6 @@ extern "C"
#define FPOA_USART3_RX K210_IO_FUNC_UART3_RX
#define FPOA_USART3_TX K210_IO_FUNC_UART3_TX
/* ch438 FPIOA */
#define FPIOA_CH438_ALE 11
#define FPIOA_CH438_NWR 12
#define FPIOA_CH438_NRD 13
#define FPIOA_CH438_D0 14
#define FPIOA_CH438_D1 15
#define FPIOA_CH438_D2 16
#define FPIOA_CH438_D3 17
#define FPIOA_CH438_D4 18
#define FPIOA_CH438_D5 29
#define FPIOA_CH438_D6 20
#define FPIOA_CH438_D7 31
#define FPIOA_CH438_INT 22
/* w5500 FPIOA */
#define FPIOA_ENET_NRST 0
#define FPIOA_ENET_NINT 9

View File

@ -42,10 +42,6 @@ ifeq ($(CONFIG_DEV_GPIO),y)
CSRCS += k210_gpio.c
endif
ifeq ($(CONFIG_BSP_USING_CH438),y)
CSRCS += k210_ch438.c ch438_demo.c
endif
ifeq ($(CONFIG_BSP_USING_CH376),y)
CSRCS += k210_ch376.c ch376_demo.c
endif
@ -58,8 +54,4 @@ ifeq ($(CONFIG_BSP_USING_TOUCH),y)
CSRCS += k210_touch.c
endif
ifeq ($(CONFIG_BSP_USING_CAN),y)
CSRCS += can_demo.c
endif
include $(TOPDIR)/boards/Board.mk

View File

@ -1,147 +0,0 @@
/*
* 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 can_demo.c
* @brief edu-riscv64 can_demo.c
* @version 1.0
* @author AIIT XUOS Lab
* @date 2022.11.10
*/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <nuttx/pthread.h>
#include <sys/ioctl.h>
#include <nuttx/time.h>
#include <nuttx/fs/fs.h>
#include <nuttx/fs/ioctl.h>
#include <nuttx/arch.h>
#include <nuttx/board.h>
#include <arch/board/board.h>
#include <stdint.h>
#include <stdio.h>
#include <unistd.h>
#include <stdbool.h>
#include "time.h"
#include <debug.h>
#include <assert.h>
#include <fcntl.h>
#include <termios.h>
#include <nuttx/ioexpander/gpio.h>
#include "k210_uart.h"
#include "k210_fpioa.h"
#include "k210_gpiohs.h"
#include "k210_gpio_common.h"
static int fd, flag=0;
static void serial_thread_entry(void)
{
uint8_t ch;
while(read(fd, &ch, 1) == 1)
{
printf("%02x ",ch);
}
}
static void start_thread(void)
{
int ret;
pthread_t thread;
pthread_attr_t attr = PTHREAD_ATTR_INITIALIZER;
attr.priority = 20;
attr.stacksize = 2048;
ret = pthread_create(&thread, &attr, (void*)serial_thread_entry, NULL);
if (ret != 0)
{
printf("task create failed, status=%d\n", ret);
}
flag = 1;
}
static void set_baud(unsigned long speed)
{
struct termios cfg;
tcgetattr(fd, &cfg);
cfsetspeed(&cfg, speed);
tcsetattr(fd, TCSANOW, &cfg);
}
static void can_cfg_start(void)
{
uint8_t cmd[8];
set_baud(9600);
up_mdelay(1000);
k210_gpiohs_set_direction(FPIOA_CAN_NCFG, GPIO_DM_OUTPUT);
k210_gpiohs_set_value(FPIOA_CAN_NCFG, GPIO_PV_LOW);
up_mdelay(200);
cmd[0] = 0xAA;
cmd[1] = 0x55;
cmd[2] = 0xFD;
cmd[3] = 0x32;
cmd[4] = 0x01;
cmd[5] = 0x0B;
cmd[6] = 0xc4;
cmd[7] = 0x29;
write(fd, cmd, 8);
}
static void can_cfg_end(void)
{
k210_gpiohs_set_direction(FPIOA_CAN_NCFG, GPIO_DM_OUTPUT);
k210_gpiohs_set_value(FPIOA_CAN_NCFG, GPIO_PV_HIGH);
set_baud(115200);
}
void can_test(void)
{
uint8_t msg[8];
uint8_t i;
fd = open("/dev/ttyS1", O_RDWR);
if (flag == 0)
{
/* 1、start thread */
start_thread();
up_mdelay(20);
/* 2、config can prama */
can_cfg_start();
up_mdelay(20);
/* 3、exit config */
can_cfg_end();
up_mdelay(20);;
}
/* 4、send data */
for(i=0;i<10;i++)
{
msg[0] = 0x11;
msg[1] = 0x22;
msg[2] = 0x33;
msg[3] = 0x44;
msg[4] = 0x55;
msg[5] = 0x66;
msg[6] = 0x77;
msg[7] = 0x99;
write(fd, msg, 8);
up_mdelay(20);
}
}

View File

@ -1,84 +0,0 @@
/*
* 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 ch438_demo.c
* @brief edu-riscv64 ch438_demo.c
* @version 1.0
* @author AIIT XUOS Lab
* @date 2022.03.17
*/
/****************************************************************************
* Included Files
****************************************************************************/
#include "k210_ch438.h"
#include <sys/ioctl.h>
#include <nuttx/ioexpander/gpio.h>
void CH438Demo(void)
{
int fd, m0fd, m1fd;
int i;
char sendbuffer1[4] = {0xC0,0x04,0x01,0x09};
char sendbuffer2[6] = {0xC0,0x00,0x03,0x12,0x34,0x61};
char sendbuffer3[3] = {0xC1,0x04,0x01};
char sendbuffer4[3] = {0xC1,0x00,0x03};
char buffer[256];
int readlen;
fd = open("/dev/extuart_dev3", O_RDWR);
ioctl(fd, OPE_INT, (unsigned long)9600);
m0fd = open("/dev/gpio0", O_RDWR);
m1fd = open("/dev/gpio1", O_RDWR);
ioctl(m0fd, GPIOC_WRITE, (unsigned long)1);
ioctl(m1fd, GPIOC_WRITE, (unsigned long)1);
sleep(1);
write(fd, sendbuffer1,4);
sleep(1);
readlen = read(fd, buffer, 256);
printf("readlen1 = %d\n", readlen);
for(i = 0;i< readlen; ++i)
{
printf("0x%x\n", buffer[i]);
}
write(fd, sendbuffer2,6);
sleep(1);
readlen = read(fd, buffer, 256);
printf("readlen1 = %d\n", readlen);
for(i = 0;i< readlen; ++i)
{
printf("0x%x\n", buffer[i]);
}
write(fd, sendbuffer3,3);
sleep(1);
readlen = read(fd, buffer, 256);
printf("readlen1 = %d\n", readlen);
for(i = 0;i< readlen; ++i)
{
printf("0x%x\n", buffer[i]);
}
write(fd, sendbuffer4,3);
sleep(1);
readlen = read(fd, buffer, 256);
printf("readlen1 = %d\n", readlen);
for(i = 0;i< readlen; ++i)
{
printf("0x%x\n", buffer[i]);
}
close(fd);
}

View File

@ -82,10 +82,6 @@ int k210_bringup(void)
}
#endif
#ifdef CONFIG_BSP_USING_CH438
board_ch438_initialize();
#endif
#ifdef CONFIG_K210_LCD
k210_sysctl_init();
board_lcd_initialize();
@ -96,7 +92,6 @@ int k210_bringup(void)
#endif
#ifdef CONFIG_K210_UART1
#ifdef CONFIG_ADAPTER_ESP8285_WIFI
sysctl_clock_enable(SYSCTL_CLOCK_UART1);
sysctl_reset(SYSCTL_RESET_UART1);
@ -110,23 +105,12 @@ int k210_bringup(void)
k210_gpiohs_set_value(FPIOA_WIFI_EN, GPIO_PV_HIGH);
#endif
#ifdef CONFIG_BSP_USING_CAN
sysctl_clock_enable(SYSCTL_CLOCK_UART1);
sysctl_reset(SYSCTL_RESET_UART1);
fpioa_set_function(GPIO_CAN_TXD, FPOA_USART1_TX);
fpioa_set_function(GPIO_CAN_RXD, FPOA_USART1_RX);
k210_fpioa_config(GPIO_CAN_CFG, HS_GPIO(FPIOA_CAN_NCFG) | K210_IOFLAG_GPIOHS);
#endif
#endif
#ifdef CONFIG_K210_UART2
sysctl_clock_enable(SYSCTL_CLOCK_UART2);
sysctl_reset(SYSCTL_RESET_UART2);
fpioa_set_function(GPIO_EC200T_RXD, FPOA_USART2_RX);
fpioa_set_function(GPIO_EC200T_TXD, FPOA_USART2_TX);
fpioa_set_function(GPIO_E220_RXD, FPOA_USART2_RX);
fpioa_set_function(GPIO_E220_TXD, FPOA_USART2_TX);
#endif
#ifdef CONFIG_K210_UART3

View File

@ -1,922 +0,0 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiOS 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 k210_ch438.c
* @brief edu-riscv64 k210_ch438.c
* @version 1.0
* @author AIIT XUOS Lab
* @date 2022.06.08
*/
#include "k210_ch438.h"
#define CH438PORTNUM 8
#define CH438_BUFFSIZE 256
#define CH438_INCREMENT MSEC2TICK(33)
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
static FAR void getInterruptStatus(FAR void *arg);
static void ch438_io_config(void);
static void CH438SetOutput(void);
static void CH438SetInput(void);
static uint8_t ReadCH438Data(uint8_t addr);
static void WriteCH438Data(uint8_t addr, const uint8_t dat);
static void WriteCH438Block(uint8_t mAddr, uint8_t mLen, const uint8_t *mBuf);
static void Ch438UartSend(uint8_t ext_uart_no, const uint8_t *Data, uint16_t Num);
uint8_t CH438UARTRcv(uint8_t ext_uart_no, uint8_t *buf, size_t size);
static void K210CH438Init(void);
static void CH438PortInit(uint8_t ext_uart_no, uint32_t baud_rate);
static int K210Ch438WriteData(uint8_t ext_uart_no, const uint8_t *write_buffer, size_t size);
static size_t K210Ch438ReadData(uint8_t ext_uart_no, size_t size);
static void Ch438InitDefault(void);
static int ch438_open(FAR struct file *filep);
static int ch438_close(FAR struct file *filep);
static ssize_t ch438_read(FAR struct file *filep, FAR char *buffer, size_t buflen);
static ssize_t ch438_write(FAR struct file *filep, FAR const char *buffer, size_t buflen);
static int ch438_ioctl(FAR struct file *filep, int cmd, unsigned long arg);
static int ch438_register(FAR const char *devpath, uint8_t ext_uart_no);
/****************************************************************************
* Private type
****************************************************************************/
struct ch438_dev_s
{
sem_t devsem; /* ch438 port devsem */
uint8_t port; /* ch438 port number*/
};
/****************************************************************************
* Private Data
****************************************************************************/
/*mutex of corresponding port*/
static pthread_mutex_t mutex[CH438PORTNUM] =
{
PTHREAD_MUTEX_INITIALIZER,
PTHREAD_MUTEX_INITIALIZER,
PTHREAD_MUTEX_INITIALIZER,
PTHREAD_MUTEX_INITIALIZER,
PTHREAD_MUTEX_INITIALIZER,
PTHREAD_MUTEX_INITIALIZER,
PTHREAD_MUTEX_INITIALIZER,
PTHREAD_MUTEX_INITIALIZER
};
/* Condition variable of corresponding port */
static pthread_cond_t cond[CH438PORTNUM] =
{
PTHREAD_COND_INITIALIZER,
PTHREAD_COND_INITIALIZER,
PTHREAD_COND_INITIALIZER,
PTHREAD_COND_INITIALIZER,
PTHREAD_COND_INITIALIZER,
PTHREAD_COND_INITIALIZER,
PTHREAD_COND_INITIALIZER,
PTHREAD_COND_INITIALIZER
};
/* This array shows whether the current serial port is selected */
static bool const g_uart_selected[CH438PORTNUM] =
{
#ifdef CONFIG_CH438_EXTUART0
[0] = true,
#endif
#ifdef CONFIG_CH438_EXTUART1
[1] = true,
#endif
#ifdef CONFIG_CH438_EXTUART2
[2] = true,
#endif
#ifdef CONFIG_CH438_EXTUART3
[3] = true,
#endif
#ifdef CONFIG_CH438_EXTUART4
[4] = true,
#endif
#ifdef CONFIG_CH438_EXTUART5
[5] = true,
#endif
#ifdef CONFIG_CH438_EXTUART6
[6] = true,
#endif
#ifdef CONFIG_CH438_EXTUART7
[7] = true,
#endif
};
/* ch438 Callback work queue structure */
static struct work_s g_ch438irqwork;
/* there is data available on the corresponding port */
static volatile bool done[CH438PORTNUM] = {false,false,false,false,false,false,false,false};
/* Eight port data buffer */
static uint8_t buff[CH438PORTNUM][CH438_BUFFSIZE];
/* the value of interrupt number of SSR register */
static uint8_t Interruptnum[CH438PORTNUM] = {0x01,0x02,0x04,0x08,0x10,0x20,0x40,0x80,};
/* Offset address of serial port number */
static uint8_t offsetadd[CH438PORTNUM] = {0x00,0x10,0x20,0x30,0x08,0x18,0x28,0x38,};
/* port open status global variable */
static volatile bool g_ch438open[CH438PORTNUM] = {false,false,false,false,false,false,false,false};
/* Ch438 POSIX interface */
static const struct file_operations g_ch438fops =
{
ch438_open,
ch438_close,
ch438_read,
ch438_write,
NULL,
ch438_ioctl,
NULL
};
/****************************************************************************
* Name: getInterruptStatus
*
* Description:
* thread task getInterruptStatus
*
****************************************************************************/
static FAR void getInterruptStatus(FAR void *arg)
{
uint8_t i;
uint8_t gInterruptStatus; /* Interrupt register status */
gInterruptStatus = ReadCH438Data(REG_SSR_ADDR);
if(gInterruptStatus)
{
for(i = 0; i < CH438PORTNUM; i++)
{
if(g_uart_selected[i] && (gInterruptStatus & Interruptnum[i]))
{
pthread_mutex_lock(&mutex[i]);
done[i] = true;
pthread_cond_signal(&cond[i]);
pthread_mutex_unlock(&mutex[i]);
}
}
}
work_queue(HPWORK, &g_ch438irqwork, getInterruptStatus, NULL, CH438_INCREMENT);
}
/****************************************************************************
* Name: Ch438SetPinMode
*
* Description:
* Configure pin mode
*
* Input Parameters:
* hard_io - Hardware IO
* soft_io - Software IO mapped to
* dir - true for output, false for input
*
****************************************************************************/
static void ch438_io_config(void)
{
k210_fpioa_config(CH438_NWR_PIN, CH438_FUNC_GPIO(FPIOA_CH438_NWR));
k210_fpioa_config(CH438_NRD_PIN, CH438_FUNC_GPIO(FPIOA_CH438_NRD));
k210_fpioa_config(CH438_ALE_PIN, CH438_FUNC_GPIO(FPIOA_CH438_ALE));
k210_fpioa_config(CH438_D0_PIN, CH438_FUNC_GPIO(FPIOA_CH438_D0));
k210_fpioa_config(CH438_D1_PIN, CH438_FUNC_GPIO(FPIOA_CH438_D1));
k210_fpioa_config(CH438_D2_PIN, CH438_FUNC_GPIO(FPIOA_CH438_D2));
k210_fpioa_config(CH438_D3_PIN, CH438_FUNC_GPIO(FPIOA_CH438_D3));
k210_fpioa_config(CH438_D4_PIN, CH438_FUNC_GPIO(FPIOA_CH438_D4));
k210_fpioa_config(CH438_D5_PIN, CH438_FUNC_GPIO(FPIOA_CH438_D5));
k210_fpioa_config(CH438_D6_PIN, CH438_FUNC_GPIO(FPIOA_CH438_D6));
k210_fpioa_config(CH438_D7_PIN, CH438_FUNC_GPIO(FPIOA_CH438_D7));
}
/****************************************************************************
* Name: CH438SetOutput
*
* Description:
* Configure pin mode to output
*
****************************************************************************/
static void CH438SetOutput(void)
{
k210_gpiohs_set_direction(FPIOA_CH438_D0, GPIO_DM_OUTPUT);
k210_gpiohs_set_direction(FPIOA_CH438_D1, GPIO_DM_OUTPUT);
k210_gpiohs_set_direction(FPIOA_CH438_D2, GPIO_DM_OUTPUT);
k210_gpiohs_set_direction(FPIOA_CH438_D3, GPIO_DM_OUTPUT);
k210_gpiohs_set_direction(FPIOA_CH438_D4, GPIO_DM_OUTPUT);
k210_gpiohs_set_direction(FPIOA_CH438_D5, GPIO_DM_OUTPUT);
k210_gpiohs_set_direction(FPIOA_CH438_D6, GPIO_DM_OUTPUT);
k210_gpiohs_set_direction(FPIOA_CH438_D7, GPIO_DM_OUTPUT);
}
/****************************************************************************
* Name: CH438SetInput
*
* Description:
* Configure pin mode to input
*
****************************************************************************/
static void CH438SetInput(void)
{
k210_gpiohs_set_direction(FPIOA_CH438_D0, GPIO_DM_INPUT_PULL_UP);
k210_gpiohs_set_direction(FPIOA_CH438_D1, GPIO_DM_INPUT_PULL_UP);
k210_gpiohs_set_direction(FPIOA_CH438_D2, GPIO_DM_INPUT_PULL_UP);
k210_gpiohs_set_direction(FPIOA_CH438_D3, GPIO_DM_INPUT_PULL_UP);
k210_gpiohs_set_direction(FPIOA_CH438_D4, GPIO_DM_INPUT_PULL_UP);
k210_gpiohs_set_direction(FPIOA_CH438_D5, GPIO_DM_INPUT_PULL_UP);
k210_gpiohs_set_direction(FPIOA_CH438_D6, GPIO_DM_INPUT_PULL_UP);
k210_gpiohs_set_direction(FPIOA_CH438_D7, GPIO_DM_INPUT_PULL_UP);
}
/****************************************************************************
* Name: ReadCH438Data
*
* Description:
* Read data from ch438 address
*
****************************************************************************/
static uint8_t ReadCH438Data(uint8_t addr)
{
uint8_t dat = 0;
k210_gpiohs_set_value(FPIOA_CH438_NWR, true);
k210_gpiohs_set_value(FPIOA_CH438_NRD, true);
k210_gpiohs_set_value(FPIOA_CH438_ALE, true);
CH438SetOutput();
up_udelay(1);
if(addr &0x80) k210_gpiohs_set_value(FPIOA_CH438_D7, true); else k210_gpiohs_set_value(FPIOA_CH438_D7, false);
if(addr &0x40) k210_gpiohs_set_value(FPIOA_CH438_D6, true); else k210_gpiohs_set_value(FPIOA_CH438_D6, false);
if(addr &0x20) k210_gpiohs_set_value(FPIOA_CH438_D5, true); else k210_gpiohs_set_value(FPIOA_CH438_D5, false);
if(addr &0x10) k210_gpiohs_set_value(FPIOA_CH438_D4, true); else k210_gpiohs_set_value(FPIOA_CH438_D4, false);
if(addr &0x08) k210_gpiohs_set_value(FPIOA_CH438_D3, true); else k210_gpiohs_set_value(FPIOA_CH438_D3, false);
if(addr &0x04) k210_gpiohs_set_value(FPIOA_CH438_D2, true); else k210_gpiohs_set_value(FPIOA_CH438_D2, false);
if(addr &0x02) k210_gpiohs_set_value(FPIOA_CH438_D1, true); else k210_gpiohs_set_value(FPIOA_CH438_D1, false);
if(addr &0x01) k210_gpiohs_set_value(FPIOA_CH438_D0, true); else k210_gpiohs_set_value(FPIOA_CH438_D0, false);
up_udelay(1);
k210_gpiohs_set_value(FPIOA_CH438_ALE, false);
up_udelay(1);
CH438SetInput();
up_udelay(1);
k210_gpiohs_set_value(FPIOA_CH438_NRD, false);
up_udelay(1);
if (k210_gpiohs_get_value(FPIOA_CH438_D7)) dat |= 0x80;
if (k210_gpiohs_get_value(FPIOA_CH438_D6)) dat |= 0x40;
if (k210_gpiohs_get_value(FPIOA_CH438_D5)) dat |= 0x20;
if (k210_gpiohs_get_value(FPIOA_CH438_D4)) dat |= 0x10;
if (k210_gpiohs_get_value(FPIOA_CH438_D3)) dat |= 0x08;
if (k210_gpiohs_get_value(FPIOA_CH438_D2)) dat |= 0x04;
if (k210_gpiohs_get_value(FPIOA_CH438_D1)) dat |= 0x02;
if (k210_gpiohs_get_value(FPIOA_CH438_D0)) dat |= 0x01;
k210_gpiohs_set_value(FPIOA_CH438_NRD, true);
k210_gpiohs_set_value(FPIOA_CH438_ALE, true);
up_udelay(1);
return dat;
}
/****************************************************************************
* Name: WriteCH438Data
*
* Description:
* write data to ch438 address
*
****************************************************************************/
static void WriteCH438Data(uint8_t addr, const uint8_t dat)
{
k210_gpiohs_set_value(FPIOA_CH438_ALE, true);
k210_gpiohs_set_value(FPIOA_CH438_NRD, true);
k210_gpiohs_set_value(FPIOA_CH438_NWR, true);
CH438SetOutput();
up_udelay(1);
if(addr &0x80) k210_gpiohs_set_value(FPIOA_CH438_D7, true); else k210_gpiohs_set_value(FPIOA_CH438_D7, false);
if(addr &0x40) k210_gpiohs_set_value(FPIOA_CH438_D6, true); else k210_gpiohs_set_value(FPIOA_CH438_D6, false);
if(addr &0x20) k210_gpiohs_set_value(FPIOA_CH438_D5, true); else k210_gpiohs_set_value(FPIOA_CH438_D5, false);
if(addr &0x10) k210_gpiohs_set_value(FPIOA_CH438_D4, true); else k210_gpiohs_set_value(FPIOA_CH438_D4, false);
if(addr &0x08) k210_gpiohs_set_value(FPIOA_CH438_D3, true); else k210_gpiohs_set_value(FPIOA_CH438_D3, false);
if(addr &0x04) k210_gpiohs_set_value(FPIOA_CH438_D2, true); else k210_gpiohs_set_value(FPIOA_CH438_D2, false);
if(addr &0x02) k210_gpiohs_set_value(FPIOA_CH438_D1, true); else k210_gpiohs_set_value(FPIOA_CH438_D1, false);
if(addr &0x01) k210_gpiohs_set_value(FPIOA_CH438_D0, true); else k210_gpiohs_set_value(FPIOA_CH438_D0, false);
up_udelay(1);
k210_gpiohs_set_value(FPIOA_CH438_ALE, false);
up_udelay(1);
if(dat &0x80) k210_gpiohs_set_value(FPIOA_CH438_D7, true); else k210_gpiohs_set_value(FPIOA_CH438_D7, false);
if(dat &0x40) k210_gpiohs_set_value(FPIOA_CH438_D6, true); else k210_gpiohs_set_value(FPIOA_CH438_D6, false);
if(dat &0x20) k210_gpiohs_set_value(FPIOA_CH438_D5, true); else k210_gpiohs_set_value(FPIOA_CH438_D5, false);
if(dat &0x10) k210_gpiohs_set_value(FPIOA_CH438_D4, true); else k210_gpiohs_set_value(FPIOA_CH438_D4, false);
if(dat &0x08) k210_gpiohs_set_value(FPIOA_CH438_D3, true); else k210_gpiohs_set_value(FPIOA_CH438_D3, false);
if(dat &0x04) k210_gpiohs_set_value(FPIOA_CH438_D2, true); else k210_gpiohs_set_value(FPIOA_CH438_D2, false);
if(dat &0x02) k210_gpiohs_set_value(FPIOA_CH438_D1, true); else k210_gpiohs_set_value(FPIOA_CH438_D1, false);
if(dat &0x01) k210_gpiohs_set_value(FPIOA_CH438_D0, true); else k210_gpiohs_set_value(FPIOA_CH438_D0, false);
up_udelay(1);
k210_gpiohs_set_value(FPIOA_CH438_NWR, false);
up_udelay(1);
k210_gpiohs_set_value(FPIOA_CH438_NWR, true);
k210_gpiohs_set_value(FPIOA_CH438_ALE, true);
up_udelay(1);
CH438SetInput();
return;
}
/****************************************************************************
* Name: WriteCH438Block
*
* Description:
* Write data block from ch438 address
*
****************************************************************************/
static void WriteCH438Block(uint8_t mAddr, uint8_t mLen, const uint8_t *mBuf)
{
while(mLen--)
WriteCH438Data(mAddr, *mBuf++);
}
/****************************************************************************
* Name: CH438UARTSend
*
* Description:
* Enable FIFO mode, which is used for ch438 serial port to send multi byte data,
* with a maximum of 128 bytes of data sent at a time
*
****************************************************************************/
static void Ch438UartSend(uint8_t ext_uart_no, const uint8_t *Data, uint16_t Num)
{
uint8_t REG_LSR_ADDR,REG_THR_ADDR;
REG_LSR_ADDR = offsetadd[ext_uart_no] | REG_LSR0_ADDR;
REG_THR_ADDR = offsetadd[ext_uart_no] | REG_THR0_ADDR;
while(1)
{
while((ReadCH438Data(REG_LSR_ADDR) & BIT_LSR_TEMT) == 0); /* wait for sending data done, THR and TSR is NULL */
if(Num <= 128)
{
WriteCH438Block(REG_THR_ADDR, Num, Data);
break;
}
else
{
WriteCH438Block(REG_THR_ADDR, 128, Data);
Num -= 128;
Data += 128;
}
}
}
/****************************************************************************
* Name: CH438UARTRcv
*
* Description:
* Disable FIFO mode for ch438 serial port to receive multi byte data
*
****************************************************************************/
uint8_t CH438UARTRcv(uint8_t ext_uart_no, uint8_t *buf, size_t size)
{
uint8_t rcv_num = 0;
uint8_t dat = 0;
uint8_t REG_LSR_ADDR,REG_RBR_ADDR;
uint8_t *read_buffer;
size_t buffer_index = 0;
read_buffer = buf;
REG_LSR_ADDR = offsetadd[ext_uart_no] | REG_LSR0_ADDR;
REG_RBR_ADDR = offsetadd[ext_uart_no] | REG_RBR0_ADDR;
/* Wait for the data to be ready */
while ((ReadCH438Data(REG_LSR_ADDR) & BIT_LSR_DATARDY) == 0);
while (((ReadCH438Data(REG_LSR_ADDR) & BIT_LSR_DATARDY) == 0x01) && (size != 0))
{
dat = ReadCH438Data(REG_RBR_ADDR);
*read_buffer = dat;
read_buffer++;
buffer_index++;
if (255 == buffer_index) {
buffer_index = 0;
read_buffer = buf;
}
++rcv_num;
--size;
}
return rcv_num;
}
/****************************************************************************
* Name: K210CH438Init
*
* Description:
* ch438 initialization
*
****************************************************************************/
static void K210CH438Init(void)
{
CH438SetOutput();
k210_gpiohs_set_direction(FPIOA_CH438_NWR, GPIO_DM_OUTPUT);
k210_gpiohs_set_direction(FPIOA_CH438_NRD, GPIO_DM_OUTPUT);
k210_gpiohs_set_direction(FPIOA_CH438_ALE, GPIO_DM_OUTPUT);
k210_gpiohs_set_value(FPIOA_CH438_NWR, true);
k210_gpiohs_set_value(FPIOA_CH438_NRD, true);
k210_gpiohs_set_value(FPIOA_CH438_ALE, true);
}
/****************************************************************************
* Name: CH438PortInit
*
* Description:
* ch438 port initialization
*
****************************************************************************/
static void CH438PortInit(uint8_t ext_uart_no, uint32_t baud_rate)
{
uint32_t div;
uint8_t DLL,DLM,dlab;
uint8_t REG_LCR_ADDR;
uint8_t REG_DLL_ADDR;
uint8_t REG_DLM_ADDR;
uint8_t REG_IER_ADDR;
uint8_t REG_MCR_ADDR;
uint8_t REG_FCR_ADDR;
REG_LCR_ADDR = offsetadd[ext_uart_no] | REG_LCR0_ADDR;
REG_DLL_ADDR = offsetadd[ext_uart_no] | REG_DLL0_ADDR;
REG_DLM_ADDR = offsetadd[ext_uart_no] | REG_DLM0_ADDR;
REG_IER_ADDR = offsetadd[ext_uart_no] | REG_IER0_ADDR;
REG_MCR_ADDR = offsetadd[ext_uart_no] | REG_MCR0_ADDR;
REG_FCR_ADDR = offsetadd[ext_uart_no] | REG_FCR0_ADDR;
/* reset the uart */
WriteCH438Data(REG_IER_ADDR, BIT_IER_RESET);
up_mdelay(50);
dlab = ReadCH438Data(REG_IER_ADDR);
dlab &= 0xDF;
WriteCH438Data(REG_IER_ADDR, dlab);
/* set LCR register DLAB bit 1 */
dlab = ReadCH438Data(REG_LCR_ADDR);
dlab |= 0x80;
WriteCH438Data(REG_LCR_ADDR, dlab);
div = (Fpclk >> 4) / baud_rate;
DLM = div >> 8;
DLL = div & 0xff;
/* set bps */
WriteCH438Data(REG_DLL_ADDR, DLL);
WriteCH438Data(REG_DLM_ADDR, DLM);
/* set FIFO mode, 112 bytes */
WriteCH438Data(REG_FCR_ADDR, BIT_FCR_RECVTG1 | BIT_FCR_RECVTG0 | BIT_FCR_FIFOEN);
/* 8 bit word size, 1 bit stop bit, no crc */
WriteCH438Data(REG_LCR_ADDR, BIT_LCR_WORDSZ1 | BIT_LCR_WORDSZ0);
/* enable interrupt */
WriteCH438Data(REG_IER_ADDR, BIT_IER_IERECV);
/* allow interrupt output, DTR and RTS is 1 */
WriteCH438Data(REG_MCR_ADDR, BIT_MCR_OUT2);
/* release the data in FIFO */
WriteCH438Data(REG_FCR_ADDR, ReadCH438Data(REG_FCR_ADDR)| BIT_FCR_TFIFORST);
}
/****************************************************************************
* Name: K210Ch438ReadData
*
* Description:
* Read data from ch438 port
*
****************************************************************************/
static int K210Ch438WriteData(uint8_t ext_uart_no, const uint8_t *write_buffer, size_t size)
{
int write_len, write_len_continue;
int i, write_index;
DEBUGASSERT(write_buffer != NULL);
write_len = size;
write_len_continue = size;
if(write_len > 256)
{
if(0 == write_len % 256)
{
write_index = write_len / 256;
for(i = 0; i < write_index; i ++)
{
Ch438UartSend(ext_uart_no, write_buffer + i * 256, 256);
}
}
else
{
write_index = 0;
while(write_len_continue > 256)
{
Ch438UartSend(ext_uart_no, write_buffer + write_index * 256, 256);
write_index++;
write_len_continue = write_len - write_index * 256;
}
Ch438UartSend(ext_uart_no, write_buffer + write_index * 256, write_len_continue);
}
}
else
{
Ch438UartSend(ext_uart_no, write_buffer, write_len);
}
return OK;
}
/****************************************************************************
* Name: K210Ch438ReadData
*
* Description:
* Read data from ch438 port
*
****************************************************************************/
static size_t K210Ch438ReadData(uint8_t ext_uart_no, size_t size)
{
size_t RevLen = 0;
uint8_t InterruptStatus;
uint8_t REG_IIR_ADDR;
uint8_t REG_LSR_ADDR;
uint8_t REG_MSR_ADDR;
pthread_mutex_lock(&mutex[ext_uart_no]);
while(done[ext_uart_no] == false)
pthread_cond_wait(&cond[ext_uart_no], &mutex[ext_uart_no]);
if(done[ext_uart_no] == true)
{
REG_IIR_ADDR = offsetadd[ext_uart_no] | REG_IIR0_ADDR;
REG_LSR_ADDR = offsetadd[ext_uart_no] | REG_LSR0_ADDR;
REG_MSR_ADDR = offsetadd[ext_uart_no] | REG_MSR0_ADDR;
/* Read the interrupt status of the serial port */
InterruptStatus = ReadCH438Data(REG_IIR_ADDR) & 0x0f;
ch438info("InterruptStatus is %d\n", InterruptStatus);
switch(InterruptStatus)
{
case INT_NOINT: /* no interrupt */
break;
case INT_THR_EMPTY: /* the transmit hold register is not interrupted */
break;
case INT_RCV_OVERTIME: /* receive data timeout interrupt */
case INT_RCV_SUCCESS: /* receive data available interrupt */
RevLen = CH438UARTRcv(ext_uart_no, buff[ext_uart_no], size);
break;
case INT_RCV_LINES: /* receive line status interrupt */
ReadCH438Data(REG_LSR_ADDR);
break;
case INT_MODEM_CHANGE: /* modem input change interrupt */
ReadCH438Data(REG_MSR_ADDR);
break;
default:
break;
}
done[ext_uart_no] = false;
}
pthread_mutex_unlock(&mutex[ext_uart_no]);
return RevLen;
}
/****************************************************************************
* Name: Ch438InitDefault
*
* Description:
* Ch438 default initialization function
*
****************************************************************************/
static void Ch438InitDefault(void)
{
int ret = 0;
int i;
/* Initialize the mutex */
for(i = 0; i < CH438PORTNUM; i++)
{
if(!g_uart_selected[i])
{
continue;
}
ret = pthread_mutex_init(&mutex[i], NULL);
if(ret != 0)
{
ch438err("pthread_mutex_init failed, status=%d\n", ret);
}
}
/* Initialize the condition variable */
for(i = 0; i < CH438PORTNUM; i++)
{
if(!g_uart_selected[i])
{
continue;
}
ret = pthread_cond_init(&cond[i], NULL);
if(ret != 0)
{
ch438err("pthread_cond_init failed, status=%d\n", ret);
}
}
ch438_io_config();
K210CH438Init();
/* If a port is checked, the port will be initialized. Otherwise, the interrupt of the port will be disabled. */
#ifdef CONFIG_CH438_EXTUART0
CH438PortInit(0, CONFIG_CH438_EXTUART0_BAUD);
#else
WriteCH438Data(REG_IER0_ADDR, 0x00);
#endif
#ifdef CONFIG_CH438_EXTUART1
CH438PortInit(1, CONFIG_CH438_EXTUART1_BAUD);
#else
WriteCH438Data(REG_IER1_ADDR, 0x00);
#endif
#ifdef CONFIG_CH438_EXTUART2
CH438PortInit(2, CONFIG_CH438_EXTUART2_BAUD);
#else
WriteCH438Data(REG_IER2_ADDR, 0x00);
#endif
#ifdef CONFIG_CH438_EXTUART3
CH438PortInit(3, CONFIG_CH438_EXTUART3_BAUD);
#else
WriteCH438Data(REG_IER3_ADDR, 0x00);
#endif
#ifdef CONFIG_CH438_EXTUART4
CH438PortInit(4, CONFIG_CH438_EXTUART4_BAUD);
#else
WriteCH438Data(REG_IER4_ADDR, 0x00);
#endif
#ifdef CONFIG_CH438_EXTUART5
CH438PortInit(5, CONFIG_CH438_EXTUART5_BAUD);
#else
WriteCH438Data(REG_IER5_ADDR, 0x00);
#endif
#ifdef CONFIG_CH438_EXTUART6
CH438PortInit(6, CONFIG_CH438_EXTUART6_BAUD);
#else
WriteCH438Data(REG_IER6_ADDR, 0x00);
#endif
#ifdef CONFIG_CH438_EXTUART7
CH438PortInit(7, CONFIG_CH438_EXTUART7_BAUD);
#else
WriteCH438Data(REG_IER7_ADDR, 0x00);
#endif
up_mdelay(10);
work_queue(HPWORK, &g_ch438irqwork, getInterruptStatus, NULL, CH438_INCREMENT);
}
/****************************************************************************
* Name: ch438_open
****************************************************************************/
static int ch438_open(FAR struct file *filep)
{
FAR struct inode *inode = filep->f_inode;
FAR struct ch438_dev_s *priv = inode->i_private;
uint8_t port = priv->port;
int ret = OK;
DEBUGASSERT(port >= 0 && port < CH438PORTNUM);
ret = nxsem_wait_uninterruptible(&priv->devsem);
if (ret < 0)
{
return ret;
}
if(g_ch438open[port])
{
ch438err("ERROR: ch438 port %d is opened!\n",port);
return -EBUSY;
}
g_ch438open[port] = true;
nxsem_post(&priv->devsem);
return ret;
}
/****************************************************************************
* Name: ch438_close
****************************************************************************/
static int ch438_close(FAR struct file *filep)
{
FAR struct inode *inode = filep->f_inode;
FAR struct ch438_dev_s *priv = inode->i_private;
uint8_t port = priv->port;
int ret = OK;
DEBUGASSERT(port >= 0 && port < CH438PORTNUM);
ret = nxsem_wait_uninterruptible(&priv->devsem);
if (ret < 0)
{
return ret;
}
if(!g_ch438open[port])
{
ch438err("ERROR: ch438 port %d is closed!\n",port);
return -EBUSY;
}
g_ch438open[port] = false;
nxsem_post(&priv->devsem);
return ret;
}
/****************************************************************************
* Name: ch438_read
****************************************************************************/
static ssize_t ch438_read(FAR struct file *filep, FAR char *buffer, size_t buflen)
{
size_t length = 0;
FAR struct inode *inode = filep->f_inode;
FAR struct ch438_dev_s *priv = inode->i_private;
uint8_t port = priv->port;
DEBUGASSERT(port >= 0 && port < CH438PORTNUM);
length = K210Ch438ReadData(port, buflen);
memcpy(buffer, buff[port], length);
if(length > buflen)
{
length = buflen;
}
return length;
}
/****************************************************************************
* Name: ch438_write
****************************************************************************/
static ssize_t ch438_write(FAR struct file *filep, FAR const char *buffer, size_t buflen)
{
FAR struct inode *inode = filep->f_inode;
FAR struct ch438_dev_s *priv = inode->i_private;
uint8_t port = priv->port;
DEBUGASSERT(port >= 0 && port < CH438PORTNUM);
K210Ch438WriteData(port, (const uint8_t *)buffer, buflen);
return buflen;
}
/****************************************************************************
* Name: ch438_ioctl
****************************************************************************/
static int ch438_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
{
FAR struct inode *inode = filep->f_inode;
FAR struct ch438_dev_s *priv = inode->i_private;
uint8_t port = priv->port;
int ret = OK;
DEBUGASSERT(port >= 0 && port < CH438PORTNUM);
switch(cmd)
{
case OPE_INT:
case OPE_CFG:
CH438PortInit(port, (uint32_t)arg);
break;
default:
ch438info("Unrecognized cmd: %d\n", cmd);
ret = -ENOTTY;
break;
}
return ret;
}
/****************************************************************************
* Name: ch438_register
*
* Description:
* Register /dev/ext_uartN
*
****************************************************************************/
static int ch438_register(FAR const char *devpath, uint8_t port)
{
FAR struct ch438_dev_s *priv;
int ret = 0;
/* port number check */
DEBUGASSERT(port >= 0 && port < CH438PORTNUM);
priv = (FAR struct ch438_dev_s *)kmm_malloc(sizeof(struct ch438_dev_s));
if(priv == NULL)
{
ch438err("ERROR: Failed to allocate instance\n");
return -ENOMEM;
}
priv->port = port;
nxsem_init(&priv->devsem, 0, 1);
/* Register the character driver */
ret = register_driver(devpath, &g_ch438fops, 0666, priv);
if(ret < 0)
{
kmm_free(priv);
}
return ret;
}
/****************************************************************************
* Name: board_ch438_initialize
*
* Description:
* ch438 initialize
*
****************************************************************************/
void board_ch438_initialize(void)
{
Ch438InitDefault();
#ifdef CONFIG_CH438_EXTUART0
ch438_register("/dev/extuart_dev0", 0);
#endif
#ifdef CONFIG_CH438_EXTUART1
ch438_register("/dev/extuart_dev1", 1);
#endif
#ifdef CONFIG_CH438_EXTUART2
ch438_register("/dev/extuart_dev2", 2);
#endif
#ifdef CONFIG_CH438_EXTUART3
ch438_register("/dev/extuart_dev3", 3);
#endif
#ifdef CONFIG_CH438_EXTUART4
ch438_register("/dev/extuart_dev4", 4);
#endif
#ifdef CONFIG_CH438_EXTUART5
ch438_register("/dev/extuart_dev5", 5);
#endif
#ifdef CONFIG_CH438_EXTUART6
ch438_register("/dev/extuart_dev6", 6);
#endif
#ifdef CONFIG_CH438_EXTUART7
ch438_register("/dev/extuart_dev7", 7);
#endif
}

View File

@ -1,326 +0,0 @@
/*
* Copyright (c) 2020 AIIT XUOS Lab
* XiOS 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 k210_ch438.h
* @brief edu-riscv64 k210_ch438.h
* @version 1.0
* @author AIIT XUOS Lab
* @date 2022.04.26
*/
#ifndef __BOARDS_XIDATONG_SRC_RISCV64_CH438_H
#define __BOARDS_XIDATONG_SRC_RISCV64_CH438_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <nuttx/kmalloc.h>
#include <nuttx/arch.h>
#include <nuttx/irq.h>
#include <nuttx/pthread.h>
#include <nuttx/semaphore.h>
#include <nuttx/wqueue.h>
#include <nuttx/wdog.h>
#include <nuttx/clock.h>
#include <nuttx/time.h>
#include <nuttx/fs/fs.h>
#include <nuttx/fs/ioctl.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <sys/ioctl.h>
#include <errno.h>
#include <stddef.h>
#include <stdint.h>
#include <stdio.h>
#include <sched.h>
#include <debug.h>
#include <assert.h>
#include <unistd.h>
#include <stdbool.h>
#include <string.h>
#include <stdlib.h>
#include <fcntl.h>
#include <nuttx/board.h>
#include <arch/board/board.h>
#include "riscv_internal.h"
#include "k210_config.h"
#include "k210_fpioa.h"
#include "k210_gpiohs.h"
#include "edu-riscv64.h"
/******************************************************************************************/
/* chip definition */
/* CH438serial port0 register address */
#define REG_RBR0_ADDR 0x00 /* serial port0receive buffer register address */
#define REG_THR0_ADDR 0x00 /* serial port0send hold register address */
#define REG_IER0_ADDR 0x01 /* serial port0interrupt enable register address */
#define REG_IIR0_ADDR 0x02 /* serial port0interrupt identifies register address */
#define REG_FCR0_ADDR 0x02 /* serial port0FIFO controls register address */
#define REG_LCR0_ADDR 0x03 /* serial port0circuit control register address */
#define REG_MCR0_ADDR 0x04 /* serial port0MODEM controls register address */
#define REG_LSR0_ADDR 0x05 /* serial port0line status register address */
#define REG_MSR0_ADDR 0x06 /* serial port0address of MODEM status register */
#define REG_SCR0_ADDR 0x07 /* serial port0the user can define the register address */
#define REG_DLL0_ADDR 0x00 /* Baud rate divisor latch low 8-bit byte address */
#define REG_DLM0_ADDR 0x01 /* Baud rate divisor latch high 8-bit byte address */
/* CH438serial port1 register address */
#define REG_RBR1_ADDR 0x10 /* serial port1receive buffer register address */
#define REG_THR1_ADDR 0x10 /* serial port1send hold register address */
#define REG_IER1_ADDR 0x11 /* serial port1interrupt enable register address */
#define REG_IIR1_ADDR 0x12 /* serial port1interrupt identifies register address */
#define REG_FCR1_ADDR 0x12 /* serial port1FIFO controls register address */
#define REG_LCR1_ADDR 0x13 /* serial port1circuit control register address */
#define REG_MCR1_ADDR 0x14 /* serial port1MODEM controls register address */
#define REG_LSR1_ADDR 0x15 /* serial port1line status register address */
#define REG_MSR1_ADDR 0x16 /* serial port1address of MODEM status register */
#define REG_SCR1_ADDR 0x17 /* serial port1the user can define the register address */
#define REG_DLL1_ADDR 0x10 /* Baud rate divisor latch low 8-bit byte address */
#define REG_DLM1_ADDR 0x11 /* Baud rate divisor latch high 8-bit byte address */
/* CH438serial port2 register address */
#define REG_RBR2_ADDR 0x20 /* serial port2receive buffer register address */
#define REG_THR2_ADDR 0x20 /* serial port2send hold register address */
#define REG_IER2_ADDR 0x21 /* serial port2interrupt enable register address */
#define REG_IIR2_ADDR 0x22 /* serial port2interrupt identifies register address */
#define REG_FCR2_ADDR 0x22 /* serial port2FIFO controls register address */
#define REG_LCR2_ADDR 0x23 /* serial port2circuit control register address */
#define REG_MCR2_ADDR 0x24 /* serial port2MODEM controls register address */
#define REG_LSR2_ADDR 0x25 /* serial port2line status register address */
#define REG_MSR2_ADDR 0x26 /* serial port2address of MODEM status register */
#define REG_SCR2_ADDR 0x27 /* serial port2the user can define the register address */
#define REG_DLL2_ADDR 0x20 /* Baud rate divisor latch low 8-bit byte address */
#define REG_DLM2_ADDR 0x21 /* Baud rate divisor latch high 8-bit byte address */
/* CH438serial port3 register address */
#define REG_RBR3_ADDR 0x30 /* serial port3receive buffer register address */
#define REG_THR3_ADDR 0x30 /* serial port3send hold register address */
#define REG_IER3_ADDR 0x31 /* serial port3interrupt enable register address */
#define REG_IIR3_ADDR 0x32 /* serial port3interrupt identifies register address */
#define REG_FCR3_ADDR 0x32 /* serial port3FIFO controls register address */
#define REG_LCR3_ADDR 0x33 /* serial port3circuit control register address */
#define REG_MCR3_ADDR 0x34 /* serial port3MODEM controls register address */
#define REG_LSR3_ADDR 0x35 /* serial port3line status register address */
#define REG_MSR3_ADDR 0x36 /* serial port3address of MODEM status register */
#define REG_SCR3_ADDR 0x37 /* serial port3the user can define the register address */
#define REG_DLL3_ADDR 0x30 /* Baud rate divisor latch low 8-bit byte address */
#define REG_DLM3_ADDR 0x31 /* Baud rate divisor latch high 8-bit byte address */
/* CH438serial port4 register address */
#define REG_RBR4_ADDR 0x08 /* serial port4receive buffer register address */
#define REG_THR4_ADDR 0x08 /* serial port4send hold register address */
#define REG_IER4_ADDR 0x09 /* serial port4interrupt enable register address */
#define REG_IIR4_ADDR 0x0A /* serial port4interrupt identifies register address */
#define REG_FCR4_ADDR 0x0A /* serial port4FIFO controls register address */
#define REG_LCR4_ADDR 0x0B /* serial port4circuit control register address */
#define REG_MCR4_ADDR 0x0C /* serial port4MODEM controls register address */
#define REG_LSR4_ADDR 0x0D /* serial port4line status register address */
#define REG_MSR4_ADDR 0x0E /* serial port4address of MODEM status register */
#define REG_SCR4_ADDR 0x0F /* serial port4the user can define the register address */
#define REG_DLL4_ADDR 0x08 /* Baud rate divisor latch low 8-bit byte address */
#define REG_DLM4_ADDR 0x09 /* Baud rate divisor latch high 8-bit byte address */
/* CH438serial port5 register address */
#define REG_RBR5_ADDR 0x18 /* serial port5receive buffer register address */
#define REG_THR5_ADDR 0x18 /* serial port5send hold register address */
#define REG_IER5_ADDR 0x19 /* serial port5interrupt enable register address */
#define REG_IIR5_ADDR 0x1A /* serial port5interrupt identifies register address */
#define REG_FCR5_ADDR 0x1A /* serial port5FIFO controls register address */
#define REG_LCR5_ADDR 0x1B /* serial port5circuit control register address */
#define REG_MCR5_ADDR 0x1C /* serial port5MODEM controls register address */
#define REG_LSR5_ADDR 0x1D /* serial port5line status register address */
#define REG_MSR5_ADDR 0x1E /* serial port5address of MODEM status register */
#define REG_SCR5_ADDR 0x1F /* serial port5the user can define the register address */
#define REG_DLL5_ADDR 0x18 /* Baud rate divisor latch low 8-bit byte address */
#define REG_DLM5_ADDR 0x19 /* Baud rate divisor latch high 8-bit byte address */
/* CH438serial port6 register address */
#define REG_RBR6_ADDR 0x28 /* serial port6receive buffer register address */
#define REG_THR6_ADDR 0x28 /* serial port6send hold register address */
#define REG_IER6_ADDR 0x29 /* serial port6interrupt enable register address */
#define REG_IIR6_ADDR 0x2A /* serial port6interrupt identifies register address */
#define REG_FCR6_ADDR 0x2A /* serial port6FIFO controls register address */
#define REG_LCR6_ADDR 0x2B /* serial port6circuit control register address */
#define REG_MCR6_ADDR 0x2C /* serial port6MODEM controls register address */
#define REG_LSR6_ADDR 0x2D /* serial port6line status register address */
#define REG_MSR6_ADDR 0x2E /* serial port6address of MODEM status register */
#define REG_SCR6_ADDR 0x2F /* serial port6the user can define the register address */
#define REG_DLL6_ADDR 0x28 /* Baud rate divisor latch low 8-bit byte address */
#define REG_DLM6_ADDR 0x29 /* Baud rate divisor latch high 8-bit byte address */
/* CH438serial port7 register address */
#define REG_RBR7_ADDR 0x38 /* serial port7receive buffer register address */
#define REG_THR7_ADDR 0x38 /* serial port7send hold register address */
#define REG_IER7_ADDR 0x39 /* serial port7interrupt enable register address */
#define REG_IIR7_ADDR 0x3A /* serial port7interrupt identifies register address */
#define REG_FCR7_ADDR 0x3A /* serial port7FIFO controls register address */
#define REG_LCR7_ADDR 0x3B /* serial port7circuit control register address */
#define REG_MCR7_ADDR 0x3C /* serial port7MODEM controls register address */
#define REG_LSR7_ADDR 0x3D /* serial port7line status register address */
#define REG_MSR7_ADDR 0x3E /* serial port7address of MODEM status register */
#define REG_SCR7_ADDR 0x3F /* serial port7the user can define the register address */
#define REG_DLL7_ADDR 0x38 /* Baud rate divisor latch low 8-bit byte address */
#define REG_DLM7_ADDR 0x39 /* Baud rate divisor latch high 8-bit byte address */
#define REG_SSR_ADDR 0x4F /* pecial status register address */
/* IER register bit */
#define BIT_IER_RESET 0x80 /* The bit is 1 soft reset serial port */
#define BIT_IER_LOWPOWER 0x40 /* The bit is 1 close serial port internal reference clock */
#define BIT_IER_SLP 0x20 /* serial port0 is SLP, 1 close clock vibrator */
#define BIT_IER1_CK2X 0x20 /* serial port1 is CK2X, 1 force the external clock signal after 2 times as internal */
#define BIT_IER_IEMODEM 0x08 /* The bit is 1 allows MODEM input status to interrupt */
#define BIT_IER_IELINES 0x04 /* The bit is 1 allow receiving line status to be interrupted */
#define BIT_IER_IETHRE 0x02 /* The bit is 1 allows the send hold register to break in mid-air */
#define BIT_IER_IERECV 0x01 /* The bit is 1 allows receiving data interrupts */
/* IIR register bit */
#define BIT_IIR_FIFOENS1 0x80
#define BIT_IIR_FIFOENS0 0x40 /* The two is 1 said use FIFO */
/* Interrupt type: 0001 has no interrupt, 0110 receiving line status is interrupted, 0100 receiving data can be interrupted,
1100 received data timeout interrupt, 0010THR register air interrupt, 0000MODEM input change interrupt */
#define BIT_IIR_IID3 0x08
#define BIT_IIR_IID2 0x04
#define BIT_IIR_IID1 0x02
#define BIT_IIR_NOINT 0x01
/* FCR register bit */
/* Trigger point: 00 corresponds to 1 byte, 01 corresponds to 16 bytes, 10 corresponds to 64 bytes, 11 corresponds to 112 bytes */
#define BIT_FCR_RECVTG1 0x80 /* Set the trigger point for FIFO interruption and automatic hardware flow control */
#define BIT_FCR_RECVTG0 0x40 /* Set the trigger point for FIFO interruption and automatic hardware flow control */
#define BIT_FCR_TFIFORST 0x04 /* The bit is 1 empty the data sent in FIFO */
#define BIT_FCR_RFIFORST 0x02 /* The bit is 1 empty the data sent in FIFO */
#define BIT_FCR_FIFOEN 0x01 /* The bit is 1 use FIFO, 0 disable FIFO */
/* LCR register bit */
#define BIT_LCR_DLAB 0x80 /* To access DLL, DLM, 0 to access RBR/THR/IER */
#define BIT_LCR_BREAKEN 0x40 /* 1 forces a BREAK line interval*/
/* Set the check format: when PAREN is 1, 00 odd check, 01 even check, 10 MARK (set 1), 11 blank (SPACE, clear 0) */
#define BIT_LCR_PARMODE1 0x20 /* Sets the parity bit format */
#define BIT_LCR_PARMODE0 0x10 /* Sets the parity bit format */
#define BIT_LCR_PAREN 0x08 /* A value of 1 allows you to generate and receive parity bits when sending */
#define BIT_LCR_STOPBIT 0x04 /* If is 1, then two stop bits, is 0, a stop bit */
/* Set word length: 00 for 5 data bits, 01 for 6 data bits, 10 for 7 data bits and 11 for 8 data bits */
#define BIT_LCR_WORDSZ1 0x02 /* Set the word length length */
#define BIT_LCR_WORDSZ0 0x01
/* MCR register bit */
#define BIT_MCR_AFE 0x20 /* For 1 allows automatic flow control of CTS and RTS hardware */
#define BIT_MCR_LOOP 0x10 /* Is the test mode of 1 enabling internal loop */
#define BIT_MCR_OUT2 0x08 /* 1 Allows an interrupt request for the serial port output */
#define BIT_MCR_OUT1 0x04 /* The MODEM control bit defined for the user */
#define BIT_MCR_RTS 0x02 /* The bit is 1 RTS pin output effective */
#define BIT_MCR_DTR 0x01 /* The bit is 1 DTR pin output effective */
/* LSR register bit */
#define BIT_LSR_RFIFOERR 0x80 /* 1 said There is at least one error in receiving FIFO */
#define BIT_LSR_TEMT 0x40 /* 1 said THR and TSR are empty */
#define BIT_LSR_THRE 0x20 /* 1 said THR is empty*/
#define BIT_LSR_BREAKINT 0x10 /* The bit is 1 said the BREAK line interval was detected*/
#define BIT_LSR_FRAMEERR 0x08 /* The bit is 1 said error reading data frame */
#define BIT_LSR_PARERR 0x04 /* The bit is 1 said parity error */
#define BIT_LSR_OVERR 0x02 /* 1 said receive FIFO buffer overflow */
#define BIT_LSR_DATARDY 0x01 /* The bit is 1 said receive data received in FIFO */
/* MSR register bit */
#define BIT_MSR_DCD 0x80 /* The bit is 1 said DCD pin effective */
#define BIT_MSR_RI 0x40 /* The bit is 1 said RI pin effective */
#define BIT_MSR_DSR 0x20 /* The bit is 1 said DSR pin effective */
#define BIT_MSR_CTS 0x10 /* The bit is 1 said CTS pin effective */
#define BIT_MSR_DDCD 0x08 /* The bit is 1 said DCD pin The input state has changed */
#define BIT_MSR_TERI 0x04 /* The bit is 1 said RI pin The input state has changed */
#define BIT_MSR_DDSR 0x02 /* The bit is 1 said DSR pin The input state has changed */
#define BIT_MSR_DCTS 0x01 /* The bit is 1 said CTS pin The input state has changed */
/* Interrupt status code */
#define INT_NOINT 0x01 /* There is no interruption */
#define INT_THR_EMPTY 0x02 /* THR empty interruption */
#define INT_RCV_OVERTIME 0x0C /* Receive timeout interrupt */
#define INT_RCV_SUCCESS 0x04 /* Interrupts are available to receive data */
#define INT_RCV_LINES 0x06 /* Receiving line status interrupted */
#define INT_MODEM_CHANGE 0x00 /* MODEM input changes interrupt */
#define CH438_IIR_FIFOS_ENABLED 0xC0 /* use FIFO */
#define Fpclk 1843200 /* Define the internal clock frequency*/
/* ch438 debug */
#ifdef CONFIG_DEBUG_CH438_ERROR
# define ch438err _err
#else
# define ch438err _none
#endif
#ifdef CONFIG_DEBUG_CH438_WARN
# define ch438warn _warn
#else
# define ch438warn _none
#endif
#ifdef CONFIG_DEBUG_CH438_INFO
# define ch438info _info
#else
# define ch438info _none
#endif
#define CH438_FUNC_GPIO(n) ((K210_IO_FUNC_GPIOHS0 + n) | K210_IOFLAG_GPIOHS)
/* ioctl cmd */
#define OPE_INT 0x0000
#define OPE_CFG 0x0001
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
#ifdef CONFIG_BSP_USING_CH438
void board_ch438_initialize(void);
#endif
#endif /* __BOARDS_XIDATONG_SRC_RISCV64_CH438_H */