summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--controller/fw/src/ldpc_wrapper.cpp84
-rw-r--r--controller/fw/src/main.c76
-rw-r--r--controller/fw/src/mspdebug_wrapper.c213
-rw-r--r--controller/fw/src/mspdebug_wrapper.h6
-rw-r--r--controller/fw/src/signal_processing.c0
-rw-r--r--controller/fw/src/spi_flash.c189
-rw-r--r--controller/fw/src/spi_flash.h31
-rw-r--r--controller/fw/src/sr_global.h8
-rw-r--r--controller/fw/src/tinyaes_adaptor.c13
9 files changed, 620 insertions, 0 deletions
diff --git a/controller/fw/src/ldpc_wrapper.cpp b/controller/fw/src/ldpc_wrapper.cpp
new file mode 100644
index 0000000..da63343
--- /dev/null
+++ b/controller/fw/src/ldpc_wrapper.cpp
@@ -0,0 +1,84 @@
+
+#include <stdlib.h>
+#include <algorithm>
+#include <cstdint>
+#include <cmath>
+
+#include "ldpc/generic.hh"
+#include "ldpc/layered_decoder.hh"
+
+static const int DEFAULT_TRIALS = 25;
+
+struct DVB_S2_TABLE_C9
+{
+ static const int M = 360;
+ static const int N = 16200;
+ static const int K = 13320;
+ static const int LINKS_MIN_CN = 15;
+ static const int LINKS_MAX_CN = 19;
+ static const int LINKS_TOTAL = 49319;
+ static const int DEG_MAX = 13;
+ static const int DEG[];
+ static const int LEN[];
+ static const int POS[];
+};
+
+const int DVB_S2_TABLE_C9::DEG[] = {
+ 13, 3, 0
+};
+
+const int DVB_S2_TABLE_C9::LEN[] = {
+ 1, 36, 0
+};
+
+const int DVB_S2_TABLE_C9::POS[] = {
+ 3, 2409, 499, 1481, 908, 559, 716, 1270, 333, 2508, 2264, 1702, 2805,
+ 4, 2447, 1926,
+ 5, 414, 1224,
+ 6, 2114, 842,
+ 7, 212, 573,
+ 0, 2383, 2112,
+ 1, 2286, 2348,
+ 2, 545, 819,
+ 3, 1264, 143,
+ 4, 1701, 2258,
+ 5, 964, 166,
+ 6, 114, 2413,
+ 7, 2243, 81,
+ 0, 1245, 1581,
+ 1, 775, 169,
+ 2, 1696, 1104,
+ 3, 1914, 2831,
+ 4, 532, 1450,
+ 5, 91, 974,
+ 6, 497, 2228,
+ 7, 2326, 1579,
+ 0, 2482, 256,
+ 1, 1117, 1261,
+ 2, 1257, 1658,
+ 3, 1478, 1225,
+ 4, 2511, 980,
+ 5, 2320, 2675,
+ 6, 435, 1278,
+ 7, 228, 503,
+ 0, 1885, 2369,
+ 1, 57, 483,
+ 2, 838, 1050,
+ 3, 1231, 1990,
+ 4, 1738, 68,
+ 5, 2392, 951,
+ 6, 163, 645,
+ 7, 2644, 1704,
+};
+
+extern "C" {
+
+ int ldpc_decode(float *symbols, int trials) {
+ if (trials < 0)
+ trials = DEFAULT_TRIALS;
+
+ LDPCDecoder<float, SumProductAlgorithm<float, SelfCorrectedUpdate<float>>, LDPC<DVB_S2_TABLE_C9>> decoder;
+ return decoder.run(symbols, symbols+decoder.K, trials, 1);
+ }
+
+}
diff --git a/controller/fw/src/main.c b/controller/fw/src/main.c
new file mode 100644
index 0000000..3131df1
--- /dev/null
+++ b/controller/fw/src/main.c
@@ -0,0 +1,76 @@
+
+#include <stdbool.h>
+
+#include <libopencm3/stm32/rcc.h>
+#include <libopencm3/stm32/spi.h>
+#include <libopencm3/stm32/gpio.h>
+
+#include "spi_flash.h"
+
+static struct spi_flash_if spif;
+
+static void clock_setup(void)
+{
+ rcc_clock_setup_pll(&rcc_hse_8mhz_3v3[RCC_CLOCK_3V3_168MHZ]);
+ rcc_periph_clock_enable(RCC_GPIOA);
+ rcc_periph_clock_enable(RCC_GPIOB);
+ rcc_periph_clock_enable(RCC_SPI1);
+}
+
+static void led_setup(void)
+{
+ gpio_mode_setup(GPIOA, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, GPIO6 | GPIO7);
+}
+
+static void spi_flash_if_set_cs(bool val) {
+ if (val)
+ gpio_set(GPIOB, GPIO0);
+ else
+ gpio_clear(GPIOB, GPIO0);
+}
+
+static void spi_flash_setup(void)
+{
+ gpio_mode_setup(GPIOB, GPIO_MODE_AF, GPIO_PUPD_NONE, GPIO3 | GPIO4 | GPIO5); /* SPI flash SCK/MISO/MOSI */
+ gpio_mode_setup(GPIOB, GPIO_MODE_OUTPUT, GPIO_PUPD_NONE, GPIO0); /* SPI flash CS */
+ gpio_set_output_options(GPIOB, GPIO_OTYPE_PP, GPIO_OSPEED_50MHZ, GPIO0 | GPIO3 | GPIO4 | GPIO5);
+ gpio_set_af(GPIOB, 5, GPIO3 | GPIO4 | GPIO5);
+
+ spif_init(&spif, 256, SPI1, &spi_flash_if_set_cs);
+}
+
+/*
+void spi_flash_test(void) {
+ spif_clear_mem(&spif);
+
+ uint32_t buf[1024];
+ for (size_t addr=0; addr<0x10000; addr += sizeof(buf)) {
+ for (size_t i=0; i<sizeof(buf); i+= sizeof(buf[0]))
+ buf[i/sizeof(buf[0])] = addr + i;
+
+ spif_write(&spif, addr, sizeof(buf), (char *)buf);
+ }
+
+ for (size_t i=0; i<sizeof(buf)/sizeof(buf[0]); i++)
+ buf[i] = 0;
+ spif_read(&spif, 0x1030, sizeof(buf), (char *)buf);
+ asm volatile ("bkpt");
+}
+*/
+
+int main(void)
+{
+ clock_setup();
+ led_setup();
+ spi_flash_setup();
+
+ gpio_set(GPIOA, GPIO6);
+
+ while (1) {
+ gpio_toggle(GPIOA, GPIO6 | GPIO7);
+ for (int i = 0; i < 6000000; i++)
+ __asm__("nop");
+ }
+
+ return 0;
+}
diff --git a/controller/fw/src/mspdebug_wrapper.c b/controller/fw/src/mspdebug_wrapper.c
new file mode 100644
index 0000000..3a6d526
--- /dev/null
+++ b/controller/fw/src/mspdebug_wrapper.c
@@ -0,0 +1,213 @@
+
+#include <unistd.h>
+#include <errno.h>
+
+#include <libopencm3/stm32/gpio.h>
+
+#include "output.h"
+#include "jtaglib.h"
+
+#include "sr_global.h"
+#include "mspdebug_wrapper.h"
+
+#define BLOCK_SIZE 512 /* bytes */
+
+
+static struct jtdev sr_jtdev;
+
+
+int flash_and_reset(size_t img_start, size_t img_len, ssize_t (*read_block)(int addr, size_t len, uint8_t *out))
+{
+ union {
+ uint8_t bytes[BLOCK_SIZE];
+ uint16_t words[BLOCK_SIZE/2];
+ } block;
+
+ /* Initialize JTAG connection */
+ unsigned int jtag_id = jtag_init(&sr_jtdev);
+
+ if (sr_jtdev.failed)
+ return -EPIPE;
+
+ if (jtag_id != 0x89 && jtag_id != 0x91)
+ return -EINVAL;
+
+ /* Clear flash */
+ jtag_erase_flash(&sr_jtdev, JTAG_ERASE_MAIN, 0);
+ if (sr_jtdev.failed)
+ return -EPIPE;
+
+ /* Write flash */
+ for (size_t p = img_start; p < img_start + img_len; p += BLOCK_SIZE) {
+ ssize_t nin = read_block(p, BLOCK_SIZE, block.bytes);
+
+ if (nin < 0)
+ return nin;
+
+ if (nin & 1) { /* pad unaligned */
+ block.bytes[nin] = 0;
+ nin ++;
+ }
+
+ /* Convert to little-endian */
+ for (ssize_t i=0; i<nin/2; i++)
+ block.words[i] = htole(block.words[i]);
+
+ jtag_write_flash(&sr_jtdev, p, nin/2, block.words);
+ if (sr_jtdev.failed)
+ return -EPIPE;
+ }
+
+ /* Verify flash */
+ /* FIXME
+ word = jtag_read_mem(NULL, 16, addr+index );
+ */
+
+ /* Execute power on reset */
+ jtag_execute_puc(&sr_jtdev);
+ if (sr_jtdev.failed)
+ return -EPIPE;
+
+ return 0;
+}
+
+/* mspdebug HAL shim */
+
+int printc_err(const char *fmt, ...) {
+ UNUSED(fmt);
+ /* ignore */
+ return 0;
+}
+
+
+static void sr_jtdev_power_on(struct jtdev *p) {
+ UNUSED(p);
+ /* ignore */
+}
+
+static void sr_jtdev_connect(struct jtdev *p) {
+ UNUSED(p);
+ /* ignore */
+}
+
+enum sr_gpio_types {
+ SR_GPIO_TCK,
+ SR_GPIO_TMS,
+ SR_GPIO_TDI,
+ SR_GPIO_RST,
+ SR_GPIO_TST,
+ SR_GPIO_TDO,
+ SR_NUM_GPIOS
+};
+
+struct {
+ uint32_t port;
+ uint16_t num;
+} gpios[SR_NUM_GPIOS] = {
+ [SR_GPIO_TCK] = {GPIOD, 8},
+ [SR_GPIO_TMS] = {GPIOD, 9},
+ [SR_GPIO_TDI] = {GPIOD, 10},
+ [SR_GPIO_RST] = {GPIOD, 11},
+ [SR_GPIO_TST] = {GPIOD, 12},
+ [SR_GPIO_TDO] = {GPIOD, 13},
+};
+
+static void sr_gpio_write(int num, int out) {
+ if (out)
+ gpio_set(gpios[num].port, gpios[num].num);
+ else
+ gpio_clear(gpios[num].port, gpios[num].num);
+}
+
+static void sr_jtdev_tck(struct jtdev *p, int out) {
+ UNUSED(p);
+ sr_gpio_write(SR_GPIO_TCK, out);
+}
+
+static void sr_jtdev_tms(struct jtdev *p, int out) {
+ UNUSED(p);
+ sr_gpio_write(SR_GPIO_TMS, out);
+}
+
+static void sr_jtdev_tdi(struct jtdev *p, int out) {
+ UNUSED(p);
+ sr_gpio_write(SR_GPIO_TDI, out);
+}
+
+static void sr_jtdev_rst(struct jtdev *p, int out) {
+ UNUSED(p);
+ sr_gpio_write(SR_GPIO_RST, out);
+}
+
+static void sr_jtdev_tst(struct jtdev *p, int out) {
+ UNUSED(p);
+ sr_gpio_write(SR_GPIO_TST, out);
+}
+
+static int sr_jtdev_tdo_get(struct jtdev *p) {
+ UNUSED(p);
+ return gpio_get(gpios[SR_GPIO_TST].port, gpios[SR_GPIO_TST].num);
+}
+
+static void sr_jtdev_tclk(struct jtdev *p, int out) {
+ UNUSED(p);
+ sr_gpio_write(SR_GPIO_TST, out);
+}
+
+static int sr_jtdev_tclk_get(struct jtdev *p) {
+ UNUSED(p);
+ return gpio_get(gpios[SR_GPIO_TDI].port, gpios[SR_GPIO_TDI].num);
+}
+
+static void sr_jtdev_tclk_strobe(struct jtdev *p, unsigned int count) {
+ UNUSED(p);
+ while (count--) {
+ gpio_set(gpios[SR_GPIO_TDI].port, gpios[SR_GPIO_TDI].num);
+ gpio_clear(gpios[SR_GPIO_TDI].port, gpios[SR_GPIO_TDI].num);
+ }
+}
+
+static void sr_jtdev_led_green(struct jtdev *p, int out) {
+ UNUSED(p);
+ UNUSED(out);
+ /* ignore */
+}
+
+static void sr_jtdev_led_red(struct jtdev *p, int out) {
+ UNUSED(p);
+ UNUSED(out);
+ /* ignore */
+}
+
+
+static struct jtdev_func sr_jtdev_vtable = {
+ .jtdev_open = NULL,
+ .jtdev_close = NULL,
+
+ .jtdev_power_off = NULL,
+ .jtdev_release = NULL,
+
+ .jtdev_power_on = sr_jtdev_power_on,
+ .jtdev_connect = sr_jtdev_connect,
+
+ .jtdev_tck = sr_jtdev_tck,
+ .jtdev_tms = sr_jtdev_tms,
+ .jtdev_tdi = sr_jtdev_tdi,
+ .jtdev_rst = sr_jtdev_rst,
+ .jtdev_tst = sr_jtdev_tst,
+ .jtdev_tdo_get = sr_jtdev_tdo_get,
+
+ .jtdev_tclk = sr_jtdev_tclk,
+ .jtdev_tclk_get = sr_jtdev_tclk_get,
+ .jtdev_tclk_strobe = sr_jtdev_tclk_strobe,
+
+ .jtdev_led_green = sr_jtdev_led_green,
+ .jtdev_led_red = sr_jtdev_led_red,
+
+};
+
+static struct jtdev sr_jtdev = {
+ 0,
+ .f = &sr_jtdev_vtable
+};
+
diff --git a/controller/fw/src/mspdebug_wrapper.h b/controller/fw/src/mspdebug_wrapper.h
new file mode 100644
index 0000000..245d9fb
--- /dev/null
+++ b/controller/fw/src/mspdebug_wrapper.h
@@ -0,0 +1,6 @@
+#ifndef __MSPDEBUG_WRAPPER_H__
+#define __MSPDEBUG_WRAPPER_H__
+
+int flash_and_reset(size_t img_start, size_t img_len, ssize_t (*read_block)(int addr, size_t len, uint8_t *out));
+
+#endif /* __MSPDEBUG_WRAPPER_H__ */
diff --git a/controller/fw/src/signal_processing.c b/controller/fw/src/signal_processing.c
new file mode 100644
index 0000000..e69de29
--- /dev/null
+++ b/controller/fw/src/signal_processing.c
diff --git a/controller/fw/src/spi_flash.c b/controller/fw/src/spi_flash.c
new file mode 100644
index 0000000..98c773f
--- /dev/null
+++ b/controller/fw/src/spi_flash.c
@@ -0,0 +1,189 @@
+/* Library for SPI flash 25* devices.
+ * Copyright (c) 2014 Multi-Tech Systems
+ * Copyright (c) 2020 Jan Goette <ma@jaseg.de>
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+ * SOFTWARE.
+ */
+
+#include "spi_flash.h"
+#include <libopencm3/stm32/spi.h>
+
+enum {
+ WRITE_ENABLE = 0x06,
+ WRITE_DISABLE = 0x04,
+ READ_IDENTIFICATION = 0x9F,
+ READ_STATUS = 0x05,
+ WRITE_STATUS = 0x01,
+ READ_DATA = 0x03,
+ READ_DATA_FAST = 0x0B,
+ PAGE_PROGRAM = 0x02,
+ SECTOR_ERASE = 0xD8,
+ BULK_ERASE = 0xC7,
+ DEEP_POWER_DOWN = 0xB9,
+ DEEP_POWER_DOWN_RELEASE = 0xAB,
+};
+
+enum {
+ STATUS_SRWD = 0x80, // 0b 1000 0000
+ STATUS_BP2 = 0x10, // 0b 0001 0000
+ STATUS_BP1 = 0x08, // 0b 0000 1000
+ STATUS_BP0 = 0x04, // 0b 0000 0100
+ STATUS_WEL = 0x02, // 0b 0000 0010
+ STATUS_WIP = 0x01, // 0b 0000 0001
+};
+
+
+static void spif_write_page(struct spi_flash_if *spif, size_t addr, size_t len, const char* data);
+static uint8_t spif_read_status(struct spi_flash_if *spif);
+static void spif_enable_write(struct spi_flash_if *spif);
+static void spif_wait_for_write(struct spi_flash_if *spif);
+
+#define low_byte(x) (x&0xff)
+#define mid_byte(x) ((x>>8)&0xff)
+#define high_byte(x) ((x>>16)&0xff)
+
+
+void spif_init(struct spi_flash_if *spif, size_t page_size, uint32_t spi_base, void (*cs)(bool val)) {
+
+ spif->spi_base = spi_base;
+ spif->page_size = page_size;
+ spif->cs = cs;
+ spif->cs(1);
+
+ spi_reset(spif->spi_base);
+ spi_init_master(spif->spi_base,
+ SPI_CR1_BAUDRATE_FPCLK_DIV_2,
+ SPI_CR1_CPOL_CLK_TO_1_WHEN_IDLE,
+ SPI_CR1_CPHA_CLK_TRANSITION_2,
+ SPI_CR1_DFF_8BIT,
+ SPI_CR1_MSBFIRST);
+
+ spi_enable_software_slave_management(spif->spi_base);
+ spi_set_nss_high(spif->spi_base);
+
+ spi_enable(spif->spi_base);
+
+ spif->cs(0);
+ spi_send(spif->spi_base, READ_IDENTIFICATION);
+ spif->id.mfg_id = spi_xfer(spif->spi_base, 0);
+ spif->id.type = spi_xfer(spif->spi_base, 0);
+ spif->id.size = 1<<spi_xfer(spif->spi_base, 0);
+ spif->cs(1);
+}
+
+void spif_read(struct spi_flash_if *spif, size_t addr, size_t len, char* data) {
+ spif_enable_write(spif);
+
+ spif->cs(0);
+ spi_xfer(spif->spi_base, READ_DATA);
+ spi_xfer(spif->spi_base, high_byte(addr));
+ spi_xfer(spif->spi_base, mid_byte(addr));
+ spi_xfer(spif->spi_base, low_byte(addr));
+
+ for (size_t i = 0; i < len; i++)
+ data[i] = spi_xfer(spif->spi_base, 0);
+
+ spif->cs(1);
+}
+
+void spif_write(struct spi_flash_if *spif, size_t addr, size_t len, const char* data) {
+ size_t written = 0, write_size = 0;
+
+ while (written < len) {
+ write_size = spif->page_size - ((addr + written) % spif->page_size);
+ if (written + write_size > len)
+ write_size = len - written;
+
+ spif_write_page(spif, addr + written, write_size, data + written);
+ written += write_size;
+ }
+}
+
+static uint8_t spif_read_status(struct spi_flash_if *spif) {
+ spif->cs(0);
+ spi_xfer(spif->spi_base, READ_STATUS);
+ uint8_t status = spi_xfer(spif->spi_base, 0);
+ spif->cs(1);
+
+ return status;
+}
+
+void spif_clear_sector(struct spi_flash_if *spif, size_t addr) {
+ spif_enable_write(spif);
+
+ spif->cs(0);
+ spi_xfer(spif->spi_base, SECTOR_ERASE);
+ spi_xfer(spif->spi_base, high_byte(addr));
+ spi_xfer(spif->spi_base, mid_byte(addr));
+ spi_xfer(spif->spi_base, low_byte(addr));
+ spif->cs(1);
+
+ spif_wait_for_write(spif);
+}
+
+void spif_clear_mem(struct spi_flash_if *spif) {
+ spif_enable_write(spif);
+
+ spif->cs(0);
+ spi_xfer(spif->spi_base, BULK_ERASE);
+ spif->cs(1);
+
+ spif_wait_for_write(spif);
+}
+
+static void spif_write_page(struct spi_flash_if *spif, size_t addr, size_t len, const char* data) {
+ spif_enable_write(spif);
+
+ spif->cs(0);
+ spi_xfer(spif->spi_base, PAGE_PROGRAM);
+ spi_xfer(spif->spi_base, high_byte(addr));
+ spi_xfer(spif->spi_base, mid_byte(addr));
+ spi_xfer(spif->spi_base, low_byte(addr));
+
+ for (size_t i = 0; i < len; i++) {
+ spi_xfer(spif->spi_base, data[i]);
+ }
+
+ spif->cs(1);
+ spif_wait_for_write(spif);
+}
+
+static void spif_enable_write(struct spi_flash_if *spif) {
+ spif->cs(0);
+ spi_xfer(spif->spi_base, WRITE_ENABLE);
+ spif->cs(1);
+}
+
+static void spif_wait_for_write(struct spi_flash_if *spif) {
+ while (spif_read_status(spif) & STATUS_WIP)
+ for (int i = 0; i < 800; i++)
+ ;
+}
+
+void spif_deep_power_down(struct spi_flash_if *spif) {
+ spif->cs(0);
+ spi_xfer(spif->spi_base, DEEP_POWER_DOWN);
+ spif->cs(1);
+}
+
+void spif_wakeup(struct spi_flash_if *spif) {
+ spif->cs(0);
+ spi_xfer(spif->spi_base, DEEP_POWER_DOWN_RELEASE);
+ spif->cs(1);
+}
diff --git a/controller/fw/src/spi_flash.h b/controller/fw/src/spi_flash.h
new file mode 100644
index 0000000..e647c6a
--- /dev/null
+++ b/controller/fw/src/spi_flash.h
@@ -0,0 +1,31 @@
+#ifndef __SPI_FLASH_H__
+#define __SPI_FLASH_H__
+
+#include <stdbool.h>
+#include <unistd.h>
+
+struct spi_mem_id {
+ size_t size;
+ uint8_t mfg_id;
+ uint8_t type;
+};
+
+struct spi_flash_if {
+ struct spi_mem_id id;
+ uint32_t spi_base;
+ size_t page_size;
+ void (*cs)(bool val);
+};
+
+void spif_init(struct spi_flash_if *spif, size_t page_size, uint32_t spi_base, void (*cs)(bool val));
+
+void spif_write(struct spi_flash_if *spif, size_t addr, size_t len, const char* data);
+void spif_read(struct spi_flash_if *spif, size_t addr, size_t len, char* data);
+
+void spif_clear_mem(struct spi_flash_if *spif);
+void spif_clear_sector(struct spi_flash_if *spif, size_t addr);
+
+void spif_deep_power_down(struct spi_flash_if *spif);
+void spif_wakeup(struct spi_flash_if *spif);
+
+#endif /* __SPI_FLASH_H__ */
diff --git a/controller/fw/src/sr_global.h b/controller/fw/src/sr_global.h
new file mode 100644
index 0000000..8aa219d
--- /dev/null
+++ b/controller/fw/src/sr_global.h
@@ -0,0 +1,8 @@
+#ifndef __SR_GLOBAL_H__
+#define __SR_GLOBAL_H__
+
+#define UNUSED(x) ((void) x)
+
+static inline uint16_t htole(uint16_t val) { return val; }
+
+#endif /* __SR_GLOBAL_H__ */
diff --git a/controller/fw/src/tinyaes_adaptor.c b/controller/fw/src/tinyaes_adaptor.c
new file mode 100644
index 0000000..2489e68
--- /dev/null
+++ b/controller/fw/src/tinyaes_adaptor.c
@@ -0,0 +1,13 @@
+
+#include <stddef.h>
+#include <string.h>
+
+void *memcpy(void *restrict dest, const void *restrict src, size_t n) {
+ unsigned char *d = dest;
+ const unsigned char *s = src;
+
+ while (n--)
+ *d++ = *s++;
+
+ return dest;
+}