litedram: Add basic support for LiteX LiteDRAM

This comes in two parts:

 - A generator script which uses LiteX to generate litedram cores
along with their init files for various boards (currently Arty and
Nexys-video). This comes with configs for arty and nexys_video.

 - A fusesoc "generator" which uses pre-generated litedram cores

The generation process is manual on purpose. This include pre-generated
cores for the two above boards.

This is done so that one doesn't have to install LiteX to build
microwatt. In addition, the generator script or wrapper vhdl tend to
break when LiteX changes significantly which happens.

This is still rather standalone and hasn't been plumbed into the SoC
or the FPGA toplevel files yet.

At this point LiteDRAM self-initializes using a built-in VexRiscv
"Minimum" core obtained from LiteX and included in this commit. There
is some plumbing to generate and cores that are initialized by Microwatt
directly but this isn't working yet and so isn't enabled yet.

Signed-off-by: Benjamin Herrenschmidt <benh@kernel.crashing.org>
pull/170/head
Benjamin Herrenschmidt 6 years ago
parent 31b55b2a75
commit 982cf166dd

@ -152,11 +152,21 @@ TAGS:

.PHONY: TAGS

clean:
_clean:
rm -f *.o work-*cf unisim-*cf $(all)
rm -f fpga/*.o fpga/work-*cf
rm -f sim-unisim/*.o sim-unisim/unisim-*cf
rm -f TAGS
rm -f scripts/mw_debug/*.o
rm -f scripts/mw_debug/mw_debug

distclean: clean
clean: _clean
make -f scripts/mw_debug/Makefile clean

distclean: _clean
rm -f *~ fpga/~
rm -rf litedram/build
rm -f litedram/extras/*~
rm -f litedram/gen-src/*~
rm -f litedram/gen-src/sdram_init/*~
make -f scripts/mw_debug/Makefile distclean

File diff suppressed because it is too large Load Diff

@ -0,0 +1,45 @@
#!/usr/bin/python3
from fusesoc.capi2.generator import Generator
import os
import sys
import pathlib

class LiteDRAMGenerator(Generator):
def run(self):
board = self.config.get('board')

# Collect a bunch of directory path
script_dir = os.path.dirname(sys.argv[0])
base_dir = os.path.join(script_dir, os.pardir)
gen_dir = os.path.join(base_dir, "generated", board)
extras_dir = os.path.join(base_dir, "extras")

print("Adding LiteDRAM for board... ", board)

# Grab init-cpu.txt if it exists
cpu_file = os.path.join(gen_dir, "init-cpu.txt")
if os.path.exists(cpu_file):
cpu = pathlib.Path(cpu_file).read_text()
else:
cpu = None

# Add files to fusesoc
files = []
f = os.path.join(gen_dir, "litedram_core.v")
files.append({f : {'file_type' : 'verilogSource'}})
f = os.path.join(gen_dir, "litedram-wrapper.vhdl")
files.append({f : {'file_type' : 'vhdlSource-2008'}})
f = os.path.join(gen_dir, "litedram_core.init")
files.append({f : {'file_type' : 'user'}})

# Look for init CPU types and add corresponding files
if cpu == "vexriscv":
f = os.path.join(base_dir, "extras", "VexRiscv.v")
files.append({f : {'file_type' : 'verilogSource'}})

self.add_files(files)

g = LiteDRAMGenerator()
g.run()
g.write()

@ -0,0 +1,42 @@
# This file is Copyright (c) 2018-2019 Florent Kermarrec <florent@enjoy-digital.fr>
# License: BSD

{
# General ------------------------------------------------------------------
"cpu": "vexriscv", # Type of CPU used for init/calib (vexriscv, lm32)
"cpu_variant":"minimal",
"speedgrade": -1, # FPGA speedgrade
"memtype": "DDR3", # DRAM type

# PHY ----------------------------------------------------------------------
"cmd_delay": 0, # Command additional delay (in taps)
"cmd_latency": 0, # Command additional latency
"sdram_module": "MT41K128M16", # SDRAM modules of the board or SO-DIMM
"sdram_module_nb": 2, # Number of byte groups
"sdram_rank_nb": 1, # Number of ranks
"sdram_phy": "A7DDRPHY", # Type of FPGA PHY

# Electrical ---------------------------------------------------------------
"rtt_nom": "60ohm", # Nominal termination
"rtt_wr": "60ohm", # Write termination
"ron": "34ohm", # Output driver impedance

# Frequency ----------------------------------------------------------------
"input_clk_freq": 100e6, # Input clock frequency
"sys_clk_freq": 100e6, # System clock frequency (DDR_clk = 4 x sys_clk)
"iodelay_clk_freq": 200e6, # IODELAYs reference clock frequency

# Core ---------------------------------------------------------------------
"cmd_buffer_depth": 16, # Depth of the command buffer

# User Ports ---------------------------------------------------------------
"user_ports": {
"native_0": {
"type": "native",
},
},

# CSR Port -----------------------------------------------------------------
"csr_expose": "False", # expose access to CSR (I/O) ports
"csr_align" : 32, # CSR alignment
}

@ -0,0 +1,150 @@
#!/usr/bin/python3

from fusesoc.capi2.generator import Generator
from litex.build.tools import write_to_file
from litex.build.tools import replace_in_file
from litex.build.generic_platform import *
from litex.build.xilinx import XilinxPlatform
from litex.build.lattice import LatticePlatform
from litex.soc.integration.builder import *
from litedram.gen import *
import subprocess
import os
import sys
import yaml
import shutil

def make_new_dir(base, added):
r = os.path.join(base, added)
if os.path.exists(r):
shutil.rmtree(r)
os.mkdir(r)
return r
gen_src_dir = os.path.dirname(os.path.realpath(__file__))
base_dir = os.path.join(gen_src_dir, os.pardir)
build_top_dir = make_new_dir(base_dir, "build")
gen_src_dir = os.path.join(base_dir, "gen-src")
gen_dir = make_new_dir(base_dir, "generated")

# Build the init code for microwatt-initialized DRAM
#
# XXX Not working yet
#
def build_init_code(build_dir):

# More path fudging
sw_dir = os.path.join(build_dir, "software");
sw_inc_dir = os.path.join(build_dir, "include")
gen_inc_dir = os.path.join(sw_inc_dir, "generated")
src_dir = os.path.join(gen_src_dir, "sdram_init")
lxbios_src_dir = os.path.join(soc_directory, "software", "bios")
lxbios_inc_dir = os.path.join(soc_directory, "software", "include")
print(" sw dir:", sw_dir)
print("gen_inc_dir:", gen_inc_dir)
print(" src dir:", src_dir)
print(" lx src dir:", lxbios_src_dir)
print(" lx inc dir:", lxbios_inc_dir)

# Generate mem.h
mem_h = "#define MAIN_RAM_BASE 0x40000000"
write_to_file(os.path.join(gen_inc_dir, "mem.h"), mem_h)

# Environment
env_vars = []
def _makefile_escape(s): # From LiteX
return s.replace("\\", "\\\\")
def add_var(k, v):
env_vars.append("{}={}\n".format(k, _makefile_escape(v)))

add_var("BUILD_DIR", sw_dir)
add_var("SRC_DIR", src_dir)
add_var("GENINC_DIR", gen_inc_dir)
add_var("LXSRC_DIR", lxbios_src_dir)
add_var("LXINC_DIR", lxbios_inc_dir)
write_to_file(os.path.join(gen_inc_dir, "variables.mak"), "".join(env_vars))

# Build init code
print(" Generating init software...")
makefile = os.path.join(src_dir, "Makefile")
r = subprocess.check_call(["make", "-C", build_dir, "-I", gen_inc_dir, "-f", makefile])
print("Make result:", r)

return os.path.join(sw_dir, "obj", "sdram_init.hex")

def generate_one(t):

print("Generating target:", t)

# Muck with directory path
build_dir = make_new_dir(build_top_dir, t)
t_dir = make_new_dir(gen_dir, t)

# Grab config file
cfile = os.path.join(gen_src_dir, t + ".yml")
core_config = yaml.load(open(cfile).read(), Loader=yaml.Loader)

### TODO: Make most stuff below a function in litedram gen.py and
### call it rather than duplicate it
###

# Convert YAML elements to Python/LiteX
for k, v in core_config.items():
replaces = {"False": False, "True": True, "None": None}
for r in replaces.keys():
if v == r:
core_config[k] = replaces[r]
if "clk_freq" in k:
core_config[k] = float(core_config[k])
if k == "sdram_module":
core_config[k] = getattr(litedram_modules, core_config[k])
if k == "sdram_phy":
core_config[k] = getattr(litedram_phys, core_config[k])

# Generate core
if core_config["sdram_phy"] in [litedram_phys.ECP5DDRPHY]:
platform = LatticePlatform("LFE5UM5G-45F-8BG381C", io=[], toolchain="trellis")
elif core_config["sdram_phy"] in [litedram_phys.A7DDRPHY, litedram_phys.K7DDRPHY, litedram_phys.V7DDRPHY]:
platform = XilinxPlatform("", io=[], toolchain="vivado")
else:
raise ValueError("Unsupported SDRAM PHY: {}".format(core_config["sdram_phy"]))

soc = LiteDRAMCore(platform, core_config, integrated_rom_size=0x6000)

# Build into build_dir
builder = Builder(soc, output_dir=build_dir, compile_gateware=False)
vns = builder.build(build_name="litedram_core", regular_comb=False)

# Grab generated gatewar dir
gw_dir = os.path.join(build_dir, "gateware")

# Generate init-cpu.txt if any and generate init code if none
cpu = core_config["cpu"]
if cpu is None:
print("Microwatt based inits not supported yet !")
src_wrap_file = os.path.join(gen_src_dir, "wrapper-mw-init.vhdl")
src_init_file = build_init_code(build_dir)
else:
write_to_file(os.path.join(t_dir, "init-cpu.txt"), cpu)
src_wrap_file = os.path.join(gen_src_dir, "wrapper-self-init.vhdl")
src_init_file = os.path.join(gw_dir, "mem.init")

# Copy generated files to target dir, amend them if necessary
core_file = os.path.join(gw_dir, "litedram_core.v")
dst_init_file = os.path.join(t_dir, "litedram_core.init")
dst_wrap_file = os.path.join(t_dir, "litedram-wrapper.vhdl")
replace_in_file(core_file, "mem.init", "litedram_core.init")
shutil.copy(core_file, t_dir)
shutil.copyfile(src_init_file, dst_init_file)
shutil.copyfile(src_wrap_file, dst_wrap_file)

def main():

targets = ['arty','nexys-video']
for t in targets:
generate_one(t)

# XXX TODO: Remove build dir unless told not to via cmdline option
if __name__ == "__main__":
main()

@ -0,0 +1,42 @@
# This file is Copyright (c) 2018-2019 Florent Kermarrec <florent@enjoy-digital.fr>
# License: BSD

{
# General ------------------------------------------------------------------
"cpu": "vexriscv", # Type of CPU used for init/calib (vexriscv, lm32)
"cpu_variant":"minimal",
"speedgrade": -1, # FPGA speedgrade
"memtype": "DDR3", # DRAM type

# PHY ----------------------------------------------------------------------
"cmd_delay": 0, # Command additional delay (in taps)
"cmd_latency": 0, # Command additional latency
"sdram_module": "MT41K256M16", # SDRAM modules of the board or SO-DIMM
"sdram_module_nb": 2, # Number of byte groups
"sdram_rank_nb": 1, # Number of ranks
"sdram_phy": "A7DDRPHY", # Type of FPGA PHY

# Electrical ---------------------------------------------------------------
"rtt_nom": "60ohm", # Nominal termination
"rtt_wr": "60ohm", # Write termination
"ron": "34ohm", # Output driver impedance

# Frequency ----------------------------------------------------------------
"input_clk_freq": 100e6, # Input clock frequency
"sys_clk_freq": 100e6, # System clock frequency (DDR_clk = 4 x sys_clk)
"iodelay_clk_freq": 200e6, # IODELAYs reference clock frequency

# Core ---------------------------------------------------------------------
"cmd_buffer_depth": 16, # Depth of the command buffer

# User Ports ---------------------------------------------------------------
"user_ports": {
"native_0": {
"type": "native",
},
},

# CSR Port -----------------------------------------------------------------
"csr_expose": "False", # expose access to CSR (I/O) ports
"csr_align" : 32, # 64-bit alignment
}

@ -0,0 +1,75 @@
#### Directories

include variables.mak
OBJ = $(BUILD_DIR)/obj

PROGRAM = sdram_init
OBJECTS = $(OBJ)/head.o $(OBJ)/main.o $(OBJ)/sdram.o

#### Compiler

ARCH = $(shell uname -m)
ifneq ("$(ARCH)", "ppc64")
ifneq ("$(ARCH)", "ppc64le")
CROSS_COMPILE = powerpc64le-linux-gnu-
endif
endif

CC = $(CROSS_COMPILE)gcc
LD = $(CROSS_COMPILE)ld
OBJCOPY = $(CROSS_COMPILE)objcopy

#### Flags

CPPFLAGS = -nostdinc
CPPFLAGS += -I$(SRC_DIR)/libc/include -I$(LXSRC_DIR) -I$(LXINC_DIR) -I$(GENINC_DIR) -I$(SRC_DIR)/include
CPPFLAGS += -isystem $(shell $(CC) -print-file-name=include)
CFLAGS = -Os -g -Wall -std=c99 -m64 -mabi=elfv2 -msoft-float -mno-string -mno-multiple -mno-vsx -mno-altivec -mlittle-endian -fno-stack-protector -mstrict-align -ffreestanding -fdata-sections -ffunction-sections -fno-delete-null-pointer-checks
ASFLAGS = $(CPPFLAGS) $(CFLAGS)
LDFLAGS = -static -nostdlib -Ttext-segment=0xffff0000 -T $(SRC_DIR)/$(PROGRAM).lds --gc-sections

#### Pretty print

ifeq ($(VERBOSE),1)
define Q
$(2)
endef
else
define Q
@echo " [$1] $(3)"
@$(2)
endef
endif

#### Rules. This is a bit crappy, I'm sure we can do better with the
#### handling of the various path, but this will have to do
#### until I can be bothered getting my head around the finer
#### points of Makefiles

all: objdir $(OBJ)/$(PROGRAM).hex

$(OBJ)/sdram.o: $(LXSRC_DIR)/sdram.c
$(call Q,CC, $(CC) $(CPPFLAGS) $(CFLAGS) -c $< -o $@, $@)
$(OBJ)/%.o : $(SRC_DIR)/%.S
$(call Q,AS, $(CC) $(ASFLAGS) -c $< -o $@, $@)
$(OBJ)/%.o : $(SRC_DIR)/%.c
$(call Q,CC, $(CC) $(CPPFLAGS) $(CFLAGS) -c $< -o $@, $@)
$(OBJ)/%.o : $(SRC_DIR)/libc/src/%.c
$(call Q,CC, $(CC) $(CPPFLAGS) $(CFLAGS) -c $< -o $@, $@)

LIBC_SRC := $(wildcard $(SRC_DIR)/libc/src/*.c)
LIBC_OBJ := $(patsubst $(SRC_DIR)/libc/src/%.c, $(OBJ)/%.o,$(LIBC_SRC))
$(OBJ)/libc.o: $(LIBC_OBJ)
$(call Q,LD, $(LD) -r -o $@ $^, $@)

$(OBJ)/$(PROGRAM).elf: $(OBJECTS) $(OBJ)/libc.o
$(call Q,LD, $(LD) $(LDFLAGS) -o $@ $^, $@)

$(OBJ)/$(PROGRAM).bin: $(OBJ)/$(PROGRAM).elf
$(call Q,OC, $(OBJCOPY) -O binary -S $^ $@, $@)

$(OBJ)/$(PROGRAM).hex: $(OBJ)/$(PROGRAM).bin
$(call Q,HX, $(SRC_DIR)/bin2hex.py $^ > $@, $@)

objdir:
@mkdir -p $(OBJ)

@ -0,0 +1,17 @@
#!/usr/bin/python3

import sys
import subprocess
import struct

with open(sys.argv[1], "rb") as f:
while True:
word = f.read(8)
if len(word) == 8:
print("%016x" % struct.unpack('Q', word));
elif len(word) == 4:
print("00000000%08x" % struct.unpack('I', word));
elif len(word) == 0:
exit(0);
else:
raise Exception("Bad length")

@ -0,0 +1,102 @@
/* Copyright 2013-2014 IBM Corp.
*
* 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.
*/

