risc-v/k230: add IPI support to speed up RPTUN/RPMSG

This patch adds inter-processor interrupt support using K230 mailbox
device to improve the RPMsg efficiency. The polling logic has been
dropped.

Major changes:

- in arch/risc-v/include/k230:
  - irq.h          add IRQ for IPI devices
- in arch/risc-v/src/k230:
  - Kconfig        add IPI related config, increase polling delay
  - Make.defs      add k230_ipi.c to CHIP_SRCS
  - k230_hart.c    fix typo, add notes of zero MISA reading w/ NUTTSBI
  - k230_irq.c     use K230_PLIC_IRQS as ext IRQ limit to support IPI
  - k230_rptun.c   use IPI instead of polling
- in boards/risc-v/k230/canmv230/configs
  - master         enable IPI support
  - remote         enable IPI, TMPFS, RPMSGFS etc

New additions:

- in arch/risc-v/src/k230:
  - k230_ipi.h     add K230 IPI related defintions
  - k230_ipi.c     add K230 IPI driver

Signed-off-by: Yanfeng Liu <yfliu2008@qq.com>
This commit is contained in:
Yanfeng Liu 2024-02-20 18:07:03 +08:00 committed by Xiang Xiao
parent 5452f013df
commit 4456b2db29
10 changed files with 466 additions and 171 deletions

View File

@ -32,17 +32,21 @@
/* Map RISC-V exception code to NuttX IRQ */
#ifndef CONFIG_BUILD_KERNEL
# define K230_IRQ_TIMER (RISCV_IRQ_MTIMER)
# define K230_IRQ_UART0 (RISCV_IRQ_MEXT + 16)
# define K230_IRQ_UART3 (RISCV_IRQ_MEXT + 19)
# define K230_IRQ_TIMER (RISCV_IRQ_MTIMER)
# define K230_IRQ_UART0 (RISCV_IRQ_MEXT + 16)
#else
# define K230_IRQ_TIMER (RISCV_IRQ_STIMER)
# define K230_IRQ_UART0 (RISCV_IRQ_SEXT + 16)
# define K230_IRQ_UART3 (RISCV_IRQ_SEXT + 19)
# define K230_IRQ_TIMER (RISCV_IRQ_STIMER)
# define K230_IRQ_UART0 (RISCV_IRQ_SEXT + 16)
#endif
#define K230_IRQ_UART3 (K230_IRQ_UART0 + 3)
#define K230_IRQ_IPI0 (K230_IRQ_UART0 + 93)
#define K230_IRQ_IPI3 (K230_IRQ_IPI0 + 3)
#define K230_PLIC_IRQS 208
/* NR_IRQS is needed by NuttX */
#define NR_IRQS (K230_IRQ_UART3 + 1)
#define NR_IRQS (K230_IRQ_IPI3 + 1)
#endif /* __ARCH_RISCV_INCLUDE_K230_IRQ_H */

View File

@ -22,22 +22,25 @@ config K230_RPTUN_SHM_SIZE
---help---
RPTUN shared memory size in bytes.
config K230_RPTUN_IPI
bool "use IPI for RPTUN"
default n
depends on K230_IPI
config K230_RPTUN_IPI_DEV
int "IPI device num for RPTUN purpose"
default 0
---help---
Use Inter-Processor interruption to improve efficiency.
Not ready yet.
config K230_RPTUN_WORK_DELAY
int "RPTUN work delay"
default 50
depends on !K230_RPTUN_IPI
---help---
Ticks for polling RPTUN. Polling doesn't need IPI.
Choose the IPI device for RPTUN purpose, should be within 0..3
endif # RPTUN
config K230_IPI
bool "Enable K230 IPI driver"
default y if RPTUN
default n
if K230_IPI
config K230_IPI_RESET_UPON_INIT
bool "Reset K230 mailbox device upon initialization"
default n
---help---
Reset whole K230 mailbox device upon k230_ipi_init.
endif # K230_IPI

View File

@ -39,5 +39,5 @@ CHIP_CSRCS += k230_userspace.c
endif
ifeq ($(CONFIG_RPTUN),y)
CHIP_CSRCS += k230_rptun.c
CHIP_CSRCS += k230_rptun.c k230_ipi.c
endif

View File

