Spike

Table of Contents

1. Spike

基于 https://github.com/riscv/riscv-isa-sim.git, master 分支, commit: 1cfffe

1.1. interpreter

spike 和 qemu 类似, 但它不像 QEMU TCG 那样执行二进制翻译: 它通过一个 interpreter 在 host 上执行 riscv 指令

interpreter 的核心是一个 loop:

  1. fetch

    通过虚拟的 mmu 来执行

  2. decode

    spike 并没有像 qemu/objdump/gdb 一样使用 binutils 来解析指令, 但也是用的类似的机制: 根据每条指令的 mask 和 match 来匹配二进制指令

  3. execute

    由于 spike 不需要进行二进制翻译, 所以指令执行通过一个简单的回调即可, 例如 rv64i_addi 函数用来执行 addi 指令

spike 通过 DECLARE_INSN 完成 decode 和 execute 所需的相关信息 (mask, match, callback) 的注册

1.1.1. register

spike 通过 riscv.mk.in 和 encoding.h 实现了和 opcodes 类似的功能.

riscv.mk.in 是 automake 的输入, 做为 Makefile 的模板. 指令列表定义在这里.

riscv_insn_ext_i = \
    add \
    addi \
    addiw \
    addw \
    and \
    andi \
    auipc \
    beq \
    bge \
    bgeu \
    ...

riscv_insn_list = \
    $(riscv_insn_ext_a) \
    $(riscv_insn_ext_c) \
    $(riscv_insn_ext_i) \
    ...

insn_list.h: $(src_dir)/riscv/riscv.mk.in
    for insn in $(foreach insn,$(riscv_insn_list),$(subst .,_,$(insn))) ; do \
        printf 'DEFINE_INSN(%s)\n' "$${insn}" ; \
    done > [email protected]
    mv [email protected] $@

make 时生成的 insn_list.h:

...
DEFINE_INSN(addi)
DEFINE_INSN(addiw)
...

使用 insn_list.h 完成指令的注册:

