aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--.gitignore1
-rw-r--r--Drivers/Makefile16
-rw-r--r--Makefile121
-rw-r--r--gettimeofday.c63
-rw-r--r--include/stm-fmc.h18
-rw-r--r--include/stm-init.h9
-rw-r--r--include/stm-led.h16
-rw-r--r--include/stm-uart.h17
-rw-r--r--libc/gettimeofday.c26
-rw-r--r--main.c33
-rw-r--r--printf.c (renamed from libc/printf.c)0
-rw-r--r--src/stm-uart.c76
-rw-r--r--stm-fmc.c (renamed from src/stm-fmc.c)36
-rw-r--r--stm-fmc.h45
-rw-r--r--stm-init.c (renamed from src/stm-init.c)44
-rw-r--r--stm-init.h43
-rw-r--r--stm-led.h50
-rw-r--r--stm-uart.c87
-rw-r--r--stm-uart.h49
-rw-r--r--stm32f4xx_hal_conf.h (renamed from include/stm32f4xx_hal_conf.h)0
-rw-r--r--stm32f4xx_hal_msp.c (renamed from src/stm32f4xx_hal_msp.c)0
-rw-r--r--stm32f4xx_it.c (renamed from src/stm32f4xx_it.c)0
-rw-r--r--stm32f4xx_it.h (renamed from include/stm32f4xx_it.h)0
-rw-r--r--syscalls.c (renamed from libc/syscalls.c)9
24 files changed, 521 insertions, 238 deletions
diff --git a/.gitignore b/.gitignore
index 890e4fe..e3b4b63 100644
--- a/.gitignore
+++ b/.gitignore
@@ -1,4 +1,5 @@
*.o
+*.mo
*.bin
*.elf
*.hex
diff --git a/Drivers/Makefile b/Drivers/Makefile
index 376eac0..29aae70 100644
--- a/Drivers/Makefile
+++ b/Drivers/Makefile
@@ -6,20 +6,20 @@ AR=arm-none-eabi-ar
vpath %.c STM32F4xx_HAL_Driver/Src
# Default STDPERIPH_SETTINGS to settings suitable for STM32F429BIT6 (dev-bridge rev01)
-STDPERIPH_SETTINGS ?= -DUSE_STDPERIPH_DRIVER -DSTM32F4XX -DSTM32F429xx
+#STDPERIPH_SETTINGS ?= -DUSE_STDPERIPH_DRIVER -DSTM32F4XX -DSTM32F429xx
-CFLAGS = -ggdb -O2 -Wall -Wextra -Warray-bounds
-CFLAGS += -mcpu=cortex-m4 -mthumb -mlittle-endian -mthumb-interwork
-CFLAGS += -mfloat-abi=hard -mfpu=fpv4-sp-d16
-CFLAGS += $(STDPERIPH_SETTINGS)
-CFLAGS += -ICMSIS/Include -ICMSIS/Device/ST/STM32F4xx/Include -ISTM32F4xx_HAL_Driver/Inc
+#CFLAGS += -ggdb -O2 -Wall -Wextra -Warray-bounds
+#CFLAGS += -mcpu=cortex-m4 -mthumb -mlittle-endian -mthumb-interwork
+#CFLAGS += -mfloat-abi=hard -mfpu=fpv4-sp-d16
+#CFLAGS += -ICMSIS/Include -ICMSIS/Device/ST/STM32F4xx/Include -ISTM32F4xx_HAL_Driver/Inc
+#CFLAGS += $(STDPERIPH_SETTINGS)
-SRCS = stm32f4xx_hal.c stm32f4xx_hal_msp_template.c \
+SRCS = stm32f4xx_hal.c stm32f4xx_hal_msp_template.c \
stm32f4xx_hal_adc.c stm32f4xx_hal_nand.c \
stm32f4xx_hal_adc_ex.c stm32f4xx_hal_nor.c \
stm32f4xx_hal_can.c stm32f4xx_hal_pccard.c \
stm32f4xx_hal_cortex.c stm32f4xx_hal_pcd.c \
- stm32f4xx_hal_crc.c stm32f4xx_hal_pwr.c \
+ stm32f4xx_hal_crc.c stm32f4xx_hal_pwr.c \
stm32f4xx_hal_cryp.c stm32f4xx_hal_pwr_ex.c \
stm32f4xx_hal_cryp_ex.c stm32f4xx_hal_rcc.c \
stm32f4xx_hal_dac.c stm32f4xx_hal_rcc_ex.c \
diff --git a/Makefile b/Makefile
index e98134a..4fd6c98 100644
--- a/Makefile
+++ b/Makefile
@@ -1,35 +1,57 @@
+# Copyright (c) 2015, SUNET
+#
+# Redistribution and use in source and binary forms, with or
+# without modification, are permitted provided that the following
+# conditions are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+#
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
+# STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
+# ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+
+# "stm32-native" projects
SELF-TESTS = fmc-test led-test short-test uart-test fmc-perf
+vpath %.c self-test
-LIBHAL-TESTS = cores test-bus test-hash test-aes-key-wrap test-pbkdf2 test-ecdsa #test-rsa
+# apps originally written for unix-like environment
+LIBHAL-TESTS = cores test-bus test-hash test-aes-key-wrap test-pbkdf2 #test-ecdsa #test-rsa
+vpath %.c libhal/tests libhal/utils
-# put your *.o targets here, make should handle the rest!
-SRCS = stm32f4xx_hal_msp.c stm32f4xx_it.c stm-fmc.c stm-init.c stm-uart.c
-
-TOPLEVEL=.
+# absolute path, because we're going to be passing -I cflags to sub-makes
+TOPLEVEL = $(shell pwd)
# Location of the Libraries folder from the STM32F0xx Standard Peripheral Library
-STD_PERIPH_LIB ?= $(TOPLEVEL)/Drivers
+STD_PERIPH_LIB = $(TOPLEVEL)/Drivers
-# Location of the linker scripts
-LDSCRIPT_INC ?= $(TOPLEVEL)/Device/ldscripts
+# linker script
+LDSCRIPT = $(TOPLEVEL)/Device/ldscripts/stm32f429bitx.ld
-# MCU selection parameters
-#
-STDPERIPH_SETTINGS ?= -DUSE_STDPERIPH_DRIVER -DSTM32F4XX -DSTM32F429xx
-#
-# For the dev-bridge rev01 board, use stm32f429bitx.ld.
-MCU_LINKSCRIPT ?= stm32f429bitx.ld
+# board-specific objects, to link into every project
+BOARD_OBJS = stm32f4xx_hal_msp.o stm32f4xx_it.o stm-fmc.o stm-init.o stm-uart.o \
+ Device/startup_stm32f429xx.o Device/system_stm32f4xx.o
-# add startup file to build
-#
-# For the dev-bridge rev01 board, use startup_stm32f429xx.s.
-SRCS += $(TOPLEVEL)/Device/startup_stm32f429xx.s
-SRCS += $(TOPLEVEL)/Device/system_stm32f4xx.c
-
-# that's it, no need to change anything below this line!
+# a few objects for libhal/test projects
+LIBC_OBJS = syscalls.o printf.o gettimeofday.o
-###################################################
+LIBS = $(STD_PERIPH_LIB)/libstmf4.a libhal/libhal.a thirdparty/libtfm/libtfm.a
+# cross-building tools
PREFIX=arm-none-eabi-
export CC=$(PREFIX)gcc
export AS=$(PREFIX)as
@@ -38,33 +60,20 @@ export OBJCOPY=$(PREFIX)objcopy
export OBJDUMP=$(PREFIX)objdump
export SIZE=$(PREFIX)size
-#CFLAGS = -ggdb -O2 -Wall -Wextra -Warray-bounds
-CFLAGS = -ggdb -O2 -Wall -Warray-bounds
+# whew, that's a lot of cflags
+CFLAGS = -ggdb -O2 -Wall -Warray-bounds #-Wextra
CFLAGS += -mcpu=cortex-m4 -mthumb -mlittle-endian -mthumb-interwork
CFLAGS += -mfloat-abi=hard -mfpu=fpv4-sp-d16
-CFLAGS += $(STDPERIPH_SETTINGS)
+CFLAGS += -DUSE_STDPERIPH_DRIVER -DSTM32F4XX -DSTM32F429xx
CFLAGS += -ffunction-sections -fdata-sections
CFLAGS += -Wl,--gc-sections
CFLAGS += -std=c99
-
-###################################################
-
-vpath %.c src self-test
-vpath %.a $(STD_PERIPH_LIB)
-
-IFLAGS += -I include -I $(STD_PERIPH_LIB) -I $(STD_PERIPH_LIB)/CMSIS/Device/ST/STM32F4xx/Include
-IFLAGS += -I $(STD_PERIPH_LIB)/CMSIS/Include -I $(STD_PERIPH_LIB)/STM32F4xx_HAL_Driver/Inc
-
-%.o: %.c
- $(CC) -c $(CFLAGS) $(IFLAGS) -o $@ $<
-
-OBJS = $(patsubst %.s,%.o, $(patsubst %.c,%.o, $(SRCS)))
-
-###################################################
-
-.PHONY: lib self-test
-
-LIBS = $(STD_PERIPH_LIB)/libstmf4.a libhal/libhal.a thirdparty/libtfm/libtfm.a
+CFLAGS += -I $(TOPLEVEL) -I $(STD_PERIPH_LIB)
+CFLAGS += -I $(STD_PERIPH_LIB)/CMSIS/Device/ST/STM32F4xx/Include
+CFLAGS += -I $(STD_PERIPH_LIB)/CMSIS/Include
+CFLAGS += -I $(STD_PERIPH_LIB)/STM32F4xx_HAL_Driver/Inc
+CFLAGS += -I libhal
+export CFLAGS
all: lib self-test libhal-tests
@@ -73,10 +82,8 @@ init:
lib: $(LIBS)
-export CFLAGS
-
$(STD_PERIPH_LIB)/libstmf4.a:
- $(MAKE) -C $(STD_PERIPH_LIB) STDPERIPH_SETTINGS="$(STDPERIPH_SETTINGS) -I $(PWD)/include"
+ $(MAKE) -C $(STD_PERIPH_LIB)
thirdparty/libtfm/libtfm.a:
$(MAKE) -C thirdparty/libtfm PREFIX=$(PREFIX)
@@ -86,8 +93,8 @@ libhal/libhal.a: hal_io_fmc.o thirdparty/libtfm/libtfm.a
self-test: $(SELF-TESTS:=.elf)
-%.elf: %.o $(OBJS) $(STD_PERIPH_LIB)/libstmf4.a
- $(CC) $(CFLAGS) $^ -o $@ -L$(LDSCRIPT_INC) -T$(MCU_LINKSCRIPT) -g -Wl,-Map=$*.map
+%.elf: %.o $(BOARD_OBJS) $(STD_PERIPH_LIB)/libstmf4.a
+ $(CC) $(CFLAGS) $^ -o $@ -T$(LDSCRIPT) -g -Wl,-Map=$*.map
$(OBJCOPY) -O ihex $*.elf $*.hex
$(OBJCOPY) -O binary $*.elf $*.bin
$(OBJDUMP) -St $*.elf >$*.lst
@@ -95,26 +102,23 @@ self-test: $(SELF-TESTS:=.elf)
libhal-tests: $(LIBHAL-TESTS:=.bin)
-vpath %.c libhal/tests
-CFLAGS += -I libhal
-
# .mo extension for files with main() that need to be wrapped as __main()
%.mo: %.c
- $(CC) -c $(CFLAGS) $(IFLAGS) -Dmain=__main -o $@ $<
+ $(CC) -c $(CFLAGS) -Dmain=__main -o $@ $<
-vpath %.c libc libhal/utils
-%.bin: %.mo main.o syscalls.o printf.o gettimeofday.o $(OBJS) $(LIBS)
- $(CC) $(CFLAGS) $^ -o $*.elf -L$(LDSCRIPT_INC) -T$(MCU_LINKSCRIPT) -g -Wl,-Map=$*.map
+%.bin: %.mo main.o $(BOARD_OBJS) $(LIBC_OBJS) $(LIBS)
+ $(CC) $(CFLAGS) $^ -o $*.elf -T$(LDSCRIPT) -g -Wl,-Map=$*.map
$(OBJCOPY) -O ihex $*.elf $*.hex
$(OBJCOPY) -O binary $*.elf $*.bin
$(OBJDUMP) -St $*.elf >$*.lst
$(SIZE) $*.elf
-.SECONDARY: $(OBJS) *.mo main.o syscalls.o printf.o gettimeofday.o
+# don't automatically delete objects, to avoid a lot of unnecessary rebuilding
+.SECONDARY: $(BOARD_OBJS) $(LIBC_OBJS)
clean:
find ./ -name '*~' | xargs rm -f
- rm -f $(OBJS) *.o *.mo
+ rm -f $(BOARD_OBJS) $(LIBC_OBJS) *.o *.mo
rm -f *.elf
rm -f *.hex
rm -f *.bin
@@ -125,4 +129,3 @@ distclean: clean
$(MAKE) -C $(STD_PERIPH_LIB) clean
$(MAKE) -C thirdparty/libtfm clean
$(MAKE) -C libhal clean
- $(MAKE) -C libc clean
diff --git a/gettimeofday.c b/gettimeofday.c
new file mode 100644
index 0000000..b13485d
--- /dev/null
+++ b/gettimeofday.c
@@ -0,0 +1,63 @@
+/*
+ * gettimeofday.c
+ * --------------
+ * A simple implementation of gettimeofday() for CMSIS.
+ * This assumes a 1ms SysTick. It obviously does not return the absolute time,
+ * just the time since boot, but it's only used to calculate elapsed time in
+ * code we're porting from unix.
+ *
+ * Copyright (c) 2015, NORDUnet A/S All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are
+ * met:
+ * - Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ *
+ * - Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the distribution.
+ *
+ * - Neither the name of the NORDUnet nor the names of its contributors may
+ * be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
+ * IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
+ * TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
+ * PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+ * HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+ * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
+ * TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
+ * PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
+ * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
+ * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#include <stdint.h>
+
+#include "stm32f4xx_hal.h"
+
+/* Don't #include <sys/time.h> because of conflicting prototype in newlib. */
+
+/* from the manpage */
+struct timeval {
+ time_t tv_sec; /* seconds */
+ suseconds_t tv_usec; /* microseconds */
+};
+
+struct timezone {
+ int tz_minuteswest; /* minutes west of Greenwich */
+ int tz_dsttime; /* type of DST correction */
+};
+
+int gettimeofday(struct timeval *tv, struct timezone *tz)
+{
+ uint32_t tick = HAL_GetTick(); /* uptime in ms */
+
+ tv->tv_sec = tick / 1000;
+ tv->tv_usec = (tick % 1000) * 1000;
+
+ return 0;
+}
diff --git a/include/stm-fmc.h b/include/stm-fmc.h
deleted file mode 100644
index cf9b77e..0000000
--- a/include/stm-fmc.h
+++ /dev/null
@@ -1,18 +0,0 @@
-//------------------------------------------------------------------------------
-// stm-fmc.h
-//------------------------------------------------------------------------------
-
-#include <stdint.h>
-
-//------------------------------------------------------------------------------
-// Prototypes
-//------------------------------------------------------------------------------
-void fmc_init(void);
-
-int fmc_write_32(uint32_t addr, uint32_t *data);
-int fmc_read_32(uint32_t addr, uint32_t *data);
-
-
-//------------------------------------------------------------------------------
-// EOF
-//------------------------------------------------------------------------------
diff --git a/include/stm-init.h b/include/stm-init.h
deleted file mode 100644
index fdf7dd0..0000000
--- a/include/stm-init.h
+++ /dev/null
@@ -1,9 +0,0 @@
-#ifndef __STM_INIT_H
-#define __STM_INIT_H
-
-#include "stm32f4xx_hal.h"
-
-extern void stm_init(void);
-extern void Error_Handler(void);
-
-#endif /* __STM_INIT_H */
diff --git a/include/stm-led.h b/include/stm-led.h
deleted file mode 100644
index bd2a1e3..0000000
--- a/include/stm-led.h
+++ /dev/null
@@ -1,16 +0,0 @@
-#ifndef __STM_LED_H
-#define __STM_LED_H
-
-#include "stm32f4xx_hal.h"
-
-#define LED_PORT GPIOJ
-#define LED_RED GPIO_PIN_1
-#define LED_YELLOW GPIO_PIN_2
-#define LED_GREEN GPIO_PIN_3
-#define LED_BLUE GPIO_PIN_4
-
-#define led_on(pin) HAL_GPIO_WritePin(LED_PORT,pin,SET)
-#define led_off(pin) HAL_GPIO_WritePin(LED_PORT,pin,RESET)
-#define led_toggle(pin) HAL_GPIO_TogglePin(LED_PORT,pin)
-
-#endif /* __STM_LED_H */
diff --git a/include/stm-uart.h b/include/stm-uart.h
deleted file mode 100644
index c57afd5..0000000
--- a/include/stm-uart.h
+++ /dev/null
@@ -1,17 +0,0 @@
-#ifndef __STM32_DEV_BRIDGE_UART_H
-#define __STM32_DEV_BRIDGE_UART_H
-
-#include "stm32f4xx_hal.h"
-
-#define USART2_BAUD_RATE 115200
-
-extern void MX_USART2_UART_Init(void);
-
-extern void uart_send_char(uint8_t ch);
-extern void uart_send_string(char *s);
-extern void uart_send_number(uint32_t num, uint8_t digits, uint8_t radix);
-#define uart_send_binary(num, bits) uart_send_number(num, bits, 2)
-#define uart_send_integer(num, digits) uart_send_number(num, digits, 10)
-#define uart_send_hex(num, digits) uart_send_number(num, digits, 16)
-
-#endif /* __STM32_DEV_BRIDGE_UART_H */
diff --git a/libc/gettimeofday.c b/libc/gettimeofday.c
deleted file mode 100644
index b0561c3..0000000
--- a/libc/gettimeofday.c
+++ /dev/null
@@ -1,26 +0,0 @@
-#include <stdint.h>
-
-#include "stm32f4xx_hal.h"
-
-/* Don't #include <sys/time.h> because of conflicting prototype in newlib. */
-
-/* from the manpage: */
-struct timeval {
- time_t tv_sec; /* seconds */
- suseconds_t tv_usec; /* microseconds */
-};
-
-struct timezone {
- int tz_minuteswest; /* minutes west of Greenwich */
- int tz_dsttime; /* type of DST correction */
-};
-
-int gettimeofday(struct timeval *tv, struct timezone *tz)
-{
- uint32_t tick = HAL_GetTick(); /* uptime in ms */
-
- tv->tv_sec = tick / 1000;
- tv->tv_usec = (tick % 1000) * 1000;
-
- return 0;
-}
diff --git a/main.c b/main.c
index 6d19a7e..dc72898 100644
--- a/main.c
+++ b/main.c
@@ -1,5 +1,36 @@
-/* A wrapper for test programs that contain main() (currently libhal/tests).
+/*
+ * main.c
+ * ------
+ * A wrapper for test programs that contain main() (currently libhal/tests).
* We compile them with -Dmain=__main, so we can do stm setup first.
+ *
+ * Copyright (c) 2015, NORDUnet A/S All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are
+ * met:
+ * - Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ *
+ * - Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the distribution.
+ *
+ * - Neither the name of the NORDUnet nor the names of its contributors may
+ * be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
+ * IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
+ * TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
+ * PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+ * HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+ * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
+ * TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
+ * PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
+ * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
+ * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*/
#include "stm-init.h"
diff --git a/libc/printf.c b/printf.c
index a6153d8..a6153d8 100644
--- a/libc/printf.c
+++ b/printf.c
diff --git a/src/stm-uart.c b/src/stm-uart.c
deleted file mode 100644
index 7676645..0000000
--- a/src/stm-uart.c
+++ /dev/null
@@ -1,76 +0,0 @@
-/* Includes ------------------------------------------------------------------*/
-#include "stm32f4xx_hal.h"
-#include "stm-uart.h"
-
-#include <string.h>
-
-static UART_HandleTypeDef huart2;
-
-extern void Error_Handler();
-
-
-/* Private variables ---------------------------------------------------------*/
-
-/* Private function prototypes -----------------------------------------------*/
-
-/* USART2 init function */
-void MX_USART2_UART_Init(void)
-{
- huart2.Instance = USART2;
- huart2.Init.BaudRate = USART2_BAUD_RATE;
- huart2.Init.WordLength = UART_WORDLENGTH_8B;
- huart2.Init.StopBits = UART_STOPBITS_1;
- huart2.Init.Parity = UART_PARITY_NONE;
- huart2.Init.Mode = UART_MODE_TX_RX;
- huart2.Init.HwFlowCtl = UART_HWCONTROL_NONE;
- huart2.Init.OverSampling = UART_OVERSAMPLING_16;
-
- if (HAL_UART_Init(&huart2) != HAL_OK) {
- /* Initialization Error */
- Error_Handler();
- }
-}
-
-void uart_send_char(uint8_t ch)
-{
- HAL_UART_Transmit(&huart2, &ch, 1, 0x1);
-}
-
-void uart_send_string(char *s)
-{
- HAL_UART_Transmit(&huart2, (uint8_t *) s, strlen(s), 0x1);
-}
-
-/* Generalized routine to send binary, decimal, and hex integers.
- * This code is adapted from Chris Giese's printf.c
- */
-void uart_send_number(uint32_t num, uint8_t digits, uint8_t radix)
-{
- #define BUFSIZE 32
- char buf[BUFSIZE];
- char *where = buf + BUFSIZE;
-
- /* initialize buf so we can add leading 0 by adjusting the pointer */
- memset(buf, '0', BUFSIZE);
-
- /* build the string backwards, starting with the least significant digit */
- do {
- uint32_t temp;
- temp = num % radix;
- where--;
- if (temp < 10)
- *where = temp + '0';
- else
- *where = temp - 10 + 'A';
- num = num / radix;
- } while (num != 0);
-
- if (where > buf + BUFSIZE - digits)
- /* pad with leading 0 */
- where = buf + BUFSIZE - digits;
- else
- /* number is larger than the specified number of digits */
- digits = buf + BUFSIZE - where;
-
- HAL_UART_Transmit(&huart2, (uint8_t *) where, digits, 0x1);
-}
diff --git a/src/stm-fmc.c b/stm-fmc.c
index 19b7fdc..3b36cbf 100644
--- a/src/stm-fmc.c
+++ b/stm-fmc.c
@@ -1,6 +1,36 @@
-//------------------------------------------------------------------------------
-// stm-fmc.c
-//------------------------------------------------------------------------------
+/*
+ * stm-fmc.c
+ * ---------
+ * Functions to set up and use the FMC bus.
+ *
+ * Copyright (c) 2015, NORDUnet A/S All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are
+ * met:
+ * - Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ *
+ * - Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the distribution.
+ *
+ * - Neither the name of the NORDUnet nor the names of its contributors may
+ * be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
+ * IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
+ * TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
+ * PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+ * HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+ * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
+ * TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
+ * PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
+ * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
+ * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
//------------------------------------------------------------------------------
diff --git a/stm-fmc.h b/stm-fmc.h
new file mode 100644
index 0000000..9e34d32
--- /dev/null
+++ b/stm-fmc.h
@@ -0,0 +1,45 @@
+/*
+ * stm-fmc.h
+ * ---------
+ * Functions to set up and use the FMC bus.
+ *
+ * Copyright (c) 2015, NORDUnet A/S All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are
+ * met:
+ * - Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ *
+ * - Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the distribution.
+ *
+ * - Neither the name of the NORDUnet nor the names of its contributors may
+ * be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
+ * IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
+ * TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
+ * PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+ * HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+ * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
+ * TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
+ * PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
+ * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
+ * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef __STM_FMC_H
+#define __STM_FMC_H
+
+#include <stdint.h>
+
+extern void fmc_init(void);
+
+extern int fmc_write_32(uint32_t addr, uint32_t *data);
+extern int fmc_read_32(uint32_t addr, uint32_t *data);
+
+#endif /* __STM_FMC_H */
diff --git a/src/stm-init.c b/stm-init.c
index f8610cd..aef1b95 100644
--- a/src/stm-init.c
+++ b/stm-init.c
@@ -35,16 +35,26 @@
/* Includes ------------------------------------------------------------------*/
#include "stm32f4xx_hal.h"
#include "stm-init.h"
+#ifdef HAL_GPIO_MODULE_ENABLED
#include "stm-led.h"
+#endif
+#ifdef HAL_SRAM_MODULE_ENABLED
#include "stm-fmc.h"
+#endif
+#ifdef HAL_UART_MODULE_ENABLED
#include "stm-uart.h"
+#endif
/* Private variables ---------------------------------------------------------*/
-static GPIO_InitTypeDef GPIO_InitStruct;
/* Private function prototypes -----------------------------------------------*/
static void SystemClock_Config(void);
+#ifdef HAL_GPIO_MODULE_ENABLED
static void MX_GPIO_Init(void);
+#endif
+#ifdef HAL_UART_MODULE_ENABLED
+static void MX_USART2_UART_Init(void);
+#endif
void stm_init(void)
{
@@ -63,8 +73,12 @@ void stm_init(void)
HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0);
/* Initialize all configured peripherals */
+#ifdef HAL_GPIO_MODULE_ENABLED
MX_GPIO_Init();
+#endif
+#ifdef HAL_UART_MODULE_ENABLED
MX_USART2_UART_Init();
+#endif
}
/** System Clock Configuration
@@ -127,6 +141,29 @@ static void old_SystemClock_Config(void)
}
#endif
+#ifdef HAL_UART_MODULE_ENABLED
+/* USART2 init function */
+static void MX_USART2_UART_Init(void)
+{
+ extern UART_HandleTypeDef huart2;
+
+ huart2.Instance = USART2;
+ huart2.Init.BaudRate = USART2_BAUD_RATE;
+ huart2.Init.WordLength = UART_WORDLENGTH_8B;
+ huart2.Init.StopBits = UART_STOPBITS_1;
+ huart2.Init.Parity = UART_PARITY_NONE;
+ huart2.Init.Mode = UART_MODE_TX_RX;
+ huart2.Init.HwFlowCtl = UART_HWCONTROL_NONE;
+ huart2.Init.OverSampling = UART_OVERSAMPLING_16;
+
+ if (HAL_UART_Init(&huart2) != HAL_OK) {
+ /* Initialization Error */
+ Error_Handler();
+ }
+}
+#endif
+
+#ifdef HAL_GPIO_MODULE_ENABLED
/** Configure pins as
* Analog
* Input
@@ -136,6 +173,8 @@ static void old_SystemClock_Config(void)
*/
static void MX_GPIO_Init(void)
{
+ GPIO_InitTypeDef GPIO_InitStruct;
+
/* GPIO Ports Clock Enable */
__GPIOJ_CLK_ENABLE();
@@ -146,6 +185,7 @@ static void MX_GPIO_Init(void)
GPIO_InitStruct.Speed = GPIO_SPEED_LOW;
HAL_GPIO_Init(LED_PORT, &GPIO_InitStruct);
}
+#endif
/**
* @brief This function is executed in case of error occurrence.
@@ -154,7 +194,9 @@ static void MX_GPIO_Init(void)
*/
void Error_Handler(void)
{
+#ifdef HAL_GPIO_MODULE_ENABLED
HAL_GPIO_WritePin(LED_PORT, LED_RED, GPIO_PIN_SET);
+#endif
while (1) { ; }
}
diff --git a/stm-init.h b/stm-init.h
new file mode 100644
index 0000000..60a728a
--- /dev/null
+++ b/stm-init.h
@@ -0,0 +1,43 @@
+/*
+ * stm-init.h
+ * ----------
+ * Functions to set up the stm32 peripherals.
+ *
+ * Copyright (c) 2015, NORDUnet A/S All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are
+ * met:
+ * - Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ *
+ * - Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the distribution.
+ *
+ * - Neither the name of the NORDUnet nor the names of its contributors may
+ * be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
+ * IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
+ * TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
+ * PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+ * HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+ * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
+ * TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
+ * PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
+ * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
+ * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef __STM_INIT_H
+#define __STM_INIT_H
+
+#include "stm32f4xx_hal.h"
+
+extern void stm_init(void);
+extern void Error_Handler(void);
+
+#endif /* __STM_INIT_H */
diff --git a/stm-led.h b/stm-led.h
new file mode 100644
index 0000000..5af084a
--- /dev/null
+++ b/stm-led.h
@@ -0,0 +1,50 @@
+/*
+ * stm-led.h
+ * ---------
+ * Defines to control the LEDs through GPIO pins.
+ *
+ * Copyright (c) 2015, NORDUnet A/S All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are
+ * met:
+ * - Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ *
+ * - Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the distribution.
+ *
+ * - Neither the name of the NORDUnet nor the names of its contributors may
+ * be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
+ * IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
+ * TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
+ * PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+ * HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+ * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
+ * TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
+ * PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
+ * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
+ * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef __STM_LED_H
+#define __STM_LED_H
+
+#include "stm32f4xx_hal.h"
+
+#define LED_PORT GPIOJ
+#define LED_RED GPIO_PIN_1
+#define LED_YELLOW GPIO_PIN_2
+#define LED_GREEN GPIO_PIN_3
+#define LED_BLUE GPIO_PIN_4
+
+#define led_on(pin) HAL_GPIO_WritePin(LED_PORT,pin,SET)
+#define led_off(pin) HAL_GPIO_WritePin(LED_PORT,pin,RESET)
+#define led_toggle(pin) HAL_GPIO_TogglePin(LED_PORT,pin)
+
+#endif /* __STM_LED_H */
diff --git a/stm-uart.c b/stm-uart.c
new file mode 100644
index 0000000..602a59c
--- /dev/null
+++ b/stm-uart.c
@@ -0,0 +1,87 @@
+/*
+ * stm-uart.c
+ * ----------
+ * Functions for sending strings and numbers over the uart.
+ *
+ * Copyright (c) 2015, NORDUnet A/S All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are
+ * met:
+ * - Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ *
+ * - Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the distribution.
+ *
+ * - Neither the name of the NORDUnet nor the names of its contributors may
+ * be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
+ * IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
+ * TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
+ * PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+ * HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+ * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
+ * TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
+ * PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
+ * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
+ * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#include "stm32f4xx_hal.h"
+#include "stm-uart.h"
+
+#include <string.h>
+
+/* initialized in MX_USART2_UART_Init() in stm-init.c */
+UART_HandleTypeDef huart2;
+
+/* send a single character */
+void uart_send_char(uint8_t ch)
+{
+ HAL_UART_Transmit(&huart2, &ch, 1, 0x1);
+}
+
+/* send a string */
+void uart_send_string(char *s)
+{
+ HAL_UART_Transmit(&huart2, (uint8_t *) s, strlen(s), 0x1);
+}
+
+/* Generalized routine to send binary, decimal, and hex integers.
+ * This code is adapted from Chris Giese's printf.c
+ */
+void uart_send_number(uint32_t num, uint8_t digits, uint8_t radix)
+{
+ #define BUFSIZE 32
+ char buf[BUFSIZE];
+ char *where = buf + BUFSIZE;
+
+ /* initialize buf so we can add leading 0 by adjusting the pointer */
+ memset(buf, '0', BUFSIZE);
+
+ /* build the string backwards, starting with the least significant digit */
+ do {
+ uint32_t temp;
+ temp = num % radix;
+ where--;
+ if (temp < 10)
+ *where = temp + '0';
+ else
+ *where = temp - 10 + 'A';
+ num = num / radix;
+ } while (num != 0);
+
+ if (where > buf + BUFSIZE - digits)
+ /* pad with leading 0 */
+ where = buf + BUFSIZE - digits;
+ else
+ /* number is larger than the specified number of digits */
+ digits = buf + BUFSIZE - where;
+
+ HAL_UART_Transmit(&huart2, (uint8_t *) where, digits, 0x1);
+}
diff --git a/stm-uart.h b/stm-uart.h
new file mode 100644
index 0000000..7019a48
--- /dev/null
+++ b/stm-uart.h
@@ -0,0 +1,49 @@
+/*
+ * stm-uart.h
+ * ---------
+ * Functions and defines to use the UART.
+ *
+ * Copyright (c) 2015, NORDUnet A/S All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are
+ * met:
+ * - Redistributions of source code must retain the above copyright notice,
+ * this list of conditions and the following disclaimer.
+ *
+ * - Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the distribution.
+ *
+ * - Neither the name of the NORDUnet nor the names of its contributors may
+ * be used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
+ * IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
+ * TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
+ * PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+ * HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+ * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
+ * TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
+ * PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
+ * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
+ * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef __STM32_UART_H
+#define __STM32_UART_H
+
+#include "stm32f4xx_hal.h"
+
+#define USART2_BAUD_RATE 115200
+
+extern void uart_send_char(uint8_t ch);
+extern void uart_send_string(char *s);
+extern void uart_send_number(uint32_t num, uint8_t digits, uint8_t radix);
+#define uart_send_binary(num, bits) uart_send_number(num, bits, 2)
+#define uart_send_integer(num, digits) uart_send_number(num, digits, 10)
+#define uart_send_hex(num, digits) uart_send_number(num, digits, 16)
+
+#endif /* __STM32_UART_H */
diff --git a/include/stm32f4xx_hal_conf.h b/stm32f4xx_hal_conf.h
index fd13d9e..fd13d9e 100644
--- a/include/stm32f4xx_hal_conf.h
+++ b/stm32f4xx_hal_conf.h
diff --git a/src/stm32f4xx_hal_msp.c b/stm32f4xx_hal_msp.c
index ee2cb7e..ee2cb7e 100644
--- a/src/stm32f4xx_hal_msp.c
+++ b/stm32f4xx_hal_msp.c
diff --git a/src/stm32f4xx_it.c b/stm32f4xx_it.c
index b2b64bf..b2b64bf 100644
--- a/src/stm32f4xx_it.c
+++ b/stm32f4xx_it.c
diff --git a/include/stm32f4xx_it.h b/stm32f4xx_it.h
index 546d79c..546d79c 100644
--- a/include/stm32f4xx_it.h
+++ b/stm32f4xx_it.h
diff --git a/libc/syscalls.c b/syscalls.c
index 9212763..58f3ecc 100644
--- a/libc/syscalls.c
+++ b/syscalls.c
@@ -34,10 +34,11 @@
* newlib version 1.17.0
****************************************************************************/
-/* 2015-10-29 pselkirk for cryptech:
- * Changed asm to __asm for c99 compatibility.
- * Added _exit, _kill, and _getpid from mifi's 2013 revision.
- */
+/****************************************************************************
+* 2015-10-29 pselkirk for cryptech:
+* Changed asm to __asm for c99 compatibility.
+* Added _exit, _kill, and _getpid from mifi's 2013 revision.
+****************************************************************************/
#include <stdlib.h>
#include <errno.h>