@ -127,10 +127,12 @@ static void k230_hart_cleanup(void)
void k230_hart_init(void)
{
#define MISA_VECTOR_BIT ('V'-'A')
#define MISA_VECOTR_MASK (1 << MISA_VECTOR_BIT)
#define MISA_VECTOR_BIT ('V'-'A')
#define MISA_VECTOR_MASK (1 << MISA_VECTOR_BIT)
g_big = (READ_CSR(CSR_MISA) & MISA_VECOTR_MASK);
/* When called from sbi_start(), MISA is 0 somehow. */
g_big = (READ_CSR(CSR_MISA) & MISA_VECTOR_MASK);
k230_hart_cleanup();
@ -147,8 +149,8 @@ void k230_hart_init(void)
}
/****************************************************************************
* Name: k230_hart_on_big()
* Description: returns true if running on big core
* Name: k230_hart_is_big()
* Description: returns true if running on big core.
****************************************************************************/
bool k230_hart_is_big(void)

View File

@ -0,0 +1,207 @@
/****************************************************************************
* arch/risc-v/src/k230/k230_ipi.c
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you 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.
*
****************************************************************************/
#if !defined(CONFIG_BUILD_KERNEL) || defined(CONFIG_NUTTSBI)
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdint.h>
#include <assert.h>
#include <debug.h>
#include <nuttx/arch.h>
#include <nuttx/irq.h>
#include <nuttx/mutex.h>
#include "riscv_internal.h"
#include "chip.h"
#include "k230_ipi.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define K230_IPI_IRQ(n) (K230_IRQ_IPI0 + n)
#define K230_SOC_RESET_ADDR 0x91101020ul
#define K230_MBOX_RESET_BIT 17
#define K230_RESET_DELAY_US 100
/****************************************************************************
* Private Types
****************************************************************************/
struct k230_ipi_entry_s
{
uint16_t role; /* role of this node */
uint16_t mask; /* allowed line masks */
ipi_callback_t cbfn; /* the callback function */
void *args; /* argument for callback */
};
/****************************************************************************
* Private Variables
****************************************************************************/
static mutex_t g_ipi_lock = NXMUTEX_INITIALIZER;
static struct k230_ipi_entry_s g_ipi_confs[K230_IPI_DEVN_MAX + 1] =
{
0
};
/****************************************************************************
* Private Functions
****************************************************************************/
static int k230_ipi_isr(int irq, void *context, void *args)
{
uint32_t devn = (uintptr_t)args;
bool remote = (g_ipi_confs[devn].role == IPI_ROLE_REMOTE);
uintptr_t regc = remote ? K230_IPI_M2R_INTCLR(devn):
K230_IPI_R2M_INTCLR(devn);
uintptr_t regs = remote ? K230_IPI_M2R_INTSTS(devn):
K230_IPI_R2M_INTSTS(devn);
uint32_t stat = getreg32(regs);
for (uint32_t i = 0; i <= K230_IPI_LINE_MAX; i++)
{
if (stat & (3 << (i << 1)))
{
g_ipi_confs[devn].cbfn(IPI_COMB(devn, i), g_ipi_confs[devn].args);
putreg32(i, regc);
}
}
return 0;
}
/****************************************************************************
* Public Functions
****************************************************************************/
int k230_ipi_init(uintptr_t devn, uint16_t mask, uint16_t role,
ipi_callback_t ipcb, void *args)
{
int ret = -EBUSY;
bool master = (role == IPI_ROLE_MASTER);
#ifdef CONFIG_K230_IPI_RESET_ON_INIT
static bool mbox_reset = false;
#endif
DEBUGASSERT(devn <= K230_IPI_DEVN_MAX);
DEBUGASSERT(mask);
DEBUGASSERT(ipcb);
DEBUGASSERT(role == IPI_ROLE_MASTER || role == IPI_ROLE_REMOTE);
nxmutex_lock(&g_ipi_lock);
if (0 == g_ipi_confs[devn].role)
{
g_ipi_confs[devn].mask = mask;
g_ipi_confs[devn].cbfn = ipcb;
g_ipi_confs[devn].args = args;
g_ipi_confs[devn].role = role;
ret = 0;
}
nxmutex_unlock(&g_ipi_lock);
if (0 == ret)
{
#ifdef CONFIG_K230_IPI_RESET_UPON_INIT
/* Reset whole mailbox device */
if (master && !mbox_reset)
{
uint32_t val = getreg32(K230_SOC_RESET_ADDR);
val &= ~(1 << K230_MBOX_RESET_BIT);
putreg32(val, K230_SOC_RESET_ADDR);
up_udelay(K230_RESET_DELAY_US);
val |= (1 << K230_MBOX_RESET_BIT);
putreg32(val, K230_SOC_RESET_ADDR);
up_udelay(K230_RESET_DELAY_US);
mbox_reset = true;
sinfo("mbox reset @ %lx\n", K230_SOC_RESET_ADDR);
}
#endif
/* Attach and enable the IRQ */
ret = irq_attach(K230_IPI_IRQ(devn), k230_ipi_isr, (void *)devn);
up_enable_irq(K230_IPI_IRQ(devn));
/* enable IPI device like RTT/Linux does */
uint32_t v = (master ? 3u : 1u) | (mask << 16);
putreg32(v, K230_IPI_R2M_INTEN(devn));
putreg32(v, K230_IPI_M2R_INTEN(devn));
}
sinfo("devn=%ld,lmsk=%x,role=%c,r2me=%x,m2re=%x,ret=%d\n",
devn, mask, master ? 'M' : 'R',
getreg32(K230_IPI_R2M_INTEN(devn)),
getreg32(K230_IPI_M2R_INTEN(devn)), ret);
return ret;
}
void k230_ipi_notify(uint8_t devn, uint8_t line)
{
DEBUGASSERT(devn <= K230_IPI_DEVN_MAX);
DEBUGASSERT(line <= K230_IPI_LINE_MAX);
nxmutex_lock(&g_ipi_lock);
uint16_t role = g_ipi_confs[devn].role;
uint16_t mask = g_ipi_confs[devn].mask;
nxmutex_unlock(&g_ipi_lock);
if ((1 << line) & mask)
{
bool master = (role == IPI_ROLE_MASTER);
uintptr_t regs = master ? K230_IPI_M2R_INTSET(devn):
K230_IPI_R2M_INTSET(devn);
putreg32(line, regs);
}
}
void k230_ipi_finish(uint8_t devn, uint16_t mask)
{
DEBUGASSERT(devn <= K230_IPI_DEVN_MAX);
DEBUGASSERT(g_ipi_confs[devn].mask == mask);
uint16_t role = g_ipi_confs[devn].role;
DEBUGASSERT(role == IPI_ROLE_MASTER || role == IPI_ROLE_MASTER);
/* reset device and disable interrupts */
bool remote = (role == IPI_ROLE_REMOTE);
putreg32(2u | mask << 16, remote ? K230_IPI_M2R_INTEN(devn):
K230_IPI_R2M_INTEN(devn));
up_disable_irq(K230_IPI_IRQ(devn));
irq_detach(K230_IPI_IRQ(devn));
nxmutex_lock(&g_ipi_lock);
memset(g_ipi_confs + devn, 0, sizeof(g_ipi_confs[0]));
nxmutex_unlock(&g_ipi_lock);
sinfo("devn=%d,mask=%x\n", devn, mask);
}
#endif /* !defined(CONFIG_BUILD_KERNEL) || defined(CONFIG_NUTTSBI) */