#define STACK_TOP 0xffff4000

#define FIXUP_ENDIAN \
tdi 0,0,0x48; /* Reverse endian of b . + 8 */ \
b 191f; /* Skip trampoline if endian is good */ \
.long 0xa600607d; /* mfmsr r11 */ \
.long 0x01006b69; /* xori r11,r11,1 */ \
.long 0x05009f42; /* bcl 20,31,$+4 */ \
.long 0xa602487d; /* mflr r10 */ \
.long 0x14004a39; /* addi r10,r10,20 */ \
.long 0xa64b5a7d; /* mthsrr0 r10 */ \
.long 0xa64b7b7d; /* mthsrr1 r11 */ \
.long 0x2402004c; /* hrfid */ \
191:


/* Load an immediate 64-bit value into a register */
#define LOAD_IMM64(r, e) \
lis r,(e)@highest; \
ori r,r,(e)@higher; \
rldicr r,r, 32, 31; \
oris r,r, (e)@h; \
ori r,r, (e)@l;

.section ".head","ax"

. = 0
.global start
start:
FIXUP_ENDIAN

/* setup stack */
LOAD_IMM64(%r1, STACK_TOP - 0x100)
LOAD_IMM64(%r12, main)
mtctr %r12,
bctrl
ba 0

/* XXX: litedram init should not take exceptions, maybe we could get
* rid of these to save space, along with a core tweak to suppress
* exceptions in case they happen (just terminate ?)
*/

