未验证 提交 3ea51663 编写于 作者: Y Yaochenger 提交者: GitHub

[bsp][core-v-mcu]修改后兼容原有CLI,兼容原有FreeRTOS函数接口 (#6747)

* [bsp][core-v-mcu]兼容原有FreeRTOS函数接口,兼容CLI
上级 0a6ffce4
/*
* Copyright (c) 2006-2018, RT-Thread Development Team
* Copyright (c) 2006-2022, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
......
/*
* Copyright (c) 2006-2018, RT-Thread Development Team
* Copyright (c) 2006-2022, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
......
/*
* Copyright (c) 2006-2018, RT-Thread Development Team
* Copyright (c) 2006-2022, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
......@@ -9,7 +9,7 @@
*/
#include "board.h"
#include <rtdevice.h>
#include "rtthread.h"
#include <drv_usart.h>
#include "hal_udma_ctrl_reg_defs.h"
#include "hal_udma_uart_reg_defs.h"
......@@ -23,7 +23,7 @@
#include <drv_log.h>
#if !defined(BSP_USING_UART1) && !defined(BSP_USING_UART2) && !defined(BSP_USING_UART3) && !defined(BSP_USING_UART4) && \
!defined(BSP_USING_UART5) && !defined(BSP_USING_UART6) && !defined(BSP_USING_UART7) && !defined(BSP_USING_UART8)
!defined(BSP_USING_UART5) && !defined(BSP_USING_UART6) && !defined(BSP_USING_UART7) && !defined(BSP_USING_UART8)
#error "Please define at least one BSP_USING_UARTx"
/* this driver can be disabled at menuconfig -> RT-Thread Components -> Device Drivers */
#endif
......@@ -58,21 +58,21 @@ static rt_err_t corev_control(struct rt_serial_device *serial, int cmd, void *ar
}
uint16_t rt_writeraw(uint8_t uart_id, uint16_t write_len, uint8_t* write_buffer) {
UdmaUart_t* puart = (UdmaUart_t*)(UDMA_CH_ADDR_UART + uart_id * UDMA_CH_SIZE);
UdmaUart_t* puart = (UdmaUart_t*)(UDMA_CH_ADDR_UART + uart_id * UDMA_CH_SIZE);
while (puart->status_b.tx_busy) {
}
while (puart->status_b.tx_busy) {
}
puart->tx_saddr = (uint32_t)write_buffer;
puart->tx_size = write_len;
puart->tx_cfg_b.en = 1;
puart->tx_saddr = (uint32_t)write_buffer;
puart->tx_size = write_len;
puart->tx_cfg_b.en = 1;
return 0;
return 0;
}
static int corev_putc(struct rt_serial_device *serial, char c)
{
char put_data =c;
char put_data =c;
struct corev_uart *uart;
RT_ASSERT(serial != RT_NULL);
......@@ -84,19 +84,19 @@ static int corev_putc(struct rt_serial_device *serial, char c)
static int corev_getc(struct rt_serial_device *serial)
{
signed char ch;
int ch;
struct corev_uart *uart;
RT_ASSERT(serial != RT_NULL);
uart = (struct corev_uart *)serial->parent.user_data;
ch = -1;
UdmaUart_t* puart = (UdmaUart_t*)(UDMA_CH_ADDR_UART + 0 * UDMA_CH_SIZE);
UdmaUart_t* puart = (UdmaUart_t*)(UDMA_CH_ADDR_UART + 0 * UDMA_CH_SIZE);
if (puart->valid_b.rx_data_valid == 1) {
ch = puart->data_b.rx_data & 0xff;
}
if (puart->valid_b.rx_data_valid == 1) {
ch = puart->data_b.rx_data & 0xff;
}
return (int)ch;
return ch;
}
rt_size_t corevdma_transmit(struct rt_serial_device *serial, rt_uint8_t *buf, rt_size_t size, int direction)
......@@ -120,20 +120,29 @@ static const struct rt_uart_ops corev_uart_ops =
corevdma_transmit
};
extern int irq_cli_flag;
void uart_rx_isr (void *id){
rt_interrupt_enter();
if (id == 6) {
while (*(int*)0x1a102130) {
u1buffer[u1wrptr++] = puart1->data_b.rx_data & 0xff;
u1wrptr &= 0x7f;
}
}
if (id == 2) {//use this uart
while (puart0->valid) {
uart_isr(&(uart_obj[UART1_INDEX].serial));
}
}
rt_interrupt_leave();
rt_interrupt_enter();
if (id == 6) {
while (*(int*)0x1a102130) {
u1buffer[u1wrptr++] = puart1->data_b.rx_data & 0xff;
u1wrptr &= 0x7f;
}
}
if (id == 2) {//use this uart
while (puart0->valid) {
if(irq_cli_flag==1)
{
uart_isr(&(uart_obj[UART1_INDEX].serial));
}
else if(irq_cli_flag==0)
{
u0buffer[u0wrptr++] = puart0->data_b.rx_data & 0xff;
u0wrptr &= 0x7f;
}
}
}
rt_interrupt_leave();
}
int rt_hw_usart_init(void)
......
# files format check exclude path, please follow the instructions below to modify;
# If you need to exclude an entire folder, add the folder path in dir_path;
# If you need to exclude a file, add the path to the file in file_path.
dir_path:
- bmsis
- core_v_hal
- core_v_udma_driver
......@@ -21,6 +21,10 @@ bmsis/core-v-mcu/source/core-v-mcu.c
bmsis/core-v-mcu/source/crt0.S
bmsis/core-v-mcu/source/vectors.S
core_v_udma_driver/source/udma_uart_driver.c
core_v_udma_driver/source/udma_cam_driver.c
core_v_udma_driver/source/udma_i2cm_driver.c
core_v_udma_driver/source/udma_qspi_driver.c
core_v_udma_driver/source/udma_sdio_driver.c
""")
path = [
......
......@@ -37,6 +37,16 @@
#include <rthw.h>
#include <rtthread.h>
#include "rtconfig.h"
#ifdef PKG_USING_FREERTOS_WRAPPER
#include "N25Q.h"
#include "hal_apb_i2cs.h"
FLASH_DEVICE_OBJECT gFlashDeviceObject[N_QSPIM];
uint8_t gQSPIFlashPresentFlg[N_QSPIM] = {0};
uint8_t gMicronFlashDetectedFlg[N_QSPIM] = {0};
#endif
#define HEAP_SIZE (( unsigned int) (64 * 1024 ))
#define FOR_SIMULATION_TESTING 0
#if (FOR_SIMULATION_TESTING == 1)
......@@ -63,10 +73,6 @@ typedef struct
void forSimulationTesting(void);
#endif
//FLASH_DEVICE_OBJECT gFlashDeviceObject[N_QSPIM];
uint8_t gQSPIFlashPresentFlg[N_QSPIM] = {0};
uint8_t gMicronFlashDetectedFlg[N_QSPIM] = {0};
/* test some assumptions we make about compiler settings */
static_assert(sizeof(uintptr_t) == 4,
"uintptr_t is not 4 bytes. Make sure you are using -mabi=ilp32*");
......@@ -76,18 +82,17 @@ static_assert(sizeof(uintptr_t) == 4,
* section for our heap), so when using LTO it will be removed. We force it to
* stay with the "used" attribute
*/
__attribute__((section(".heap"), used)) uint8_t ucHeap[configTOTAL_HEAP_SIZE];
__attribute__((section(".heap"), used)) uint8_t ucHeap[HEAP_SIZE];
/* Inform linker script about .heap section size. Note: GNU ld seems to
* internally represent integers with the bfd_vma type, that is a type that can
* contain memory addresses (typdefd to some int type depending on the
* architecture). uint32_t seems to me the most fitting candidate for rv32.
*/
uint32_t __heap_size = configTOTAL_HEAP_SIZE;
uint32_t __heap_size = HEAP_SIZE;
volatile uint32_t system_core_clock = 5000000u;
/* interrupt handling */
void timer_irq_handler(uint32_t mcause);
void undefined_handler(uint32_t mcause);
......
......@@ -19,7 +19,11 @@
#define HAL_INCLUDE_HAL_FC_EVENT_H_
#include "core-v-mcu-pmsis.h"
#ifdef PKG_USING_FREERTOS_WRAPPER
#include <FreeRTOS.h>
#include <semphr.h>
#include <task.h>
#endif
/*!
* @addtogroup FC_EventHandler
* @{
......@@ -45,9 +49,9 @@ void pi_fc_event_handler_init(uint32_t fc_event_irq);
* This function pops an event and executes the handler corresponding to the event.
*/
void fc_soc_event_handler(void);
//void pi_fc_event_handler_set(uint32_t event_id, pi_fc_event_handler_t event_handler, SemaphoreHandle_t semaphoreHandle);//This function based on freertos
#ifdef PKG_USING_FREERTOS_WRAPPER
void pi_fc_event_handler_set(uint32_t event_id, pi_fc_event_handler_t event_handler, SemaphoreHandle_t semaphoreHandle);//This function based on freertos
#endif
void user_pi_fc_event_handler_set(uint32_t event_id,pi_fc_event_handler_t event_handler);
void pi_fc_event_handler_clear(uint32_t event_id);
......
......@@ -26,7 +26,10 @@
#include "hal_fc_event.h"
#include "hal_soc_eu_periph.h"
#include "rtthread.h"
#ifdef PKG_USING_FREERTOS_WRAPPER
#include "FreeRTOS.h"
#include "semphr.h"
#endif
/*******************************************************************************
* Variables, macros, structures,... definition
******************************************************************************/
......@@ -36,9 +39,10 @@
******************************************************************************/
static void fc_event_null_event(void *arg);
static volatile pi_fc_event_handler_t fc_event_handlers[SOC_EU_NB_FC_EVENTS];
#ifdef PKG_USING_FREERTOS_WRAPPER
static SemaphoreHandle_t fc_event_semaphores[SOC_EU_NB_FC_EVENTS];
#endif
static void fc_event_null_event(void *arg)
{
return;
......@@ -54,7 +58,19 @@ void pi_fc_event_handler_init(uint32_t fc_event_irq)
/* NVIC_SetVector(fc_event_irq, (uint32_t)__handler_wrapper_light_fc_event_handler);*/
//irqn_enable(fc_event_irq);
}
#ifdef PKG_USING_FREERTOS_WRAPPER
void pi_fc_event_handler_set(uint32_t event_id,
pi_fc_event_handler_t event_handler,
SemaphoreHandle_t semaphoreHandle)
{
if (event_handler != NULL) {
fc_event_handlers[event_id] = event_handler;
}
if (semaphoreHandle != NULL) {
fc_event_semaphores[event_id] = semaphoreHandle;
}
}
#endif
void user_pi_fc_event_handler_set(uint32_t event_id,
pi_fc_event_handler_t event_handler)
{
......@@ -66,13 +82,18 @@ void user_pi_fc_event_handler_set(uint32_t event_id,
void pi_fc_event_handler_clear(uint32_t event_id)
{
fc_event_handlers[event_id] = (pi_fc_event_handler_t)fc_event_null_event;
#ifdef PKG_USING_FREERTOS_WRAPPER
fc_event_semaphores[event_id] = NULL;
#endif
}
/* TODO: Use Eric's FIRQ ABI */
void fc_soc_event_handler1 (uint32_t mcause)
{
uint32_t val = 0;
#ifdef PKG_USING_FREERTOS_WRAPPER
static BaseType_t xHigherPriorityTaskWoken;
#endif
uint32_t event_id = *(uint32_t*)(0x1a106090); // new event fifo address
event_id &= 0xFF;
......@@ -81,4 +102,12 @@ void fc_soc_event_handler1 (uint32_t mcause)
if (fc_event_handlers[event_id] != NULL) {
fc_event_handlers[event_id]((void *)event_id);
}
#ifdef PKG_USING_FREERTOS_WRAPPER
if (fc_event_semaphores[event_id] != NULL) {
/* Unblock the task by releasing the semaphore. */
SemaphoreHandle_t xSemaphoreHandle = fc_event_semaphores[event_id];
xSemaphoreGiveFromISR( xSemaphoreHandle, &xHigherPriorityTaskWoken );
portYIELD_FROM_ISR( xHigherPriorityTaskWoken );
}
#endif
}
......@@ -19,7 +19,9 @@
#include "core-v-mcu-config.h"
#include "hal_apb_soc_ctrl_regs.h"
#include "hal_pinmux.h"
#ifdef PKG_USING_FREERTOS_WRAPPER
#include "FreeRTOS.h"
#endif
void hal_setpullup(uint8_t io_num, uint8_t on) {
SocCtrl_t* psoc_ctrl = SOC_CTRL_START_ADDR;
......
#ifndef __CAMERA_H__
#define __CAMERA_H__
#include <queue.h>
#include "himax.h"
typedef struct {
volatile uint32_t *rx_saddr; // 0x00
volatile uint32_t rx_size; // 0x04
volatile uint32_t rx_cfg; // 0x08
volatile uint32_t rx_initcfg;// 0x0C
volatile uint32_t *tx_saddr; // 0x10
volatile uint32_t tx_size; // 0x14
volatile uint32_t tx_cfg; // 0x18
volatile uint32_t tx_initcfg;// 0x1C
volatile uint32_t cfg_glob; // 0x20
volatile uint32_t cfg_ll; // 0x24
volatile uint32_t cfg_ur; // 0x28
volatile uint32_t cfg_size; // 0x2C
volatile uint32_t cfg_filter;// 0x30
volatile uint32_t vsync_pol; // 0x34
} camera_struct_t;
typedef struct {
uint16_t addr;
uint8_t data;
}reg_cfg_t;
#endif
/*
* Copyright (C) 2018 ETH Zurich and University of Bologna
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
/*
* Copyright (C) 2018 GreenWaves Technologies
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
#ifndef __HIMAX_H__
#define __HIMAX_H__
/*
* HIMAX camera macros
*/
// Register address
// Read only registers
#define MODEL_ID_H 0x0000
#define MODEL_ID_L 0x0001
#define FRAME_COUNT 0x0005
#define PIXEL_ORDER 0x0006
// R&W registers
// Sensor mode control
#define MODE_SELECT 0x0100
#define IMG_ORIENTATION 0x0101
#define SW_RESET 0x0103
#define GRP_PARAM_HOLD 0x0104
// Sensor exposure gain control
#define INTEGRATION_H 0x0202
#define INTEGRATION_L 0x0203
#define ANALOG_GAIN 0x0205
#define DIGITAL_GAIN_H 0x020E
#define DIGITAL_GAIN_L 0x020F
// Frame timing control
#define FRAME_LEN_LINES_H 0x0340
#define FRAME_LEN_LINES_L 0x0341
#define LINE_LEN_PCK_H 0x0342
#define LINE_LEN_PCK_L 0x0343
// Binning mode control
#define READOUT_X 0x0383
#define READOUT_Y 0x0387
#define BINNING_MODE 0x0390
// Test pattern control
#define TEST_PATTERN_MODE 0x0601
// Black level control
#define BLC_CFG 0x1000
#define BLC_TGT 0x1003
#define BLI_EN 0x1006
#define BLC2_TGT 0x1007
// Sensor reserved
#define DPC_CTRL 0x1008
#define SINGLE_THR_HOT 0x100B
#define SINGLE_THR_COLD 0x100C
// VSYNC,HSYNC and pixel shift register
#define VSYNC_HSYNC_PIXEL_SHIFT_EN 0x1012
// Automatic exposure gain control
#define AE_CTRL 0x2100
#define AE_TARGET_MEAN 0x2101
#define AE_MIN_MEAN 0x2102
#define CONVERGE_IN_TH 0x2103
#define CONVERGE_OUT_TH 0x2104
#define MAX_INTG_H 0x2105
#define MAX_INTG_L 0x2106
#define MIN_INTG 0x2107
#define MAX_AGAIN_FULL 0x2108
#define MAX_AGAIN_BIN2 0x2109
#define MIN_AGAIN 0x210A
#define MAX_DGAIN 0x210B
#define MIN_DGAIN 0x210C
#define DAMPING_FACTOR 0x210D
#define FS_CTRL 0x210E
#define FS_60HZ_H 0x210F
#define FS_60HZ_L 0x2110
#define FS_50HZ_H 0x2111
#define FS_50HZ_L 0x2112
#define FS_HYST_TH 0x2113
// Motion detection control
#define MD_CTRL 0x2150
#define I2C_CLEAR 0x2153
#define WMEAN_DIFF_TH_H 0x2155
#define WMEAN_DIFF_TH_M 0x2156
#define WMEAN_DIFF_TH_L 0x2157
#define MD_THH 0x2158
#define MD_THM1 0x2159
#define MD_THM2 0x215A
#define MD_THL 0x215B
// Sensor timing control
#define QVGA_WIN_EN 0x3010
#define SIX_BIT_MODE_EN 0x3011
#define PMU_AUTOSLEEP_FRAMECNT 0x3020
#define ADVANCE_VSYNC 0x3022
#define ADVANCE_HSYNC 0x3023
#define EARLY_GAIN 0x3035
// IO and clock control
#define BIT_CONTROL 0x3059
#define OSC_CLK_DIV 0x3060
#define ANA_Register_11 0x3061
#define IO_DRIVE_STR 0x3062
#define IO_DRIVE_STR2 0x3063
#define ANA_Register_14 0x3064
#define OUTPUT_PIN_STATUS_CONTROL 0x3065
#define ANA_Register_17 0x3067
#define PCLK_POLARITY 0x3068
/*
* Useful value of Himax registers
*/
#define HIMAX_RESET 0x01
#define Pclk_rising_edge 0x00
#define Pclk_falling_edge 0x01
#define BYPASS_BIGEND 5
enum{
HIMAX_Standby = 0x0,
HIMAX_Streaming = 0x1, // I2C triggered streaming enable
HIMAX_Streaming2 = 0x3, // Output N frames
HIMAX_Streaming3 = 0x5 // Hardware Trigger
};
#endif
/*
* Copyright 2021 QuickLogic
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifndef DRIVERS_INCLUDE_UDMA_CAM_DRIVER_H_
#define DRIVERS_INCLUDE_UDMA_CAM_DRIVER_H_
#include <stdint.h>
#include <stdbool.h>
#include "hal_udma_ctrl_reg_defs.h"
#include "hal_udma_cam_reg_defs.h"
typedef enum {
kCamReset,
kCamID,
kCamInit,
kCamFrame
} udma_cam_control_type_t;
typedef enum {
kSPIm_Cfg = (0x0 << 28),
kSPIm_SOT = (0x1 << 28),
kSPIm_SendCmd = (0x2 << 28),
kSPIm_Dummy = (0x4 << 28),
kSPIm_Wait = (0x5 << 28),
kSPIm_TxData = (0x6 << 28),
kSPIm_RxData = (0x7 << 28),
kSPIm_Repeat = (0x8 << 28),
kSPIm_EOT = (0x9 << 28),
kSPIm_RepeatEnd = (0xa << 28),
kSPIm_RxCheck = (0xb << 28),
kSPIm_FDX = (0xc << 28),
kSPIm_UCA = (0xd << 28),
kSPIm_UCS = (0xe << 28)
} cam_cmd_t;
uint16_t udma_cam_control(udma_cam_control_type_t control_type, void* pparam);
void cam_open (uint8_t cam_id);
// helper functions
void _himaxRegWrite(unsigned int addr, unsigned char value);
#endif /* DRIVERS_INCLUDE_UDMA_CAM_DRIVER_H_ */
/*
* Copyright 2021 QuickLogic
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifndef DRIVERS_INCLUDE_UDMA_I2CM_DRIVER_H_
#define DRIVERS_INCLUDE_UDMA_I2CM_DRIVER_H_
#include <stdint.h>
#include <stdbool.h>
#include "hal_udma_ctrl_reg_defs.h"
#define SEMAPHORE_WAIT_TIME_IN_MS 10
typedef enum {
kI2cmReset
} udma_i2cm_control_type_t;
typedef enum {
kI2cmCmdStart = 0x00,
kI2cmCmdStop = 0x20,
kI2cmCmdRdAck = 0x40,
kI2cmCmdRdNack = 0x60,
kI2cmCmdWr = 0x80,
kI2cmCmdWait = 0xA0,
kI2cmCmdRpt = 0xC0,
kI2cmCmdCfg = 0xE0,
kI2cmCmdWaitEvt = 0x10,
} i2cm_cmd_t;
uint16_t udma_i2cm_open (uint8_t i2c_id, uint32_t i2c_clk_freq);
uint16_t udma_i2cm_close (uint8_t i2c_id);
uint16_t udma_i2cm_control(uint8_t i2c_id, udma_i2cm_control_type_t control_type, void* pparam);
uint8_t udma_i2cm_write(uint8_t i2c_id, uint8_t i2c_addr, uint8_t reg_addr, uint16_t write_len, uint8_t* write_data, bool more_follows);
uint8_t udma_i2cm_read(uint8_t i2c_id, uint8_t i2c_addr, uint8_t reg_addr, uint16_t read_len, uint8_t* read_buffer, bool more_follows);
uint8_t udma_i2cm_16read8(uint8_t i2c_id, uint8_t i2c_addr, uint16_t reg_addr, uint16_t read_len, uint8_t* read_buffer, bool more_follows);
// helper functions
uint8_t _udma_i2cm_write_addr_plus_regaddr (uint8_t i2c_id, uint8_t i2c_addr, uint8_t reg_addr);
uint8_t _udma_i2cm_write_addr_plus_reg16addr (uint8_t i2c_id, uint8_t i2c_addr, uint16_t reg_addr);
uint8_t _udma_i2cm_read(uint8_t i2c_id, uint8_t i2c_addr, uint16_t read_len, uint8_t* read_buffer, bool more_follows);
uint8_t _udma_i2cm_send_stop(uint8_t i2c_id);
#endif /* DRIVERS_INCLUDE_UDMA_I2CM_DRIVER_H_ */
/*
* Copyright 2021 QuickLogic
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifndef DRIVERS_INCLUDE_UDMA_QSPIM_DRIVER_H_
#define DRIVERS_INCLUDE_UDMA_QSPIM_DRIVER_H_
#include <stdint.h>
#include <stdbool.h>
#include "hal_udma_ctrl_reg_defs.h"
typedef enum {
kQSPImReset
} udma_qspim_control_type_t;
typedef enum {
kSPIm_Cfg = (0x0 << 28),
kSPIm_SOT = (0x1 << 28),
kSPIm_SendCmd = (0x2 << 28),
kSPIm_Dummy = (0x4 << 28),
kSPIm_Wait = (0x5 << 28),
kSPIm_TxData = (0x6 << 28),
kSPIm_RxData = (0x7 << 28),
kSPIm_Repeat = (0x8 << 28),
kSPIm_EOT = (0x9 << 28),
kSPIm_RepeatEnd = (0xa << 28),
kSPIm_RxCheck = (0xb << 28),
kSPIm_FDX = (0xc << 28),
kSPIm_UCA = (0xd << 28),
kSPIm_UCS = (0xe << 28)
} spim_cmd_t;
uint16_t udma_qspim_open (uint8_t qspim_id, uint32_t spi_clk_freq);
uint16_t udma_qspim_close (uint8_t qspim_id);
uint16_t udma_qspim_control(uint8_t qspim_id, udma_qspim_control_type_t control_type, void* pparam);
void udma_qspim_write(uint8_t qspim_id, uint8_t cs, uint16_t write_len, uint8_t* write_data);
void udma_qspim_read(uint8_t qspim_id, uint8_t cs, uint16_t read_len, uint8_t* read_buffer);
uint8_t udma_flash_erase(uint8_t qspim_id, uint8_t cs, uint32_t addr, uint8_t cmd);
uint32_t udma_flash_readid(uint8_t qspim_id, uint8_t cs);
void udma_flash_read(uint8_t qspim_id, uint8_t cs, uint32_t flash_addr,uint8_t *l2addr,uint16_t read_len ) ;
void udma_flash_write(uint8_t qspim_id, uint8_t cs, uint32_t flash_addr,uint8_t *l2addr,uint16_t write_len ) ;
uint32_t udma_flash_reset_enable(uint8_t qspim_id, uint8_t cs);
uint32_t udma_flash_reset_memory(uint8_t qspim_id, uint8_t cs);
// helper functions
#endif /* DRIVERS_INCLUDE_UDMA_QSPIM_DRIVER_H_ */
/*
* Copyright 2021 QuickLogic
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifndef DRIVERS_INCLUDE_UDMA_SDIO_DRIVER_H_
#define DRIVERS_INCLUDE_UDMA_SDIO_DRIVER_H_
#include <stdint.h>
#include <stdbool.h>
#include "hal_udma_ctrl_reg_defs.h"
typedef enum {
kSDIOmReset
} udma_sdio_control_type_t;
/*
typedef enum {
kSPIm_Cfg = (0x0 << 28),
kSPIm_SOT = (0x1 << 28),
kSPIm_SendCmd = (0x2 << 28),
kSPIm_Dummy = (0x4 << 28),
kSPIm_Wait = (0x5 << 28),
kSPIm_TxData = (0x6 << 28),
kSPIm_RxData = (0x7 << 28),
kSPIm_Repeat = (0x8 << 28),
kSPIm_EOT = (0x9 << 28),
kSPIm_RepeatEnd = (0xa << 28),
kSPIm_RxCheck = (0xb << 28),
kSPIm_FDX = (0xc << 28),
kSPIm_UCA = (0xd << 28),
kSPIm_UCS = (0xe << 28)
} spim_cmd_t;
*/
uint16_t udma_sdio_open (uint8_t sdio_id);
uint16_t udma_sdio_close (uint8_t sdio_id);
uint16_t udma_sdio_control(uint8_t sdio_id, udma_sdio_control_type_t control_type, void* pparam);
uint8_t udma_sdio_sendCmd(uint8_t sdio_id, uint8_t aCmdOpCode, uint8_t aRspType, uint32_t aCmdArgument, uint32_t *aResponseBuf);
void udma_sdio_write(uint8_t sdio_id, uint8_t cs, uint16_t write_len, uint8_t* write_data);
void udma_sdio_read(uint8_t sdio_id, uint8_t cs, uint16_t read_len, uint8_t* read_buffer);
uint8_t udma_flash_erase(uint8_t sdio_id, uint8_t cs, uint32_t addr, uint8_t cmd);
uint32_t udma_flash_readid(uint8_t sdio_id, uint8_t cs);
void udma_flash_read(uint8_t sdio_id, uint8_t cs, uint32_t flash_addr,uint8_t *l2addr,uint16_t read_len ) ;
void udma_flash_write(uint8_t sdio_id, uint8_t cs, uint32_t flash_addr,uint8_t *l2addr,uint16_t write_len ) ;
uint32_t udma_flash_reset_enable(uint8_t sdio_id, uint8_t cs);
uint32_t udma_flash_reset_memory(uint8_t sdio_id, uint8_t cs);
uint8_t udma_sdio_readBlockData(uint8_t sdio_id, uint32_t aNumOfBlocks, uint32_t *aBuf, uint32_t aBufLen);
uint8_t udma_sdio_writeBlockData(uint8_t sdio_id, uint32_t aNumOfBlocks, uint32_t *aBuf, uint32_t aBufLen);
void udma_sdio_clearDataSetup(uint8_t sdio_id);
// helper functions
#endif /* DRIVERS_INCLUDE_UDMA_QSPIM_DRIVER_H_ */
......@@ -36,4 +36,5 @@ uint16_t udma_uart_readraw(uint8_t uart_id, uint16_t read_len, uint8_t* read_buf
uint8_t udma_uart_getchar(uint8_t uart_id);
uint16_t udma_uart_control(uint8_t uart_id, udma_uart_control_type_t control_type, void* pparam);
uint8_t uart_getchar (uint8_t id);
#endif //__UDMA_UART_DRIVER_H_
/*
* Copyright 2021 QuickLogic
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifdef PKG_USING_FREERTOS_WRAPPER
#include "FreeRTOS.h"
#include <camera.h>
#include <string.h>
#include <stdint.h>
#include <stdbool.h>
#include "semphr.h"
#include "core-v-mcu-config.h"
#include "hal_fc_event.h"
#include "hal_udma_ctrl_reg_defs.h"
#include "hal_udma_cam_reg_defs.h"
#include <udma_cam_driver.h>
#include <udma_i2cm_driver.h>
#include "himax.h"
#include "camera.h"
reg_cfg_t himaxRegInit[] = {
{BLC_TGT, 0x08}, // BLC target :8 at 8 bit mode
{BLC2_TGT, 0x08}, // BLI target :8 at 8 bit mode
{0x3044, 0x0A}, // Increase CDS time for settling
{0x3045, 0x00}, // Make symetric for cds_tg and rst_tg
{0x3047, 0x0A}, // Increase CDS time for settling
{0x3050, 0xC0}, // Make negative offset up to 4x
{0x3051, 0x42},
{0x3052, 0x50},
{0x3053, 0x00},
{0x3054, 0x03}, // tuning sf sig clamping as lowest
{0x3055, 0xF7}, // tuning dsun
{0x3056, 0xF8}, // increase adc nonoverlap clk
{0x3057, 0x29}, // increase adc pwr for missing code
{0x3058, 0x1F}, // turn on dsun
{0x3059, 0x1E},
{0x3064, 0x00},
{0x3065, 0x04}, // pad pull 0
{BLC_CFG, 0x43}, // BLC_on, IIR
{0x1001, 0x43}, // BLC dithering en
{0x1002, 0x43}, // blc_darkpixel_thd
{0x0350, 0x00}, // Dgain Control
{BLI_EN, 0x01}, // BLI enable
{0x1003, 0x00}, // BLI Target [Def: 0x20]
{DPC_CTRL, 0x01}, // DPC option 0: DPC off 1 : mono 3 : bayer1 5 : bayer2
{0x1009, 0xA0}, // cluster hot pixel th
{0x100A, 0x60}, // cluster cold pixel th
{SINGLE_THR_HOT, 0x90}, // single hot pixel th
{SINGLE_THR_COLD, 0x40}, // single cold pixel th
{0x1012, 0x00}, // Sync. shift disable
{0x2000, 0x07},
{0x2003, 0x00},
{0x2004, 0x1C},
{0x2007, 0x00},
{0x2008, 0x58},
{0x200B, 0x00},
{0x200C, 0x7A},
{0x200F, 0x00},
{0x2010, 0xB8},
{0x2013, 0x00},
{0x2014, 0x58},
{0x2017, 0x00},
{0x2018, 0x9B},
{AE_CTRL, 0x01}, //Automatic Exposure Gain Control
{AE_TARGET_MEAN, 0x3C}, //AE target mean [Def: 0x3C]
{AE_MIN_MEAN, 0x0A}, //AE min target mean [Def: 0x0A]
{INTEGRATION_H, 0x00}, //Integration H [Def: 0x01]
{INTEGRATION_L, 0x60}, //Integration L [Def: 0x08]
{ANALOG_GAIN, 0x00}, //Analog Global Gain
{DAMPING_FACTOR, 0x20}, //Damping Factor [Def: 0x20]
{DIGITAL_GAIN_H, 0x01}, //Digital Gain High [Def: 0x01]
{DIGITAL_GAIN_L, 0x00}, //Digital Gain Low [Def: 0x00]
{0x2103, 0x03},
{0x2104, 0x05},
{0x2105, 0x01},
{0x2106, 0x54},
{0x2108, 0x03},
{0x2109, 0x04},
{0x210B, 0xC0},
{0x210E, 0x00}, //Flicker Control
{0x210F, 0x00},
{0x2110, 0x3C},
{0x2111, 0x00},
{0x2112, 0x32},
{0x2150, 0x30},
{0x0340, 0x02},
{0x0341, 0x16},
{0x0342, 0x01},
{0x0343, 0x78},
{0x3010, 0x01},
{0x0383, 0x01},
{0x0387, 0x01},
{0x0390, 0x00},
{0x3011, 0x70},
{0x3059, 0x02},
{0x3060, 0x01},
// {0x3060, 0x25}, //Clock gating and clock divisors
{0x3068, 0x20}, //PCLK0 polarity
{IMG_ORIENTATION, 0x01}, // change the orientation
{0x0104, 0x01},
{0x0100, 0x01},
//{0x0601, 0x11} //Test pattern walking ones
//{0x0601, 0x01} //Test pattern colour bar
};
SemaphoreHandle_t cam_semaphore_rx;
static uint8_t cam;
static void camISR() {
}
void cam_open (uint8_t cam_id)
{
int i = 0;
volatile UdmaCtrl_t* pudma_ctrl = (UdmaCtrl_t*)UDMA_CH_ADDR_CTRL;
/* Enable reset and enable uart clock */
pudma_ctrl->reg_rst |= (UDMA_CTRL_CAM0_CLKEN << cam_id);
pudma_ctrl->reg_rst &= ~(UDMA_CTRL_CAM0_CLKEN << cam_id);
pudma_ctrl->reg_cg |= (UDMA_CTRL_CAM0_CLKEN << cam_id);
//psdio_regs->clk_div_b.clk_div = 5;
//psdio_regs->clk_div_b.valid = 1;
hal_setpinmux(21, 0);
hal_setpinmux(22, 0);
hal_setpinmux(25, 0);
for(i=0; i<8; i++ )
{
//set pin muxes to sdio functionality
hal_setpinmux(29+i, 0);
}
/* See if already initialized */
if (cam_semaphore_rx != NULL ){
return;
}
/* Set semaphore */
SemaphoreHandle_t shSemaphoreHandle; // FreeRTOS.h has a define for xSemaphoreHandle, so can't use that
shSemaphoreHandle = xSemaphoreCreateBinary();
configASSERT(shSemaphoreHandle);
xSemaphoreGive(shSemaphoreHandle);
cam_semaphore_rx = shSemaphoreHandle;
/* Set handlers. */
pi_fc_event_handler_set(SOC_EVENT_UDMA_CAM_RX(cam_id), camISR, cam_semaphore_rx);
/* Enable SOC events propagation to FC. */
hal_soc_eu_set_fc_mask(SOC_EVENT_UDMA_CAM_RX(cam_id));
/* configure */
cam = 0x48; // Himax address
udma_cam_control(kCamReset, NULL);
return;
}
uint16_t udma_cam_control(udma_cam_control_type_t control_type, void* pparam) {
short retval = 0;
uint16_t i;
SemaphoreHandle_t shSemaphoreHandle;
camera_struct_t *camera;
//camera = (camera_struct_t *)0x1A102300; // Peripheral 5?
camera = (camera_struct_t *)(UDMA_CH_ADDR_CAM + 0 * UDMA_CH_SIZE);
shSemaphoreHandle = cam_semaphore_rx;
switch (control_type) {
case kCamReset:
_himaxRegWrite(SW_RESET, HIMAX_RESET);
break;
case kCamID:
udma_i2cm_16read8(0, cam, MODEL_ID_H, 2, &retval, 0);
retval = (retval >> 8) & 0xff | (retval <<8);
break;
case kCamInit:
for(i=0; i<(sizeof(himaxRegInit)/sizeof(reg_cfg_t)); i++){
_himaxRegWrite(himaxRegInit[i].addr, himaxRegInit[i].data);
}
camera->cfg_ll = 0<<16 | 0;
camera->cfg_ur = 323<<16 | 243; // 320 x 240 ?
camera->cfg_filter = (1 << 16) | (1 << 8) | 1;
camera->cfg_size = 324;
camera->vsync_pol = 1;
camera->cfg_glob = (0 << 0) | // framedrop disabled
(000000 << 1) | // number of frames to drop
(0 << 7) | // Frame slice disabled
(004 << 8) | // Format binary 100 = ByPass little endian
(0000 << 11); // Shift value ignored in bypass
break;
case kCamFrame:
configASSERT( xSemaphoreTake( shSemaphoreHandle, 1000000 ) == pdTRUE );
camera->rx_saddr = pparam;
camera->rx_size = (244*324);
camera->rx_cfg = 0x12; // start 16-bit transfers
camera->cfg_glob = camera->cfg_glob |
(1 << 31) ; // enable 1 == go
configASSERT( xSemaphoreTake( shSemaphoreHandle, 1000000 ) == pdTRUE );
camera->cfg_glob = camera->cfg_glob &
(0x7fffffff) ; // enable 1 == go
configASSERT( xSemaphoreGive( shSemaphoreHandle ) == pdTRUE );
}
return retval;
}
void _himaxRegWrite(unsigned int addr, unsigned char value){
uint8_t naddr;
uint16_t data;
naddr = (addr>>8) & 0xff;
data = (value << 8) | (addr & 0xff);
udma_i2cm_write (0, cam, naddr, 2, &data, 0);
// i2c_16write8(cam,addr,value);
}
#endif
/*
* Copyright 2021 QuickLogic
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifdef PKG_USING_FREERTOS_WRAPPER
#include "FreeRTOS.h"
#include <string.h>
#include <stdint.h>
#include <stdbool.h>
#include "semphr.h"
#include "core-v-mcu-config.h"
#include "hal_fc_event.h"
#include "hal_udma_ctrl_reg_defs.h"
#include "hal_udma_i2cm_reg_defs.h"
#include <udma_i2cm_driver.h>
SemaphoreHandle_t i2cm_semaphores_rx[N_I2CM];
SemaphoreHandle_t i2cm_semaphores_tx[N_I2CM];
void i2cmTXHandler(void *arg)
{
uint32_t lCounter = 0;
lCounter++;
}
void i2cmRXHandler(void *arg)
{
uint32_t lCounter = 0;
lCounter++;
}
static uint8_t aucclkdiv[2];
uint16_t udma_i2cm_open (uint8_t i2cm_id, uint32_t clk_freq) {
volatile UdmaCtrl_t* pudma_ctrl = (UdmaCtrl_t*)UDMA_CH_ADDR_CTRL;
UdmaI2cm_t* pi2cm_regs = (UdmaI2cm_t*)(UDMA_CH_ADDR_I2CM + i2cm_id * UDMA_CH_SIZE);
uint32_t clk_divisor;
/* See if already initialized */
if (i2cm_semaphores_rx[i2cm_id] != NULL || i2cm_semaphores_tx[i2cm_id] != NULL) {
return 1;
}
/* Enable reset and enable uart clock */
pudma_ctrl->reg_rst |= (UDMA_CTRL_I2CM0_CLKEN << i2cm_id);
pudma_ctrl->reg_rst &= ~(UDMA_CTRL_I2CM0_CLKEN << i2cm_id);
pudma_ctrl->reg_cg |= (UDMA_CTRL_I2CM0_CLKEN << i2cm_id);
/* Set semaphore */
SemaphoreHandle_t shSemaphoreHandle; // FreeRTOS.h has a define for xSemaphoreHandle, so can't use that
shSemaphoreHandle = xSemaphoreCreateBinary();
configASSERT(shSemaphoreHandle);
xSemaphoreGive(shSemaphoreHandle);
i2cm_semaphores_rx[i2cm_id] = shSemaphoreHandle;
shSemaphoreHandle = xSemaphoreCreateBinary();
configASSERT(shSemaphoreHandle);
xSemaphoreGive(shSemaphoreHandle);
i2cm_semaphores_tx[i2cm_id] = shSemaphoreHandle;
/* Set handlers. */
pi_fc_event_handler_set(SOC_EVENT_UDMA_I2C_RX(i2cm_id), i2cmRXHandler/*NULL*/, i2cm_semaphores_rx[i2cm_id]);
pi_fc_event_handler_set(SOC_EVENT_UDMA_I2C_TX(i2cm_id), i2cmTXHandler/*NULL*/, i2cm_semaphores_tx[i2cm_id]);
/* Enable SOC events propagation to FC. */
hal_soc_eu_set_fc_mask(SOC_EVENT_UDMA_I2C_RX(i2cm_id));
hal_soc_eu_set_fc_mask(SOC_EVENT_UDMA_I2C_TX(i2cm_id));
/* configure */
clk_divisor = 5000000/clk_freq;
aucclkdiv[0] = (clk_divisor >> 0) & 0xFF;
aucclkdiv[1] = (clk_divisor >> 8) & 0xFF;
return 0;
}
uint16_t udma_i2cm_control(uint8_t i2cm_id, udma_i2cm_control_type_t control_type, void* pparam) {
volatile UdmaCtrl_t* pudma_ctrl = (UdmaCtrl_t*)UDMA_CH_ADDR_CTRL;
UdmaI2cm_t* pi2cm_regs = (UdmaI2cm_t*)(UDMA_CH_ADDR_I2CM + i2cm_id * UDMA_CH_SIZE);
switch(control_type) {
case kI2cmReset:
pudma_ctrl->reg_rst |= (UDMA_CTRL_I2CM0_CLKEN << i2cm_id);
pudma_ctrl->reg_rst &= ~(UDMA_CTRL_I2CM0_CLKEN << i2cm_id);
break;
default:
configASSERT(0);
}
return 0;
}
static uint8_t auccmd_rx[16];
uint8_t udma_i2cm_read(uint8_t i2cm_id, uint8_t i2cm_addr, uint8_t reg_addr, uint16_t read_len, uint8_t* read_buffer, bool more_follows) {
_udma_i2cm_write_addr_plus_regaddr(i2cm_id, i2cm_addr, reg_addr);
return _udma_i2cm_read(i2cm_id, i2cm_addr, read_len, read_buffer, more_follows);
}
uint8_t udma_i2cm_16read8(uint8_t i2cm_id, uint8_t i2cm_addr, uint16_t reg_addr, uint16_t read_len, uint8_t* read_buffer, bool more_follows) {
_udma_i2cm_write_addr_plus_reg16addr(i2cm_id, i2cm_addr, reg_addr);
return _udma_i2cm_read(i2cm_id, i2cm_addr, read_len, read_buffer, more_follows);
}
static uint8_t auccmd_tx[32];
uint8_t udma_i2cm_write (uint8_t i2cm_id, uint8_t i2cm_addr, uint8_t reg_addr, uint16_t write_len, uint8_t *write_data, bool more_follows) {
UdmaI2cm_t* pi2cm_regs = (UdmaI2cm_t*)(UDMA_CH_ADDR_I2CM + i2cm_id * UDMA_CH_SIZE);
uint8_t* pcmd = auccmd_tx;
uint8_t* pdata = write_data;
SemaphoreHandle_t shSemaphoreHandleTx = i2cm_semaphores_tx[i2cm_id];
uint8_t lStatus = pdFALSE;
configASSERT(write_len < 256);
if( xSemaphoreTake( shSemaphoreHandleTx, SEMAPHORE_WAIT_TIME_IN_MS ) == pdTRUE ) // Wait for any prior transmission to complete
{
*pcmd++ = kI2cmCmdCfg;
*pcmd++ = aucclkdiv[1];
*pcmd++ = aucclkdiv[0];
*pcmd++ = kI2cmCmdStart; // Put Start transaction on I2C bus
*pcmd++ = kI2cmCmdRpt; // Set up for several writes: i2cm_CMD_RPT
*pcmd++ = (uint8_t)(write_len + 2); // I@CM_ADDR + REG_ADDR + data
*pcmd++ = kI2cmCmdWr; // Command to repeat: I2C CMD_WR
*pcmd++ = i2cm_addr & 0xfe; // Clear R/WRbar bit from i2c device's address to indicate write
*pcmd++ = reg_addr; // Target address for following data
for (int i = 0; i != write_len; i++) {
*pcmd++ = *pdata++;
}
pi2cm_regs->tx_saddr = auccmd_tx;
pi2cm_regs->tx_size = (uint32_t)(pcmd - auccmd_tx);
pi2cm_regs->tx_cfg_b.en = 1;
// Block until UDMA transaction is completed
xSemaphoreTake( shSemaphoreHandleTx, SEMAPHORE_WAIT_TIME_IN_MS );
xSemaphoreGive( shSemaphoreHandleTx );
if (!more_follows) {
_udma_i2cm_send_stop(i2cm_id);
}
lStatus = pdTRUE;
}
else
{
xSemaphoreGive( shSemaphoreHandleTx );
}
return lStatus;
}
uint8_t _udma_i2cm_write_addr_plus_regaddr (uint8_t i2cm_id, uint8_t i2cm_addr, uint8_t reg_addr) {
UdmaI2cm_t* pi2cm_regs = (UdmaI2cm_t*)(UDMA_CH_ADDR_I2CM + i2cm_id * UDMA_CH_SIZE);
uint8_t* pcmd = auccmd_tx;
uint8_t lStatus = pdFALSE;
SemaphoreHandle_t shSemaphoreHandle = i2cm_semaphores_tx[i2cm_id];
if( xSemaphoreTake( shSemaphoreHandle, SEMAPHORE_WAIT_TIME_IN_MS ) == pdTRUE )
{
pi2cm_regs->tx_cfg_b.en = 0;
*pcmd++ = kI2cmCmdCfg;
*pcmd++ = aucclkdiv[1];
*pcmd++ = aucclkdiv[0];
*pcmd++ = kI2cmCmdStart; // Put Start transaction on I2C bus
*pcmd++ = kI2cmCmdWr; // Write device's address (next byte)
*pcmd++ = i2cm_addr & 0xfe; // Clear R/WRbar bit from i2c device's address to indicate write
*pcmd++ = kI2cmCmdWr; // I2C CMD_WR
pi2cm_regs->tx_saddr = auccmd_tx;
pi2cm_regs->tx_size = (uint32_t)(pcmd - auccmd_tx);
pi2cm_regs->tx_cfg_b.en = 1;
// Block until UDMA operation is completed
if( xSemaphoreTake( shSemaphoreHandle, SEMAPHORE_WAIT_TIME_IN_MS ) == pdTRUE )
{
//pi2cm_regs->tx_cfg_b.en = 0;
pcmd = auccmd_tx;
*pcmd++ = reg_addr;
pi2cm_regs->tx_saddr = auccmd_tx;
pi2cm_regs->tx_size = (uint32_t)(pcmd - auccmd_tx);
pi2cm_regs->tx_cfg_b.en = 1;
// Block until UDMA operation is completed
xSemaphoreTake( shSemaphoreHandle, SEMAPHORE_WAIT_TIME_IN_MS );
xSemaphoreGive( shSemaphoreHandle );
lStatus = pdTRUE;
}
else
{
xSemaphoreGive( shSemaphoreHandle );
}
}
else
{
xSemaphoreGive( shSemaphoreHandle );
}
return lStatus;
}
uint8_t _udma_i2cm_write_addr_plus_reg16addr (uint8_t i2cm_id, uint8_t i2cm_addr, uint16_t reg_addr) {
UdmaI2cm_t* pi2cm_regs = (UdmaI2cm_t*)(UDMA_CH_ADDR_I2CM + i2cm_id * UDMA_CH_SIZE);
uint8_t* pcmd = auccmd_tx;
uint8_t lStatus = pdFALSE;
SemaphoreHandle_t shSemaphoreHandle = i2cm_semaphores_tx[i2cm_id];
if( xSemaphoreTake( shSemaphoreHandle, SEMAPHORE_WAIT_TIME_IN_MS ) == pdTRUE )
{
pi2cm_regs->tx_cfg_b.en = 0;
*pcmd++ = kI2cmCmdCfg;
*pcmd++ = aucclkdiv[1];
*pcmd++ = aucclkdiv[0];
*pcmd++ = kI2cmCmdStart; // Put Start transaction on I2C bus
*pcmd++ = kI2cmCmdWr; // Write device's address (next byte)
*pcmd++ = i2cm_addr & 0xfe; // Clear R/WRbar bit from i2c device's address to indicate write
*pcmd++ = kI2cmCmdRpt; // 2 byte register address
*pcmd++ = 2;
*pcmd++ = kI2cmCmdWr; // I2C CMD_WR
pi2cm_regs->tx_saddr = auccmd_tx;
pi2cm_regs->tx_size = (uint32_t)(pcmd - auccmd_tx);
pi2cm_regs->tx_cfg_b.en = 1;
// Block until UDMA operation is completed
if( xSemaphoreTake( shSemaphoreHandle, SEMAPHORE_WAIT_TIME_IN_MS ) == pdTRUE )
{
//pi2cm_regs->tx_cfg_b.en = 0;
pcmd = auccmd_tx;
*pcmd++ = reg_addr & 0xff;
*pcmd++ = (reg_addr >> 8) & 0xff;
pi2cm_regs->tx_saddr = auccmd_tx;
pi2cm_regs->tx_size = (uint32_t)(pcmd - auccmd_tx);
pi2cm_regs->tx_cfg_b.en = 1;
// Block until UDMA operation is completed
xSemaphoreTake( shSemaphoreHandle, SEMAPHORE_WAIT_TIME_IN_MS );
xSemaphoreGive( shSemaphoreHandle );
lStatus = pdTRUE;
}
else
{
xSemaphoreGive( shSemaphoreHandle );
}
}
else
{
xSemaphoreGive( shSemaphoreHandle );
}
return lStatus;
}
uint8_t _udma_i2cm_read(uint8_t i2cm_id, uint8_t i2cm_addr, uint16_t read_len, uint8_t* read_buffer, bool more_follows) {
UdmaI2cm_t* pi2cm_regs = (UdmaI2cm_t*)(UDMA_CH_ADDR_I2CM + i2cm_id * UDMA_CH_SIZE);
uint8_t* pcmd = auccmd_rx;
uint8_t lStatus = pdFALSE;
configASSERT(read_len < 256);
SemaphoreHandle_t shSemaphoreHandle = i2cm_semaphores_rx[i2cm_id];
if( xSemaphoreTake( shSemaphoreHandle, SEMAPHORE_WAIT_TIME_IN_MS ) == pdTRUE )
{
shSemaphoreHandle = i2cm_semaphores_tx[i2cm_id];
if( xSemaphoreTake( shSemaphoreHandle, SEMAPHORE_WAIT_TIME_IN_MS ) == pdTRUE )
{
pi2cm_regs->tx_cfg_b.en = 0;
*pcmd++ = kI2cmCmdCfg;
*pcmd++ = aucclkdiv[1];
*pcmd++ = aucclkdiv[0];
*pcmd++ = kI2cmCmdStart; // Put Start transaction on I2C bus
*pcmd++ = kI2cmCmdWr; // Write device's address (next byte)
*pcmd++ = i2cm_addr | 0x01; // Device's address with read bit set
if (read_len > 1) { // Do len-1 reads with ACK, and follow by 1 read with NACK
*pcmd++ = kI2cmCmdRpt; // Tell controller to repeat the following command
*pcmd++ = (uint8_t)(read_len - 1); // len-1 times
*pcmd++ = kI2cmCmdRdAck; // command to repeat is read with ack
}
*pcmd++ = kI2cmCmdRdNack; // Read last byte with NACK to indicate the end of the read
//
pi2cm_regs->rx_saddr = read_buffer;
pi2cm_regs->rx_size = read_len;
pi2cm_regs->rx_cfg_b.en = 1;
pi2cm_regs->tx_saddr = auccmd_rx;
pi2cm_regs->tx_size = (uint32_t)(pcmd - auccmd_rx);
pi2cm_regs->tx_cfg_b.en = 1;
// Block until UDMA operation is complete
shSemaphoreHandle = i2cm_semaphores_rx[i2cm_id];
xSemaphoreTake( shSemaphoreHandle, SEMAPHORE_WAIT_TIME_IN_MS );
xSemaphoreGive( shSemaphoreHandle );
shSemaphoreHandle = i2cm_semaphores_tx[i2cm_id];
xSemaphoreTake( shSemaphoreHandle, SEMAPHORE_WAIT_TIME_IN_MS );
xSemaphoreGive( shSemaphoreHandle );
if (!more_follows) {
_udma_i2cm_send_stop(i2cm_id);
}
lStatus = pdTRUE;
}
else
{
xSemaphoreGive( shSemaphoreHandle );
lStatus = pdFALSE;
}
}
else
{
xSemaphoreGive( shSemaphoreHandle );
lStatus = pdFALSE;
}
return lStatus;
}
static uint8_t auci2cm_stop_seq[] = {
kI2cmCmdStop, kI2cmCmdWait, 0x0
};
uint8_t _udma_i2cm_send_stop(uint8_t i2cm_id) {
UdmaI2cm_t* pi2cm_regs = (UdmaI2cm_t*)(UDMA_CH_ADDR_I2CM + i2cm_id * UDMA_CH_SIZE);
SemaphoreHandle_t shSemaphoreHandle = i2cm_semaphores_tx[i2cm_id];
uint8_t lStatus = pdFALSE;
if( xSemaphoreTake( shSemaphoreHandle, SEMAPHORE_WAIT_TIME_IN_MS ) == pdTRUE )
{
pi2cm_regs->tx_saddr = auci2cm_stop_seq;
pi2cm_regs->tx_size = sizeof(auci2cm_stop_seq);
pi2cm_regs->tx_cfg_b.en = 1;
// Block until UDMA transaction is completed
xSemaphoreTake( shSemaphoreHandle, SEMAPHORE_WAIT_TIME_IN_MS );
xSemaphoreGive( shSemaphoreHandle );
lStatus = pdTRUE;
}
else
{
xSemaphoreGive( shSemaphoreHandle );
}
return lStatus;
}
#endif
/*
* Copyright 2021 QuickLogic
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifdef PKG_USING_FREERTOS_WRAPPER
#include "FreeRTOS.h"
#include <string.h>
#include <stdint.h>
#include <stdbool.h>
#include "semphr.h"
#include "core-v-mcu-config.h"
#include "hal_fc_event.h"
#include "hal_udma_ctrl_reg_defs.h"
#include "hal_udma_sdio_reg_defs.h"
#include <udma_sdio_driver.h>
#define BLOCK_SIZE 512
uint16_t udma_sdio_open (uint8_t sdio_id)
{
int i = 0;
volatile UdmaCtrl_t* pudma_ctrl = (UdmaCtrl_t*)UDMA_CH_ADDR_CTRL;
UdmaSdio_t* psdio_regs = (UdmaSdio_t*)(UDMA_CH_ADDR_SDIO + sdio_id * UDMA_CH_SIZE);
/* Enable reset and enable uart clock */
pudma_ctrl->reg_rst |= (UDMA_CTRL_SDIO0_CLKEN << sdio_id);
pudma_ctrl->reg_rst &= ~(UDMA_CTRL_SDIO0_CLKEN << sdio_id);
pudma_ctrl->reg_cg |= (UDMA_CTRL_SDIO0_CLKEN << sdio_id);
psdio_regs->clk_div_b.clk_div = 7;//5;
psdio_regs->clk_div_b.valid = 1;
//Restore pin muxes
for(i=0; i<6; i++ )
{
//set pin muxes to sdio functionality
hal_setpinmux(37+i, 0);
}
return 0;
}
uint16_t udma_sdio_control(uint8_t sdio_id, udma_sdio_control_type_t control_type, void* pparam) {
volatile UdmaCtrl_t* pudma_ctrl = (UdmaCtrl_t*)UDMA_CH_ADDR_CTRL;
UdmaSdio_t* psdio_regs = (UdmaSdio_t*)(UDMA_CH_ADDR_SDIO + sdio_id * UDMA_CH_SIZE);
switch(control_type) {
case kSDIOmReset:
pudma_ctrl->reg_rst |= (UDMA_CTRL_SDIO0_CLKEN << sdio_id);
pudma_ctrl->reg_rst &= ~(UDMA_CTRL_SDIO0_CLKEN << sdio_id);
break;
default:
configASSERT(0);
}
return 0;
}
void udma_sdio_clearDataSetup(uint8_t sdio_id)
{
UdmaSdio_t *psdio_regs = (UdmaSdio_t*)(UDMA_CH_ADDR_SDIO + sdio_id * UDMA_CH_SIZE);
psdio_regs->data_setup = 0x00000000;
}
uint8_t udma_sdio_writeBlockData(uint8_t sdio_id, uint32_t aNumOfBlocks, uint32_t *aBuf, uint32_t aBufLen)
{
uint8_t lSts = 0;
uint32_t lData = 0;
UdmaSdio_t *psdio_regs = (UdmaSdio_t*)(UDMA_CH_ADDR_SDIO + sdio_id * UDMA_CH_SIZE);
psdio_regs->tx_cfg_b.clr = 1;
psdio_regs->tx_cfg_b.en = 0;
psdio_regs->tx_cfg_b.datasize = 2;
psdio_regs->tx_saddr = aBuf;
psdio_regs->tx_size = aBufLen;
lData = 0;
psdio_regs->data_setup = 0x00000000;
lData |= 1 << 0; //Data Enable - Enable data transfer for current command
lData |= 0 << 1; //RWN: Set transfer direction 1 read; 0 write
lData |= 1 << 2; //QUAD mode: Use quad mode.
lData |= ( aNumOfBlocks - 1 ) << 8; //Number of blocks
lData |= ( BLOCK_SIZE - 1 ) << 16; //Block size
psdio_regs->data_setup = lData;
psdio_regs->tx_cfg_b.en = 1;
}
uint8_t udma_sdio_readBlockData(uint8_t sdio_id, uint32_t aNumOfBlocks, uint32_t *aBuf, uint32_t aBufLen)
{
uint8_t lSts = 0;
uint32_t lData = 0;
UdmaSdio_t *psdio_regs = (UdmaSdio_t*)(UDMA_CH_ADDR_SDIO + sdio_id * UDMA_CH_SIZE);
psdio_regs->rx_cfg_b.clr = 1;
psdio_regs->rx_cfg_b.en = 0;
psdio_regs->rx_cfg_b.datasize = 2;
psdio_regs->rx_saddr = aBuf;
psdio_regs->rx_size = aBufLen;
lData = 0;
psdio_regs->data_setup = 0x00000000;
lData |= 1 << 0; //Data Enable - Enable data transfer for current command
lData |= 1 << 1; //RWN: Set transfer direction 1 read; 0 write
lData |= 1 << 2; //QUAD mode: Use quad mode.
lData |= ( aNumOfBlocks - 1 ) << 8; //Number of blocks
lData |= ( BLOCK_SIZE - 1 ) << 16; //Block size
psdio_regs->data_setup = lData;
psdio_regs->rx_cfg_b.en = 1;
}
uint8_t udma_sdio_sendCmd(uint8_t sdio_id, uint8_t aCmdOpCode, uint8_t aRspType, uint32_t aCmdArgument, uint32_t *aResponseBuf)
{
uint8_t lSts = 0;
uint32_t lData = 0;
uint32_t lLoopCounter = 0;
UdmaSdio_t *psdio_regs = (UdmaSdio_t*)(UDMA_CH_ADDR_SDIO + sdio_id * UDMA_CH_SIZE);
lData |= (aRspType & REG_CMD_OP_CMD_RSP_TYPE_MASK ) << REG_CMD_OP_CMD_RSP_TYPE_LSB;
lData |= ( aCmdOpCode & REG_CMD_OP_CMD_OP_MASK ) << REG_CMD_OP_CMD_OP_LSB;
psdio_regs->cmd_op = lData;
//psdio_regs->cmd_op_b.cmd_op = ( aCmdOpCode & 0x3F );
//psdio_regs->cmd_op_b.cmd_rsp_type = ( aRspType & 0x07 );
psdio_regs->cmd_arg = aCmdArgument;
psdio_regs->start = 1;
while( ( ( psdio_regs->status & ( REG_STATUS_EOT_MASK << REG_STATUS_EOT_LSB ) ) >> REG_STATUS_EOT_LSB ) == 0 )
{
if( ( ( psdio_regs->status & ( REG_STATUS_ERROR_MASK << REG_STATUS_ERROR_LSB ) ) >> REG_STATUS_ERROR_LSB ) == 1 )
{
lSts = (psdio_regs->status & ( REG_STATUS_CMD_ERR_STATUS_MASK << REG_STATUS_CMD_ERR_STATUS_LSB ) ) >> REG_STATUS_CMD_ERR_STATUS_LSB;
break;
}
else
{
if(++lLoopCounter >= 0x00010000 )
{
lSts = 5;
break;
}
}
}
psdio_regs->status_b.eot = 1; //Write 1 to EOT bit to clear it.
if( aResponseBuf )
{
aResponseBuf[0] = psdio_regs->rsp0;
aResponseBuf[1] = psdio_regs->rsp1;
aResponseBuf[2] = psdio_regs->rsp2;
aResponseBuf[3] = psdio_regs->rsp3;
}
return lSts;
}
#if 0
static uint32_t auccmd[16];
void udma_qspim_read(uint8_t qspim_id, uint8_t cs, uint16_t read_len, uint8_t* read_buffer) {
UdmaQspi_t* pqspim_regs = (UdmaQspi_t*)(UDMA_CH_ADDR_QSPIM + qspim_id * UDMA_CH_SIZE);
uint32_t* pcmd = auccmd;
configASSERT(read_len < 256);
SemaphoreHandle_t shSemaphoreHandle = qspim_semaphores_rx[qspim_id];
configASSERT( xSemaphoreTake( shSemaphoreHandle, 1000000 ) == pdTRUE );
shSemaphoreHandle = qspim_semaphores_cmd[qspim_id];
configASSERT( xSemaphoreTake( shSemaphoreHandle, 1000000 ) == pdTRUE );
shSemaphoreHandle = qspim_semaphores_eot[qspim_id];
configASSERT( xSemaphoreTake( shSemaphoreHandle, 1000000 ) == pdTRUE );
pqspim_regs->rx_cfg_b.en = 0;
pqspim_regs->tx_cfg_b.en = 0;
pqspim_regs->cmd_cfg_b.en = 0;
*pcmd++ = kSPIm_Cfg | aucclkdiv;
*pcmd++ = kSPIm_SOT | cs; //cs 1
*pcmd++ = kSPIm_RxData | (0x00470000 | (read_len-1)) ; // 4 words recieved
*pcmd++ = kSPIm_EOT | 1; // generate event
pqspim_regs->rx_saddr = read_buffer;
pqspim_regs->rx_size = read_len;
pqspim_regs->rx_cfg_b.en = 1;
pqspim_regs->cmd_saddr = auccmd;
pqspim_regs->cmd_size = (uint32_t)(pcmd - auccmd)*4;
pqspim_regs->cmd_cfg_b.en = 1;
// Block until UDMA operation is complete
shSemaphoreHandle = qspim_semaphores_rx[qspim_id];
configASSERT( xSemaphoreTake( shSemaphoreHandle, 1000000 ) == pdTRUE );
configASSERT( xSemaphoreGive( shSemaphoreHandle ) == pdTRUE );
shSemaphoreHandle = qspim_semaphores_cmd[qspim_id];
configASSERT( xSemaphoreTake( shSemaphoreHandle, 1000000 ) == pdTRUE );
configASSERT( xSemaphoreGive( shSemaphoreHandle ) == pdTRUE );
}
void udma_qspim_write (uint8_t qspim_id, uint8_t cs, uint16_t write_len, uint8_t *write_data) {
UdmaQspi_t* pqspim_regs = (UdmaQspi_t*)(UDMA_CH_ADDR_QSPIM + qspim_id * UDMA_CH_SIZE);
uint32_t* pcmd = auccmd;
uint32_t tmp_size;
configASSERT(write_len < 256);
SemaphoreHandle_t shSemaphoreHandle = qspim_semaphores_tx[qspim_id];
configASSERT( xSemaphoreTake( shSemaphoreHandle, 1000000 ) == pdTRUE );
shSemaphoreHandle = qspim_semaphores_cmd[qspim_id];
configASSERT( xSemaphoreTake( shSemaphoreHandle, 1000000 ) == pdTRUE );
shSemaphoreHandle = qspim_semaphores_eot[qspim_id];
configASSERT( xSemaphoreTake( shSemaphoreHandle, 1000000 ) == pdTRUE );
pqspim_regs->rx_cfg_b.clr = 1;
pqspim_regs->tx_cfg_b.clr = 1;
pqspim_regs->cmd_cfg_b.clr = 1;
*pcmd++ = kSPIm_Cfg | aucclkdiv;
*pcmd++ = kSPIm_SOT | cs;
*pcmd++ = kSPIm_TxData | 0x0470000 | write_len -1;
*pcmd++ = kSPIm_EOT | 1; // generate event
pqspim_regs->tx_saddr = write_data;
pqspim_regs->tx_size = write_len-1;
pqspim_regs->tx_cfg_b.datasize = 2;
pqspim_regs->tx_cfg_b.en = 1;
pqspim_regs->cmd_saddr = auccmd;
pqspim_regs->cmd_size = (uint32_t)(pcmd - auccmd)*4;
pqspim_regs->cmd_cfg_b.en = 1;
// Block until UDMA operation is complete
shSemaphoreHandle = qspim_semaphores_tx[qspim_id];
configASSERT( xSemaphoreTake( shSemaphoreHandle, 1000000 ) == pdTRUE );
configASSERT( xSemaphoreGive( shSemaphoreHandle ) == pdTRUE );
shSemaphoreHandle = qspim_semaphores_cmd[qspim_id];
configASSERT( xSemaphoreTake( shSemaphoreHandle, 1000000 ) == pdTRUE );
configASSERT( xSemaphoreGive( shSemaphoreHandle ) == pdTRUE );
shSemaphoreHandle = qspim_semaphores_eot[qspim_id];
configASSERT( xSemaphoreTake( shSemaphoreHandle, 1000000 ) == pdTRUE );
configASSERT( xSemaphoreGive( shSemaphoreHandle ) == pdTRUE );
}
#endif
#endif
\ No newline at end of file
......@@ -27,31 +27,23 @@
#include "udma_uart_driver.h"
#include "rtthread.h"
#include "rtdevice.h"
#define unuse_freertos_in_uart
#ifdef PKG_USING_FREERTOS_WRAPPER
#include <FreeRTOS.h>
#include <semphr.h>
#include <task.h>
#endif
#ifdef PKG_USING_FREERTOS_WRAPPER
SemaphoreHandle_t uart_semaphores_rx[N_UART];
SemaphoreHandle_t uart_semaphores_tx[N_UART];
#endif
char u1buffer[128], u0buffer[128];
int u1rdptr, u1wrptr, u0rdptr,u0wrptr;
UdmaUart_t *puart0 = (UdmaUart_t*)(UDMA_CH_ADDR_UART);
UdmaUart_t *puart1 = (UdmaUart_t*)(UDMA_CH_ADDR_UART + UDMA_CH_SIZE);
uint16_t outdata(uint8_t uart_id, uint16_t write_len, uint8_t* write_buffer) {
UdmaUart_t* puart = (UdmaUart_t*)(UDMA_CH_ADDR_UART + uart_id * UDMA_CH_SIZE);
while (puart->status_b.tx_busy) { // ToDo: Why is this necessary? Thought the semaphore should have protected
}
puart->tx_saddr = (uint32_t)write_buffer;
puart->tx_size = write_len;
puart->tx_cfg_b.en = 1; //enable the transfer
return 0;
}
#define UART_RX_BUFFER_LEN 16
rt_uint8_t uart_rxbuffer[UART_RX_BUFFER_LEN]={0};
struct rt_ringbuffer uart_rxTCB;
struct rt_semaphore shell_rx_semaphore;
extern void uart_rx_isr (void *id);
uint8_t uart_getchar (uint8_t id) {
uint8_t retval;
if (id == 1) {
......@@ -66,19 +58,40 @@ uint8_t uart_getchar (uint8_t id) {
}
return retval;
}
void uart_rx_isr (void *id);
uint16_t udma_uart_open (uint8_t uart_id, uint32_t xbaudrate) {
UdmaUart_t* puart;
volatile UdmaCtrl_t* pudma_ctrl = (UdmaCtrl_t*)UDMA_CH_ADDR_CTRL;
#ifdef PKG_USING_FREERTOS_WRAPPER
/* See if already initialized */
if (uart_semaphores_rx[uart_id] != NULL || uart_semaphores_tx[uart_id] != NULL) {
return 1;
}
#endif
/* Enable reset and enable uart clock */
pudma_ctrl->reg_rst |= (UDMA_CTRL_UART0_CLKEN << uart_id);
pudma_ctrl->reg_rst &= ~(UDMA_CTRL_UART0_CLKEN << uart_id);
pudma_ctrl->reg_cg |= (UDMA_CTRL_UART0_CLKEN << uart_id);
user_pi_fc_event_handler_set(SOC_EVENT_UART_RX(uart_id), uart_rx_isr);
#ifdef PKG_USING_FREERTOS_WRAPPER
/* Set semaphore */
SemaphoreHandle_t shSemaphoreHandle =NULL; // FreeRTOS.h has a define for xSemaphoreHandle, so can't use that
shSemaphoreHandle = xSemaphoreCreateBinary();
configASSERT(shSemaphoreHandle);
xSemaphoreGive(shSemaphoreHandle);
uart_semaphores_rx[uart_id] = shSemaphoreHandle;
shSemaphoreHandle = xSemaphoreCreateBinary();
configASSERT(shSemaphoreHandle);
xSemaphoreGive(shSemaphoreHandle);
uart_semaphores_tx[uart_id] = shSemaphoreHandle;
#endif
#ifdef PKG_USING_FREERTOS_WRAPPER
/* Set handlers. */
pi_fc_event_handler_set(SOC_EVENT_UART_RX(uart_id), uart_rx_isr, uart_semaphores_rx[uart_id]);
pi_fc_event_handler_set(SOC_EVENT_UDMA_UART_TX(uart_id), NULL, uart_semaphores_tx[uart_id]);
#else
user_pi_fc_event_handler_set(SOC_EVENT_UART_RX(uart_id), uart_rx_isr);
#endif
/* Enable SOC events propagation to FC. */
hal_soc_eu_set_fc_mask(SOC_EVENT_UART_RX(uart_id));
hal_soc_eu_set_fc_mask(SOC_EVENT_UDMA_UART_TX(uart_id));
......@@ -87,7 +100,8 @@ uint16_t udma_uart_open (uint8_t uart_id, uint32_t xbaudrate) {
puart = (UdmaUart_t*)(UDMA_CH_ADDR_UART + uart_id * UDMA_CH_SIZE);
puart->uart_setup_b.div = (uint16_t)(5000000/xbaudrate);
puart->uart_setup_b.bits = 3; // 8-bits
// if (uart_id == 0) puart->uart_setup_b.rx_polling_en = 1;
// if (uart_id == 1)
puart->irq_en_b.rx_irq_en = 1;
puart->uart_setup_b.en_tx = 1;
puart->uart_setup_b.en_rx = 1;
......@@ -105,10 +119,15 @@ uint16_t udma_uart_open (uint8_t uart_id, uint32_t xbaudrate) {
return 0;
}
#ifdef PKG_USING_FREERTOS_WRAPPER
uint16_t udma_uart_writeraw(uint8_t uart_id, uint16_t write_len, uint8_t* write_buffer) {
UdmaUart_t* puart = (UdmaUart_t*)(UDMA_CH_ADDR_UART + uart_id * UDMA_CH_SIZE);
SemaphoreHandle_t shSemaphoreHandle = uart_semaphores_tx[uart_id];
if( xSemaphoreTake( shSemaphoreHandle, 1000000 ) != pdTRUE ) {
return 1;
}
while (puart->status_b.tx_busy) {
while (puart->status_b.tx_busy) { // ToDo: Why is this necessary? Thought the semaphore should have protected
}
puart->tx_saddr = (uint32_t)write_buffer;
......@@ -117,12 +136,14 @@ uint16_t udma_uart_writeraw(uint8_t uart_id, uint16_t write_len, uint8_t* write_
return 0;
}
#endif
uint16_t udma_uart_read(uint8_t uart_id, uint16_t read_len, uint8_t* read_buffer) {
uint16_t ret = 0;
uint8_t last_char = 0;
UdmaUart_t* puart = (UdmaUart_t*)(UDMA_CH_ADDR_UART + uart_id * UDMA_CH_SIZE);
while ( (ret < (read_len - 2)) && (last_char != 0xd)) {
if (puart->valid_b.rx_data_valid == 1) {
last_char = (uint8_t)(puart->data_b.rx_data & 0xff);
......
......@@ -8,6 +8,7 @@
#
CONFIG_RT_NAME_MAX=8
# CONFIG_RT_USING_ARCH_DATA_TYPE is not set
# CONFIG_RT_USING_SMART is not set
# CONFIG_RT_USING_SMP is not set
CONFIG_RT_ALIGN_SIZE=4
# CONFIG_RT_THREAD_PRIORITY_8 is not set
......@@ -65,14 +66,17 @@ CONFIG_RT_USING_HEAP=y
#
CONFIG_RT_USING_DEVICE=y
# CONFIG_RT_USING_DEVICE_OPS is not set
# CONFIG_RT_USING_DM is not set
# CONFIG_RT_USING_INTERRUPT_INFO is not set
CONFIG_RT_USING_CONSOLE=y
CONFIG_RT_CONSOLEBUF_SIZE=128
CONFIG_RT_CONSOLE_DEVICE_NAME="uart1"
CONFIG_RT_VER_NUM=0x50000
# CONFIG_RT_USING_CACHE is not set
# CONFIG_ARCH_ARM_BOOTWITH_FLUSH_CACHE is not set
# CONFIG_ARCH_CPU_STACK_GROWS_UPWARD is not set
# CONFIG_RT_USING_CPU_FFS is not set
CONFIG_ARCH_RISCV=y
# CONFIG_ARCH_CPU_STACK_GROWS_UPWARD is not set
#
# RT-Thread Components
......@@ -104,6 +108,7 @@ CONFIG_FINSH_ARG_MAX=10
# Device Drivers
#
CONFIG_RT_USING_DEVICE_IPC=y
CONFIG_RT_UNAMED_PIPE_NUMBER=64
# CONFIG_RT_USING_SYSTEM_WORKQUEUE is not set
CONFIG_RT_USING_SERIAL=y
CONFIG_RT_USING_SERIAL_V1=y
......@@ -118,10 +123,14 @@ CONFIG_RT_SERIAL_RB_BUFSZ=64
CONFIG_RT_USING_PIN=y
# CONFIG_RT_USING_ADC is not set
# CONFIG_RT_USING_DAC is not set
# CONFIG_RT_USING_NULL is not set
# CONFIG_RT_USING_ZERO is not set
# CONFIG_RT_USING_RANDOM is not set
# CONFIG_RT_USING_PWM is not set
# CONFIG_RT_USING_MTD_NOR is not set
# CONFIG_RT_USING_MTD_NAND is not set
# CONFIG_RT_USING_PM is not set
# CONFIG_RT_USING_FDT is not set
# CONFIG_RT_USING_RTC is not set
# CONFIG_RT_USING_SDIO is not set
# CONFIG_RT_USING_SPI is not set
......@@ -129,10 +138,13 @@ CONFIG_RT_USING_PIN=y
# CONFIG_RT_USING_AUDIO is not set
# CONFIG_RT_USING_SENSOR is not set
# CONFIG_RT_USING_TOUCH is not set
# CONFIG_RT_USING_LCD is not set
# CONFIG_RT_USING_HWCRYPTO is not set
# CONFIG_RT_USING_PULSE_ENCODER is not set
# CONFIG_RT_USING_INPUT_CAPTURE is not set
# CONFIG_RT_USING_DEV_BUS is not set
# CONFIG_RT_USING_WIFI is not set
# CONFIG_RT_USING_VIRTIO is not set
#
# Using USB
......@@ -723,6 +735,7 @@ CONFIG_RT_LIBC_DEFAULT_TIMEZONE=8
# CONFIG_PKG_USING_SLCAN2RTT is not set
# CONFIG_PKG_USING_SOEM is not set
# CONFIG_PKG_USING_QPARAM is not set
# CONFIG_PKG_USING_CorevMCU_CLI is not set
#
# Arduino libraries
......@@ -743,10 +756,13 @@ CONFIG_RT_LIBC_DEFAULT_TIMEZONE=8
# CONFIG_PKG_USING_ARDUINO_CAPACITIVESENSOR is not set
# CONFIG_PKG_USING_ARDUINO_ADAFRUIT_ADXL375 is not set
# CONFIG_PKG_USING_ARDUINO_ADAFRUIT_VL53L0X is not set
# CONFIG_PKG_USING_ARDUINO_ADAFRUIT_VL53L1X is not set
# CONFIG_PKG_USING_ARDUINO_ADAFRUIT_SENSOR is not set
# CONFIG_PKG_USING_ARDUINO_ADAFRUIT_VL6180X is not set
# CONFIG_PKG_USING_ADAFRUIT_MAX31855 is not set
# CONFIG_PKG_USING_ARDUINO_ADAFRUIT_MAX31865 is not set
# CONFIG_PKG_USING_ARDUINO_ADAFRUIT_MAX31856 is not set
# CONFIG_PKG_USING_ARDUINO_ADAFRUIT_MAX6675 is not set
# CONFIG_PKG_USING_ARDUINO_ADAFRUIT_MLX90614 is not set
# CONFIG_PKG_USING_ARDUINO_ADAFRUIT_LSM9DS1 is not set
# CONFIG_PKG_USING_ARDUINO_ADAFRUIT_AHTX0 is not set
......@@ -952,4 +968,3 @@ CONFIG_BSP_USING_UART1=y
# Onboard System Settings
#
CONFIG_DEFAULT_SYSTEM_CLOCK=5000000u
CONFIG_configTOTAL_HEAP_SIZE="( unsigned int) (64 * 1024 )"
......@@ -13,6 +13,11 @@
#include <stdio.h>
#include <stdint.h>
#include "rtconfig.h"
#include "udma_uart_driver.h"
#include "stdlib.h"
/*Note:Bsp shell switch flag,do not modify*/
int irq_cli_flag = 1;
/*If add CorevMCU_CLI package,please put the code in example.c here*/
#define rtthread_task
static struct rt_thread test1_thread;
......@@ -25,30 +30,30 @@ static void test2_thread_entry(void* parameter);
void test_init(void)
{
rt_kprintf("Hello RT-Thread\r\n");
rt_kprintf("Hello RT-Thread!\r\n");
}
INIT_APP_EXPORT(test_init);
int main(void)
{
#ifndef rtthread_task
rt_thread_init(&test1_thread,
"test1",
test1_thread_entry,
RT_NULL,
&rt_test1_thread_stack[0],
sizeof(rt_test1_thread_stack),
6,
20);
rt_thread_init(&test1_thread,
"test1",
test1_thread_entry,
RT_NULL,
&rt_test1_thread_stack[0],
sizeof(rt_test1_thread_stack),
6,
20);
rt_thread_startup(&test1_thread);
rt_thread_startup(&test1_thread);
test2_thread = rt_thread_create( "test2",
test2_thread_entry,
RT_NULL,
512,
5,
20);
test2_thread = rt_thread_create( "test2",
test2_thread_entry,
RT_NULL,
512,
5,
20);
rt_thread_startup(test2_thread);
#endif
......@@ -58,16 +63,16 @@ static void test1_thread_entry(void* parameter)
{
while (1)
{
rt_kprintf("test1\r\n");
rt_thread_delay(500);
rt_kprintf("test1\r\n");
rt_thread_delay(500);
}
}
static void test2_thread_entry(void* parameter)
{
while (1)
{
while (1)
{
rt_kprintf("test2\r\n");
rt_thread_delay(500);
}
rt_thread_delay(500);
}
}
......@@ -39,12 +39,7 @@ menu "Onboard System Settings"
int "IDEFAULT_SYSTEM_CLOCK"
range 1 10000000
default 5000000u
config configTOTAL_HEAP_SIZE
string "!!Please remove the Double quotation marks in rtconfig.h"
default "( ( unsigned int) (64 * 1024 ) )"
endmenu
endmenu
/*
* Copyright (c) 2006-2019, RT-Thread Development Team
* Copyright (c) 2006-2022, RT-Thread Development Team
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2022-12-08 WangShun the first version
* 2022-12-08 WangShun the first version
* 2022-12-13 WangShun put the rt_system_heap_init in head
*/
#include <stdint.h>
......@@ -25,29 +26,30 @@ extern void rt_systick_config(void);
static rt_uint8_t rt_heap[RT_HEAP_SIZE];
void *rt_heap_begin_get(void)
{
return rt_heap;
return rt_heap;
}
void *rt_heap_end_get(void)
{
return rt_heap + RT_HEAP_SIZE;
return rt_heap + RT_HEAP_SIZE;
}
#endif
void rt_hw_board_init()
{
/* System Clock Update */
extern void system_init(void);
system_init();
/* System Tick Configuration */
rt_systick_config();
volatile uint32_t mtvec = 0;
__asm volatile( "csrr %0, mtvec" : "=r"( mtvec ) );
__asm volatile( "csrs mie, %0" :: "r"(0x880) );
/*Initialize heap first, or system_ Semaphore in init cannot be created*/
#if defined(RT_USING_USER_MAIN) && defined(RT_USING_HEAP)
rt_system_heap_init(rt_heap_begin_get(), rt_heap_end_get());
#endif
/* System Clock Update */
extern void system_init(void);
system_init();
/* System Tick Configuration */
rt_systick_config();
volatile uint32_t mtvec = 0;
__asm volatile( "csrr %0, mtvec" : "=r"( mtvec ) );
__asm volatile( "csrs mie, %0" :: "r"(0x880) );
/* USART driver initialization is open by default */
#ifdef RT_USING_SERIAL
rt_hw_usart_init();
......
......@@ -45,7 +45,7 @@ SECTIONS
__stack_size = DEFINED(__stack_size) ? __stack_size : 0x800;
PROVIDE(__stack_size = __stack_size);
/* __heap_size = DEFINED(__heap_size) ? __heap_size : 0x400; */
__heap_size = 0x10000;
__heap_size = 0x06000;
PROVIDE(__heap_size = __heap_size);
/*
......
......@@ -184,4 +184,13 @@ BSP支持RT-Thread的Finsh组件,输入version可以查看rt-thread的版本
5.点击debug开始调试
![run](figures/run.png)
\ No newline at end of file
![run](figures/run.png)
### 4.CLI组件
​ OPENHW提供的FreeRTOS工程支持一个CLI组件用于测试,再使用RT-Thread时为了确保兼容原有的CLI,所以将原来的CLI做成了独立的软件包,同时该软件包自动开启了FreeRTOS兼容层,所以该软件包既可以支持原有的CLI组件,同时依旧可以使用FreeRTOS的接口函数。
#### 4.1使用方法
​ 在ENV工具中使用menuconfig配置开启CorevMCU_CL软件包,将example.c中的示例代码放到main.c提示的地方即可。
......@@ -176,4 +176,12 @@ Cancle`Start OpenOCD locally`,the configuration parameters are as follows:![de
5.Click debug to start debugging:
![run](figures/run.png)
\ No newline at end of file
![run](figures/run.png)
### 4.CLI components
​ The FreeRTOS project provided by OPENHW supports a CLI component for testing. To ensure compatibility with the original CLI when using RT Thread again, the original CLI is made into an independent software package. At the same time, the software package automatically opens the FreeRTOS compatibility layer, so the software package can support the original CLI components and still use FreeRTOS interface functions.
#### 4.1使用方法
​ Enable CorevMCU with menuconfig configuration in ENV tool_ CL software package, just put the sample code in example. c at the prompt of main. c.
\ No newline at end of file
......@@ -69,6 +69,7 @@
/* Device Drivers */
#define RT_USING_DEVICE_IPC
#define RT_UNAMED_PIPE_NUMBER 64
#define RT_USING_SERIAL
#define RT_USING_SERIAL_V1
#define RT_SERIAL_RB_BUFSZ 64
......@@ -234,6 +235,5 @@
/* Onboard System Settings */
#define DEFAULT_SYSTEM_CLOCK 5000000u
#define configTOTAL_HEAP_SIZE ( unsigned int) (64 * 1024 )
#endif
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册