View File

@ -0,0 +1,155 @@
/****************************************************************************
* arch/risc-v/src/k230/k230_ipi.h
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you 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 __ARCH_RISCV_SRC_K230_K230_IPI_H
#define __ARCH_RISCV_SRC_K230_K230_IPI_H
#ifndef __ASSEMBLY__
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/****************************************************************************
* Included Files
****************************************************************************/
#include <stdint.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* K230 has 4 IPI devices, each has 10 registers with 32 bit width. */
#define K230_IPI_DEVN_MAX 3
#define K230_IPI_LINE_MAX 15
#define K230_IPI_BASE(n) (0x91104000ul + n * 0x28)
/* The IPI registers are organized in two directions (M2R or R2M), there are
* 5 registers for each direction, with 16 IPI lines for each node. Though
* K230 names the two directions as CPU2DSP or DSP2CPU, we use M2R or R2M.
*
* The Status register has 2-bit counter for each IPI line.
* The Set/Clear registers accepts values from 0..15 for 16 IPI lines.
* Setting a line increases its counter by 1, clearing the line decreases it
* by 1. The Error register further uses the high/low 16 bits to flag the
* over/under-run situations of counters.
*
* The Enable register's bit 16..31 are for line enable, bit 0 is for device
* interrupt enable, bit 1 for resetting line counters to zero.
*
* Also note the directions M2R/R2M are tied to the CPU cores: little core is
* M and big core is R. So we can also select the direction based on current
* core, but due to that we can't read correct MISA register value with NSBI
* booting environment, that method is not used and the role is passed in.
*/
#define K230_IPI_M2R_INTEN(n) (K230_IPI_BASE(n) + 0)
#define K230_IPI_M2R_INTSET(n) (K230_IPI_BASE(n) + 4)
#define K230_IPI_M2R_INTCLR(n) (K230_IPI_BASE(n) + 8)
#define K230_IPI_M2R_INTSTS(n) (K230_IPI_BASE(n) + 12)
#define K230_IPI_M2R_INTERR(n) (K230_IPI_BASE(n) + 16)
#define K230_IPI_R2M_INTEN(n) (K230_IPI_BASE(n) + 20)
#define K230_IPI_R2M_INTSET(n) (K230_IPI_BASE(n) + 24)
#define K230_IPI_R2M_INTCLR(n) (K230_IPI_BASE(n) + 28)
#define K230_IPI_R2M_INTSTS(n) (K230_IPI_BASE(n) + 32)
#define K230_IPI_R2M_INTERR(n) (K230_IPI_BASE(n) + 36)
#define IPI_ROLE_MASTER 1 /* master role, for little core */
#define IPI_ROLE_REMOTE 2 /* remote role, for big core */
/* Tools for handling uint16_t device and line id combo */
#define IPI_DEVN(x) ((x & 0xFF00) >> 8)
#define IPI_LINE(x) (x & 0xFF)
#define IPI_COMB(d,l) ((d << 8) | (l & 0xFF))
/****************************************************************************
* Public types
****************************************************************************/
/****************************************************************************
* Name: ipi_callback_t
* Description:
* Callback for a particular IPI line. Should be brief as maybe running in
* ISR context.
* Params;
* comb: combined IPI dev and line ids, see IPI_COMB above
* args: the args used in subscription
****************************************************************************/
typedef void (*ipi_callback_t)(uint16_t comb, void *args);
/****************************************************************************
* Public functions
****************************************************************************/
/****************************************************************************
* Name: k230_ipi_init
* Description:
* Initialzie IPI device with receiving and sending line masks.
* Params:
* devn: IPI device number in 0..K230_IPI_DEVN_MAX
* mask: allowed lines mask for notifying peers or receiving notifications
* role: IPI role of this node (IPI_ROLE_MASTER or IPI_ROLE_REMOTE)
* ipcb: callback for incoming IPI notifications
* args: last parameter for the callback.
* Returns:
* 0 on success, or negative value on errors
****************************************************************************/
int k230_ipi_init(uintptr_t devn, uint16_t mask, uint16_t role,
ipi_callback_t ipcb, void *args);
/****************************************************************************
* Name: k230_ipi_notify
* Description:
* Notify peers via IPI.
* Params:
* devn: device id in 0..K230_IPI_DEVN_MAX
* line: line id in 0..K230_IPI_LINE_MAX
****************************************************************************/
void k230_ipi_notify(uint8_t devn, uint8_t line);
/****************************************************************************
* Name: k230_ipi_finish
* Description:
* Deinitializes IPI device
* Params:
* devn: IPI device number initialized previously.
* mask: line masks iniitialied previously.
****************************************************************************/
void k230_ipi_finish(uint8_t devn, uint16_t mask);
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_RISCV_SRC_K230_K230_IPI_H */