#define EXCEPTION(nr) \
.= nr; \
b .

/* More exception stubs */
EXCEPTION(0x100)
EXCEPTION(0x200)
EXCEPTION(0x300)
EXCEPTION(0x380)
EXCEPTION(0x400)
EXCEPTION(0x480)
EXCEPTION(0x500)
EXCEPTION(0x600)
EXCEPTION(0x700)
EXCEPTION(0x800)
EXCEPTION(0x900)
EXCEPTION(0x980)
EXCEPTION(0xa00)
EXCEPTION(0xb00)
EXCEPTION(0xc00)
EXCEPTION(0xd00)
EXCEPTION(0xe00)
EXCEPTION(0xe20)
EXCEPTION(0xe40)
EXCEPTION(0xe60)
EXCEPTION(0xe80)
EXCEPTION(0xf00)
EXCEPTION(0xf20)
EXCEPTION(0xf40)
EXCEPTION(0xf60)
EXCEPTION(0xf80)
#if 0
EXCEPTION(0x1000)
EXCEPTION(0x1100)
EXCEPTION(0x1200)
EXCEPTION(0x1300)
EXCEPTION(0x1400)
EXCEPTION(0x1500)
EXCEPTION(0x1600)
#endif

.text

@ -0,0 +1,3 @@
static inline void flush_cpu_dcache(void) { }
static inline void flush_l2_cache(void) { }