void processor_t::register_base_instructions() {
#define DECLARE_INSN(name, match, mask)                       \
    insn_bits_t name##_match = (match), name##_mask = (mask); \
    bool name##_supported = true;

#include "encoding.h"
#undef DECLARE_INSN

#define DEFINE_INSN(name)                                          \
    extern reg_t rv32i_##name(processor_t*, insn_t, reg_t);        \
    extern reg_t rv64i_##name(processor_t*, insn_t, reg_t);        \
    extern reg_t rv32e_##name(processor_t*, insn_t, reg_t);        \
    extern reg_t rv64e_##name(processor_t*, insn_t, reg_t);        \
    register_insn((insn_desc_t){                                   \
        name##_supported, name##_match, name##_mask, rv32i_##name, \
        rv64i_##name, rv32e_##name, rv64e_##name});
#include "insn_list.h"
#undef DEFINE_INSN
    // ...
}

void processor_t::register_insn(insn_desc_t desc) {
    instructions.push_back(desc);
}

其中 DEFINE_INSN 需要的 xxx_supported, xxx_match, xxx_mask 定义在 encoding.h 中

// ...
#define MATCH_ADDI 0x13
#define MASK_ADDI  0x707f
// ...
DECLARE_INSN(addi, MATCH_ADDI, MASK_ADDI)
// ...

DEFINE_INSN 还需要 rv64i_xxx 等函数, 它们定义在 build/xxx.cc 中, 但这个文件是编译时生成的

$(riscv_gen_srcs): %.cc: insns/%.h insn_template.cc
    sed 's/NAME/$(subst .cc,,$@)/' $(src_dir)/riscv/insn_template.cc | sed 's/OPCODE/$(call get_opcode,$(src_dir)/riscv/encoding.h,$(subst .cc,,$@))/' > $@

即 make 进会根据 riscv_insn_list 找到 insns 下的 xxx.h, 然后根据 riscv/insn_template.cc 生成 xxx.cc, 里面会 rv64i_xxx 的定义

1.1.2. init

int main(int argc, char** argv)
  //
  sim_t s(&cfg, halted,
      mems, plugin_devices, htif_args, dm_config, log_path, dtb_enabled, dtb_file, cmd_file);
    for (size_t i = 0; i < cfg->nprocs(); i++):
      procs[i] = new processor_t(&isa, cfg->varch(), this, cfg->hartids()[i], halted, log_file.get(), sout_);
        register_base_instructions();
        mmu = new mmu_t(sim, this);
        for (auto e : isa->get_extensions()) register_extension(e.second);
        reset();

其中 reset 会把 target pc 设置为 DEFAULT_RSTVEC (0x00001000), 这是 target 指令的首地址, 位于 bootrom

1.1.3. execute

1.1.3.1. host

spike 执行时分为 host 和 target 两部分, host 和 target 可以用不同的 thread 来实现, 但默认配置下它们是通过 coroutine 实现的 (swapcontext)

// spike.cc
int main(int argc, char** argv)
  //
  sim_t s(&cfg, halted,
      mems, plugin_devices, htif_args, dm_config, log_path, dtb_enabled, dtb_file,
      cmd_file);
  auto return_code = s.run();

// sim.cc
int sim_t::run() {
  host = context_t::current();
  target.init(sim_thread_main, this);
  return htif_t::run();
}

其中 htif (Host Target InterFace) 用来沟通 host 与 target, 例如, target 的 pk (proxy kernel) 通过 htif 让 host 响应 target 发起的 syscall

int htif_t::run():
  start();
    load_program();
    // 前面 sim_t 初始化时已经设置了 target pc 到 bootrom 的 DEFAULT_RSTVEC (0x00001000) 处
    reset();
      set_rom();
  if (tohost_addr == 0) {
    while (true)
      idle();
  }
  // ...

void sim_t::idle():
  target.switch_to();
  // ~~~~~~~~~~~~~~~~
    swapcontext(prev->context.get(), context.get())
      sim_thread_main()
        sim_t::main()

sim_t::main() :
  while (!done()):
    step(INTERLEAVE);

void sim_t::step(size_t n):
    for (size_t i = 0, steps = 0; i < n; i += steps):
    steps = std::min(n - i, INTERLEAVE - current_step);
    procs[current_proc]->step(steps);

    current_step += steps;
    if (current_step == INTERLEAVE):
      current_step = 0;
      procs[current_proc]->get_mmu()->yield_load_reservation();
      host->switch_to();
      // ~~~~~~~~~~~~~~~

target 执行一定 step 后, 会通过 host 的 switch_to 切换到 host, 后者对应 htif_t::run, 会处理和 fromhost, tohost 相关的功能:

int htif_t::run():
  // ...
  while (!signal_exit && exitcode == 0)
  {
    uint64_t tohost;

    try {
      if ((tohost = from_target(mem.read_uint64(tohost_addr))) != 0)
        mem.write_uint64(tohost_addr, target_endian<uint64_t>::zero);
    } catch (mem_trap_t& t) {
      bad_address("accessing tohost", t.get_tval());
    }

    try {
      if (tohost != 0) {
        command_t cmd(mem, tohost, fromhost_callback);
        device_list.handle_command(cmd);
      } else {
        idle();
      }
      device_list.tick();
    }
    // ...
  }

  stop();

  return exit_code();
}

假设 target 是 pk, 希望调用 sys_write 这个 syscall:

  1. target::step 会把 sys_write 对应的信息以特定的编码写到 tohost memory 中
  2. target 会 switch_to host, host 从 idle 处开始执行
  3. host 从 tohost buffer 拿到具体的信息放在 mem 中
  4. host 调用 device 的 handle_command, 在初始化时注册的 syscall_proxy 这个 device 会响应这个 cmd, 最终代理执行这个 sys_write
1.1.3.2. target

target 端执行的代码在 processor_t::step, 用来处理 target 指令的 fetch/decode/execute

void processor_t::step(size_t n):
  try:
    while (n > 0) {
      size_t instret = 0;
      reg_t pc = state.pc;
      mmu_t* _mmu = mmu;

      while (instret < n):
        insn_fetch_t fetch = mmu->load_insn(pc);
        pc = execute_insn(this, pc, fetch);
      n -= instret;
  catch (trap_t &t):
    take_trap(t, pc);
1.1.3.2.1. load_insn
insn_fetch_t load_insn(reg_t addr):
  icache_entry_t entry;
  return refill_icache(addr, &entry)->data;

icache_entry_t* refill_icache(reg_t addr, icache_entry_t* entry):
  auto tlb_entry = translate_insn_addr(addr);
  insn_bits_t insn = from_le(*(uint16_t*)(tlb_entry.host_offset + addr));
  int length = insn_length(insn);

  if (likely(length == 4)) {
    insn |= (insn_bits_t)from_le(*(const int16_t*)translate_insn_addr_to_host(addr + 2)) << 16;
  } else { // ... }

  insn_fetch_t fetch = {proc->decode_insn(insn), insn};
  entry->tag = addr;
  entry->next = &icache[icache_index(addr + length)];
  entry->data = fetch;
  return entry;
1.1.3.2.2. decode_insn

decode_insn 扫描 register_base_instructions 注册的 insn_desc_t, 查找与 mask/match 匹配的指令, 返回到对应的 callback 例如 rv64i_addi

insn_func_t processor_t::decode_insn(insn_t insn):
  int cnt = 0;
  insn_desc_t* p = &instructions[0];
  while ((insn.bits() & p->mask) != p->match || !desc.func(xlen, rve))
    p++, cnt++;
  desc = *p;

  if (p->mask != 0 && p > &instructions[0]) {
    if (p->match != (p - 1)->match && p->match != (p + 1)->match) {
      // move to front of opcode list to reduce miss penalty
      while (--p >= &instructions[0])
        *(p + 1) = *p;
        instructions[0] = desc;

    opcode_cache[idx] = desc;
    opcode_cache[idx].match = insn.bits();

  return desc.func(xlen, rve);
1.1.3.2.3. execute_insn
reg_t execute_insn(processor_t* p, reg_t pc, insn_fetch_t fetch)
  return fetch.func(p, fetch.insn, pc);

其中 fetch.func 对应具体的指令实现, 以 rv64i_addi 为例:

reg_t rv64i_addi(processor_t* p, insn_t insn, reg_t pc) {
#define xlen 64
    reg_t npc = sext_xlen(pc + insn_length(MATCH_ADDI));
#include "insns/addi.h"
#undef xlen
    return npc;
}

insns/addi.h 的内容为:

WRITE_RD(sext_xlen(RS1 + insn.i_imm()));

WRITE_RD 最终会修改 processor->state_t->XPR, 以模拟修改寄存器的操作

1.1.3.2.4. trap
  1. ecall

    导致 trap 的 ecall 指令在模拟时只是 throw 一个 c++ 的 trap_t exception 即可, 外层的 processor_t::step 会 catch 这个 trap_t, 调用 take_trap

    switch (STATE.prv)
    {
      case PRV_U: throw trap_user_ecall();
      case PRV_S:
        if (STATE.v)
          throw trap_virtual_supervisor_ecall();
        else
          throw trap_supervisor_ecall();
      case PRV_M: throw trap_machine_ecall();
      default: abort();
    }
    
  2. take_trap

    take_trap 模拟了中断的处理: 跳转到 tvec, 设置 epc, cause 等

    void processor_t::take_trap(trap_t& t, reg_t epc):
      // ....
      // default handle the trap in M-mode
      reg_t vector = (state.mtvec->read() & 1) && interrupt ? 4 * bit : 0;
      state.pc = (state.mtvec->read() & ~(reg_t)1) + vector;
      state.mepc->write(epc);
      state.mcause->write(t.cause());
      state.mtval->write(t.get_tval());
      // ...
      reg_t s = state.mstatus->read();
      s = set_field(s, MSTATUS_MPIE, get_field(s, MSTATUS_MIE));
      s = set_field(s, MSTATUS_MPP, state.prv);
      // ..
      state.mstatus->write(s);
      set_privilege(PRV_M);
    
  3. mret

    从 trap 返回的 mret 指令:

    require_privilege(PRV_M);
    // 从 mepc 恢复 pc
    set_pc_and_serialize(p->get_state()->mepc->read());
    reg_t s = STATE.mstatus->read();
    // ...
    s = set_field(s, MSTATUS_MIE, get_field(s, MSTATUS_MPIE));
    s = set_field(s, MSTATUS_MPIE, 1);
    // ...
    p->put_csr(CSR_MSTATUS, s);
    p->set_privilege(prev_prv);
    // ...
    

1.1.4. 添加新的指令

添加新的指令时有两种选择:

  1. 把它做为 base instruction
    • 修改 riscv.mk.in 中指令的列表,
    • 添加 insns/xxx.h
    • 为了支持 debug, 还需要修改 disasm/disasm.cc, 添加针对 xxx 指令的部分
  2. 使用 spike 自带的 extension 机制, 可以参考 riscv/extension.h

1.1.5. interrupt

ecall, ebreak 等指令以及 mmu 等触发的同步的 interrupt 在 step 时通过 try catch 直接可以处理.

为了模拟外部的异步的中断, spike 提供了一个 clint 模块, 针对它的内存读写指令会反映到 mip 寄存器:

bool clint_t::store(reg_t addr, size_t len, const uint8_t* bytes) {
    if (addr >= MSIP_BASE &&
        addr + len <= MSIP_BASE + procs.size() * sizeof(msip_t)) {
        std::vector<msip_t> msip(procs.size());
        std::vector<msip_t> mask(procs.size(), 0);
        memcpy((uint8_t*)&msip[0] + addr - MSIP_BASE, bytes, len);
        memset((uint8_t*)&mask[0] + addr - MSIP_BASE, 0xff, len);
        for (size_t i = 0; i < procs.size(); ++i) {
            if (!(mask[i] & 0xFF)) continue;
            procs[i]->state.mip->backdoor_write_with_mask(MIP_MSIP, 0);
            /*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
            if (!!(msip[i] & 1))
                procs[i]->state.mip->backdoor_write_with_mask(
                    MIP_MSIP, MIP_MSIP);
        }
    }
    /* ... */
    return true;
}

step 时会读取 mip 以触发外部中断:

void processor_t::step(size_t n) {
    while (n > 0) {
        try {
            take_pending_interrupt();
              take_interrupt(state.mip->read() & state.mie->read());
                              /*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
            /* ... */
            execute_insn();
            catch (trap_t& t) {
                /* ... */
            }
        }
    }
}

1.2. htif

htif 是 Host Target InterFace, 代码在 fesvr 目录 (Front End SerVeR), spike 通过它可以与 host 交互:

  1. 读取 host 的数据
  2. 发送数据给 host

有了这个 IO 通道, 可以完成一些更复杂的功能, 例如:

  1. target 通知 host 程序执行结果并返回结果
  2. target 要求 host 执行 syscall

例如 https://github.com/sunwayforever/hello_world/blob/main/hello_baremetal/riscv/main.c, 通过把 tohost 置为 1, 可以通知 host 停止模拟并返回结果

1.3. pk

spike 可以直接运行 bare-metal 程序 (例如 https://github.com/sunwayforever/hello_world/tree/main/hello_baremetal/riscv).

如果要运行非 bare-metal 程序, 则需要 pk (Proxy Kernel), 为非 bare-metal 的 riscv 程序提供一个基本的执行环境, 类似于 qemu 的 user-mode emulation. 例如:

  1. bootloader
  2. 中断向量
  3. 加载 elf
  4. 支持 syscall, 主要是 IO 和 memory 相关

pk 本身可以响应一部分 syscall, 例如 sys_dup, 但有一些 syscall 需要通过 htif 由 host 去执行, 以 sys_write 为例:

/* ------- */
void boot_loader(uintptr_t dtb):
  uintptr_t kernel_stack_top = pk_vm_init();
  extern char trap_entry;
  write_csr(stvec, pa2kva(&trap_entry));
  /* ... */

/* ------- */
trap_entry:
  csrrw sp, sscratch, sp
  bnez sp, 1f
  csrr sp, sscratch
1:addi sp,sp,-320
  save_tf
  move  a0,sp
  jal handle_trap

/* ------- */
void handle_trap(trapframe_t* tf):
  if ((intptr_t)tf->cause < 0)
    return handle_interrupt(tf);

  typedef void (*trap_handler)(trapframe_t*);

  const static trap_handler trap_handlers[] = {
    [CAUSE_MISALIGNED_FETCH] = handle_misaligned_fetch,
    [CAUSE_FETCH_ACCESS] = handle_instruction_access_fault,
    [CAUSE_LOAD_ACCESS] = handle_load_access_fault,
    [CAUSE_STORE_ACCESS] = handle_store_access_fault,
    [CAUSE_FETCH_PAGE_FAULT] = handle_fault_fetch,
    [CAUSE_ILLEGAL_INSTRUCTION] = handle_illegal_instruction,
    [CAUSE_USER_ECALL] = handle_syscall,
    /* ... */
  };
  trap_handler f = (void*)pa2kva(trap_handlers[tf->cause]);
  f(tf);

/* ------- */
static void handle_syscall(trapframe_t* tf):
  tf->gpr[10] = do_syscall(tf->gpr[10], tf->gpr[11], tf->gpr[12], tf->gpr[13],
                           tf->gpr[14], tf->gpr[15], tf->gpr[17]);
  tf->epc += 4;

/* ------- */
long do_syscall(long a0, long a1, long a2, long a3, long a4, long a5, unsigned long n):
  const static void* syscall_table[] = {
    [SYS_exit] = sys_exit,
    [SYS_exit_group] = sys_exit,
    [SYS_read] = sys_read,
    [SYS_pread] = sys_pread,
    [SYS_write] = sys_write,
    /* ... */
  };

  syscall_t f = 0;
  if (n < ARRAY_SIZE(syscall_table))
    f = syscall_table[n];
  if (!f)
    return sys_stub_nosys();
  f = (void*)pa2kva(f);
  return f(a0, a1, a2, a3, a4, a5, n);

/* ------- */
ssize_t sys_write(int fd, const char* buf, size_t n):
  /* ... */
  if (f):
    for (size_t total = 0;;):
      /* ... */
      r = file_write(f, kbuf, cur);
      /* ... */
    return r;


ssize_t file_write(file_t* f, const void* buf, size_t size):
  return frontend_syscall(SYS_write, f->kfd, kva2pa(buf), size, 0, 0, 0, 0);


long frontend_syscall(
    long n, uint64_t a0, uint64_t a1, uint64_t a2, uint64_t a3, uint64_t a4,
    uint64_t a5, uint64_t a6):
  static volatile uint64_t magic_mem[8];

  static spinlock_t lock = SPINLOCK_INIT;
  spinlock_lock(&lock);

  magic_mem[0] = n;
  magic_mem[1] = a0;
  magic_mem[2] = a1;
  magic_mem[3] = a2;
  magic_mem[4] = a3;
  magic_mem[5] = a4;
  magic_mem[6] = a5;
  magic_mem[7] = a6;

  htif_syscall(kva2pa_maybe(magic_mem));

  long ret = magic_mem[0];

  spinlock_unlock(&lock);
  return ret;

/* ------- */
void htif_syscall(uintptr_t arg):
  do_tohost_fromhost(0, 0, arg);

后续 htif 对 tohost 的处理参考 host

1.4. boot

spike 定义了 abstract_device_t, 其实现包括 mem_t, rom_device_t, mmio_device_t, bus_t, 每个 device 需要指定其对应的地址范围, 后续 target 对相应内存的访问会被 relay 到不同的 device.

htif_t::run 会调用 set_rom 设置 bootrom 的内容:

void sim_t::set_rom() {
    const int reset_vec_size = 8;

    reg_t start_pc = cfg->start_pc.value_or(get_entry_point());

    uint32_t reset_vec[reset_vec_size] = {
        // auipc  t0,0x0, 相当于 t0 = pc + (0x0<<12) = pc
        0x297,
        // 按约定 a1 需要保存 dtb 的地址. 这里的 dtb 是紧挨在 reset_vec 之后的:
        // rom.insert(rom.end(), dtb.begin(), dtb.end()).
        // reset_vec_size*4<<20 是因为 addi 指令里 imm 放在高 12 位
        0x28593 + (reset_vec_size * 4 << 20),          // addi   a1, t0, &dtb
        0xf1402573,                                    // csrr   a0, mhartid
        // 后面的 start_pc 所在的位置与 reset_vec 开头的位置 (t0) 相差 24 byte
        get_core(0)->get_xlen() == 32 ? 0x0182a283u :  // lw     t0,24(t0)
            0x0182b283u,                               // ld     t0,24(t0)
        0x28067,                                       // jr     t0
        // 这里插入一个 0, 是为了让 start_pc 与 reset_vec 开头的位置相差 24 byte
        // (而不是 20 byte), 以便 start_pc 的位置是 8 byte 对齐的 (ld 需要访问 8
        // byte 对齐的地址, reset_vec 的地址 DEFAULT_RSTVEC 已经是 8 byte 对齐的,
        // 再加上 24 得到的 start_pc 地址也会是对齐的)
        0,
        (uint32_t)(start_pc & 0xffffffff),
        (uint32_t)(start_pc >> 32)};
    // ...
    std::vector<char> rom(
        (char*)reset_vec, (char*)reset_vec + sizeof(reset_vec));

    rom.insert(rom.end(), dtb.begin(), dtb.end());
    const int align = 0x1000;
    rom.resize((rom.size() + align - 1) / align * align);

    boot_rom.reset(new rom_device_t(rom));
    bus.add_device(DEFAULT_RSTVEC, boot_rom.get());
}
  1. sim_t 初始化时已经把 target pc 设置为 DEFAULT_RSTVEC (0x00001000)
  2. bus.add_device 后 target 针对 DEFAULT_RSTVEC 地址的访问会读取到 bootrom 的数据
  3. bootrom 把 elf 的 entry (start_pc) 直接写到 reset_vec 中, 所以 bootrom 启动后会跳转到 elf 的 entry, 完成启动
  4. 启动时按约定需要把 dtb 放在 a1 中, 参考 dtb

1.5. commit log

spike 是一个 riscv 的 ISS (instruction stream simulator), 运行时可以产生 commit log, 用来比对 DUT 和 DUV 的结果. 默认情况下不产生 commit log, 要生成 commit log 需要:

  1. configure 时指定 --enable-commitlog
  2. 运行时指定 --log-commits

找开 commit log 后, 针对寄存器和内存的读写操作的结果都会被记录下来, 例如:

core   0: 3 0x0000000000001000 (0x00000297) x 5 0x0000000000001000
core   0: 3 0x0000000000001004 (0x02028593) x11 0x0000000000001020
core   0: 3 0x0000000000001008 (0xf1402573) x10 0x0000000000000000
core   0: 3 0x000000000000100c (0x0182b283) x 5 0x0000000080000040 mem 0x0000000000001018
core   0: 3 0x0000000000001010 (0x00028067)
core   0: 3 0x0000000080000040 (0x00001117) x 2 0x0000000080001040
core   0: 3 0x0000000080000044 (0xfc010113) x 2 0x0000000080001000
core   0: 3 0x0000000080000048 (0xfb9ff0ef) x 1 0x000000008000004c
core   0: 3 0x0000000080000000 (0xfe010113) x 2 0x0000000080000fe0
core   0: 3 0x0000000080000004 (0x00813c23) mem 0x0000000080000ff8 0x0000000000000000
core   0: 3 0x0000000080000008 (0x02010413) x 8 0x0000000080001000
core   0: 3 0x000000008000000c (0x00100793) x15 0x0000000000000001
core   0: 3 0x0000000080000010 (0xfef42623) mem 0x0000000080000fec 0x00000001
core   0: 3 0x0000000080000014 (0xfec42783) x15 0x0000000000000001 mem 0x0000000080000fec
core   0: 3 0x0000000080000018 (0x0017879b) x15 0x0000000000000002
core   0: 3 0x000000008000001c (0xfef42423) mem 0x0000000080000fe8 0x00000002
core   0: 3 0x0000000080000020 (0x00001797) x15 0x0000000080001020
core   0: 3 0x0000000080000024 (0xfe078793) x15 0x0000000080001000
core   0: 3 0x0000000080000028 (0x00100713) x14 0x0000000000000001
core   0: 3 0x000000008000002c (0x00e7b023) mem 0x0000000080001000 0x0000000000000001
core   0: 3 0x0000000080000030 (0x00000013)
core   0: 3 0x0000000080000034 (0x01813403) x 8 0x0000000000000000 mem 0x0000000080000ff8
core   0: 3 0x0000000080000038 (0x02010113) x 2 0x0000000080001000
core   0: 3 0x000000008000003c (0x00008067)

使用 spike 做 ISS 的例子参考 https://github.com/chipsalliance/riscv-dvOpen-Source-Verification-Platform-for-RISC-V-Processors

1.7. force-riscv

1.7.1. 做为交互式 ISG

force-riscv 是一个 RISC-V 的 ISG (instruction stream generator), 但它内置了一个名为 handcar 的模拟器, handcar 基于 spike 改写, 添加了一些功能例如提供了读写寄存器的接口.

由于它内置了一个模拟器, 所以 fore-riscv 在生成随机指令时是可以用一些 `运行时` 的信息来控制指令的生成, 例如:

  1. 根据寄存器的值生成不同的指令
  2. 生成对齐或非对齐的数据访问
  3. 生成指令访问指定的虚拟地址

force-riscv 通过 python api 可以控制具体生成什么样的指令, 例如:

  1. 指定使用特定的寄存器
  2. 指定 imm 的值
  3. 使用随机的寄存器时 reserve 某些寄存器
from riscv.EnvRISCV import EnvRISCV
from riscv.GenThreadRISCV import GenThreadRISCV
from base.Sequence import Sequence


class MySequence(Sequence):
    def generate(self, **kargs):
        # 通过 handcar 给 x5 赋值
        self.initializeRegister("x5", 0x123)
        # 生成随机的 addi 指令
        self.genInstruction("ADDI##RISCV")
        # 指定 addi 使用 x5, 且 imm 使用特定范围的随机值
        self.genInstruction("ADDI##RISCV", {"rs1": 5, "simm12": "0x123-0x126", "rd": 5})
        (reg_value, value_valid) = self.readRegister("x5")
        # 根据 x5 的值生成不同的指令
        if reg_value == 0x123:
            self.genInstruction("ADD##RISCV", {"rs1": 5, "rs2": 5, "rd": 5})
        else:
            self.genInstruction("ADD##RISCV", {"rs1": 5, "rs2": 6, "rd": 5})

        # handcar 本身配置了页表 (参考 riscv/arch_data/paging/ 下的 xml), 这里可
        # 以生成针对指定 va 的内存访问
        target_addr = self.genVA(Range = "0x10000-0x10000")
        self.genInstruction("LD##RISCV",{"LSTarget": target_addr})

        self.genInstruction("SRA##RISCV")

MainSequenceClass = MySequence
GenThreadClass = GenThreadRISCV
EnvClass = EnvRISCV

python api 可以使用的指令 (例如 ADD##RISCV) 及配置 (例如 rs1, simm12) 在 riscv/arch_data/instr/ 下的 xml 里可以找到

另外, force-riscv 生成的 elf 里并不仅仅包含 python api (例如上面 Sequence::generate) 生成的指令, 它还会自己生成一些初始化的代码, 例如完成寄存器 (包括 CSR) 的初始化, 例如初始化中断和页表等.

1.7.2. 做为交互式 ISS

https://github.com/chipsalliance/riscv-dv 使用 spike 的 commit log 做 ISS, 但由于 handcar 把 spike 修改成了交互式执行, 所以 handcar 可以做为一个交互式的 ISS

使用 handcar 做交互式 ISS 的例子参考 https://github.com/sunwayforever/handcar_test

handcar 相对于 spike 主要改动:

  1. 修改成交互执行 (step)

    spike 原来的逻辑是:

    host:               |    guest:
                        |
    while (true):       |    while(true):
      switch_to(guest)  |      step() for n steps
      // htif           |      switch_to(host)
      switch(tohost):   |
        case io:        |
         ...            |
        case xxx:       |
    

    handcar 把 spike 编译成一个 handcar_cosim.so, 需要用户自己调用 step, 因此不再有 host, guest 的概念, 同时因为去掉了 host, 所以无法支持 htif 的功能了.

    交互执行时无法支持调试, 所以去掉了 remote bitbang (rbb) 功能, 因此不支持 openocd

  2. sparse memory

    spike 需要用 -m 来虚拟一块或多块不同范围的物理内存, 限制了测试程序只能访问提前配置好的地址(例如编译测试代码时需要用 ldscript 配置一下地址). 通过 sparse memory 机制, 测试程序可以使用任何地址. sparse memory 的实现在 ForceMemory.cc 中.

    由于所有 memory 操作都由 sparse memory 完成, 所以之前 spike 定义的 mmio_plugin_t, mem_t, rom_device_t 等不再使用, 也不再支持 -m 参数

Backlinks

opcodes (binutils > opcodes > riscv_opcodes): as/objdump/gdb 都使用了 opcodes, qemu/spike/gem5 则定义了它们自己的一套类似的机制

slow_unaligned_access (mtune > riscv_tune_param > slow_unaligned_access): 两次 foo 调用至少有一次会导致 unaligned access, 这里就需要 trap_handler 来处理了 (参考 Spike 中的 handle_misaligned_fetch)

Author: [email protected]
Date: 2023-02-15 Wed 10:22
Last updated: 2023-09-06 Wed 12:58

知识共享许可协议