View File

@ -128,7 +128,7 @@ void up_disable_irq(int irq)
/* Clear enable bit for the irq */
if (0 <= extirq && extirq <= 63)
if (0 <= extirq && extirq <= K230_PLIC_IRQS)
{
modifyreg32(K230_PLIC_ENABLE1 + (4 * (extirq / 32)),
1 << (extirq % 32), 0);
@ -172,7 +172,7 @@ void up_enable_irq(int irq)
/* Enable the irq in PLIC */
if (0 <= extirq && extirq <= 63)
if (0 <= extirq && extirq < K230_PLIC_IRQS)
{
modifyreg32(K230_PLIC_ENABLE1 + (4 * (extirq / 32)),
0, 1 << (extirq % 32));

View File

@ -50,22 +50,17 @@
#include <arch/board/board.h>
#include "hardware/k230_memorymap.h"
#include "k230_hart.h"
#include "riscv_internal.h"
#include "k230_hart.h"
#include "k230_ipi.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#ifdef CONFIG_DEBUG_ERROR
# define rperr _err
# define rpwarn _warn
# define rpinfo _info
#else
# define rperr(x...)
# define rpwarn(x...)
# define rpinfo(x...)
#endif
#define rpinfo rpmsginfo
#define rpwarn rpmsgwarn
#define rperr rpmsgerr
/* Vring config parameters taken from nrf53_rptun */
@ -82,21 +77,38 @@
#define VRING_SHMEM_END (VRING_SHMEM + CONFIG_K230_RPTUN_SHM_SIZE)
/****************************************************************************
* Private Types
****************************************************************************/
/* Design notes:
*
* Though there are 16 IPI lines per K230 IPI device, we use only 1 IPI
* line for each core to notify the peer. Later we will see if more lines
* are really needed.
*
* For configurations, master and remote builds should use same IPI device
* defined by CONFIG_K230_RPTUN_IPI_DEVN otherwise the IPI notifications
* won't reach each other.
*/
#define RPTUN_IPI_DEVN CONFIG_K230_RPTUN_IPI_DEV
#define RPTUN_IPI_LINE 0
#define RPTUN_IPI_LINE_MASK (1 << RPTUN_IPI_LINE)
#if RPTUN_IPI_DEVN < 0 || RPTUN_IPI_DEVN > K230_IPI_DEVN_MAX
#error Invalid K230_RPTUN_IPI_DEV number
#endif
#ifdef CONFIG_K230_RPTUN_MASTER
#define RPTUN_IPI_ROLE IPI_ROLE_MASTER
#else
#define RPTUN_IPI_ROLE IPI_ROLE_REMOTE
#endif
/****************************************************************************
* Use polling now as IPI is not ready initially.
* Private Types
****************************************************************************/
struct k230_rptun_shmem_s
{
volatile uintptr_t base;
#ifndef CONFIG_K230_RPTUN_IPI
volatile uint32_t seq_rmt; /* seqno for remote to watch */
volatile uint32_t seq_mst; /* seqno for master to watch */
#endif
struct rptun_rsc_s rsc;
};
@ -109,10 +121,6 @@ struct k230_rptun_dev_s
struct k230_rptun_shmem_s *shmem;
struct simple_addrenv_s addrenv[VRINGS];
char peername[RPMSG_NAME_SIZE + 1];
#ifndef CONFIG_K230_RPTUN_IPI
volatile uint32_t seq;
struct work_s work;
#endif
};
#define as_k230_rptun_dev(d) container_of(d, struct k230_rptun_dev_s, rptun)
@ -129,10 +137,7 @@ static int rp_start(struct rptun_dev_s *dev);
static int rp_stop(struct rptun_dev_s *dev);
static int rp_notify(struct rptun_dev_s *dev, uint32_t notifyid);
static int rp_set_callback(struct rptun_dev_s *, rptun_callback_t, void *);
#ifndef CONFIG_K230_RPTUN_IPI
static void k230_rptun_work(void *arg);
#endif /* CONFIG_K230_RPTUN_IPI */
static void k230_rptun_callback(uint16_t comb, void *args);
/****************************************************************************
* Private Data
@ -156,29 +161,16 @@ static const struct rptun_ops_s g_k230_rptun_ops =
static struct k230_rptun_dev_s g_rptun_dev;
#ifdef CONFIG_K230_RPTUN_IPI
static sem_t g_rptun_rx_sig = SEM_INITIALIZER(0);
#endif
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: rp_get_cpuname
****************************************************************************/
static const char *rp_get_cpuname(struct rptun_dev_s *dev)
{
struct k230_rptun_dev_s *priv = as_k230_rptun_dev(dev);
return priv->peername;
}
/****************************************************************************
* Name: rp_get_resource
****************************************************************************/
static struct rptun_rsc_s *rp_get_resource(struct rptun_dev_s *dev)
{
struct k230_rptun_dev_s *priv = as_k230_rptun_dev(dev);
@ -223,7 +215,7 @@ static struct rptun_rsc_s *rp_get_resource(struct rptun_dev_s *dev)
priv->shmem->base = (uintptr_t)priv->shmem;
rpinfo("shmem:%p, dev:%p\n", priv->shmem->base, dev);
rpinfo("shmem:%lx, dev:%p\n", priv->shmem->base, dev);
}
else
{
@ -241,71 +233,43 @@ static struct rptun_rsc_s *rp_get_resource(struct rptun_dev_s *dev)
return &priv->shmem->rsc;
}
/****************************************************************************
* Name: rp_is_autostart
****************************************************************************/
static bool rp_is_autostart(struct rptun_dev_s *dev)
{
return true;
}
/****************************************************************************
* Name: rp_is_master
****************************************************************************/
static bool rp_is_master(struct rptun_dev_s *dev)
{
struct k230_rptun_dev_s *priv = as_k230_rptun_dev(dev);
return priv->master;
}
/****************************************************************************
* Name: rp_start
****************************************************************************/
static int rp_start(struct rptun_dev_s *dev)
{
rpinfo("%p\n", dev);
#ifdef CONFIG_K230_RPTUN_MASTER
k230_hart_big_boot(0x7000000);
#endif
return 0;
}
/****************************************************************************
* Name: rp_stop
****************************************************************************/
static int rp_stop(struct rptun_dev_s *dev)
{
rpinfo("%p\n", dev);
#ifdef CONFIG_K230_RPTUN_MASTER
k230_hart_big_stop();
#endif
return 0;
}
/****************************************************************************
* Name: rp_notify
****************************************************************************/
static int rp_notify(struct rptun_dev_s *dev, uint32_t vqid)
{
#ifdef CONFIG_K230_RPTUN_IPI
k230_ipi_signal(RPTUN_IPI_NOTIFY_RX);
#else
struct k230_rptun_dev_s *priv = as_k230_rptun_dev(dev);
if (priv->master)
{
priv->shmem->seq_rmt++;
}
else
{
priv->shmem->seq_mst++;
}
#endif /* CONFIG_K230_RPTUN_IPI */
UNUSED(dev);
UNUSED(vqid);
k230_ipi_notify(RPTUN_IPI_DEVN, RPTUN_IPI_LINE);
return 0;
}
/****************************************************************************
* Name: rp_reg_cb
****************************************************************************/
static int rp_set_callback(struct rptun_dev_s *dev, rptun_callback_t cb,
void *arg)
{
@ -313,44 +277,16 @@ static int rp_set_callback(struct rptun_dev_s *dev, rptun_callback_t cb,
priv->callback = cb;
priv->arg = arg;
rpinfo("%p, arg:%p\n", cb, arg);
return 0;
}
#ifndef CONFIG_K230_RPTUN_IPI
static void k230_rptun_work(void *arg)
static void k230_rptun_callback(uint16_t comb, void *args)
{
struct k230_rptun_dev_s *dev = arg;
bool should_notify = false;
if (dev->shmem != NULL)
{
if (dev->master && dev->seq != dev->shmem->seq_mst)
{
dev->seq = dev->shmem->seq_mst;
should_notify = true;
}
else if (!dev->master && dev->seq != dev->shmem->seq_rmt)
{
dev->seq = dev->shmem->seq_rmt;
should_notify = true;
}
if (should_notify && dev->callback != NULL)
{
dev->callback(dev->arg, RPTUN_NOTIFY_ALL);
}
}
work_queue(HPWORK, &dev->work, k230_rptun_work, dev,
CONFIG_K230_RPTUN_WORK_DELAY);
UNUSED(comb);
struct k230_rptun_dev_s *dev = args;
if (dev->callback) dev->callback(dev->arg, RPTUN_NOTIFY_ALL);
}
#endif /* !CONFIG_K230_RPTUN_IPI */
/****************************************************************************
* Public Functions
****************************************************************************/
@ -364,20 +300,19 @@ int k230_rptun_init(const char *peername)
/* master is responsible for initializing shmem */
memset((void *)SHMEM, 0, SHMEM_SIZE);
rpinfo("\ncleared %d @ %p\n", SHMEM_SIZE, SHMEM);
rpinfo("cleared %ld @ %p\n", SHMEM_SIZE, SHMEM);
dev->master = true;
#else
dev->master = false;
#endif
#ifdef CONFIG_K230_RPTUN_IPI
k230_ipi_init();
#ifdef CONFIG_K230_RPTUN_MASTER
k230_rptun_ipi_master(dev);
#else
k230_rptun_ipi_remote(dev);
#endif
#endif /* CONFIG_K230_RPTUN_IPI */
ret = k230_ipi_init(RPTUN_IPI_DEVN, RPTUN_IPI_LINE_MASK, RPTUN_IPI_ROLE,
k230_rptun_callback, dev);
if (ret < 0)
{
rperr("k230_ipi_init failed %d\n", ret);
goto ipierr;
}
/* Configure device */
@ -387,26 +322,15 @@ int k230_rptun_init(const char *peername)
ret = rptun_initialize(&dev->rptun);
if (ret < 0)
{
rperr("ERROR: rptun_initialize failed %d!\n", ret);
rperr("rptun_initialize failed %d!\n", ret);
goto errout;
}
#ifdef CONFIG_K230_RPTUN_IPI
/* Create rptun RX thread */
ret = kthread_create("k230-rptun", CONFIG_RPTUN_PRIORITY,
CONFIG_RPTUN_STACKSIZE, k230_rptun_thread, NULL);
#else
/* Kick off work */
ret = work_queue(HPWORK, &dev->work, k230_rptun_work, dev, 0);
#endif
if (ret < 0)
{
rperr("ERROR: kthread_create or work_queue failed %d\n", ret);
}
return 0;
errout:
k230_ipi_finish(RPTUN_IPI_DEVN, RPTUN_IPI_LINE_MASK);
ipierr:
return ret;
}

View File

@ -45,11 +45,10 @@ extern "C"
/****************************************************************************
* Name: k230_rptun_init
*
* Description: initializes K230 RPTUN device.
*
* Description: initializes a K230 RPTUN device.
* Parameters:
* peername: the name of the peer that this RPTUN links to
* Returns: OK on success, or negated number on error
*
****************************************************************************/
int k230_rptun_init(const char *peername);

View File

@ -31,7 +31,6 @@ CONFIG_ARCH_USE_MMU=y
CONFIG_ARCH_USE_MPU=y
CONFIG_ARCH_USE_S_MODE=y
CONFIG_BINFMT_ELF_EXECUTABLE=y
CONFIG_BLK_RPMSG=y
CONFIG_BOARD_LATE_INITIALIZE=y
CONFIG_BOARD_LOOPSPERMSEC=6366
CONFIG_BUILD_KERNEL=y
@ -42,6 +41,8 @@ CONFIG_DEV_ZERO=y
CONFIG_ELF=y
CONFIG_FS_PROCFS=y
CONFIG_FS_ROMFS=y
CONFIG_FS_RPMSGFS=y
CONFIG_FS_TMPFS=y
CONFIG_IDLETHREAD_STACKSIZE=3072
CONFIG_INIT_FILEPATH="/system/bin/init"
CONFIG_INIT_MOUNT=y
@ -71,6 +72,7 @@ CONFIG_RAM_SIZE=16777216
CONFIG_RAM_START=0x7000000
CONFIG_RAW_BINARY=y
CONFIG_READLINE_CMD_HISTORY=y
CONFIG_RPMSG_PING=y
CONFIG_RPMSG_UART=y
CONFIG_RPMSG_UART_CONSOLE=y
CONFIG_RPTUN=y
@ -85,5 +87,4 @@ CONFIG_START_YEAR=2024
CONFIG_SYMTAB_ORDEREDBYNAME=y
CONFIG_SYSTEM_NSH=y
CONFIG_SYSTEM_NSH_PROGNAME="init"
CONFIG_TESTING_GETPRIME=y
CONFIG_USEC_PER_TICK=1000