@ -0,0 +1,29 @@
/******************************************************************************
* Copyright (c) 2004, 2008, 2012 IBM Corporation
* All rights reserved.
* This program and the accompanying materials
* are made available under the terms of the BSD License
* which accompanies this distribution, and is available at
* http://www.opensource.org/licenses/bsd-license.php
*
* Contributors:
* IBM Corporation - initial implementation
*****************************************************************************/

#ifndef _ASSERT_H
#define _ASSERT_H

#define assert(cond) \
do { if (!(cond)) { \
assert_fail(__FILE__ \
":" stringify(__LINE__) \
":" stringify(cond)); } \
} while(0)

void __attribute__((noreturn)) assert_fail(const char *msg);

#define stringify(expr) stringify_1(expr)
/* Double-indirection required to stringify expansions */
#define stringify_1(expr) #expr

#endif

@ -0,0 +1,54 @@
/* Copyright 2013-2014 IBM Corp.
*
* 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 __COMPILER_H
#define __COMPILER_H

#ifndef __ASSEMBLY__

#include <stddef.h>

/* Macros for various compiler bits and pieces */
#define __packed __attribute__((packed))
#define __align(x) __attribute__((__aligned__(x)))
#define __unused __attribute__((unused))
#define __used __attribute__((used))
#define __section(x) __attribute__((__section__(x)))
#define __noreturn __attribute__((noreturn))
/* not __const as this has a different meaning (const) */
#define __attrconst __attribute__((const))
#define __warn_unused_result __attribute__((warn_unused_result))
#define __noinline __attribute__((noinline))

#if 0 /* Provided by gcc stddef.h */
#define offsetof(type,m) __builtin_offsetof(type,m)
#endif

#define __nomcount __attribute__((no_instrument_function))

/* Compiler barrier */
static inline void barrier(void)
{
// asm volatile("" : : : "memory");
}

#endif /* __ASSEMBLY__ */

/* Stringification macro */
#define __tostr(x) #x
#define tostr(x) __tostr(x)

#endif /* __COMPILER_H */

@ -0,0 +1,26 @@
/******************************************************************************
* Copyright (c) 2004, 2008 IBM Corporation
* All rights reserved.
* This program and the accompanying materials
* are made available under the terms of the BSD License
* which accompanies this distribution, and is available at
* http://www.opensource.org/licenses/bsd-license.php
*
* Contributors:
* IBM Corporation - initial implementation
*****************************************************************************/

#ifndef _CTYPE_H
#define _CTYPE_H

#include <compiler.h>

int __attrconst isdigit(int c);
int __attrconst isxdigit(int c);
int __attrconst isprint(int c);
int __attrconst isspace(int c);

int __attrconst tolower(int c);
int __attrconst toupper(int c);

#endif

@ -0,0 +1,36 @@
/******************************************************************************
* Copyright (c) 2004, 2008 IBM Corporation
* All rights reserved.
* This program and the accompanying materials
* are made available under the terms of the BSD License
* which accompanies this distribution, and is available at
* http://www.opensource.org/licenses/bsd-license.php
*
* Contributors:
* IBM Corporation - initial implementation
*****************************************************************************/

#ifndef _ERRNO_H
#define _ERRNO_H

extern int errno;

/*
* Error number definitions
*/
#define EPERM 1 /* not permitted */
#define ENOENT 2 /* file or directory not found */
#define EIO 5 /* input/output error */
#define EBADF 9 /* Bad file number */
#define ENOMEM 12 /* not enough space */
#define EACCES 13 /* permission denied */
#define EFAULT 14 /* bad address */
#define EBUSY 16 /* resource busy */
#define EEXIST 17 /* file already exists */
#define ENODEV 19 /* device not found */
#define EINVAL 22 /* invalid argument */
#define EDOM 33 /* math argument out of domain of func */
#define ERANGE 34 /* math result not representable */
#define ENOSYS 38 /* Function not implemented */

#endif

@ -0,0 +1,30 @@
/******************************************************************************
* Copyright (c) 2004, 2008 IBM Corporation
* All rights reserved.
* This program and the accompanying materials
* are made available under the terms of the BSD License
* which accompanies this distribution, and is available at
* http://www.opensource.org/licenses/bsd-license.php
*
* Contributors:
* IBM Corporation - initial implementation
*****************************************************************************/

#ifndef _STDINT_H
#define _STDINT_H

typedef unsigned char uint8_t;
typedef signed char int8_t;

typedef unsigned short uint16_t;
typedef signed short int16_t;

typedef unsigned int uint32_t;
typedef signed int int32_t;

typedef unsigned long long uint64_t;
typedef signed long long int64_t;

typedef unsigned long int uintptr_t;

#endif

@ -0,0 +1,35 @@
/******************************************************************************
* Copyright (c) 2004, 2008 IBM Corporation
* All rights reserved.
* This program and the accompanying materials
* are made available under the terms of the BSD License
* which accompanies this distribution, and is available at
* http://www.opensource.org/licenses/bsd-license.php
*
* Contributors:
* IBM Corporation - initial implementation
*****************************************************************************/

#ifndef _STDIO_H
#define _STDIO_H

#include <stdarg.h>
#include "stddef.h"

#define EOF (-1)

int _printf(const char *format, ...) __attribute__((format (printf, 1, 2)));

#ifndef pr_fmt
#define pr_fmt(fmt) fmt
#endif

#define printf(f, ...) do { _printf(pr_fmt(f), ##__VA_ARGS__); } while(0)

int snprintf(char *str, size_t size, const char *format, ...) __attribute__((format (printf, 3, 4)));
int vsnprintf(char *str, size_t size, const char *format, va_list);

int putchar(int ch);
int puts(const char *str);

#endif

@ -0,0 +1,25 @@
/******************************************************************************
* Copyright (c) 2004, 2008 IBM Corporation
* All rights reserved.
* This program and the accompanying materials
* are made available under the terms of the BSD License
* which accompanies this distribution, and is available at
* http://www.opensource.org/licenses/bsd-license.php
*
* Contributors:
* IBM Corporation - initial implementation
*****************************************************************************/

#ifndef _STDLIB_H
#define _STDLIB_H

#include "stddef.h"

#define RAND_MAX 32767

int atoi(const char *str);
long atol(const char *str);
unsigned long int strtoul(const char *nptr, char **endptr, int base);
long int strtol(const char *nptr, char **endptr, int base);

#endif

@ -0,0 +1,45 @@
/******************************************************************************
* Copyright (c) 2004, 2016 IBM Corporation
* All rights reserved.
* This program and the accompanying materials
* are made available under the terms of the BSD License
* which accompanies this distribution, and is available at
* http://www.opensource.org/licenses/bsd-license.php
*
* Contributors:
* IBM Corporation - initial implementation
*****************************************************************************/

#ifndef _STRING_H
#define _STRING_H

#include "stddef.h"

char *strcpy(char *dest, const char *src);
char *strncpy(char *dest, const char *src, size_t n);
char *strcat(char *dest, const char *src);
int strcmp(const char *s1, const char *s2);
int strncmp(const char *s1, const char *s2, size_t n);
int strcasecmp(const char *s1, const char *s2);
int strncasecmp(const char *s1, const char *s2, size_t n);
char *strchr(const char *s, int c);
char *strrchr(const char *s, int c);
size_t strlen(const char *s);
size_t strnlen(const char *s, size_t n);
char *strstr(const char *hay, const char *needle);
char *strtok(char *src, const char *pattern);
char *strdup(const char *src);

void *memset(void *s, int c, size_t n);
void *memchr(const void *s, int c, size_t n);
void *memcpy(void *dest, const void *src, size_t n);
void *memcpy_from_ci(void *destpp, const void *srcpp, size_t len);
void *memmove(void *dest, const void *src, size_t n);
int memcmp(const void *s1, const void *s2, size_t n);

static inline int ffs(unsigned long val)
{
return __builtin_ffs(val);
}

#endif

@ -0,0 +1,26 @@
/******************************************************************************
* Copyright (c) 2004, 2008 IBM Corporation
* All rights reserved.
* This program and the accompanying materials
* are made available under the terms of the BSD License
* which accompanies this distribution, and is available at
* http://www.opensource.org/licenses/bsd-license.php
*
* Contributors:
* IBM Corporation - initial implementation
*****************************************************************************/

#ifndef _UNISTD_H
#define _UNISTD_H

#include <stddef.h>

typedef long ssize_t;

extern int open(const char *name, int flags);
extern int close(int fd);
extern ssize_t read(int fd, void *buf, size_t count);
extern ssize_t write(int fd, const void *buf, size_t count);
extern ssize_t lseek(int fd, long offset, int whence);

#endif

@ -0,0 +1,26 @@
/******************************************************************************
* Copyright (c) 2004, 2008 IBM Corporation
* All rights reserved.
* This program and the accompanying materials
* are made available under the terms of the BSD License
* which accompanies this distribution, and is available at
* http://www.opensource.org/licenses/bsd-license.php
*
* Contributors:
* IBM Corporation - initial implementation
*****************************************************************************/

#include <compiler.h>
#include <ctype.h>

int __attrconst isdigit(int ch)
{
switch (ch) {
case '0': case '1': case '2': case '3': case '4':
case '5': case '6': case '7': case '8': case '9':
return 1;
default:
return 0;
}
}

@ -0,0 +1,19 @@
/******************************************************************************
* Copyright (c) 2004, 2008 IBM Corporation
* All rights reserved.
* This program and the accompanying materials
* are made available under the terms of the BSD License
* which accompanies this distribution, and is available at
* http://www.opensource.org/licenses/bsd-license.php
*
* Contributors:
* IBM Corporation - initial implementation
*****************************************************************************/

#include <compiler.h>
#include <ctype.h>

int __attrconst isprint(int ch)
{
return (ch >= 32 && ch < 127);
}

@ -0,0 +1,30 @@
/******************************************************************************
* Copyright (c) 2004, 2008 IBM Corporation
* All rights reserved.
* This program and the accompanying materials
* are made available under the terms of the BSD License
* which accompanies this distribution, and is available at
* http://www.opensource.org/licenses/bsd-license.php
*
* Contributors:
* IBM Corporation - initial implementation
*****************************************************************************/

#include <compiler.h>
#include <ctype.h>

int __attrconst isspace(int ch)
{
switch (ch) {
case ' ':
case '\f':
case '\n':
case '\r':
case '\t':
case '\v':
return 1;
default:
return 0;
}
}

@ -0,0 +1,22 @@
/******************************************************************************
* Copyright (c) 2004, 2008 IBM Corporation
* All rights reserved.
* This program and the accompanying materials
* are made available under the terms of the BSD License
* which accompanies this distribution, and is available at
* http://www.opensource.org/licenses/bsd-license.php
*
* Contributors:
* IBM Corporation - initial implementation
*****************************************************************************/

#include <compiler.h>
#include <ctype.h>

int __attrconst isxdigit(int ch)
{
return (
(ch >= '0' && ch <= '9') |
(ch >= 'A' && ch <= 'F') |
(ch >= 'a' && ch <= 'f') );
}

@ -0,0 +1,28 @@
/******************************************************************************
* Copyright (c) 2004, 2008 IBM Corporation
* All rights reserved.
* This program and the accompanying materials
* are made available under the terms of the BSD License
* which accompanies this distribution, and is available at
* http://www.opensource.org/licenses/bsd-license.php
*
* Contributors:
* IBM Corporation - initial implementation
*****************************************************************************/

#include <stddef.h>

void *memchr(const void *ptr, int c, size_t n);
void *memchr(const void *ptr, int c, size_t n)
{
unsigned char ch = (unsigned char)c;
const unsigned char *p = ptr;

while (n-- > 0) {
if (*p == ch)
return (void *)p;
p += 1;
}

return NULL;
}

@ -0,0 +1,29 @@
/******************************************************************************
* Copyright (c) 2004, 2008 IBM Corporation
* All rights reserved.
* This program and the accompanying materials
* are made available under the terms of the BSD License
* which accompanies this distribution, and is available at
* http://www.opensource.org/licenses/bsd-license.php
*
* Contributors:
* IBM Corporation - initial implementation
*****************************************************************************/

#include <stddef.h>

int memcmp(const void *ptr1, const void *ptr2, size_t n);
int memcmp(const void *ptr1, const void *ptr2, size_t n)
{
const unsigned char *p1 = ptr1;
const unsigned char *p2 = ptr2;

while (n-- > 0) {
if (*p1 != *p2)
return (*p1 - *p2);
p1 += 1;
p2 += 1;
}

return 0;
}

@ -0,0 +1,36 @@
/******************************************************************************
* Copyright (c) 2004, 2008 IBM Corporation
* All rights reserved.
* This program and the accompanying materials
* are made available under the terms of the BSD License
* which accompanies this distribution, and is available at
* http://www.opensource.org/licenses/bsd-license.php
*
* Contributors:
* IBM Corporation - initial implementation
*****************************************************************************/

#include <stddef.h>
#include <stdint.h>

void *memcpy(void *dest, const void *src, size_t n);
void *memcpy(void *dest, const void *src, size_t n)
{
void *ret = dest;

while (n >= 8) {
*(uint64_t *)dest = *(uint64_t *)src;
dest += 8;
src += 8;
n -= 8;
}

while (n > 0) {
*(uint8_t *)dest = *(uint8_t *)src;
dest += 1;
src += 1;
n -= 1;
}

return ret;
}

@ -0,0 +1,36 @@
/******************************************************************************
* Copyright (c) 2004, 2008 IBM Corporation
* All rights reserved.
* This program and the accompanying materials
* are made available under the terms of the BSD License
* which accompanies this distribution, and is available at
* http://www.opensource.org/licenses/bsd-license.php
*
* Contributors:
* IBM Corporation - initial implementation
*****************************************************************************/

#include <stddef.h>

void *memcpy(void *dest, const void *src, size_t n);
void *memmove(void *dest, const void *src, size_t n);
void *memmove(void *dest, const void *src, size_t n)
{
/* Do the buffers overlap in a bad way? */
if (src < dest && src + n >= dest) {
char *cdest;
const char *csrc;
int i;

/* Copy from end to start */
cdest = dest + n - 1;
csrc = src + n - 1;
for (i = 0; i < n; i++) {
*cdest-- = *csrc--;
}
return dest;
} else {
/* Normal copy is possible */
return memcpy(dest, src, n);
}
}

@ -0,0 +1,40 @@
/******************************************************************************
* Copyright (c) 2004, 2008 IBM Corporation
* All rights reserved.
* This program and the accompanying materials
* are made available under the terms of the BSD License
* which accompanies this distribution, and is available at
* http://www.opensource.org/licenses/bsd-license.php
*
* Contributors:
* IBM Corporation - initial implementation
*****************************************************************************/

#define CACHE_LINE_SIZE 128

#include <stddef.h>

void *memset(void *dest, int c, size_t size);
void *memset(void *dest, int c, size_t size)
{
unsigned char *d = (unsigned char *)dest;
unsigned long big_c = 0;

if (c) {
big_c = c;
big_c |= (big_c << 8) | big_c;
big_c |= (big_c << 16) | big_c;
big_c |= (big_c << 32) | big_c;
}
while (size >= 8 && c == 0) {
*((unsigned long *)d) = big_c;
d+=8;
size-=8;
}

while (size-- > 0) {
*d++ = (unsigned char)c;
}

return dest;
}

@ -0,0 +1,27 @@
/******************************************************************************
* Copyright (c) 2004, 2008 IBM Corporation
* All rights reserved.
* This program and the accompanying materials
* are made available under the terms of the BSD License
* which accompanies this distribution, and is available at
* http://www.opensource.org/licenses/bsd-license.php
*
* Contributors:
* IBM Corporation - initial implementation
*****************************************************************************/

#include <ctype.h>

int strcasecmp(const char *s1, const char *s2);
int strcasecmp(const char *s1, const char *s2)
{
while (*s1 != 0 && *s2 != 0) {
if (toupper(*s1) != toupper(*s2))
break;
++s1;
++s2;
}

return *s1 - *s2;
}

@ -0,0 +1,26 @@
/******************************************************************************
* Copyright (c) 2004, 2008 IBM Corporation
* All rights reserved.
* This program and the accompanying materials
* are made available under the terms of the BSD License
* which accompanies this distribution, and is available at
* http://www.opensource.org/licenses/bsd-license.php
*
* Contributors:
* IBM Corporation - initial implementation
*****************************************************************************/

#include <stddef.h>

size_t strlen(const char *s);
char *strcpy(char *dst, const char *src);
char *strcat(char *dst, const char *src);
char *strcat(char *dst, const char *src)
{
size_t p;

p = strlen(dst);
strcpy(&dst[p], src);

return dst;
}

@ -0,0 +1,28 @@
/******************************************************************************
* Copyright (c) 2004, 2008 IBM Corporation
* All rights reserved.
* This program and the accompanying materials
* are made available under the terms of the BSD License
* which accompanies this distribution, and is available at
* http://www.opensource.org/licenses/bsd-license.php
*
* Contributors:
* IBM Corporation - initial implementation
*****************************************************************************/

#include <stddef.h>

char *strchr(const char *s, int c);
char *strchr(const char *s, int c)
{
char cb = c;

while (*s != 0) {
if (*s == cb) {
return (char *)s;
}
s += 1;
}

return NULL;
}

@ -0,0 +1,25 @@
/******************************************************************************
* Copyright (c) 2004, 2008 IBM Corporation
* All rights reserved.
* This program and the accompanying materials
* are made available under the terms of the BSD License
* which accompanies this distribution, and is available at
* http://www.opensource.org/licenses/bsd-license.php
*
* Contributors:
* IBM Corporation - initial implementation
*****************************************************************************/

int strcmp(const char *s1, const char *s2);
int strcmp(const char *s1, const char *s2)
{
while (*s1 != 0 && *s2 != 0) {
if (*s1 != *s2)
break;
s1 += 1;
s2 += 1;
}

return *s1 - *s2;
}

@ -0,0 +1,23 @@
/******************************************************************************
* Copyright (c) 2004, 2008 IBM Corporation
* All rights reserved.
* This program and the accompanying materials
* are made available under the terms of the BSD License
* which accompanies this distribution, and is available at
* http://www.opensource.org/licenses/bsd-license.php
*
* Contributors:
* IBM Corporation - initial implementation
*****************************************************************************/

char *strcpy(char *dst, const char *src);
char *strcpy(char *dst, const char *src)
{
char *ptr = dst;

do {
*ptr++ = *src;
} while (*src++ != 0);

return dst;
}

@ -0,0 +1,40 @@
/******************************************************************************
* Copyright (c) 2004, 2008 IBM Corporation
* All rights reserved.
* This program and the accompanying materials
* are made available under the terms of the BSD License
* which accompanies this distribution, and is available at
* http://www.opensource.org/licenses/bsd-license.php
*
* Contributors:
* IBM Corporation - initial implementation
*****************************************************************************/

#include <stddef.h>

size_t strlen(const char *s);
size_t strlen(const char *s)
{
size_t len = 0;

while (*s != 0) {
len += 1;
s += 1;
}

return len;
}

size_t strnlen(const char *s, size_t n);
size_t strnlen(const char *s, size_t n)
{
size_t len = 0;

while (*s != 0 && n) {
len += 1;
s += 1;
n--;
}

return len;
}

@ -0,0 +1,30 @@
/******************************************************************************
* Copyright (c) 2004, 2008 IBM Corporation
* All rights reserved.
* This program and the accompanying materials
* are made available under the terms of the BSD License
* which accompanies this distribution, and is available at
* http://www.opensource.org/licenses/bsd-license.php
*
* Contributors:
* IBM Corporation - initial implementation
*****************************************************************************/

#include <ctype.h>

int strncasecmp(const char *s1, const char *s2, size_t n);
int strncasecmp(const char *s1, const char *s2, size_t n)
{
if (n < 1)
return 0;

while (*s1 != 0 && *s2 != 0 && --n > 0) {
if (toupper(*s1) != toupper(*s2))
break;
++s1;
++s2;
}

return toupper(*s1) - toupper(*s2);
}

@ -0,0 +1,30 @@
/******************************************************************************
* Copyright (c) 2004, 2008 IBM Corporation
* All rights reserved.
* This program and the accompanying materials
* are made available under the terms of the BSD License
* which accompanies this distribution, and is available at
* http://www.opensource.org/licenses/bsd-license.php
*
* Contributors:
* IBM Corporation - initial implementation
*****************************************************************************/

#include <stddef.h>

int strncmp(const char *s1, const char *s2, size_t n);
int strncmp(const char *s1, const char *s2, size_t n)
{
if (n < 1)
return 0;

while (*s1 != 0 && *s2 != 0 && --n > 0) {
if (*s1 != *s2)
break;
s1 += 1;
s2 += 1;
}

return *s1 - *s2;
}

@ -0,0 +1,33 @@
/******************************************************************************
* Copyright (c) 2004, 2008 IBM Corporation
* All rights reserved.
* This program and the accompanying materials
* are made available under the terms of the BSD License
* which accompanies this distribution, and is available at
* http://www.opensource.org/licenses/bsd-license.php
*
* Contributors:
* IBM Corporation - initial implementation
*****************************************************************************/

#include <stddef.h>

char *strncpy(char *dst, const char *src, size_t n);
char *strncpy(char *dst, const char *src, size_t n)
{
char *ret = dst;

/* Copy string */
while (*src != 0 && n > 0) {
*dst++ = *src++;
n -= 1;
}

/* strncpy always clears the rest of destination string... */
while (n > 0) {
*dst++ = 0;
n -= 1;
}

return ret;
}

@ -0,0 +1,28 @@
/******************************************************************************
* Copyright (c) 2004, 2008, 2019 IBM Corporation
* All rights reserved.
* This program and the accompanying materials
* are made available under the terms of the BSD License
* which accompanies this distribution, and is available at
* http://www.opensource.org/licenses/bsd-license.php
*
* Contributors:
* IBM Corporation - initial implementation
*****************************************************************************/

#include <stddef.h>

char *strrchr(const char *s, int c);
char *strrchr(const char *s, int c)
{
char *last = NULL;
char cb = c;

while (*s != 0) {
if (*s == cb)
last = (char *)s;
s += 1;
}

return last;
}

@ -0,0 +1,39 @@
/******************************************************************************
* Copyright (c) 2004, 2008 IBM Corporation
* All rights reserved.
* This program and the accompanying materials
* are made available under the terms of the BSD License
* which accompanies this distribution, and is available at
* http://www.opensource.org/licenses/bsd-license.php
*
* Contributors:
* IBM Corporation - initial implementation
*****************************************************************************/

#include <stddef.h>

size_t strlen(const char *s);
int strncmp(const char *s1, const char *s2, size_t n);
char *strstr(const char *hay, const char *needle);
char *strstr(const char *hay, const char *needle)
{
char *pos;
size_t hlen, nlen;

if (hay == NULL || needle == NULL)
return NULL;
hlen = strlen(hay);
nlen = strlen(needle);
if (nlen < 1)
return (char *)hay;

for (pos = (char *)hay; pos < hay + hlen; pos++) {
if (strncmp(pos, needle, nlen) == 0) {
return pos;
}
}

return NULL;
}

@ -0,0 +1,48 @@
/******************************************************************************
* Copyright (c) 2004, 2008 IBM Corporation
* All rights reserved.
* This program and the accompanying materials
* are made available under the terms of the BSD License
* which accompanies this distribution, and is available at
* http://www.opensource.org/licenses/bsd-license.php
*
* Contributors:
* IBM Corporation - initial implementation
*****************************************************************************/

#include <stddef.h>

char *strtok(char *src, const char *pattern);
char *strtok(char *src, const char *pattern)
{
static char *nxtTok;
char *retVal = NULL;

if (!src) {
src = nxtTok;
if (!src)
return retVal;
}

while (*src) {
const char *pp = pattern;
while (*pp) {
if (*pp == *src) {
break;
}
pp++;
}
if (!*pp) {
if (!retVal)
retVal = src;
else if (!src[-1])
break;
} else
*src = '\0';
src++;
}

nxtTok = src;

return retVal;
}

@ -0,0 +1,113 @@
/******************************************************************************
* Copyright (c) 2004, 2008 IBM Corporation
* All rights reserved.
* This program and the accompanying materials
* are made available under the terms of the BSD License
* which accompanies this distribution, and is available at
* http://www.opensource.org/licenses/bsd-license.php
*
* Contributors:
* IBM Corporation - initial implementation
*****************************************************************************/

#include <stdlib.h>

long int strtol(const char *S, char **PTR,int BASE)
{
long rval = 0;
short int negative = 0;
short int digit;
// *PTR is S, unless PTR is NULL, in which case i override it with my own ptr
char* ptr;
if (PTR == NULL)
{
//override
PTR = &ptr;
}
// i use PTR to advance through the string
*PTR = (char *) S;
//check if BASE is ok
if ((BASE < 0) || BASE > 36)
{
return 0;
}
// ignore white space at beginning of S
while ((**PTR == ' ')
|| (**PTR == '\t')
|| (**PTR == '\n')
|| (**PTR == '\r')
)
{
(*PTR)++;
}
// check if S starts with "-" in which case the return value is negative
if (**PTR == '-')
{
negative = 1;
(*PTR)++;
}
// if BASE is 0... determine the base from the first chars...
if (BASE == 0)
{
// if S starts with "0x", BASE = 16, else 10
if ((**PTR == '0') && (*((*PTR)+1) == 'x'))
{
BASE = 16;
}
else
{
BASE = 10;
}
}
if (BASE == 16)
{
// S may start with "0x"
if ((**PTR == '0') && (*((*PTR)+1) == 'x'))
{
(*PTR)++;
(*PTR)++;
}
}
//until end of string
while (**PTR)
{
if (((**PTR) >= '0') && ((**PTR) <= '9'))
{
//digit (0..9)
digit = **PTR - '0';
}
else if (((**PTR) >= 'a') && ((**PTR) <='z'))
{
//alphanumeric digit lowercase(a (10) .. z (35) )
digit = (**PTR - 'a') + 10;
}
else if (((**PTR) >= 'A') && ((**PTR) <='Z'))
{
//alphanumeric digit uppercase(a (10) .. z (35) )
digit = (**PTR - 'A') + 10;
}
else
{
//end of parseable number reached...
break;
}
if (digit < BASE)
{
rval = (rval * BASE) + digit;
}
else
{
//digit found, but its too big for current base
//end of parseable number reached...
break;
}
//next...
(*PTR)++;
}
if (negative)
{
return rval * -1;
}
//else
return rval;
}

@ -0,0 +1,103 @@
/******************************************************************************
* Copyright (c) 2004, 2008 IBM Corporation
* All rights reserved.
* This program and the accompanying materials
* are made available under the terms of the BSD License
* which accompanies this distribution, and is available at
* http://www.opensource.org/licenses/bsd-license.php
*
* Contributors:
* IBM Corporation - initial implementation
*****************************************************************************/

#include <stdlib.h>

unsigned long int strtoul(const char *S, char **PTR,int BASE)
{
unsigned long rval = 0;
short int digit;
// *PTR is S, unless PTR is NULL, in which case i override it with my own ptr
char* ptr;
if (PTR == NULL)
{
//override
PTR = &ptr;
}
// i use PTR to advance through the string
*PTR = (char *) S;
//check if BASE is ok
if ((BASE < 0) || BASE > 36)
{
return 0;
}
// ignore white space at beginning of S
while ((**PTR == ' ')
|| (**PTR == '\t')
|| (**PTR == '\n')
|| (**PTR == '\r')
)
{
(*PTR)++;
}
// if BASE is 0... determine the base from the first chars...
if (BASE == 0)
{
// if S starts with "0x", BASE = 16, else 10
if ((**PTR == '0') && (*((*PTR)+1) == 'x'))
{
BASE = 16;
}
else
{
BASE = 10;
}
}
if (BASE == 16)
{
// S may start with "0x"
if ((**PTR == '0') && (*((*PTR)+1) == 'x'))
{
(*PTR)++;
(*PTR)++;
}
}
//until end of string
while (**PTR)
{
if (((**PTR) >= '0') && ((**PTR) <='9'))
{
//digit (0..9)
digit = **PTR - '0';
}
else if (((**PTR) >= 'a') && ((**PTR) <='z'))
{
//alphanumeric digit lowercase(a (10) .. z (35) )
digit = (**PTR - 'a') + 10;
}
else if (((**PTR) >= 'A') && ((**PTR) <='Z'))
{
//alphanumeric digit uppercase(a (10) .. z (35) )
digit = (**PTR - 'A') + 10;
}
else
{
//end of parseable number reached...
break;
}
if (digit < BASE)
{
rval = (rval * BASE) + digit;
}
else
{
//digit found, but its too big for current base
//end of parseable number reached...
break;
}
//next...
(*PTR)++;
}
//done
return rval;
}

@ -0,0 +1,19 @@
/******************************************************************************
* Copyright (c) 2004, 2008 IBM Corporation
* All rights reserved.
* This program and the accompanying materials
* are made available under the terms of the BSD License
* which accompanies this distribution, and is available at
* http://www.opensource.org/licenses/bsd-license.php
*
* Contributors:
* IBM Corporation - initial implementation