Cleanup and refactoring of the STM32w port

This is a general cleanup of things like code style issues and code structure of the STM32w port to make it more like the rest of Contiki is structured.
This commit is contained in:
Adam Dunkels 2013-03-15 16:14:09 +01:00
parent 12b3d02ba1
commit a5046e83c7
118 changed files with 4470 additions and 4281 deletions

View file

@ -21,17 +21,17 @@ CONTIKI_CPU=$(CONTIKI)/cpu/stm32w108
CONTIKI_CPU_DIRS = . dev hal simplemac hal/micro/cortexm3 hal/micro/cortexm3/stm32w108 CONTIKI_CPU_DIRS = . dev hal simplemac hal/micro/cortexm3 hal/micro/cortexm3/stm32w108
STM32W_C = leds-arch.c leds.c clock.c watchdog.c uart1.c uart1-putchar.c slip_uart1.c slip.c\ STM32W_C = leds-arch.c leds.c clock.c watchdog.c uart1.c uart1-putchar.c slip-uart1.c slip.c\
stm32w-radio.c stm32w_systick.c uip_arch.c rtimer-arch.c adc.c micro.c sleep.c \ stm32w-radio.c stm32w-systick.c uip-arch.c rtimer-arch.c adc.c micro.c sleep.c \
micro-common.c micro-common-internal.c clocks.c mfg-token.c nvm.c flash.c rand.c system-timer.c micro-common.c micro-common-internal.c clocks.c mfg-token.c nvm.c flash.c rand.c system-timer.c
STM32W_S = spmr.s79 context-switch.s79 STM32W_S = spmr.s79 context-switch.s79
ifdef IAR ifdef IAR
STM32W_C += low_level_init.c STM32W_C += low-level-init.c
STM32W_S += cstartup_M.s STM32W_S += cstartup-m.s
else else
STM32W_C += crt_stm32w108.c STM32W_C += crt-stm32w108.c
endif endif
ifdef ELF_LOADER ifdef ELF_LOADER
@ -104,9 +104,14 @@ CFLAGSNO = -mthumb -mcpu=cortex-m3 -D "PLATFORM_HEADER=\"hal/micro/cortexm3/comp
CFLAGS += $(CFLAGSNO) $(OPTI) CFLAGS += $(CFLAGSNO) $(OPTI)
ASFLAGS = -mthumb -mcpu=cortex-m3 -c -g -Wall -Os -ffunction-sections \ ASFLAGS = -mthumb -mcpu=cortex-m3 -c -g -Wall -Os -ffunction-sections \
-mlittle-endian -fshort-enums -x assembler-with-cpp -Wa,-EL -mlittle-endian -fshort-enums -x assembler-with-cpp -Wa,-EL
ifndef CPU_LD_CONFIG
CPU_LD_CONFIG=$(CONTIKI_CPU)/gnu.ld
endif # CPU_LD_CONFIG
LDFLAGS += -mcpu=cortex-m3 \ LDFLAGS += -mcpu=cortex-m3 \
-mthumb \ -mthumb \
-Wl,-T -Xlinker $(CONTIKI_CPU)/gnu.ld \ -Wl,-T -Xlinker $(CPU_LD_CONFIG) \
-Wl,-static \ -Wl,-static \
-u Default_Handler \ -u Default_Handler \
-nostartfiles \ -nostartfiles \
@ -185,9 +190,8 @@ FLASHEROPTS = -f -i rs232 -p $(PORT) -r
ifdef BTM ifdef BTM
#if already in bootloader mode #if already in bootloader mode
FLASHEROPTS += -b FLASHEROPTS += -b
endif endif
endif endif
### Custom rules ### Custom rules
@ -216,7 +220,7 @@ $(OBJECTDIR)/%.o: %.c
$(CC) $(CFLAGS) $< --dependencies=m $(@:.o=.P) -o $@ $(CC) $(CFLAGS) $< --dependencies=m $(@:.o=.P) -o $@
@$(SEDCOMMAND); rm -f $(@:.o=.P) @$(SEDCOMMAND); rm -f $(@:.o=.P)
@$(FINALIZE_DEPENDENCY) @$(FINALIZE_DEPENDENCY)
CUSTOM_RULE_C_TO_CO = 1 CUSTOM_RULE_C_TO_CO = 1
%.co: %.c %.co: %.c
$(CC) $(CFLAGS) -DAUTOSTART_ENABLE $< -o $@ $(CC) $(CFLAGS) -DAUTOSTART_ENABLE $< -o $@
@ -231,11 +235,11 @@ CUSTOM_RULE_LINK = 1
ifdef CORE ifdef CORE
ifeq ($(wildcard $(CORE)),) ifeq ($(wildcard $(CORE)),)
${error $(CORE) doesn't exist} ${error $(CORE) doesn\'t exist}
endif endif
.PHONY: symbols.c symbols.h .PHONY: symbols.c symbols.h
symbols.c: symbols.c:
$(NM) $(CORE) | awk -f $(CONTIKI)/tools/mknmlist > symbols.c $(NM) $(CORE) | awk -f $(CONTIKI)/tools/mknmlist > symbols.c
else else
symbols.c symbols.h: symbols.c symbols.h:
cp ${CONTIKI}/tools/empty-symbols.c symbols.c cp ${CONTIKI}/tools/empty-symbols.c symbols.c
@ -268,18 +272,18 @@ stm-motes:
$(OBJECTDIR)/%.o: %.s79 $(OBJECTDIR)/%.o: %.s79
$(AS) $(ASFLAGS) -o $@ $< $(AS) $(ASFLAGS) -o $@ $<
$(OBJECTDIR)/%.o: %.s $(OBJECTDIR)/%.o: %.s
$(AS) $(ASFLAGS) -o $@ $< $(AS) $(ASFLAGS) -o $@ $<
%.bin: %.$(TARGET) %.bin: %.$(TARGET)
$(OBJCOPY) $(OBJOPTS) $< $@ $(OBJCOPY) $(OBJOPTS) $< $@
# reset all stm32w devices sequentially, as stm32w_flasher cannot access different ports in parallel # reset all stm32w devices sequentially, as stm32w_flasher cannot access different ports in parallel
stm-reset: stm-reset:
$(foreach PORT, $(MOTES), $(FLASHER) -r -p $(PORT);$(\n)) $(foreach PORT, $(MOTES), $(FLASHER) -r -p $(PORT);$(\n))
@echo Done @echo Done
ifdef MOTE ifdef MOTE
%.upload: %.bin %.upload: %.bin
$(FLASHER) $(FLASHEROPTS) $< -p $(word $(MOTE), $(MOTES)) $(FLASHER) $(FLASHEROPTS) $< -p $(word $(MOTE), $(MOTES))

View file

@ -1,3 +1,39 @@
/**
* \addtogroup mb851-platform
*
* @{
*/
/*
* Copyright (c) 2010, STMicroelectronics.
* All rights reserved.
*
* 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.
* 3. Neither the name of the Institute 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 INSTITUTE 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 INSTITUTE 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.
*
*/
/** /**
* \file * \file
* Declarations for sensor-related functions that are * Declarations for sensor-related functions that are
@ -7,19 +43,24 @@
* \author Salvatore Pitrulli <salvopitru@users.sourceforge.net> * \author Salvatore Pitrulli <salvopitru@users.sourceforge.net>
*/ */
#ifndef BOARD_SENSORS_H
#define BOARD_SENSORS_H
/** /**
* Remember state of sensors (if active or not), in order to * Remember state of sensors (if active or not), in order to
* resume their original state after calling powerUpSensors(). * resume their original state after calling board_sensors_power_up().
* Useful when entering in sleep mode, since all system * Useful when entering in sleep mode, since all system
* peripherals have to be reinitialized. * peripherals have to be reinitialized.
*/ */
void sensorsPowerDown(); void board_sensors_power_down(void);
/** /**
* Resume the state of all on-board sensors on to the state * Resume the state of all on-board sensors on to the state
* that they had when sensorsPowerDown() was called. * that they had when board_sensors_power_down() was called.
* Useful when sensors have to be used after the micro was put * Useful when sensors have to be used after the micro was put
* in deep sleep mode. * in deep sleep mode.
*/ */
void sensorsPowerUp(); void board_sensors_power_up(void);
#endif /* BOARD_SENSORS_H */
/** @} */

View file

@ -1,3 +1,9 @@
/**
* \addtogroup mb851-platform
*
* @{
*/
/* /*
* Copyright (c) 2009, Swedish Institute of Computer Science * Copyright (c) 2009, Swedish Institute of Computer Science
* All rights reserved. * All rights reserved.
@ -26,8 +32,6 @@
* OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
* SUCH DAMAGE. * SUCH DAMAGE.
* *
* This file is part of the Contiki operating system.
*
*/ */
/** /**
@ -38,7 +42,6 @@
* Salvatore Pitrulli <salvopitru@users.sourceforge.net> * Salvatore Pitrulli <salvopitru@users.sourceforge.net>
*/ */
#include "cfs-coffee-arch.h" #include "cfs-coffee-arch.h"
#define DEBUG 1 #define DEBUG 1
@ -69,6 +72,7 @@
#define FILE_SIZE 512 #define FILE_SIZE 512
/*--------------------------------------------------------------------------*/
int int
coffee_file_test(void) coffee_file_test(void)
{ {
@ -83,13 +87,12 @@ coffee_file_test(void)
cfs_remove("T3"); cfs_remove("T3");
cfs_remove("T4"); cfs_remove("T4");
cfs_remove("T5"); cfs_remove("T5");
wfd = rfd = afd = -1; wfd = rfd = afd = -1;
for(r = 0; r < sizeof(buf); r++) { for(r = 0; r < sizeof(buf); r++) {
buf[r] = r; buf[r] = r;
} }
PRINTF("TEST 1\n"); PRINTF("TEST 1\n");
/* Test 1: Open for writing. */ /* Test 1: Open for writing. */
@ -97,7 +100,7 @@ coffee_file_test(void)
if(wfd < 0) { if(wfd < 0) {
FAIL(-1); FAIL(-1);
} }
PRINTF("PASSED\n"); PRINTF("PASSED\n");
PRINTF("TEST "); PRINTF("TEST ");
PRINTF("2\n"); PRINTF("2\n");
@ -109,7 +112,7 @@ coffee_file_test(void)
} else if(r < sizeof(buf)) { } else if(r < sizeof(buf)) {
FAIL(-3); FAIL(-3);
} }
PRINTF("PASSED\n"); PRINTF("PASSED\n");
PRINTF("TEST "); PRINTF("TEST ");
PRINTF("3\n"); PRINTF("3\n");
@ -119,7 +122,7 @@ coffee_file_test(void)
if(r >= 0) { if(r >= 0) {
FAIL(-4); FAIL(-4);
} }
PRINTF("PASSED\n"); PRINTF("PASSED\n");
PRINTF("TEST "); PRINTF("TEST ");
PRINTF("4\n"); PRINTF("4\n");
@ -129,7 +132,7 @@ coffee_file_test(void)
if(rfd < 0) { if(rfd < 0) {
FAIL(-5); FAIL(-5);
} }
PRINTF("PASSED\n"); PRINTF("PASSED\n");
PRINTF("TEST "); PRINTF("TEST ");
PRINTF("5\n"); PRINTF("5\n");
@ -139,7 +142,6 @@ coffee_file_test(void)
if(r >= 0) { if(r >= 0) {
FAIL(-6); FAIL(-6);
} }
PRINTF("PASSED\n"); PRINTF("PASSED\n");
PRINTF("TEST "); PRINTF("TEST ");
PRINTF("7\n"); PRINTF("7\n");
@ -153,7 +155,7 @@ coffee_file_test(void)
PRINTF_CFS("r=%d\n", r); PRINTF_CFS("r=%d\n", r);
FAIL(-9); FAIL(-9);
} }
PRINTF("PASSED\n"); PRINTF("PASSED\n");
PRINTF("TEST "); PRINTF("TEST ");
PRINTF("8\n"); PRINTF("8\n");
@ -165,7 +167,7 @@ coffee_file_test(void)
FAIL(-10); FAIL(-10);
} }
} }
PRINTF("PASSED\n"); PRINTF("PASSED\n");
PRINTF("TEST "); PRINTF("TEST ");
PRINTF("9\n"); PRINTF("9\n");
@ -174,7 +176,7 @@ coffee_file_test(void)
if(cfs_seek(wfd, 0, CFS_SEEK_SET) != 0) { if(cfs_seek(wfd, 0, CFS_SEEK_SET) != 0) {
FAIL(-11); FAIL(-11);
} }
PRINTF("PASSED\n"); PRINTF("PASSED\n");
PRINTF("TEST "); PRINTF("TEST ");
PRINTF("10\n"); PRINTF("10\n");
@ -186,7 +188,7 @@ coffee_file_test(void)
} else if(r < sizeof(buf)) { } else if(r < sizeof(buf)) {
FAIL(-13); FAIL(-13);
} }
PRINTF("PASSED\n"); PRINTF("PASSED\n");
PRINTF("TEST "); PRINTF("TEST ");
PRINTF("11\n"); PRINTF("11\n");
@ -200,7 +202,7 @@ coffee_file_test(void)
} else if(r < sizeof(buf)) { } else if(r < sizeof(buf)) {
FAIL(-15); FAIL(-15);
} }
PRINTF("PASSED\n"); PRINTF("PASSED\n");
PRINTF("TEST "); PRINTF("TEST ");
PRINTF("12\n"); PRINTF("12\n");
@ -211,7 +213,7 @@ coffee_file_test(void)
FAIL(-16); FAIL(-16);
} }
} }
PRINTF("PASSED\n"); PRINTF("PASSED\n");
PRINTF("TEST "); PRINTF("TEST ");
PRINTF("13\n"); PRINTF("13\n");
@ -232,7 +234,7 @@ coffee_file_test(void)
if(cfs_seek(rfd, 0, CFS_SEEK_SET) != 0) { if(cfs_seek(rfd, 0, CFS_SEEK_SET) != 0) {
FAIL(-20); FAIL(-20);
} }
PRINTF("PASSED\n"); PRINTF("PASSED\n");
PRINTF("TEST "); PRINTF("TEST ");
PRINTF("14\n"); PRINTF("14\n");
@ -247,7 +249,7 @@ coffee_file_test(void)
PRINTF_CFS("r = %d\n", r); PRINTF_CFS("r = %d\n", r);
FAIL(-22); FAIL(-22);
} }
PRINTF("PASSED\n"); PRINTF("PASSED\n");
PRINTF("TEST "); PRINTF("TEST ");
PRINTF("15\n"); PRINTF("15\n");
@ -265,7 +267,7 @@ coffee_file_test(void)
if(cfs_coffee_reserve("T2", FILE_SIZE) < 0) { if(cfs_coffee_reserve("T2", FILE_SIZE) < 0) {
FAIL(-24); FAIL(-24);
} }
PRINTF("PASSED\n"); PRINTF("PASSED\n");
PRINTF("TEST "); PRINTF("TEST ");
PRINTF("16\n"); PRINTF("16\n");
@ -276,30 +278,23 @@ coffee_file_test(void)
if(wfd < 0) { if(wfd < 0) {
FAIL(-25); FAIL(-25);
} }
offset = random_rand() % FILE_SIZE; offset = random_rand() % FILE_SIZE;
for(r = 0; r < sizeof(buf); r++) { for(r = 0; r < sizeof(buf); r++) {
buf[r] = r; buf[r] = r;
} }
if(cfs_seek(wfd, offset, CFS_SEEK_SET) != offset) { if(cfs_seek(wfd, offset, CFS_SEEK_SET) != offset) {
FAIL(-26); FAIL(-26);
} }
if(cfs_write(wfd, buf, sizeof(buf)) != sizeof(buf)) { if(cfs_write(wfd, buf, sizeof(buf)) != sizeof(buf)) {
FAIL(-27); FAIL(-27);
} }
if(cfs_seek(wfd, offset, CFS_SEEK_SET) != offset) { if(cfs_seek(wfd, offset, CFS_SEEK_SET) != offset) {
FAIL(-28); FAIL(-28);
} }
memset(buf, 0, sizeof(buf)); memset(buf, 0, sizeof(buf));
if(cfs_read(wfd, buf, sizeof(buf)) != sizeof(buf)) { if(cfs_read(wfd, buf, sizeof(buf)) != sizeof(buf)) {
FAIL(-29); FAIL(-29);
} }
for(i = 0; i < sizeof(buf); i++) { for(i = 0; i < sizeof(buf); i++) {
if(buf[i] != i) { if(buf[i] != i) {
PRINTF_CFS("buf[%d] != %d\n", i, buf[i]); PRINTF_CFS("buf[%d] != %d\n", i, buf[i]);
@ -310,30 +305,30 @@ coffee_file_test(void)
PRINTF("PASSED\n"); PRINTF("PASSED\n");
PRINTF("TEST "); PRINTF("TEST ");
PRINTF("17\n"); PRINTF("17\n");
/* Test 17: Append data to the same file many times. */ /* Test 17: Append data to the same file many times. */
#define APPEND_BYTES 3000 #define APPEND_BYTES 3000
#define BULK_SIZE 10 #define BULK_SIZE 10
for (i = 0; i < APPEND_BYTES; i += BULK_SIZE) { for(i = 0; i < APPEND_BYTES; i += BULK_SIZE) {
afd = cfs_open("T3", CFS_WRITE | CFS_APPEND); afd = cfs_open("T3", CFS_WRITE | CFS_APPEND);
if (afd < 0) { if(afd < 0) {
FAIL(-31); FAIL(-31);
} }
for (j = 0; j < BULK_SIZE; j++) { for(j = 0; j < BULK_SIZE; j++) {
buf[j] = 1 + ((i + j) & 0x7f); buf[j] = 1 + ((i + j) & 0x7f);
} }
if ((r = cfs_write(afd, buf, BULK_SIZE)) != BULK_SIZE) { if((r = cfs_write(afd, buf, BULK_SIZE)) != BULK_SIZE) {
PRINTF_CFS("Count:%d, r=%d\n", i, r); PRINTF_CFS("Count:%d, r=%d\n", i, r);
FAIL(-32); FAIL(-32);
} }
cfs_close(afd); cfs_close(afd);
} }
PRINTF("PASSED\n"); PRINTF("PASSED\n");
PRINTF("TEST "); PRINTF("TEST ");
PRINTF("18\n"); PRINTF("18\n");
/* Test 18: Read back the data written in Test 17 and verify that it /* Test 18: Read back the data written in Test 17 and verify. */
is correct. */
afd = cfs_open("T3", CFS_READ); afd = cfs_open("T3", CFS_READ);
if(afd < 0) { if(afd < 0) {
FAIL(-33); FAIL(-33);
@ -342,192 +337,202 @@ coffee_file_test(void)
while((r = cfs_read(afd, buf2, sizeof(buf2))) > 0) { while((r = cfs_read(afd, buf2, sizeof(buf2))) > 0) {
for(j = 0; j < r; j++) { for(j = 0; j < r; j++) {
if(buf2[j] != 1 + ((total_read + j) & 0x7f)) { if(buf2[j] != 1 + ((total_read + j) & 0x7f)) {
FAIL(-34); FAIL(-34);
} }
} }
total_read += r; total_read += r;
} }
if(r < 0) { if(r < 0) {
PRINTF_CFS("FAIL:-35 r=%d\n",r); PRINTF_CFS("FAIL:-35 r=%d\n", r);
FAIL(-35); FAIL(-35);
} }
if(total_read != APPEND_BYTES) { if(total_read != APPEND_BYTES) {
PRINTF_CFS("FAIL:-35 total_read=%d\n",total_read); PRINTF_CFS("FAIL:-35 total_read=%d\n", total_read);
FAIL(-35); FAIL(-35);
} }
cfs_close(afd); cfs_close(afd);
PRINTF("PASSED\n"); PRINTF("PASSED\n");
PRINTF("TEST "); PRINTF("TEST ");
PRINTF("19\n"); PRINTF("19\n");
/***************T4********************/ /* T4 */
/* file T4 and T5 writing forces to use garbage collector in greedy mode /*
* this test is designed for 10kb of file system * file T4 and T5 writing forces to use garbage collector in greedy mode
* */ * this test is designed for 10kb of file system
*/
#define APPEND_BYTES_1 2000 #define APPEND_BYTES_1 2000
#define BULK_SIZE_1 10 #define BULK_SIZE_1 10
for (i = 0; i < APPEND_BYTES_1; i += BULK_SIZE_1) { for(i = 0; i < APPEND_BYTES_1; i += BULK_SIZE_1) {
afd = cfs_open("T4", CFS_WRITE | CFS_APPEND); afd = cfs_open("T4", CFS_WRITE | CFS_APPEND);
if (afd < 0) { if(afd < 0) {
FAIL(-36); FAIL(-36);
} }
for (j = 0; j < BULK_SIZE_1; j++) { for(j = 0; j < BULK_SIZE_1; j++) {
buf[j] = 1 + ((i + j) & 0x7f); buf[j] = 1 + ((i + j) & 0x7f);
} }
if ((r = cfs_write(afd, buf, BULK_SIZE_1)) != BULK_SIZE_1) { if((r = cfs_write(afd, buf, BULK_SIZE_1)) != BULK_SIZE_1) {
PRINTF_CFS("Count:%d, r=%d\n", i, r); PRINTF_CFS("Count:%d, r=%d\n", i, r);
FAIL(-37); FAIL(-37);
} }
cfs_close(afd); cfs_close(afd);
} }
afd = cfs_open("T4", CFS_READ); afd = cfs_open("T4", CFS_READ);
if(afd < 0) { if(afd < 0) {
FAIL(-38); FAIL(-38);
} }
total_read = 0; total_read = 0;
while((r = cfs_read(afd, buf2, sizeof(buf2))) > 0) { while((r = cfs_read(afd, buf2, sizeof(buf2))) > 0) {
for(j = 0; j < r; j++) { for(j = 0; j < r; j++) {
if(buf2[j] != 1 + ((total_read + j) & 0x7f)) { if(buf2[j] != 1 + ((total_read + j) & 0x7f)) {
PRINTF_CFS("FAIL:-39, total_read=%d r=%d\n",total_read,r); PRINTF_CFS("FAIL:-39, total_read=%d r=%d\n", total_read, r);
FAIL(-39); FAIL(-39);
} }
} }
total_read += r; total_read += r;
} }
if(r < 0) { if(r < 0) {
PRINTF_CFS("FAIL:-40 r=%d\n",r); PRINTF_CFS("FAIL:-40 r=%d\n", r);
FAIL(-40); FAIL(-40);
} }
if(total_read != APPEND_BYTES_1) { if(total_read != APPEND_BYTES_1) {
PRINTF_CFS("FAIL:-41 total_read=%d\n",total_read); PRINTF_CFS("FAIL:-41 total_read=%d\n", total_read);
FAIL(-41); FAIL(-41);
} }
cfs_close(afd); cfs_close(afd);
/***************T5********************/
/* T5 */
PRINTF("PASSED\n"); PRINTF("PASSED\n");
PRINTF("TEST "); PRINTF("TEST ");
PRINTF("20\n"); PRINTF("20\n");
#define APPEND_BYTES_2 1000 #define APPEND_BYTES_2 1000
#define BULK_SIZE_2 10 #define BULK_SIZE_2 10
for (i = 0; i < APPEND_BYTES_2; i += BULK_SIZE_2) { for(i = 0; i < APPEND_BYTES_2; i += BULK_SIZE_2) {
afd = cfs_open("T5", CFS_WRITE | CFS_APPEND); afd = cfs_open("T5", CFS_WRITE | CFS_APPEND);
if (afd < 0) {
FAIL(-42);
}
for (j = 0; j < BULK_SIZE_2; j++) {
buf[j] = 1 + ((i + j) & 0x7f);
}
if ((r = cfs_write(afd, buf, BULK_SIZE_2)) != BULK_SIZE_2) {
PRINTF_CFS("Count:%d, r=%d\n", i, r);
FAIL(-43);
}
cfs_close(afd);
}
afd = cfs_open("T5", CFS_READ);
if(afd < 0) { if(afd < 0) {
FAIL(-44); FAIL(-42);
} }
total_read = 0; for(j = 0; j < BULK_SIZE_2; j++) {
while((r = cfs_read(afd, buf2, sizeof(buf2))) > 0) { buf[j] = 1 + ((i + j) & 0x7f);
for(j = 0; j < r; j++) {
if(buf2[j] != 1 + ((total_read + j) & 0x7f)) {
PRINTF_CFS("FAIL:-45, total_read=%d r=%d\n",total_read,r);
FAIL(-45);
}
}
total_read += r;
} }
if(r < 0) {
PRINTF_CFS("FAIL:-46 r=%d\n",r); if((r = cfs_write(afd, buf, BULK_SIZE_2)) != BULK_SIZE_2) {
FAIL(-46); PRINTF_CFS("Count:%d, r=%d\n", i, r);
} FAIL(-43);
if(total_read != APPEND_BYTES_2) {
PRINTF_CFS("FAIL:-47 total_read=%d\n",total_read);
FAIL(-47);
} }
cfs_close(afd); cfs_close(afd);
}
PRINTF("PASSED\n");
afd = cfs_open("T5", CFS_READ);
if(afd < 0) {
FAIL(-44);
}
total_read = 0;
while((r = cfs_read(afd, buf2, sizeof(buf2))) > 0) {
for(j = 0; j < r; j++) {
if(buf2[j] != 1 + ((total_read + j) & 0x7f)) {
PRINTF_CFS("FAIL:-45, total_read=%d r=%d\n", total_read, r);
FAIL(-45);
}
}
total_read += r;
}
if(r < 0) {
PRINTF_CFS("FAIL:-46 r=%d\n", r);
FAIL(-46);
}
if(total_read != APPEND_BYTES_2) {
PRINTF_CFS("FAIL:-47 total_read=%d\n", total_read);
FAIL(-47);
}
cfs_close(afd);
PRINTF("PASSED\n");
error = 0; error = 0;
end: end:
cfs_close(wfd); cfs_close(rfd); cfs_close(afd); cfs_close(wfd);
cfs_close(rfd);
cfs_close(afd);
return error; return error;
} }
#endif /* TESTCOFFEE */ #endif /* TESTCOFFEE */
/*--------------------------------------------------------------------------*/
void stm32w_flash_read(int32u address, void * data, int32u length) void
stm32w_flash_read(uint32_t address, void *data, uint32_t length)
{ {
int8u * pdata = (int8u *)address; uint8_t *pdata = (uint8_t *) address;
ENERGEST_ON(ENERGEST_TYPE_FLASH_READ); ENERGEST_ON(ENERGEST_TYPE_FLASH_READ);
memcpy(data, pdata, length); memcpy(data, pdata, length);
ENERGEST_OFF(ENERGEST_TYPE_FLASH_READ); ENERGEST_OFF(ENERGEST_TYPE_FLASH_READ);
} }
/*--------------------------------------------------------------------------*/
void stm32w_flash_erase(int8u sector) void
stm32w_flash_erase(uint8_t sector)
{ {
//halInternalFlashErase(MFB_PAGE_ERASE, COFFEE_START + (sector) * COFFEE_SECTOR_SIZE); /* halInternalFlashErase(MFB_PAGE_ERASE, COFFEE_START +
(sector) * COFFEE_SECTOR_SIZE); */
int16u data = 0; uint16_t data = 0;
int32u addr = COFFEE_START + (sector) * COFFEE_SECTOR_SIZE; uint32_t addr = COFFEE_START + (sector) * COFFEE_SECTOR_SIZE;
int32u end = addr + COFFEE_SECTOR_SIZE; uint32_t end = addr + COFFEE_SECTOR_SIZE;
/* This prevents from accidental write to CIB. */ /* This prevents from accidental write to CIB. */
if (!(addr >= MFB_BOTTOM && end <= MFB_TOP + 1)) { if(!(addr >= MFB_BOTTOM && end <= MFB_TOP + 1)) {
return; return;
} }
for(; addr < end; addr += 2){ for(; addr < end; addr += 2) {
halInternalFlashWrite(addr, &data, 1); halInternalFlashWrite(addr, &data, 1);
} }
} }
/*--------------------------------------------------------------------------*/
// Allocates a buffer of FLASH_PAGE_SIZE bytes statically (rather than on the stack). /*
* Allocates a buffer of FLASH_PAGE_SIZE bytes statically (rather than on
* the stack).
*/
#ifndef STATIC_FLASH_BUFFER #ifndef STATIC_FLASH_BUFFER
#define STATIC_FLASH_BUFFER 1 #define STATIC_FLASH_BUFFER 1
#endif #endif
void stm32w_flash_write(int32u address, const void * data, int32u length) void
stm32w_flash_write(uint32_t address, const void *data, uint32_t length)
{ {
const int32u end = address + length; const uint32_t end = address + length;
int32u i; uint32_t i;
int32u next_page, curr_page; uint32_t next_page, curr_page;
int16u offset; uint16_t offset;
#if STATIC_FLASH_BUFFER #if STATIC_FLASH_BUFFER
static int8u buf[FLASH_PAGE_SIZE]; static uint8_t buf[FLASH_PAGE_SIZE];
#else #else
int8u buf[FLASH_PAGE_SIZE]; uint8_t buf[FLASH_PAGE_SIZE];
#endif #endif
for(i = address; i < end;) { for(i = address; i < end;) {
next_page = (i | (FLASH_PAGE_SIZE-1)) + 1; next_page = (i | (FLASH_PAGE_SIZE - 1)) + 1;
curr_page = i & ~(FLASH_PAGE_SIZE-1); curr_page = i & ~(FLASH_PAGE_SIZE - 1);
offset = i-curr_page; offset = i - curr_page;
if(next_page > end) { if(next_page > end) {
next_page = end; next_page = end;
} }
// Read a page from flash and put it into a mirror buffer. /* Read a page from flash and put it into a mirror buffer. */
stm32w_flash_read(curr_page, buf, FLASH_PAGE_SIZE); stm32w_flash_read(curr_page, buf, FLASH_PAGE_SIZE);
// Update flash mirror data with new data. /* Update flash mirror data with new data. */
memcpy(buf + offset, data, next_page - i); memcpy(buf + offset, data, next_page - i);
// Erase flash page. /* Erase flash page. */
ENERGEST_ON(ENERGEST_TYPE_FLASH_WRITE); ENERGEST_ON(ENERGEST_TYPE_FLASH_WRITE);
halInternalFlashErase(MFB_PAGE_ERASE, i); halInternalFlashErase(MFB_PAGE_ERASE, i);
// Write modified data form mirror buffer into the flash. /* Write modified data form mirror buffer into the flash. */
halInternalFlashWrite(curr_page, (int16u *)buf, FLASH_PAGE_SIZE/2); halInternalFlashWrite(curr_page, (uint16_t *) buf, FLASH_PAGE_SIZE / 2);
ENERGEST_OFF(ENERGEST_TYPE_FLASH_WRITE); ENERGEST_OFF(ENERGEST_TYPE_FLASH_WRITE);
data = (uint8_t *)data + next_page - i; data = (uint8_t *) data + next_page - i;
i = next_page; i = next_page;
} }
} }
/** @} */

View file

@ -1,3 +1,9 @@
/**
* \addtogroup mb851-platform
*
* @{
*/
/* /*
* Copyright (c) 2010, STMicroelectronics. * Copyright (c) 2010, STMicroelectronics.
* All rights reserved. * All rights reserved.
@ -26,15 +32,12 @@
* OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
* SUCH DAMAGE. * SUCH DAMAGE.
* *
* This file is part of the Contiki operating system.
*
*/ */
/** /**
* \file * \file
* Coffee architecture-dependent header for the STM32W108-based mb851 * Coffee architecture-dependent header for the STM32W108-based mb851
* platform. * platform. STM32W108 has 128KB of program flash.
* STM32W108 has 128KB of program flash.
* \author * \author
* Salvatore Pitrulli <salvopitru@users.sourceforge.net> * Salvatore Pitrulli <salvopitru@users.sourceforge.net>
*/ */
@ -47,32 +50,34 @@
#include "hal/error.h" #include "hal/error.h"
#include "hal/micro/cortexm3/flash.h" #include "hal/micro/cortexm3/flash.h"
/* STM32W108 has 128 pages of 1024 bytes each = 128KB /*
* STM32W108 has 128KB of program flash in 128 pages of 1024 bytes each = 128KB.
* The smallest erasable unit is one page and the smallest writable * The smallest erasable unit is one page and the smallest writable
* unit is an aligned 16-bit half-word. * unit is an aligned 16-bit half-word.
*/ */
/* Byte page size, starting address on page boundary, and size of file system */
/* Byte page size, starting address on page boundary, and size of the file system */
#define FLASH_START 0x8000000 #define FLASH_START 0x8000000
/* Minimum erasable unit. */ /* Minimum erasable unit. */
#define FLASH_PAGE_SIZE 1024 #define FLASH_PAGE_SIZE 1024
/* Last 3 pages reserved for NVM. */ /* Last 3 pages reserved for NVM. */
#define FLASH_PAGES 125 #define FLASH_PAGES 125
/* Minimum reservation unit for Coffee. It can be changed by the user. */ /* Minimum reservation unit for Coffee. It can be changed by the user. */
#define COFFEE_PAGE_SIZE (FLASH_PAGE_SIZE/4) #define COFFEE_PAGE_SIZE (FLASH_PAGE_SIZE/4)
/*
/* If using IAR, COFFEE_ADDRESS reflects the static value in the linker script * If using IAR, COFFEE_ADDRESS reflects the static value in the linker script
iar-cfg-coffee.icf, so it can't be passed as a parameter for Make.*/ * iar-cfg-coffee.icf, so it can't be passed as a parameter for Make.
*/
#ifdef __ICCARM__ #ifdef __ICCARM__
#define COFFEE_ADDRESS 0x8010c00 #define COFFEE_ADDRESS 0x8010c00
#endif #endif
#if (COFFEE_ADDRESS & 0x3FF) !=0 #if (COFFEE_ADDRESS & 0x3FF) != 0
#error "COFFEE_ADDRESS not aligned to a 1024-bytes page boundary." #error "COFFEE_ADDRESS not aligned to a 1024-bytes page boundary."
#endif #endif
#define COFFEE_PAGES ((FLASH_PAGES*FLASH_PAGE_SIZE-(COFFEE_ADDRESS-FLASH_START))/COFFEE_PAGE_SIZE)
#define COFFEE_PAGES ((FLASH_PAGES*FLASH_PAGE_SIZE- \
(COFFEE_ADDRESS-FLASH_START))/COFFEE_PAGE_SIZE)
#define COFFEE_START (COFFEE_ADDRESS & ~(COFFEE_PAGE_SIZE-1)) #define COFFEE_START (COFFEE_ADDRESS & ~(COFFEE_PAGE_SIZE-1))
#define COFFEE_SIZE (COFFEE_PAGES*COFFEE_PAGE_SIZE) #define COFFEE_SIZE (COFFEE_PAGES*COFFEE_PAGE_SIZE)
@ -80,21 +85,23 @@
#define COFFEE_SECTOR_SIZE FLASH_PAGE_SIZE #define COFFEE_SECTOR_SIZE FLASH_PAGE_SIZE
#define COFFEE_NAME_LENGTH 20 #define COFFEE_NAME_LENGTH 20
///* These are used internally by the AVR flash read routines */ /* These are used internally by the AVR flash read routines */
///* Word reads are faster but take 130 bytes more PROGMEM */ /* Word reads are faster but take 130 bytes more PROGMEM */
//#define FLASH_WORD_READS 1 /* #define FLASH_WORD_READS 1 */
///* 1=Slower reads, but no page writes after erase and 18 bytes less PROGMEM. Best for dynamic file system */ /*
//#define FLASH_COMPLEMENT_DATA 0 * 1 = Slower reads, but no page writes after erase and 18 bytes less PROGMEM.
* Best for dynamic file system
*/
/* #define FLASH_COMPLEMENT_DATA 0 */
/* These are used internally by the coffee file system */ /* These are used internally by the coffee file system */
/* Micro logs are not needed for single page sectors */
#define COFFEE_MAX_OPEN_FILES 4 #define COFFEE_MAX_OPEN_FILES 4
#define COFFEE_FD_SET_SIZE 8 #define COFFEE_FD_SET_SIZE 8
#define COFFEE_DYN_SIZE (COFFEE_PAGE_SIZE*1) #define COFFEE_DYN_SIZE (COFFEE_PAGE_SIZE*1)
/* Micro logs are not needed for single page sectors */
#define COFFEE_MICRO_LOGS 0 #define COFFEE_MICRO_LOGS 0
#define COFFEE_LOG_TABLE_LIMIT 16 // It doesnt' matter as #define COFFEE_LOG_TABLE_LIMIT 16 /* It doesnt' matter as */
#define COFFEE_LOG_SIZE 128 // COFFEE_MICRO_LOGS is 0. #define COFFEE_LOG_SIZE 128 /* COFFEE_MICRO_LOGS is 0. */
#if COFFEE_PAGES <= 127 #if COFFEE_PAGES <= 127
#define coffee_page_t int8_t #define coffee_page_t int8_t
@ -102,7 +109,6 @@
#define coffee_page_t int16_t #define coffee_page_t int16_t
#endif #endif
#define COFFEE_WRITE(buf, size, offset) \ #define COFFEE_WRITE(buf, size, offset) \
stm32w_flash_write(COFFEE_START + offset, buf, size) stm32w_flash_write(COFFEE_START + offset, buf, size)
@ -113,10 +119,13 @@
stm32w_flash_erase(sector) stm32w_flash_erase(sector)
void stm32w_flash_read(int32u address, void * data, int32u length); void stm32w_flash_read(uint32_t address, void *data, uint32_t length);
void stm32w_flash_write(int32u address, const void * data, int32u length);
void stm32w_flash_erase(int8u sector); void stm32w_flash_write(uint32_t address, const void *data, uint32_t length);
void stm32w_flash_erase(uint8_t sector);
int coffee_file_test(void); int coffee_file_test(void);
#endif /* !COFFEE_ARCH_H */ #endif /* !COFFEE_ARCH_H */
/** @} */

View file

@ -1,3 +1,9 @@
/**
* \addtogroup mb851-platform
*
* @{
*/
/* /*
* Copyright (c) 2010, STMicroelectronics. * Copyright (c) 2010, STMicroelectronics.
* All rights reserved. * All rights reserved.
@ -27,22 +33,20 @@
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
* *
* This file is part of the Contiki OS
*
*/ */
/*---------------------------------------------------------------------------*/
/** /**
* \file * \file
* Clock. * Clock.
* \author * \author
* Salvatore Pitrulli <salvopitru@users.sourceforge.net> * Salvatore Pitrulli <salvopitru@users.sourceforge.net>
*/ */
/*---------------------------------------------------------------------------*/
#include PLATFORM_HEADER #include PLATFORM_HEADER
#include <stdio.h>
#include "hal/error.h" #include "hal/error.h"
#include "hal/hal.h" #include "hal/hal.h"
#include "dev/stm32w_systick.h" #include "dev/stm32w-systick.h"
#include "contiki.h" #include "contiki.h"
#include "sys/clock.h" #include "sys/clock.h"
@ -54,46 +58,39 @@
#define DEBUG DEBUG_NONE #define DEBUG DEBUG_NONE
#include "net/uip-debug.h" #include "net/uip-debug.h"
/*--------------------------------------------------------------------------*/
/* The value that will be load in the SysTick value register. */ /* The value that will be load in the SysTick value register. */
#define RELOAD_VALUE 24000-1 /* 1 ms with a 24 MHz clock */ #define RELOAD_VALUE 24000-1 /* 1 ms with a 24 MHz clock */
static volatile clock_time_t count; static volatile clock_time_t count;
static volatile unsigned long current_seconds = 0; static volatile unsigned long current_seconds = 0;
static unsigned int second_countdown = CLOCK_SECOND; static unsigned int second_countdown = CLOCK_SECOND;
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
void void
SysTick_Handler(void) SysTick_Handler(void)
{ {
count++; count++;
if(etimer_pending()) { if(etimer_pending()) {
etimer_request_poll(); etimer_request_poll();
} }
if (--second_countdown == 0) { if(--second_countdown == 0) {
current_seconds++; current_seconds++;
second_countdown = CLOCK_SECOND; second_countdown = CLOCK_SECOND;
} }
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
void void
clock_init(void) clock_init(void)
{ {
ATOMIC( ATOMIC(
/* Counts the number of ticks. */
//Counts the number of ticks. count = 0;
count = 0; SysTick_CLKSourceConfig(SysTick_CLKSource_HCLK);
SysTick_SetReload(RELOAD_VALUE);
SysTick_CLKSourceConfig(SysTick_CLKSource_HCLK); SysTick_ITConfig(ENABLE);
SysTick_SetReload(RELOAD_VALUE); SysTick_CounterCmd(SysTick_Counter_Enable);)
SysTick_ITConfig(ENABLE);
SysTick_CounterCmd(SysTick_Counter_Enable);
)
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
clock_time_t clock_time_t
@ -108,16 +105,16 @@ clock_time(void)
void void
clock_delay(unsigned int i) clock_delay(unsigned int i)
{ {
for (; i > 0; i--) { /* Needs fixing XXX */ for(; i > 0; i--) { /* Needs fixing XXX */
unsigned j; unsigned j;
for (j = 50; j > 0; j--) for(j = 50; j > 0; j--) {
asm ("nop"); asm("nop");
}
} }
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
/** /**
* Wait for a multiple of 1 ms. * Wait for a multiple of 1 ms.
*
*/ */
void void
clock_wait(clock_time_t i) clock_wait(clock_time_t i)
@ -125,7 +122,7 @@ clock_wait(clock_time_t i)
clock_time_t start; clock_time_t start;
start = clock_time(); start = clock_time();
while(clock_time() - start < (clock_time_t)i); while(clock_time() - start < (clock_time_t) i);
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
unsigned long unsigned long
@ -133,49 +130,5 @@ clock_seconds(void)
{ {
return current_seconds; return current_seconds;
} }
/*--------------------------------------------------------------------------*/
#include <stdio.h> /** @} */
void
sleep_seconds(int seconds)
{
int32u quarter_seconds = seconds * 4;
uint8_t radio_on;
halPowerDown();
radio_on = stm32w_radio_is_on();
stm32w_radio_driver.off();
halSleepForQsWithOptions(&quarter_seconds, 0);
ATOMIC(
halPowerUp();
/* Update OS system ticks. */
current_seconds += seconds - quarter_seconds / 4 ; /* Passed seconds */
count += seconds * CLOCK_SECOND - quarter_seconds * CLOCK_SECOND / 4 ;
if(etimer_pending()) {
etimer_request_poll();
}
SysTick_CLKSourceConfig(SysTick_CLKSource_HCLK);
SysTick_SetReload(RELOAD_VALUE);
SysTick_ITConfig(ENABLE);
SysTick_CounterCmd(SysTick_Counter_Enable);
)
stm32w_radio_driver.init();
if(radio_on) {
stm32w_radio_driver.on();
}
uart1_init(115200);
leds_init();
rtimer_init();
PRINTF("WakeInfo: %04x\r\n", halGetWakeInfo());
}

View file

@ -1,5 +1,11 @@
/**
* \addtogroup stm32w-cpu
*
* @{
*/
/******************** (C) COPYRIGHT 2008 STMicroelectronics ******************** /******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
* File Name : cortexm3_macro.h * File Name : cortexm3-macro.h
* Author : MCD Application Team * Author : MCD Application Team
* Version : V2.0.3 * Version : V2.0.3
* Date : 09/22/2008 * Date : 09/22/2008
@ -13,17 +19,11 @@
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. * INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/ *******************************************************************************/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __CORTEXM3_MACRO_H #ifndef __CORTEXM3_MACRO_H
#define __CORTEXM3_MACRO_H #define __CORTEXM3_MACRO_H
/* Includes ------------------------------------------------------------------*/
#include "stm32w_type.h" #include "stm32w_type.h"
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
void __WFI(void); void __WFI(void);
void __WFE(void); void __WFE(void);
void __SEV(void); void __SEV(void);
@ -31,23 +31,30 @@ void __ISB(void);
void __DSB(void); void __DSB(void);
void __DMB(void); void __DMB(void);
void __SVC(void); void __SVC(void);
u32 __MRS_CONTROL(void); u32 __MRS_CONTROL(void);
void __MSR_CONTROL(u32 Control); void __MSR_CONTROL(u32 Control);
u32 __MRS_PSP(void); u32 __MRS_PSP(void);
void __MSR_PSP(u32 TopOfProcessStack); void __MSR_PSP(u32 TopOfProcessStack);
u32 __MRS_MSP(void); u32 __MRS_MSP(void);
void __MSR_MSP(u32 TopOfMainStack); void __MSR_MSP(u32 TopOfMainStack);
void __RESETPRIMASK(void); void __RESETPRIMASK(void);
void __SETPRIMASK(void); void __SETPRIMASK(void);
u32 __READ_PRIMASK(void); u32 __READ_PRIMASK(void);
void __RESETFAULTMASK(void); void __RESETFAULTMASK(void);
void __SETFAULTMASK(void); void __SETFAULTMASK(void);
u32 __READ_FAULTMASK(void); u32 __READ_FAULTMASK(void);
void __BASEPRICONFIG(u32 NewPriority); void __BASEPRICONFIG(u32 NewPriority);
u32 __GetBASEPRI(void); u32 __GetBASEPRI(void);
u16 __REV_HalfWord(u16 Data); u16 __REV_HalfWord(u16 Data);
u32 __REV_Word(u32 Data); u32 __REV_Word(u32 Data);
#endif /* __CORTEXM3_MACRO_H */ #endif /* __CORTEXM3_MACRO_H */
/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/ /******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
/** @} */

View file

@ -0,0 +1,227 @@
/**
* \addtogroup stm32w-cpu
*
* @{
*/
/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
* File Name : stm32w-conf.h
* Author : MCD Application Team
* Version : V2.0.3
* Date : 09/22/2008
* Description : Library configuration file.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
#ifndef __STM32F10x_CONF_H
#define __STM32F10x_CONF_H
#include "stm32w108-type.h"
/*
* Uncomment the line below to compile the library in DEBUG mode, this will
* expand the "assert_param" macro in the firmware library code (see "Exported
* macro" section below)
*/
/*#define DEBUG 1*/
/*---------------------------------------------------------------------------*/
/* Comment any line below to disable the specific peripheral inclusion */
/*
* ADC
*/
/* #define _ADC */
/* #define _ADC1 */
/* #define _ADC2 */
/* #define _ADC3 */
/*
* BKP
*/
/* #define _BKP */
/*
* CAN
*/
/* #define _CAN */
/*
* CRC
*/
/* #define _CRC */
/*
* DAC
*/
/* #define _DAC */
/*
* DBGMCU
*/
/* #define _DBGMCU */
/*
* DMA
*/
/* #define _DMA */
/* #define _DMA1_Channel1 */
/* #define _DMA1_Channel2 */
/* #define _DMA1_Channel3 */
/* #define _DMA1_Channel4 */
/* #define _DMA1_Channel5 */
/* #define _DMA1_Channel6 */
/* #define _DMA1_Channel7 */
/* #define _DMA2_Channel1 */
/* #define _DMA2_Channel2 */
/* #define _DMA2_Channel3 */
/* #define _DMA2_Channel4 */
/* #define _DMA2_Channel5 */
/*
* EXTI
*/
/* #define _EXTI */
/*
* FLASH and Option Bytes
*/
#define _FLASH
/*
* Uncomment the line below to enable FLASH program/erase/protections functions,
* otherwise only FLASH configuration (latency, prefetch, half cycle) functions
* are enabled
*/
/* #define _FLASH_PROG */
/*
* FSMC
*/
/* #define _FSMC */
/*
* GPIO
*/
#define _GPIO
/* #define _GPIOA */
/* #define _GPIOB */
#define _GPIOC
/* #define _GPIOD */
/* #define _GPIOE */
#define _GPIOF
/* #define _GPIOG */
#define _AFIO
/*
* I2C
*/
/* #define _I2C */
/* #define _I2C1 */
/* #define _I2C2 */
/*
* IWDG
*/
/* #define _IWDG */
/*
* NVIC
*/
#define _NVIC
/*
* PWR
*/
/* #define _PWR */
/*
* RCC
*/
#define _RCC
/*
* RTC
*/
/* #define _RTC */
/*
* SDIO
*/
/* #define _SDIO */
/*
* SPI
*/
/* #define _SPI */
/* #define _SPI1 */
/* #define _SPI2 */
/* #define _SPI3 */
/*
* SysTick
*/
#define _SysTick
/*
* TIM
*/
/* #define _TIM */
/* #define _TIM1 */
/* #define _TIM2 */
/* #define _TIM3 */
/* #define _TIM4 */
/* #define _TIM5 */
/* #define _TIM6 */
/* #define _TIM7 */
/* #define _TIM8 */
/*
* USART
*/
/* #define _USART */
/* #define _USART1 */
/* #define _USART2 */
/* #define _USART3 */
/* #define _UART4 */
/* #define _UART5 */
/*
* WWDG
*/
/* #define _WWDG */
/*
* In the following line adjust the value of External High Speed oscillator
* (HSE) used in your application
*/
#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz */
/*
* In the following line adjust the External High Speed oscillator (HSE) Startup
* Timeout value.
*/
#define HSEStartUp_TimeOut ((u16)0x0500) /* Time out for HSE start up */
#ifdef DEBUG
/**
* \brief The assert_param macro is used for function's parameters check.
* It is used only if the library is compiled in DEBUG mode.
* \param expr If expr is false, it calls assert_failed function
* which reports the name of the source file and the source
* line number of the call that failed.
* If expr is true, it returns no value.
*/
#define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
void assert_failed(u8 * file, u32 line);
#else
#define assert_param(expr) ((void)0)
#endif /* DEBUG */
#endif /* __STM32F10x_CONF_H */
/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
/** @} */

View file

@ -1,3 +1,9 @@
/**
* \addtogroup stm32w-cpu
*
* @{
*/
/* /*
* Copyright (c) 2010, STMicroelectronics. * Copyright (c) 2010, STMicroelectronics.
* All rights reserved. * All rights reserved.
@ -27,10 +33,8 @@
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
* *
* This file is part of the Contiki OS
*
*/ */
/*---------------------------------------------------------------------------*/
/** /**
* \file * \file
* Machine dependent STM32W radio code. * Machine dependent STM32W radio code.
@ -39,7 +43,6 @@
* Chi-Anh La la@imag.fr * Chi-Anh La la@imag.fr
* Simon Duquennoy <simonduq@sics.se> * Simon Duquennoy <simonduq@sics.se>
*/ */
/*---------------------------------------------------------------------------*/
#include PLATFORM_HEADER #include PLATFORM_HEADER
#include "hal/error.h" #include "hal/error.h"
@ -72,39 +75,38 @@
#define LED_ACTIVITY 1 #define LED_ACTIVITY 1
#else #else
#define LED_RDC 0 #define LED_RDC 0
#endif #endif /* RDC_CONF_DEBUG_LED */
#if DEBUG > 0 #if DEBUG > 0
#include <stdio.h> #include <stdio.h>
#define PRINTF(...) printf(__VA_ARGS__) #define PRINTF(...) printf(__VA_ARGS__)
#else #else
#define PRINTF(...) do {} while (0) #define PRINTF(...) do {} while (0)
#endif #endif /* DEBUG > 0 */
#if LED_ACTIVITY #if LED_ACTIVITY
#define LED_TX_ON() leds_on(LEDS_GREEN) #define LED_TX_ON() leds_on(LEDS_GREEN)
#define LED_TX_OFF() leds_off(LEDS_GREEN) #define LED_TX_OFF() leds_off(LEDS_GREEN)
#define LED_RX_ON() { \ #define LED_RX_ON() do { \
if(LED_RDC == 0){ \ if(LED_RDC == 0){ \
leds_on(LEDS_RED); \ leds_on(LEDS_RED); \
} \ } \
} } while (0)
#define LED_RX_OFF() { \ #define LED_RX_OFF() do { \
if(LED_RDC == 0){ \ if(LED_RDC == 0){ \
leds_off(LEDS_RED); \ leds_off(LEDS_RED); \
} \ } \
} } while (0)
#define LED_RDC_ON() { \ #define LED_RDC_ON() do { \
if(LED_RDC == 1){ \ if(LED_RDC == 1){ \
leds_on(LEDS_RED); \ leds_on(LEDS_RED); \
} \ } \
} } while (0)
#define LED_RDC_OFF() { \ #define LED_RDC_OFF() do { \
if(LED_RDC == 1){ \ if(LED_RDC == 1){ \
leds_off(LEDS_RED); \ leds_off(LEDS_RED); \
} \ } \
} } while (0)
#else #else
#define LED_TX_ON() #define LED_TX_ON()
#define LED_TX_OFF() #define LED_TX_OFF()
@ -112,63 +114,59 @@
#define LED_RX_OFF() #define LED_RX_OFF()
#define LED_RDC_ON() #define LED_RDC_ON()
#define LED_RDC_OFF() #define LED_RDC_OFF()
#endif #endif /* LED_ACTIVITY */
#if RDC_CONF_HARDWARE_CSMA #if RDC_CONF_HARDWARE_CSMA
#define MAC_RETRIES 0 #define MAC_RETRIES 0
#endif #endif /* RDC_CONF_HARDWARE_CSMA */
#ifndef MAC_RETRIES #ifndef MAC_RETRIES
#define MAC_RETRIES 1 #define MAC_RETRIES 1
#endif #endif /* MAC_RETRIES */
#if MAC_RETRIES #if MAC_RETRIES
int8_t mac_retries_left;
int8_t mac_retries_left; #define INIT_RETRY_CNT() (mac_retries_left = packetbuf_attr(PACKETBUF_ATTR_MAX_MAC_TRANSMISSIONS))
#define DEC_RETRY_CNT() (mac_retries_left--)
#define INIT_RETRY_CNT() (mac_retries_left = packetbuf_attr(PACKETBUF_ATTR_MAX_MAC_TRANSMISSIONS)) #define RETRY_CNT_GTZ() (mac_retries_left > 0)
#define DEC_RETRY_CNT() (mac_retries_left--)
#define RETRY_CNT_GTZ() (mac_retries_left > 0)
#else #else
#define INIT_RETRY_CNT()
#define INIT_RETRY_CNT() #define DEC_RETRY_CNT()
#define DEC_RETRY_CNT() #define RETRY_CNT_GTZ() 0
#define RETRY_CNT_GTZ() 0 #endif /* MAC_RETRIES */
#endif
/* If set to 1, a send() returns only after the packet has been transmitted. /* If set to 1, a send() returns only after the packet has been transmitted.
This is necessary if you use the x-mac module, for example. */ This is necessary if you use the x-mac module, for example. */
#ifndef RADIO_WAIT_FOR_PACKET_SENT #ifndef RADIO_WAIT_FOR_PACKET_SENT
#define RADIO_WAIT_FOR_PACKET_SENT 1 #define RADIO_WAIT_FOR_PACKET_SENT 1
#endif #endif /* RADIO_WAIT_FOR_PACKET_SENT */
#define TO_PREV_STATE() { \ #define TO_PREV_STATE() do { \
if(onoroff == OFF){ \ if(onoroff == OFF){ \
ST_RadioSleep(); \ ST_RadioSleep(); \
ENERGEST_OFF(ENERGEST_TYPE_LISTEN); \ ENERGEST_OFF(ENERGEST_TYPE_LISTEN); \
} \ } \
} } while(0)
#if RDC_CONF_HARDWARE_CSMA #if RDC_CONF_HARDWARE_CSMA
#define ST_RADIO_CHECK_CCA FALSE #define ST_RADIO_CHECK_CCA FALSE
#define ST_RADIO_CCA_ATTEMPT_MAX 0 #define ST_RADIO_CCA_ATTEMPT_MAX 0
#define ST_BACKOFF_EXP_MIN 0 #define ST_BACKOFF_EXP_MIN 0
#define ST_BACKOFF_EXP_MAX 0 #define ST_BACKOFF_EXP_MAX 0
#else #else /* RDC_CONF_HARDWARE_CSMA */
#define ST_RADIO_CHECK_CCA TRUE #define ST_RADIO_CHECK_CCA TRUE
#define ST_RADIO_CCA_ATTEMPT_MAX 4 #define ST_RADIO_CCA_ATTEMPT_MAX 4
#define ST_BACKOFF_EXP_MIN 2 #define ST_BACKOFF_EXP_MIN 2
#define ST_BACKOFF_EXP_MAX 6 #define ST_BACKOFF_EXP_MAX 6
#endif #endif /* RDC_CONF_HARDWARE_CSMA */
const RadioTransmitConfig radioTransmitConfig = { const RadioTransmitConfig radioTransmitConfig = {
TRUE, // waitForAck; TRUE, /* waitForAck; */
ST_RADIO_CHECK_CCA, // checkCca; // Set to FALSE with low-power MACs. ST_RADIO_CHECK_CCA, /* checkCca;Set to FALSE with low-power MACs. */
ST_RADIO_CCA_ATTEMPT_MAX, // ccaAttemptMax; ST_RADIO_CCA_ATTEMPT_MAX, /* ccaAttemptMax; */
ST_BACKOFF_EXP_MIN, // backoffExponentMin; ST_BACKOFF_EXP_MIN, /* backoffExponentMin; */
ST_BACKOFF_EXP_MAX, // backoffExponentMax; ST_BACKOFF_EXP_MAX, /* backoffExponentMax; */
TRUE // appendCrc; TRUE /* appendCrc; */
}; };
#define MAC_RETRIES 0 #define MAC_RETRIES 0
@ -178,38 +176,38 @@ const RadioTransmitConfig radioTransmitConfig = {
*/ */
#ifndef RADIO_RXBUFS #ifndef RADIO_RXBUFS
#define RADIO_RXBUFS 1 #define RADIO_RXBUFS 1
#endif #endif /* RADIO_RXBUFS */
static uint8_t stm32w_rxbufs[RADIO_RXBUFS][STM32W_MAX_PACKET_LEN+1]; // +1 because of the first byte, which will contain the length of the packet. /* +1 because of the first byte, which will contain the length of the packet. */
static uint8_t stm32w_rxbufs[RADIO_RXBUFS][STM32W_MAX_PACKET_LEN + 1];
#if RADIO_RXBUFS > 1 #if RADIO_RXBUFS > 1
static volatile int8_t first = -1, last=0; static volatile int8_t first = -1, last = 0;
#else #else /* RADIO_RXBUFS > 1 */
static const int8_t first=0, last=0; static const int8_t first = 0, last = 0;
#endif #endif /* RADIO_RXBUFS > 1 */
#if RADIO_RXBUFS > 1 #if RADIO_RXBUFS > 1
#define CLEAN_RXBUFS() do{first = -1; last = 0;}while(0) #define CLEAN_RXBUFS() do{first = -1; last = 0;}while(0)
#define RXBUFS_EMPTY() (first == -1) #define RXBUFS_EMPTY() (first == -1)
int
int RXBUFS_FULL(){ RXBUFS_FULL()
{
int8_t first_tmp = first; int8_t first_tmp = first;
return first_tmp == last; return first_tmp == last;
} }
#else /* RADIO_RXBUFS > 1 */ #else /* RADIO_RXBUFS > 1 */
#define CLEAN_RXBUFS() (stm32w_rxbufs[0][0] = 0) #define CLEAN_RXBUFS() (stm32w_rxbufs[0][0] = 0)
#define RXBUFS_EMPTY() (stm32w_rxbufs[0][0] == 0) #define RXBUFS_EMPTY() (stm32w_rxbufs[0][0] == 0)
#define RXBUFS_FULL() (stm32w_rxbufs[0][0] != 0) #define RXBUFS_FULL() (stm32w_rxbufs[0][0] != 0)
#endif /* RADIO_RXBUFS > 1 */ #endif /* RADIO_RXBUFS > 1 */
static uint8_t __attribute__(( aligned(2) )) stm32w_txbuf[STM32W_MAX_PACKET_LEN+1]; static uint8_t
__attribute__ ((aligned(2))) stm32w_txbuf[STM32W_MAX_PACKET_LEN + 1];
#define CLEAN_TXBUF() (stm32w_txbuf[0] = 0) #define CLEAN_TXBUF() (stm32w_txbuf[0] = 0)
#define TXBUF_EMPTY() (stm32w_txbuf[0] == 0) #define TXBUF_EMPTY() (stm32w_txbuf[0] == 0)
#define CHECKSUM_LEN 2 #define CHECKSUM_LEN 2
/* /*
@ -218,65 +216,76 @@ static uint8_t __attribute__(( aligned(2) )) stm32w_txbuf[STM32W_MAX_PACKET_LEN+
#define ON 0 #define ON 0
#define OFF 1 #define OFF 1
#define BUSYWAIT_UNTIL(cond, max_time) \
do { \
rtimer_clock_t t0; \
t0 = RTIMER_NOW(); \
while(!(cond) && RTIMER_CLOCK_LT(RTIMER_NOW(), t0 + (max_time))); \
} while(0)
#define GET_LOCK() locked++
static volatile uint8_t onoroff = OFF; static volatile uint8_t onoroff = OFF;
static uint8_t receiving_packet = 0; static uint8_t receiving_packet = 0;
static s8 last_rssi; static int8_t last_rssi;
static volatile StStatus last_tx_status; static volatile StStatus last_tx_status;
#define BUSYWAIT_UNTIL(cond, max_time) \
do { \
rtimer_clock_t t0; \
t0 = RTIMER_NOW(); \
while(!(cond) && RTIMER_CLOCK_LT(RTIMER_NOW(), t0 + (max_time))); \
} while(0)
static uint8_t locked; static uint8_t locked;
#define GET_LOCK() locked++
static void RELEASE_LOCK(void) {
if(locked>0)
locked--;
}
static volatile uint8_t is_transmit_ack; static volatile uint8_t is_transmit_ack;
/*--------------------------------------------------------------------------*/
static void
RELEASE_LOCK(void)
{
if(locked > 0)
locked--;
}
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
PROCESS(stm32w_radio_process, "STM32W radio driver"); PROCESS(stm32w_radio_process, "STM32W radio driver");
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
static int stm32w_radio_init(void); static int stm32w_radio_init(void);
static int stm32w_radio_prepare(const void *payload, unsigned short payload_len);
static int stm32w_radio_prepare(const void *payload,
unsigned short payload_len);
static int stm32w_radio_transmit(unsigned short payload_len); static int stm32w_radio_transmit(unsigned short payload_len);
static int stm32w_radio_send(const void *data, unsigned short len); static int stm32w_radio_send(const void *data, unsigned short len);
static int stm32w_radio_read(void *buf, unsigned short bufsize); static int stm32w_radio_read(void *buf, unsigned short bufsize);
static int stm32w_radio_channel_clear(void); static int stm32w_radio_channel_clear(void);
static int stm32w_radio_receiving_packet(void); static int stm32w_radio_receiving_packet(void);
static int stm32w_radio_pending_packet(void); static int stm32w_radio_pending_packet(void);
static int stm32w_radio_on(void); static int stm32w_radio_on(void);
static int stm32w_radio_off(void); static int stm32w_radio_off(void);
static int add_to_rxbuf(uint8_t * src); static int add_to_rxbuf(uint8_t * src);
static int read_from_rxbuf(void * dest, unsigned short len);
static int read_from_rxbuf(void *dest, unsigned short len);
const struct radio_driver stm32w_radio_driver = /*--------------------------------------------------------------------------*/
{ const struct radio_driver stm32w_radio_driver = {
stm32w_radio_init, stm32w_radio_init,
stm32w_radio_prepare, stm32w_radio_prepare,
stm32w_radio_transmit, stm32w_radio_transmit,
stm32w_radio_send, stm32w_radio_send,
stm32w_radio_read, stm32w_radio_read,
stm32w_radio_channel_clear, stm32w_radio_channel_clear,
stm32w_radio_receiving_packet, stm32w_radio_receiving_packet,
stm32w_radio_pending_packet, stm32w_radio_pending_packet,
stm32w_radio_on, stm32w_radio_on,
stm32w_radio_off, stm32w_radio_off,
}; };
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
static int stm32w_radio_init(void) static int
stm32w_radio_init(void)
{ {
// A channel needs also to be setted. /* A channel also needs to be set. */
ST_RadioSetChannel(RF_CHANNEL); ST_RadioSetChannel(RF_CHANNEL);
// Initialize radio (analog section, digital baseband and MAC). /* Initialize radio (analog section, digital baseband and MAC). */
// Leave radio powered up in non-promiscuous rx mode. /* Leave radio powered up in non-promiscuous rx mode. */
ST_RadioInit(ST_RADIO_POWER_MODE_OFF); ST_RadioInit(ST_RADIO_POWER_MODE_OFF);
onoroff = OFF; onoroff = OFF;
@ -297,172 +306,185 @@ static int stm32w_radio_init(void)
return 0; return 0;
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
int stm32w_radio_set_channel(uint8_t channel) void
stm32w_radio_set_promiscous(uint8_t on)
{ {
if (ST_RadioSetChannel(channel) == ST_SUCCESS) if(on) {
return 0; ST_RadioEnableAddressFiltering(0);
else } else {
return 1; ST_RadioEnableAddressFiltering(ST_RADIO_AUTOACK);
}
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
static int wait_for_tx(void){ int
stm32w_radio_set_channel(uint8_t channel)
{
if (ST_RadioSetChannel(channel) == ST_SUCCESS) {
return 0;
} else {
return 1;
}
}
/*---------------------------------------------------------------------------*/
static int
wait_for_tx(void)
{
struct timer t; struct timer t;
timer_set(&t, CLOCK_SECOND / 10);
timer_set(&t, CLOCK_SECOND/10); while(!TXBUF_EMPTY()) {
while(!TXBUF_EMPTY()){ if(timer_expired(&t)) {
if(timer_expired(&t)){
PRINTF("stm32w: tx buffer full.\r\n"); PRINTF("stm32w: tx buffer full.\r\n");
return 1; return 1;
} }
/* Put CPU in sleep mode. */ /* Put CPU in sleep mode. */
halSleepWithOptions(SLEEPMODE_IDLE,0); halSleepWithOptions(SLEEPMODE_IDLE, 0);
} }
return 0; return 0;
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
static int stm32w_radio_prepare(const void *payload, unsigned short payload_len) static int
stm32w_radio_prepare(const void *payload, unsigned short payload_len)
{ {
if(payload_len > STM32W_MAX_PACKET_LEN){ if(payload_len > STM32W_MAX_PACKET_LEN) {
PRINTF("stm32w: payload length=%d is too long.\r\n", payload_len); PRINTF("stm32w: payload length=%d is too long.\r\n", payload_len);
return RADIO_TX_ERR; return RADIO_TX_ERR;
} }
#if !RADIO_WAIT_FOR_PACKET_SENT #if !RADIO_WAIT_FOR_PACKET_SENT
/* Check if the txbuf is empty. /*
* Wait for a finite time. * Check if the txbuf is empty. Wait for a finite time.
* This sould not occur if we wait for the end of transmission in stm32w_radio_transmit(). * This should not occur if we wait for the end of transmission in
*/ * stm32w_radio_transmit().
if(wait_for_tx()){ */
PRINTF("stm32w: tx buffer full.\r\n"); if(wait_for_tx()) {
return RADIO_TX_ERR; PRINTF("stm32w: tx buffer full.\r\n");
} return RADIO_TX_ERR;
}
#endif /* RADIO_WAIT_FOR_PACKET_SENT */ #endif /* RADIO_WAIT_FOR_PACKET_SENT */
/* Copy to the txbuf. /*
* The first byte must be the packet length. * Copy to the txbuf.
*/ * The first byte must be the packet length.
CLEAN_TXBUF(); */
memcpy(stm32w_txbuf + 1, payload, payload_len); CLEAN_TXBUF();
memcpy(stm32w_txbuf + 1, payload, payload_len);
return RADIO_TX_OK;
return RADIO_TX_OK;
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
static int stm32w_radio_transmit(unsigned short payload_len) static int
stm32w_radio_transmit(unsigned short payload_len)
{ {
stm32w_txbuf[0] = payload_len + CHECKSUM_LEN; stm32w_txbuf[0] = payload_len + CHECKSUM_LEN;
INIT_RETRY_CNT();
INIT_RETRY_CNT();
if(onoroff == OFF){
PRINTF("stm32w: Radio is off, turning it on.\r\n");
ST_RadioWake();
ENERGEST_ON(ENERGEST_TYPE_LISTEN);
}
if(onoroff == OFF) {
PRINTF("stm32w: Radio is off, turning it on.\r\n");
ST_RadioWake();
ENERGEST_ON(ENERGEST_TYPE_LISTEN);
}
#if RADIO_WAIT_FOR_PACKET_SENT #if RADIO_WAIT_FOR_PACKET_SENT
GET_LOCK(); GET_LOCK();
#endif /* RADIO_WAIT_FOR_PACKET_SENT */ #endif /* RADIO_WAIT_FOR_PACKET_SENT */
last_tx_status = -1; last_tx_status = -1;
LED_TX_ON(); LED_TX_ON();
if(ST_RadioTransmit(stm32w_txbuf)==ST_SUCCESS){ if(ST_RadioTransmit(stm32w_txbuf) == ST_SUCCESS) {
ENERGEST_OFF(ENERGEST_TYPE_LISTEN);
ENERGEST_OFF(ENERGEST_TYPE_LISTEN); ENERGEST_ON(ENERGEST_TYPE_TRANSMIT);
ENERGEST_ON(ENERGEST_TYPE_TRANSMIT); PRINTF("stm32w: sending %d bytes\r\n", payload_len);
PRINTF("stm32w: sending %d bytes\r\n", payload_len);
#if DEBUG > 1 #if DEBUG > 1
for(uint8_t c=1; c <= stm32w_txbuf[0]-2; c++){ for(uint8_t c = 1; c <= stm32w_txbuf[0] - 2; c++) {
PRINTF("%x:",stm32w_txbuf[c]); PRINTF("%x:", stm32w_txbuf[c]);
} }
PRINTF("\r\n"); PRINTF("\r\n");
#endif #endif
#if RADIO_WAIT_FOR_PACKET_SENT #if RADIO_WAIT_FOR_PACKET_SENT
if(wait_for_tx()){ if(wait_for_tx()) {
PRINTF("stm32w: unknown tx error.\r\n"); PRINTF("stm32w: unknown tx error.\r\n");
TO_PREV_STATE();
LED_TX_OFF();
RELEASE_LOCK();
return RADIO_TX_ERR;
}
TO_PREV_STATE(); TO_PREV_STATE();
if(last_tx_status == ST_SUCCESS || last_tx_status == ST_PHY_ACK_RECEIVED || last_tx_status == ST_MAC_NO_ACK_RECEIVED){
RELEASE_LOCK();
if(last_tx_status == ST_PHY_ACK_RECEIVED){
return RADIO_TX_OK; /* ACK status */
}
else if (last_tx_status == ST_MAC_NO_ACK_RECEIVED || last_tx_status == ST_SUCCESS){
return RADIO_TX_NOACK;
}
}
LED_TX_OFF(); LED_TX_OFF();
RELEASE_LOCK(); RELEASE_LOCK();
return RADIO_TX_ERR; return RADIO_TX_ERR;
}
TO_PREV_STATE();
if(last_tx_status == ST_SUCCESS || last_tx_status == ST_PHY_ACK_RECEIVED ||
last_tx_status == ST_MAC_NO_ACK_RECEIVED) {
RELEASE_LOCK();
if(last_tx_status == ST_PHY_ACK_RECEIVED) {
return RADIO_TX_OK; /* ACK status */
} else if(last_tx_status == ST_MAC_NO_ACK_RECEIVED ||
last_tx_status == ST_SUCCESS) {
return RADIO_TX_NOACK;
}
}
LED_TX_OFF();
RELEASE_LOCK();
return RADIO_TX_ERR;
#else /* RADIO_WAIT_FOR_PACKET_SENT */ #else /* RADIO_WAIT_FOR_PACKET_SENT */
TO_PREV_STATE();
TO_PREV_STATE(); LED_TX_OFF();
LED_TX_OFF(); return RADIO_TX_OK;
return RADIO_TX_OK;
#endif /* RADIO_WAIT_FOR_PACKET_SENT */ #endif /* RADIO_WAIT_FOR_PACKET_SENT */
}
}
#if RADIO_WAIT_FOR_PACKET_SENT #if RADIO_WAIT_FOR_PACKET_SENT
RELEASE_LOCK(); RELEASE_LOCK();
#endif /* RADIO_WAIT_FOR_PACKET_SENT */ #endif /* RADIO_WAIT_FOR_PACKET_SENT */
TO_PREV_STATE(); TO_PREV_STATE();
PRINTF("stm32w: transmission never started.\r\n"); PRINTF("stm32w: transmission never started.\r\n");
/* TODO: Do we have to retransmit? */ /* TODO: Do we have to retransmit? */
CLEAN_TXBUF();
LED_TX_OFF();
return RADIO_TX_ERR;
CLEAN_TXBUF();
LED_TX_OFF();
return RADIO_TX_ERR;
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
static int stm32w_radio_send(const void *payload, unsigned short payload_len) static int
stm32w_radio_send(const void *payload, unsigned short payload_len)
{ {
if(stm32w_radio_prepare(payload, payload_len) == RADIO_TX_ERR) if (stm32w_radio_prepare(payload, payload_len) == RADIO_TX_ERR) {
return RADIO_TX_ERR; return RADIO_TX_ERR;
}
return stm32w_radio_transmit(payload_len); return stm32w_radio_transmit(payload_len);
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
static int stm32w_radio_channel_clear(void) static int
stm32w_radio_channel_clear(void)
{ {
return ST_RadioChannelIsClear(); return ST_RadioChannelIsClear();
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
static int stm32w_radio_receiving_packet(void) static int
stm32w_radio_receiving_packet(void)
{ {
return receiving_packet; return receiving_packet;
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
static int stm32w_radio_pending_packet(void) static int
stm32w_radio_pending_packet(void)
{ {
return !RXBUFS_EMPTY(); return !RXBUFS_EMPTY();
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
static int stm32w_radio_off(void) static int
stm32w_radio_off(void)
{ {
/* Any transmit or receive packets in progress are aborted. /* Any transmit or receive packets in progress are aborted.
* Waiting for end of transmission or reception have to be done. * Waiting for end of transmission or reception have to be done.
*/ */
if(locked) if(locked) {
{ PRINTF("stm32w: try to off while sending/receiving (lock=%u).\r\n",
PRINTF("stm32w: try to off while sending/receiving (lock=%u).\r\n", locked); locked);
return 0; return 0;
} }
/* off only if there is no transmission or reception of packet. */ /* off only if there is no transmission or reception of packet. */
if(onoroff == ON && TXBUF_EMPTY() && !receiving_packet){ if(onoroff == ON && TXBUF_EMPTY() && !receiving_packet) {
LED_RDC_OFF(); LED_RDC_OFF();
ST_RadioSleep(); ST_RadioSleep();
onoroff = OFF; onoroff = OFF;
@ -475,10 +497,11 @@ static int stm32w_radio_off(void)
return 1; return 1;
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
static int stm32w_radio_on(void) static int
stm32w_radio_on(void)
{ {
PRINTF("stm32w: turn radio on\n"); PRINTF("stm32w: turn radio on\n");
if(onoroff == OFF){ if(onoroff == OFF) {
LED_RDC_ON(); LED_RDC_ON();
ST_RadioWake(); ST_RadioWake();
onoroff = ON; onoroff = ON;
@ -489,24 +512,23 @@ static int stm32w_radio_on(void)
return 1; return 1;
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
int stm32w_radio_is_on(void) int
stm32w_radio_is_on(void)
{ {
return onoroff == ON; return onoroff == ON;
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
void
ST_RadioReceiveIsrCallback(uint8_t *packet,
void ST_RadioReceiveIsrCallback(u8 *packet, boolean ackFramePendingSet,
boolean ackFramePendingSet, uint32_t time, uint16_t errors, int8_t rssi)
u32 time,
u16 errors,
s8 rssi)
{ {
LED_RX_ON(); LED_RX_ON();
PRINTF("stm32w: incomming packet received\n"); PRINTF("stm32w: incomming packet received\n");
receiving_packet = 0; receiving_packet = 0;
/* Copy packet into the buffer. It is better to do this here. */ /* Copy packet into the buffer. It is better to do this here. */
if(add_to_rxbuf(packet)){ if(add_to_rxbuf(packet)) {
process_poll(&stm32w_radio_process); process_poll(&stm32w_radio_process);
last_rssi = rssi; last_rssi = rssi;
} }
@ -516,83 +538,76 @@ void ST_RadioReceiveIsrCallback(u8 *packet,
/* Wait for sending ACK */ /* Wait for sending ACK */
BUSYWAIT_UNTIL(!is_transmit_ack, RTIMER_SECOND / 1500); BUSYWAIT_UNTIL(!is_transmit_ack, RTIMER_SECOND / 1500);
RELEASE_LOCK(); RELEASE_LOCK();
} }
/*--------------------------------------------------------------------------*/
void ST_RadioTxAckIsrCallback (void) void
ST_RadioTxAckIsrCallback(void)
{ {
/* This callback is for simplemac 1.1.0. /*
Till now we block (RTIMER_SECOND / 1500) * This callback is for simplemac 1.1.0.
to prevent radio off during ACK transmission */ * Till now we block (RTIMER_SECOND / 1500)
* to prevent radio off during ACK transmission.
*/
is_transmit_ack = 0; is_transmit_ack = 0;
//RELEASE_LOCK(); /* RELEASE_LOCK(); */
} }
/*--------------------------------------------------------------------------*/
void
void ST_RadioTransmitCompleteIsrCallback(StStatus status, ST_RadioTransmitCompleteIsrCallback(StStatus status,
u32 txSyncTime, uint32_t txSyncTime, boolean framePending)
boolean framePending)
{ {
ENERGEST_OFF(ENERGEST_TYPE_TRANSMIT); ENERGEST_OFF(ENERGEST_TYPE_TRANSMIT);
ENERGEST_ON(ENERGEST_TYPE_LISTEN); ENERGEST_ON(ENERGEST_TYPE_LISTEN);
LED_TX_OFF(); LED_TX_OFF();
last_tx_status = status; last_tx_status = status;
if(status == ST_SUCCESS || status == ST_PHY_ACK_RECEIVED){ if(status == ST_SUCCESS || status == ST_PHY_ACK_RECEIVED) {
CLEAN_TXBUF();
} else {
if(RETRY_CNT_GTZ()) {
/* Retransmission */
LED_TX_ON();
if(ST_RadioTransmit(stm32w_txbuf) == ST_SUCCESS) {
ENERGEST_OFF(ENERGEST_TYPE_LISTEN);
ENERGEST_ON(ENERGEST_TYPE_TRANSMIT);
PRINTF("stm32w: retransmission.\r\n");
DEC_RETRY_CNT();
} else {
CLEAN_TXBUF();
LED_TX_OFF();
PRINTF("stm32w: retransmission failed.\r\n");
}
} else {
CLEAN_TXBUF(); CLEAN_TXBUF();
} }
else {
if(RETRY_CNT_GTZ()){
// Retransmission
LED_TX_ON();
if(ST_RadioTransmit(stm32w_txbuf)==ST_SUCCESS){
ENERGEST_OFF(ENERGEST_TYPE_LISTEN);
ENERGEST_ON(ENERGEST_TYPE_TRANSMIT);
PRINTF("stm32w: retransmission.\r\n");
DEC_RETRY_CNT();
}
else {
CLEAN_TXBUF();
LED_TX_OFF();
PRINTF("stm32w: retransmission failed.\r\n");
}
}
else {
CLEAN_TXBUF();
}
} }
/* Debug outputs. */ /* Debug outputs. */
if(status == ST_SUCCESS || status == ST_PHY_ACK_RECEIVED){ if(status == ST_SUCCESS || status == ST_PHY_ACK_RECEIVED) {
PRINTF("stm32w: return status TX_END\r\n"); PRINTF("stm32w: return status TX_END\r\n");
} } else if(status == ST_MAC_NO_ACK_RECEIVED) {
else if (status == ST_MAC_NO_ACK_RECEIVED){ PRINTF("stm32w: return status TX_END_NOACK\r\n");
PRINTF("stm32w: return status TX_END_NOACK\r\n"); } else if(status == ST_PHY_TX_CCA_FAIL) {
} PRINTF("stm32w: return status TX_END_CCA_FAIL\r\n");
else if (status == ST_PHY_TX_CCA_FAIL){ } else if(status == ST_PHY_TX_UNDERFLOW) {
PRINTF("stm32w: return status TX_END_CCA_FAIL\r\n"); PRINTF("stm32w: return status TX_END_UNDERFLOW\r\n");
} } else {
else if(status == ST_PHY_TX_UNDERFLOW){ PRINTF("stm32w: return status TX_END_INCOMPLETE\r\n");
PRINTF("stm32w: return status TX_END_UNDERFLOW\r\n");
}
else {
PRINTF("stm32w: return status TX_END_INCOMPLETE\r\n");
} }
} }
/*--------------------------------------------------------------------------*/
boolean
boolean ST_RadioDataPendingShortIdIsrCallback(int16u shortId) { ST_RadioDataPendingShortIdIsrCallback(uint16_t shortId)
{
receiving_packet = 1; receiving_packet = 1;
return FALSE; return FALSE;
} }
/*--------------------------------------------------------------------------*/
boolean ST_RadioDataPendingLongIdIsrCallback(int8u* longId) { boolean
ST_RadioDataPendingLongIdIsrCallback(uint8_t * longId)
{
receiving_packet = 1; receiving_packet = 1;
return FALSE; return FALSE;
} }
@ -600,20 +615,16 @@ boolean ST_RadioDataPendingLongIdIsrCallback(int8u* longId) {
PROCESS_THREAD(stm32w_radio_process, ev, data) PROCESS_THREAD(stm32w_radio_process, ev, data)
{ {
int len; int len;
PROCESS_BEGIN(); PROCESS_BEGIN();
PRINTF("stm32w_radio_process: started\r\n"); PRINTF("stm32w_radio_process: started\r\n");
while(1) { while(1) {
PROCESS_YIELD_UNTIL(ev == PROCESS_EVENT_POLL); PROCESS_YIELD_UNTIL(ev == PROCESS_EVENT_POLL);
PRINTF("stm32w_radio_process: calling receiver callback\r\n"); PRINTF("stm32w_radio_process: calling receiver callback\r\n");
#if DEBUG > 1 #if DEBUG > 1
for(uint8_t c=1; c <= RCVD_PACKET_LEN; c++){ for(uint8_t c = 1; c <= RCVD_PACKET_LEN; c++) {
PRINTF("%x",stm32w_rxbuf[c]); PRINTF("%x", stm32w_rxbuf[c]);
} }
PRINTF("\r\n"); PRINTF("\r\n");
#endif #endif
@ -624,84 +635,88 @@ PROCESS_THREAD(stm32w_radio_process, ev, data)
packetbuf_set_datalen(len); packetbuf_set_datalen(len);
NETSTACK_RDC.input(); NETSTACK_RDC.input();
} }
if(!RXBUFS_EMPTY()){ if(!RXBUFS_EMPTY()) {
// Some data packet still in rx buffer (this happens because process_poll doesn't queue requests), /*
// so stm32w_radio_process need to be called again. * Some data packet still in rx buffer (this happens because process_poll
* doesn't queue requests), so stm32w_radio_process needs to be called
* again.
*/
process_poll(&stm32w_radio_process); process_poll(&stm32w_radio_process);
} }
} }
PROCESS_END(); PROCESS_END();
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
static int stm32w_radio_read(void *buf, unsigned short bufsize) static int
stm32w_radio_read(void *buf, unsigned short bufsize)
{ {
return read_from_rxbuf(buf,bufsize); return read_from_rxbuf(buf, bufsize);
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
void ST_RadioOverflowIsrCallback(void) void
ST_RadioOverflowIsrCallback(void)
{ {
PRINTF("stm32w: radio overflow\r\n"); PRINTF("stm32w: radio overflow\r\n");
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
void ST_RadioSfdSentIsrCallback(u32 sfdSentTime) void
ST_RadioSfdSentIsrCallback(uint32_t sfdSentTime)
{ {
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
void ST_RadioMacTimerCompareIsrCallback(void) void
ST_RadioMacTimerCompareIsrCallback(void)
{ {
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
static int add_to_rxbuf(uint8_t * src) static int
add_to_rxbuf(uint8_t *src)
{ {
if(RXBUFS_FULL()){ if(RXBUFS_FULL()) {
return 0; return 0;
} }
memcpy(stm32w_rxbufs[last], src, src[0] + 1); memcpy(stm32w_rxbufs[last], src, src[0] + 1);
#if RADIO_RXBUFS > 1 #if RADIO_RXBUFS > 1
last = (last + 1) % RADIO_RXBUFS; last = (last + 1) % RADIO_RXBUFS;
if(first == -1){ if(first == -1) {
first = 0; first = 0;
} }
#endif #endif
return 1; return 1;
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
static int read_from_rxbuf(void * dest, unsigned short len) static int
read_from_rxbuf(void *dest, unsigned short len)
{ {
if(RXBUFS_EMPTY()) { /* Buffers are all empty */
return 0;
}
if(RXBUFS_EMPTY()){ // Buffers are all empty if(stm32w_rxbufs[first][0] > len) { /* Too large packet for dest. */
return 0; len = 0;
} } else {
len = stm32w_rxbufs[first][0];
if(stm32w_rxbufs[first][0] > len){ // Too large packet for dest. memcpy(dest, stm32w_rxbufs[first] + 1, len);
len = 0; packetbuf_set_attr(PACKETBUF_ATTR_RSSI, last_rssi);
} }
else {
len = stm32w_rxbufs[first][0];
memcpy(dest,stm32w_rxbufs[first]+1,len);
packetbuf_set_attr(PACKETBUF_ATTR_RSSI, last_rssi);
}
#if RADIO_RXBUFS > 1 #if RADIO_RXBUFS > 1
ATOMIC( ATOMIC(first = (first + 1) % RADIO_RXBUFS;
first = (first + 1) % RADIO_RXBUFS; int first_tmp = first; if(first_tmp == last) {
int first_tmp = first; CLEAN_RXBUFS();}
if(first_tmp == last){ )
CLEAN_RXBUFS();
}
)
#else #else
CLEAN_RXBUFS(); CLEAN_RXBUFS();
#endif #endif
return len; return len;
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
short last_packet_rssi(){ short
return last_rssi; last_packet_rssi()
{
return last_rssi;
} }
/** @} */

View file

@ -1,3 +1,9 @@
/**
* \addtogroup stm32w-cpu
*
* @{
*/
/* /*
* Copyright (c) 2007, Swedish Institute of Computer Science. * Copyright (c) 2007, Swedish Institute of Computer Science.
* All rights reserved. * All rights reserved.
@ -26,8 +32,6 @@
* OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
* SUCH DAMAGE. * SUCH DAMAGE.
* *
* This file is part of the Contiki operating system.
*
*/ */
/** /**
@ -45,14 +49,15 @@
#include "hal/hal.h" #include "hal/hal.h"
#include "simplemac/include/phy-library.h" #include "simplemac/include/phy-library.h"
int stm32w_radio_set_channel(uint8_t channel);
short last_packet_rssi();
#define STM32W_MAX_PACKET_LEN 127 #define STM32W_MAX_PACKET_LEN 127
extern const struct radio_driver stm32w_radio_driver; extern const struct radio_driver stm32w_radio_driver;
int stm32w_radio_set_channel(uint8_t channel);
short last_packet_rssi();
int stm32w_radio_is_on(void); int stm32w_radio_is_on(void);
#endif /* __STM32W_H__ */ #endif /* __STM32W_H__ */
/** @} */

View file

@ -0,0 +1,150 @@
/**
* \addtogroup stm32w-cpu
*
* @{
*/
/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
* File Name : stm32w108_systick.c
* Author : MCD Application Team
* Version : V2.0.3
* Date : 09/22/2008
* Description : This file provides all the SysTick firmware functions.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
#include <stdint.h>
#include "stm32w-systick.h"
/* SysTick registers bit mask */
/* CTRL TICKINT Mask */
#define CTRL_TICKINT_Set ((uint32_t)0x00000002)
#define CTRL_TICKINT_Reset ((uint32_t)0xFFFFFFFD)
/*--------------------------------------------------------------------------*/
/**
* \brief Configures the SysTick clock source.
* \param SysTick_CLKSource specifies the SysTick clock source.
* This parameter can be one of the following values:
* SysTick_CLKSource_HCLK_Div8: AHB clock divided by 8
* selected as SysTick clock source.
* SysTick_CLKSource_HCLK: AHB clock selected as
* SysTick clock source.
*/
void
SysTick_CLKSourceConfig(uint32_t SysTick_CLKSource)
{
/* Check the parameters */
assert_param(IS_SYSTICK_CLK_SOURCE(SysTick_CLKSource));
if(SysTick_CLKSource == SysTick_CLKSource_HCLK) {
SysTick->CTRL |= SysTick_CLKSource_HCLK;
} else {
SysTick->CTRL &= SysTick_CLKSource_HCLK_Div8;
}
}
/*--------------------------------------------------------------------------*/
/**
* \brief Sets SysTick Reload value.
* \param Reload SysTick Reload new value. Must be between 1 and 0xFFFFFF.
*/
void
SysTick_SetReload(uint32_t Reload)
{
/* Check the parameters */
assert_param(IS_SYSTICK_RELOAD(Reload));
SysTick->LOAD = Reload;
}
/*--------------------------------------------------------------------------*/
/**
* \brief Enables or disables the SysTick counter.
* \param SysTick_Counter new state of the SysTick counter.
* This parameter can be one of the following values:
* - SysTick_Counter_Disable: Disable counter
* - SysTick_Counter_Enable: Enable counter
* - SysTick_Counter_Clear: Clear counter value to 0
*/
void
SysTick_CounterCmd(uint32_t SysTick_Counter)
{
/* Check the parameters */
assert_param(IS_SYSTICK_COUNTER(SysTick_Counter));
if(SysTick_Counter == SysTick_Counter_Enable) {
SysTick->CTRL |= SysTick_Counter_Enable;
} else if(SysTick_Counter == SysTick_Counter_Disable) {
SysTick->CTRL &= SysTick_Counter_Disable;
} else { /* SysTick_Counter == SysTick_Counter_Clear */
SysTick->VAL = SysTick_Counter_Clear;
}
}
/*--------------------------------------------------------------------------*/
/**
* \brief Enables or disables the SysTick Interrupt.
* \param NewState new state of the SysTick Interrupt.
* This parameter can be: ENABLE or DISABLE.
*/
void
SysTick_ITConfig(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if(NewState != DISABLE) {
SysTick->CTRL |= CTRL_TICKINT_Set;
} else {
SysTick->CTRL &= CTRL_TICKINT_Reset;
}
}
/*--------------------------------------------------------------------------*/
/**
* \brief Gets SysTick counter value.
* \return SysTick current value
*/
uint32_t
SysTick_GetCounter(void)
{
return (SysTick->VAL);
}
/*--------------------------------------------------------------------------*/
/**
* \brief Checks whether the specified SysTick flag is set or not.
* \param SysTick_FLAG specifies the flag to check.
* This parameter can be one of the following values:
* - SysTick_FLAG_COUNT
* - SysTick_FLAG_SKEW
* - SysTick_FLAG_NOREF
*/
FlagStatus
SysTick_GetFlagStatus(uint8_t SysTick_FLAG)
{
uint32_t statusreg = 0, tmp = 0;
FlagStatus bitstatus = RESET;
/* Check the parameters */
assert_param(IS_SYSTICK_FLAG(SysTick_FLAG));
/* Get the SysTick register index */
tmp = SysTick_FLAG >> 3;
if(tmp == 2) { /* The flag to check is in CTRL register */
statusreg = SysTick->CTRL;
} else { /* The flag to check is in CALIB register */
statusreg = SysTick->CALIB;
}
if((statusreg & ((uint32_t) 1 << SysTick_FLAG)) != (uint32_t) RESET) {
bitstatus = SET;
} else {
bitstatus = RESET;
}
return bitstatus;
}
/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
/** @} */

View file

@ -1,3 +1,9 @@
/**
* \addtogroup stm32w-cpu
*
* @{
*/
/******************** (C) COPYRIGHT 2008 STMicroelectronics ******************** /******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
* File Name : stm32f10x_systick.h * File Name : stm32f10x_systick.h
* Author : MCD Application Team * Author : MCD Application Team
@ -14,19 +20,17 @@
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. * INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/ *******************************************************************************/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32W_SYSTICK_H #ifndef __STM32W_SYSTICK_H
#define __STM32W_SYSTICK_H #define __STM32W_SYSTICK_H
#include "stm32w108_type.h" #include "stm32w108-type.h"
#include "stm32w_conf.h" #include "stm32w-conf.h"
#ifndef EXT #ifndef EXT
#define EXT extern #define EXT extern
#endif /* EXT */ #endif /* EXT */
typedef struct typedef struct {
{
vu32 CTRL; vu32 CTRL;
vu32 LOAD; vu32 LOAD;
vu32 VAL; vu32 VAL;
@ -41,39 +45,47 @@ typedef struct
#define SCB_BASE (SCS_BASE + 0x0D00) #define SCB_BASE (SCS_BASE + 0x0D00)
#ifdef _SysTick #ifdef _SysTick
#define SysTick ((SysTick_TypeDef *) SysTick_BASE) #define SysTick ((SysTick_TypeDef *) SysTick_BASE)
#endif /*_SysTick */ #endif /*_SysTick */
/***************** Bit definition for SysTick_CTRL register *****************/ /***************** Bit definition for SysTick_CTRL register *****************/
#define SysTick_CTRL_ENABLE ((u32)0x00000001) /* Counter enable */ /* Counter enable */
#define SysTick_CTRL_TICKINT ((u32)0x00000002) /* Counting down to 0 pends the SysTick handler */ #define SysTick_CTRL_ENABLE ((u32)0x00000001)
#define SysTick_CTRL_CLKSOURCE ((u32)0x00000004) /* Clock source */ /* Counting down to 0 pends the SysTick handler */
#define SysTick_CTRL_COUNTFLAG ((u32)0x00010000) /* Count Flag */ #define SysTick_CTRL_TICKINT ((u32)0x00000002)
/* Clock source */
#define SysTick_CTRL_CLKSOURCE ((u32)0x00000004)
/* Count Flag */
#define SysTick_CTRL_COUNTFLAG ((u32)0x00010000)
/***************** Bit definition for SysTick_LOAD register *****************/ /***************** Bit definition for SysTick_LOAD register *****************/
#define SysTick_LOAD_RELOAD ((u32)0x00FFFFFF) /* Value to load into the SysTick Current Value Register when the counter reaches 0 */ /*
* Value to load into the SysTick Current Value Register when the
* counter reaches 0
*/
#define SysTick_LOAD_RELOAD ((u32)0x00FFFFFF)
/***************** Bit definition for SysTick_VAL register ******************/ /***************** Bit definition for SysTick_VAL register ******************/
#define SysTick_VAL_CURRENT ((u32)0x00FFFFFF) /* Current value at the time the register is accessed */ /* Current value at the time the register is accessed */
#define SysTick_VAL_CURRENT ((u32)0x00FFFFFF)
/***************** Bit definition for SysTick_CALIB register ****************/ /***************** Bit definition for SysTick_CALIB register ****************/
#define SysTick_CALIB_TENMS ((u32)0x00FFFFFF) /* Reload value to use for 10ms timing */ /* Reload value to use for 10ms timing */
#define SysTick_CALIB_SKEW ((u32)0x40000000) /* Calibration value is not exactly 10 ms */ #define SysTick_CALIB_TENMS ((u32)0x00FFFFFF)
#define SysTick_CALIB_NOREF ((u32)0x80000000) /* The reference clock is not provided */ /* Calibration value is not exactly 10 ms */
#define SysTick_CALIB_SKEW ((u32)0x40000000)
/* The reference clock is not provided */
#define SysTick_CALIB_NOREF ((u32)0x80000000)
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* SysTick clock source */
#define SysTick_CLKSource_HCLK_Div8 ((u32)0xFFFFFFFB) #define SysTick_CLKSource_HCLK_Div8 ((u32)0xFFFFFFFB)
#define SysTick_CLKSource_HCLK ((u32)0x00000004) #define SysTick_CLKSource_HCLK ((u32)0x00000004)
#define IS_SYSTICK_CLK_SOURCE(SOURCE) (((SOURCE) == SysTick_CLKSource_HCLK) || \ #define IS_SYSTICK_CLK_SOURCE(SOURCE) (((SOURCE) == SysTick_CLKSource_HCLK) || \
((SOURCE) == SysTick_CLKSource_HCLK_Div8)) ((SOURCE) == SysTick_CLKSource_HCLK_Div8))
/* SysTick counter state */ /* SysTick counter state */
#define SysTick_Counter_Disable ((u32)0xFFFFFFFE) #define SysTick_Counter_Disable ((u32)0xFFFFFFFE)
@ -95,15 +107,18 @@ typedef struct
#define IS_SYSTICK_RELOAD(RELOAD) (((RELOAD) > 0) && ((RELOAD) <= 0xFFFFFF)) #define IS_SYSTICK_RELOAD(RELOAD) (((RELOAD) > 0) && ((RELOAD) <= 0xFFFFFF))
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
void SysTick_CLKSourceConfig(u32 SysTick_CLKSource); void SysTick_CLKSourceConfig(u32 SysTick_CLKSource);
void SysTick_SetReload(u32 Reload); void SysTick_SetReload(u32 Reload);
void SysTick_CounterCmd(u32 SysTick_Counter); void SysTick_CounterCmd(u32 SysTick_Counter);
void SysTick_ITConfig(FunctionalState NewState); void SysTick_ITConfig(FunctionalState NewState);
u32 SysTick_GetCounter(void); u32 SysTick_GetCounter(void);
FlagStatus SysTick_GetFlagStatus(u8 SysTick_FLAG); FlagStatus SysTick_GetFlagStatus(u8 SysTick_FLAG);
#endif /* __STM32F10x_SYSTICK_H */ #endif /* __STM32F10x_SYSTICK_H */
/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/ /******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/
/** @} */

View file

@ -1,174 +0,0 @@
/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
* File Name : stm32w_conf.h
* Author : MCD Application Team
* Version : V2.0.3
* Date : 09/22/2008
* Description : Library configuration file.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32F10x_CONF_H
#define __STM32F10x_CONF_H
/* Includes ------------------------------------------------------------------*/
#include "stm32w108_type.h"
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Uncomment the line below to compile the library in DEBUG mode, this will expanse
the "assert_param" macro in the firmware library code (see "Exported macro"
section below) */
/*#define DEBUG 1*/
/* Comment the line below to disable the specific peripheral inclusion */
/************************************* ADC ************************************/
//#define _ADC
//#define _ADC1
//#define _ADC2
//#define _ADC3
/************************************* BKP ************************************/
//#define _BKP
/************************************* CAN ************************************/
//#define _CAN
/************************************* CRC ************************************/
//#define _CRC
/************************************* DAC ************************************/
//#define _DAC
/************************************* DBGMCU *********************************/
//#define _DBGMCU
/************************************* DMA ************************************/
//#define _DMA
//#define _DMA1_Channel1
//#define _DMA1_Channel2
//#define _DMA1_Channel3
//#define _DMA1_Channel4
//#define _DMA1_Channel5
//#define _DMA1_Channel6
//#define _DMA1_Channel7
//#define _DMA2_Channel1
//#define _DMA2_Channel2
//#define _DMA2_Channel3
//#define _DMA2_Channel4
//#define _DMA2_Channel5
/************************************* EXTI ***********************************/
//#define _EXTI
/************************************* FLASH and Option Bytes *****************/
#define _FLASH
/* Uncomment the line below to enable FLASH program/erase/protections functions,
otherwise only FLASH configuration (latency, prefetch, half cycle) functions
are enabled */
/* #define _FLASH_PROG */
/************************************* FSMC ***********************************/
//#define _FSMC
/************************************* GPIO ***********************************/
#define _GPIO
//#define _GPIOA
//#define _GPIOB
#define _GPIOC
//#define _GPIOD
//#define _GPIOE
#define _GPIOF
//#define _GPIOG
#define _AFIO
/************************************* I2C ************************************/
//#define _I2C
//#define _I2C1
//#define _I2C2
/************************************* IWDG ***********************************/
//#define _IWDG
/************************************* NVIC ***********************************/
#define _NVIC
/************************************* PWR ************************************/
//#define _PWR
/************************************* RCC ************************************/
#define _RCC
/************************************* RTC ************************************/
//#define _RTC
/************************************* SDIO ***********************************/
//#define _SDIO
/************************************* SPI ************************************/
//#define _SPI
//#define _SPI1
//#define _SPI2
//#define _SPI3
/************************************* SysTick ********************************/
#define _SysTick
/************************************* TIM ************************************/
//#define _TIM
//#define _TIM1
//#define _TIM2
//#define _TIM3
//#define _TIM4
//#define _TIM5
//#define _TIM6
//#define _TIM7
//#define _TIM8
/************************************* USART **********************************/
//#define _USART
//#define _USART1
//#define _USART2
//#define _USART3
//#define _UART4
//#define _UART5
/************************************* WWDG ***********************************/
//#define _WWDG
/* In the following line adjust the value of External High Speed oscillator (HSE)
used in your application */
#define HSE_Value ((u32)8000000) /* Value of the External oscillator in Hz*/
/* In the following line adjust the External High Speed oscillator (HSE) Startup
Timeout value */
#define HSEStartUp_TimeOut ((u16)0x0500) /* Time out for HSE start up */
/* Exported macro ------------------------------------------------------------*/
#ifdef DEBUG
/*******************************************************************************
* Macro Name : assert_param
* Description : The assert_param macro is used for function's parameters check.
* It is used only if the library is compiled in DEBUG mode.
* Input : - expr: If expr is false, it calls assert_failed function
* which reports the name of the source file and the source
* line number of the call that failed.
* If expr is true, it returns no value.
* Return : None
*******************************************************************************/
#define assert_param(expr) ((expr) ? (void)0 : assert_failed((u8 *)__FILE__, __LINE__))
/* Exported functions ------------------------------------------------------- */
void assert_failed(u8* file, u32 line);
#else
#define assert_param(expr) ((void)0)
#endif /* DEBUG */
#endif /* __STM32F10x_CONF_H */
/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/

View file

@ -1,181 +0,0 @@
/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
* File Name : stm32w108_systick.c
* Author : MCD Application Team
* Version : V2.0.3
* Date : 09/22/2008
* Description : This file provides all the SysTick firmware functions.
********************************************************************************
* THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS
* WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE TIME.
* AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY DIRECT,
* INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING FROM THE
* CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Includes ------------------------------------------------------------------*/
#include "stm32w_systick.h"
/* Private typedef -----------------------------------------------------------*/
/* Private define ------------------------------------------------------------*/
/* ---------------------- SysTick registers bit mask -------------------- */
/* CTRL TICKINT Mask */
#define CTRL_TICKINT_Set ((u32)0x00000002)
#define CTRL_TICKINT_Reset ((u32)0xFFFFFFFD)
/* Private macro -------------------------------------------------------------*/
/* Private variables ---------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Private functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : SysTick_CLKSourceConfig
* Description : Configures the SysTick clock source.
* Input : - SysTick_CLKSource: specifies the SysTick clock source.
* This parameter can be one of the following values:
* - SysTick_CLKSource_HCLK_Div8: AHB clock divided by 8
* selected as SysTick clock source.
* - SysTick_CLKSource_HCLK: AHB clock selected as
* SysTick clock source.
* Output : None
* Return : None
*******************************************************************************/
void SysTick_CLKSourceConfig(u32 SysTick_CLKSource)
{
/* Check the parameters */
assert_param(IS_SYSTICK_CLK_SOURCE(SysTick_CLKSource));
if (SysTick_CLKSource == SysTick_CLKSource_HCLK)
{
SysTick->CTRL |= SysTick_CLKSource_HCLK;
}
else
{
SysTick->CTRL &= SysTick_CLKSource_HCLK_Div8;
}
}
/*******************************************************************************
* Function Name : SysTick_SetReload
* Description : Sets SysTick Reload value.
* Input : - Reload: SysTick Reload new value.
* This parameter must be a number between 1 and 0xFFFFFF.
* Output : None
* Return : None
*******************************************************************************/
void SysTick_SetReload(u32 Reload)
{
/* Check the parameters */
assert_param(IS_SYSTICK_RELOAD(Reload));
SysTick->LOAD = Reload;
}
/*******************************************************************************
* Function Name : SysTick_CounterCmd
* Description : Enables or disables the SysTick counter.
* Input : - SysTick_Counter: new state of the SysTick counter.
* This parameter can be one of the following values:
* - SysTick_Counter_Disable: Disable counter
* - SysTick_Counter_Enable: Enable counter
* - SysTick_Counter_Clear: Clear counter value to 0
* Output : None
* Return : None
*******************************************************************************/
void SysTick_CounterCmd(u32 SysTick_Counter)
{
/* Check the parameters */
assert_param(IS_SYSTICK_COUNTER(SysTick_Counter));
if (SysTick_Counter == SysTick_Counter_Enable)
{
SysTick->CTRL |= SysTick_Counter_Enable;
}
else if (SysTick_Counter == SysTick_Counter_Disable)
{
SysTick->CTRL &= SysTick_Counter_Disable;
}
else /* SysTick_Counter == SysTick_Counter_Clear */
{
SysTick->VAL = SysTick_Counter_Clear;
}
}
/*******************************************************************************
* Function Name : SysTick_ITConfig
* Description : Enables or disables the SysTick Interrupt.
* Input : - NewState: new state of the SysTick Interrupt.
* This parameter can be: ENABLE or DISABLE.
* Output : None
* Return : None
*******************************************************************************/
void SysTick_ITConfig(FunctionalState NewState)
{
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
if (NewState != DISABLE)
{
SysTick->CTRL |= CTRL_TICKINT_Set;
}
else
{
SysTick->CTRL &= CTRL_TICKINT_Reset;
}
}
/*******************************************************************************
* Function Name : SysTick_GetCounter
* Description : Gets SysTick counter value.
* Input : None
* Output : None
* Return : SysTick current value
*******************************************************************************/
u32 SysTick_GetCounter(void)
{
return(SysTick->VAL);
}
/*******************************************************************************
* Function Name : SysTick_GetFlagStatus
* Description : Checks whether the specified SysTick flag is set or not.
* Input : - SysTick_FLAG: specifies the flag to check.
* This parameter can be one of the following values:
* - SysTick_FLAG_COUNT
* - SysTick_FLAG_SKEW
* - SysTick_FLAG_NOREF
* Output : None
* Return : None
*******************************************************************************/
FlagStatus SysTick_GetFlagStatus(u8 SysTick_FLAG)
{
u32 statusreg = 0, tmp = 0 ;
FlagStatus bitstatus = RESET;
/* Check the parameters */
assert_param(IS_SYSTICK_FLAG(SysTick_FLAG));
/* Get the SysTick register index */
tmp = SysTick_FLAG >> 3;
if (tmp == 2) /* The flag to check is in CTRL register */
{
statusreg = SysTick->CTRL;
}
else /* The flag to check is in CALIB register */
{
statusreg = SysTick->CALIB;
}
if ((statusreg & ((u32)1 << SysTick_FLAG)) != (u32)RESET)
{
bitstatus = SET;
}
else
{
bitstatus = RESET;
}
return bitstatus;
}
/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/

View file

@ -1,3 +1,39 @@
/**
* \addtogroup stm32w-cpu
*
* @{
*/
/*
* Copyright (c) 2010, STMicroelectronics.
* All rights reserved.
*
* 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.
* 3. Neither the name of the Institute 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 INSTITUTE 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 INSTITUTE 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 <stdio.h> #include <stdio.h>
#include "dev/uart1.h" #include "dev/uart1.h"
@ -5,7 +41,7 @@
#include PLATFORM_HEADER #include PLATFORM_HEADER
#include "hal/micro/micro-common.h" #include "hal/micro/micro-common.h"
#include "hal/micro/cortexm3/micro-common.h" #include "hal/micro/cortexm3/micro-common.h"
//#include "uart.h" /* #include "uart.h" */
#ifdef __GNUC__ #ifdef __GNUC__
# define _LLIO_STDIN ((int) stdin) # define _LLIO_STDIN ((int) stdin)
@ -19,38 +55,40 @@
#endif #endif
#undef putchar #undef putchar
/*--------------------------------------------------------------------------*/
int __attribute__(( weak )) putchar(int c) int
__attribute__ ((weak)) putchar(int c)
{ {
uart1_writeb(c); uart1_writeb(c);
return c; return c;
} }
/*--------------------------------------------------------------------------*/
void __io_putchar(char c) void
__io_putchar(char c)
{ {
putchar(c); putchar(c);
} }
/*--------------------------------------------------------------------------*/
size_t _write(int handle, const unsigned char * buffer, size_t size) size_t
_write(int handle, const unsigned char *buffer, size_t size)
{ {
size_t nChars = 0; size_t nChars = 0;
if (handle != _LLIO_STDOUT && handle != _LLIO_STDERR) { if(handle != _LLIO_STDOUT && handle != _LLIO_STDERR) {
return _LLIO_ERROR; return _LLIO_ERROR;
} }
if(buffer == 0) {
if (buffer == 0) { /* This means that we should flush internal buffers. */
// This means that we should flush internal buffers. /* spin until TX complete (TX is idle) */
//spin until TX complete (TX is idle) while((SC1_UARTSTAT & SC_UARTTXIDLE) != SC_UARTTXIDLE) {
while ((SC1_UARTSTAT&SC_UARTTXIDLE)!=SC_UARTTXIDLE) {} }
return 0; return 0;
} }
// ensure port is configured for UART /* ensure port is configured for UART */
if(SC1_MODE != SC1_MODE_UART) { if(SC1_MODE != SC1_MODE_UART) {
return _LLIO_ERROR; return _LLIO_ERROR;
} }
while(size--) { while(size--) {
__io_putchar(*buffer++); __io_putchar(*buffer++);
++nChars; ++nChars;
@ -59,9 +97,10 @@ size_t _write(int handle, const unsigned char * buffer, size_t size)
return nChars; return nChars;
} }
/*--------------------------------------------------------------------------*/
size_t _read(int handle, unsigned char * buffer, size_t size) size_t
_read(int handle, unsigned char *buffer, size_t size)
{ {
return 0; return 0;
} }
/** @} */

View file

@ -1,3 +1,9 @@
/**
* \addtogroup stm32w-cpu
*
* @{
*/
/* /*
* Copyright (c) 2010, STMicroelectronics. * Copyright (c) 2010, STMicroelectronics.
* All rights reserved. * All rights reserved.
@ -27,10 +33,9 @@
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
* *
* This file is part of the Contiki OS
* *
*/ */
/*---------------------------------------------------------------------------*/
/** /**
* \file * \file
* Machine dependent STM32W UART1 code. * Machine dependent STM32W UART1 code.
@ -41,53 +46,42 @@
* \since * \since
* 03.04.2010 * 03.04.2010
*/ */
/*---------------------------------------------------------------------------*/
#include <stdio.h> #include <stdio.h>
#include <stdlib.h> #include <stdlib.h>
//#include <io.h>
//#include <signal.h>
#include "sys/energest.h" #include "sys/energest.h"
#include "dev/uart1.h" #include "dev/uart1.h"
#include "dev/watchdog.h" #include "dev/watchdog.h"
#include "lib/ringbuf.h" #include "lib/ringbuf.h"
#include "dev/leds.h" #include "dev/leds.h"
static int (*uart1_input_handler)(unsigned char c); static int (*uart1_input_handler) (unsigned char c);
void uart1_rx_interrupt(void);
void uart1_tx_interrupt(void);
static volatile uint8_t transmitting; static volatile uint8_t transmitting;
#ifdef UART1_CONF_TX_WITH_INTERRUPT #ifdef UART1_CONF_TX_WITH_INTERRUPT
#define TX_WITH_INTERRUPT UART1_CONF_TX_WITH_INTERRUPT #define TX_WITH_INTERRUPT UART1_CONF_TX_WITH_INTERRUPT
#else /* UART1_CONF_TX_WITH_INTERRUPT */ #else /* UART1_CONF_TX_WITH_INTERRUPT */
#define TX_WITH_INTERRUPT 1 #define TX_WITH_INTERRUPT 1
#endif /* UART1_CONF_TX_WITH_INTERRUPT */ #endif /* UART1_CONF_TX_WITH_INTERRUPT */
#if TX_WITH_INTERRUPT #if TX_WITH_INTERRUPT
#ifdef UART1_CONF_TX_BUFSIZE #ifdef UART1_CONF_TX_BUFSIZE
#define UART1_TX_BUFSIZE UART1_CONF_TX_BUFSIZE #define UART1_TX_BUFSIZE UART1_CONF_TX_BUFSIZE
#else /* UART1_CONF_TX_BUFSIZE */ #else /* UART1_CONF_TX_BUFSIZE */
#define UART1_TX_BUFSIZE 64 #define UART1_TX_BUFSIZE 64
#endif /* UART1_CONF_TX_BUFSIZE */ #endif /* UART1_CONF_TX_BUFSIZE */
static struct ringbuf txbuf; static struct ringbuf txbuf;
static uint8_t txbuf_data[UART1_TX_BUFSIZE]; static uint8_t txbuf_data[UART1_TX_BUFSIZE];
#endif /* TX_WITH_INTERRUPT */ #endif /* TX_WITH_INTERRUPT */
/*---------------------------------------------------------------------------*/
//uint8_t
//uart1_active(void)
//{
// return ((~ UTCTL1) & TXEPT) | transmitting;
//}
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
void void
uart1_set_input(int (*input)(unsigned char c)) uart1_set_input(int (*input) (unsigned char c))
{ {
uart1_input_handler = input; uart1_input_handler = input;
} }
@ -97,21 +91,23 @@ uart1_writeb(unsigned char c)
{ {
watchdog_periodic(); watchdog_periodic();
#if TX_WITH_INTERRUPT #if TX_WITH_INTERRUPT
/*
/* Put the outgoing byte on the transmission buffer. If the buffer * Put the outgoing byte on the transmission buffer. If the buffer
is full, we just keep on trying to put the byte into the buffer * is full, we just keep on trying to put the byte into the buffer
until it is possible to put it there. */ * until it is possible to put it there.
*/
while(ringbuf_put(&txbuf, c) == 0); while(ringbuf_put(&txbuf, c) == 0);
/* If there is no transmission going, we need to start it by putting /*
the first byte into the UART. */ * If there is no transmission going, we need to start it by putting
* the first byte into the UART.
*/
if(transmitting == 0) { if(transmitting == 0) {
transmitting = 1; transmitting = 1;
SC1_DATA = ringbuf_get(&txbuf); SC1_DATA = ringbuf_get(&txbuf);
INT_SC1FLAG = INT_SCTXFREE; INT_SC1FLAG = INT_SCTXFREE;
INT_SC1CFG |= INT_SCTXFREE; INT_SC1CFG |= INT_SCTXFREE;
} }
#else /* TX_WITH_INTERRUPT */ #else /* TX_WITH_INTERRUPT */
/* Loop until the transmission buffer is available. */ /* Loop until the transmission buffer is available. */
@ -119,107 +115,97 @@ uart1_writeb(unsigned char c)
/* Transmit the data. */ /* Transmit the data. */
SC1_DATA = c; SC1_DATA = c;
INT_SC1FLAG = INT_SCTXFREE; INT_SC1FLAG = INT_SCTXFREE;
#endif /* TX_WITH_INTERRUPT */ #endif /* TX_WITH_INTERRUPT */
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
#if ! WITH_UIP /* If WITH_UIP is defined, putchar() is defined by the SLIP driver */ #if ! WITH_UIP
/* If WITH_UIP is defined, putchar() is defined by the SLIP driver */
#endif /* ! WITH_UIP */ #endif /* ! WITH_UIP */
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
/** /*
* Initalize the RS232 port. * Initalize the RS232 port.
*
*/ */
void void
uart1_init(unsigned long ubr) uart1_init(unsigned long ubr)
{ {
uint16_t uartper;
GPIO_PBCFGL &= 0xF00F;
GPIO_PBCFGL |= 0x0490;
uint16_t uartper = (uint32_t)24e6/(2*ubr);
uint32_t rest = (uint32_t)24e6%(2*ubr);
SC1_UARTFRAC = 0;
if(rest > (2*ubr)/4 && rest < (3*2*ubr)/4){
SC1_UARTFRAC = 1; // + 0.5
}
else if(rest >= (3*2*ubr)/4){
uartper++; // + 1
}
SC1_UARTPER = uartper;
SC1_UARTCFG = SC_UART8BIT;
SC1_MODE = SC1_MODE_UART;
SC1_INTMODE = SC_RXVALLEVEL | SC_TXFREELEVEL; // Receive buffer has data interrupt mode and Transmit buffer free interrupt mode: Level triggered.
INT_SC1CFG = INT_SCRXVAL; // Receive buffer has data interrupt enable
uint32_t rest;
GPIO_PBCFGL &= 0xF00F;
GPIO_PBCFGL |= 0x0490;
uartper = (uint32_t) 24e6 / (2 * ubr);
rest = (uint32_t) 24e6 % (2 * ubr);
SC1_UARTFRAC = 0;
if(rest > (2 * ubr) / 4 && rest < (3 * 2 * ubr) / 4) {
SC1_UARTFRAC = 1; /* + 0.5 */
} else if(rest >= (3 * 2 * ubr) / 4) {
uartper++; /* + 1 */
}
SC1_UARTPER = uartper;
SC1_UARTCFG = SC_UART8BIT;
SC1_MODE = SC1_MODE_UART;
/*
* Receive buffer has data interrupt mode and Transmit buffer free interrupt
* mode: Level triggered.
*/
SC1_INTMODE = SC_RXVALLEVEL | SC_TXFREELEVEL;
INT_SC1CFG = INT_SCRXVAL; /* Receive buffer has data interrupt enable */
transmitting = 0; transmitting = 0;
#if TX_WITH_INTERRUPT #if TX_WITH_INTERRUPT
ringbuf_init(&txbuf, txbuf_data, sizeof(txbuf_data)); ringbuf_init(&txbuf, txbuf_data, sizeof(txbuf_data));
#endif /* TX_WITH_INTERRUPT */ #endif /* TX_WITH_INTERRUPT */
INT_SC1FLAG = 0xFFFF; INT_SC1FLAG = 0xFFFF;
INT_CFGSET = INT_SC1; INT_CFGSET = INT_SC1;
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
void uart1_rx_interrupt(void); void
void uart1_tx_interrupt(void); halSc1Isr(void)
void halSc1Isr(void)
{ {
ENERGEST_ON(ENERGEST_TYPE_IRQ); ENERGEST_ON(ENERGEST_TYPE_IRQ);
if(INT_SC1FLAG & INT_SCRXVAL){ if(INT_SC1FLAG & INT_SCRXVAL) {
uart1_rx_interrupt(); uart1_rx_interrupt();
INT_SC1FLAG = INT_SCRXVAL; INT_SC1FLAG = INT_SCRXVAL;
} }
#if TX_WITH_INTERRUPT #if TX_WITH_INTERRUPT
else if(INT_SC1FLAG & INT_SCTXFREE){ else if(INT_SC1FLAG & INT_SCTXFREE) {
uart1_tx_interrupt(); uart1_tx_interrupt();
INT_SC1FLAG = INT_SCTXFREE; INT_SC1FLAG = INT_SCTXFREE;
} }
#endif /* TX_WITH_INTERRUPT */ #endif /* TX_WITH_INTERRUPT */
ENERGEST_OFF(ENERGEST_TYPE_IRQ); ENERGEST_OFF(ENERGEST_TYPE_IRQ);
} }
/*--------------------------------------------------------------------------*/
void uart1_rx_interrupt(void) void
uart1_rx_interrupt(void)
{ {
uint8_t c; uint8_t c;
c = SC1_DATA; c = SC1_DATA;
if(uart1_input_handler != NULL) { if(uart1_input_handler != NULL) {
uart1_input_handler(c); uart1_input_handler(c);
} }
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
#if TX_WITH_INTERRUPT #if TX_WITH_INTERRUPT
void uart1_tx_interrupt(void) void
uart1_tx_interrupt(void)
{ {
if(ringbuf_elements(&txbuf) == 0) { if(ringbuf_elements(&txbuf) == 0) {
transmitting = 0; transmitting = 0;
INT_SC1CFG &= ~INT_SCTXFREE; INT_SC1CFG &= ~INT_SCTXFREE;
} else { } else {
SC1_DATA = ringbuf_get(&txbuf); SC1_DATA = ringbuf_get(&txbuf);
} }
} }
#endif /* TX_WITH_INTERRUPT */ #endif /* TX_WITH_INTERRUPT */
/*---------------------------------------------------------------------------*/ /** @} */

View file

@ -1,3 +1,9 @@
/**
* \addtogroup stm32w-cpu
*
* @{
*/
/* /*
* Copyright (c) 2007, Swedish Institute of Computer Science. * Copyright (c) 2007, Swedish Institute of Computer Science.
* All rights reserved. * All rights reserved.
@ -26,8 +32,6 @@
* OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
* SUCH DAMAGE. * SUCH DAMAGE.
* *
* This file is part of the Contiki operating system.
*
*/ */
/** /**
@ -42,9 +46,13 @@
#define BAUD2UBR(baud) baud #define BAUD2UBR(baud) baud
void uart1_set_input(int (*input)(unsigned char c)); void uart1_set_input(int (*input) (unsigned char c));
void uart1_writeb(unsigned char c); void uart1_writeb(unsigned char c);
void uart1_init(unsigned long ubr); void uart1_init(unsigned long ubr);
//uint8_t uart1_active(void);
/* uint8_t uart1_active(void); */
#endif /* __UART1_H__ */ #endif /* __UART1_H__ */
/** @} */

View file

@ -9,10 +9,10 @@ CFLAGS = -mthumb -mcpu=cortex-m3 -I "." -I "C:/Program\ Files/Raisonance/Ride/L
AROPTS = cq AROPTS = cq
SOURCE_DIR = src SOURCE_DIR = src
SOURCE_FILES = small_mprec.c syscalls.c \ SOURCE_FILES = small-mprec.c syscalls.c \
_SP_printf.c _SP_vfprintf.c _SP_puts.c _SP_sprintf.c _SP_snprintf.c\ sp-printf.c sp-vfprintf.c sp-puts.c sp-sprintf.c sp-snprintf.c\
small_dtoa.c small_wcsrtombs.c small_wcrtomb.c small_wctomb_r.c \ small-dtoa.c small-wcsrtombs.c small-wcrtomb.c small-wctomb-r.c \
scanf.c small_vfsscanf.c sscanf.c small_strtod.c scanf.c small-vfsscanf.c sscanf.c small-strtod.c
vpath %.c $(SOURCE_DIR) vpath %.c $(SOURCE_DIR)

View file

@ -56,7 +56,7 @@
#endif #endif
#include <string.h> #include <string.h>
#include "small_mprec.h" #include "small-mprec.h"
static int static int
_DEFUN (quorem, _DEFUN (quorem,
@ -203,8 +203,8 @@ _DEFUN (quorem,
*/ */
/* Scanf and printf call both the small_mprec.c file if small_printf /* Scanf and printf call both the small-mprec.c file if small_printf
* has not been specfied optimizations concerning small_mprec.c and * has not been specfied optimizations concerning small-mprec.c and
* call of balloc will be performed anyway for printf. * call of balloc will be performed anyway for printf.
*/ */
@ -292,8 +292,8 @@ _DEFUN (_dtoa_r,
* provided by Balloc variables are initialized to the beginning of the array. * provided by Balloc variables are initialized to the beginning of the array.
* - For some variables many buffers have been declared, in fact for each call of small_lshift we used a * - For some variables many buffers have been declared, in fact for each call of small_lshift we used a
* buffer that has not been used at the moment * buffer that has not been used at the moment
* - This buffers are used in the call of function declared in small_mprec.h * - This buffers are used in the call of function declared in small-mprec.h
* To have more informations look at small_mprec.c * To have more informations look at small-mprec.c
*/ */
_Bigint tab_b[BUF_LSHIFT_SIZE],tab_b1[BUF_SIZE],tab_delta[BUF_SIZE],tab_mlo[BUF_SIZE],tab_mhi[BUF_LSHIFT_SIZE],tab_S[BUF_LSHIFT_SIZE]; _Bigint tab_b[BUF_LSHIFT_SIZE],tab_b1[BUF_SIZE],tab_delta[BUF_SIZE],tab_mlo[BUF_SIZE],tab_mhi[BUF_LSHIFT_SIZE],tab_S[BUF_LSHIFT_SIZE];

View file

@ -86,7 +86,7 @@
#include <stdlib.h> #include <stdlib.h>
#include <string.h> #include <string.h>
#include <reent.h> #include <reent.h>
#include "small_mprec.h" #include "small-mprec.h"
/* reent.c knows this value */ /* reent.c knows this value */
#define _Kmax 15 #define _Kmax 15

View file

@ -98,8 +98,8 @@ Supporting OS subroutines required: <<close>>, <<fstat>>, <<isatty>>,
*/ */
/* Scanf and printf call both the small_mprec.c file if small_scanf /* Scanf and printf call both the small-mprec.c file if small_scanf
* has not been specfied optimizations concerning small_mprec.c and * has not been specfied optimizations concerning small-mprec.c and
* call of balloc will be performed anyway for scanf. * call of balloc will be performed anyway for scanf.
*/ */
@ -113,7 +113,7 @@ Supporting OS subroutines required: <<close>>, <<fstat>>, <<isatty>>,
#include <_ansi.h> #include <_ansi.h>
#include <reent.h> #include <reent.h>
#include <string.h> #include <string.h>
#include "small_mprec.h" #include "small-mprec.h"
double double
_DEFUN (_strtod_r, (ptr, s00, se), _DEFUN (_strtod_r, (ptr, s00, se),
@ -141,8 +141,8 @@ _DEFUN (_strtod_r, (ptr, s00, se),
* provided by Balloc variables are initialized to the beginning of the array. * provided by Balloc variables are initialized to the beginning of the array.
* - For some variables many buffers have been declared, in fact for each call of small_lshift we used a * - For some variables many buffers have been declared, in fact for each call of small_lshift we used a
* buffer that has not been used at the moment * buffer that has not been used at the moment
* - This buffers are used in the call of function declared in small_mprec.h * - This buffers are used in the call of function declared in small-mprec.h
* To have more informations look at small_mprec.c * To have more informations look at small-mprec.c
*/ */

View file

@ -14,8 +14,8 @@
* IMPLIED WARRANTIES, INCLUDING, WITHOUT LIMITATION, THE IMPLIED * IMPLIED WARRANTIES, INCLUDING, WITHOUT LIMITATION, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
*/ */
/* doc in _SP_sprintf.c */ /* doc in sp-sprintf.c */
/* This code created by modifying _SP_sprintf.c so copyright inherited. */ /* This code created by modifying sp-sprintf.c so copyright inherited. */
#include <stdio.h> #include <stdio.h>
#ifdef _HAVE_STDC #ifdef _HAVE_STDC

View file

@ -1,3 +1,39 @@
/**
* \addtogroup mb851-platform
*
* @{
*/
/*
* Copyright (c) 2009, Swedish Institute of Computer Science
* All rights reserved.
*
* 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.
* 3. Neither the name of the Institute 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 INSTITUTE 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 INSTITUTE 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 "contiki.h" #include "contiki.h"
#include "elfloader-arch.h" #include "elfloader-arch.h"
#include "cfs-coffee-arch.h" #include "cfs-coffee-arch.h"
@ -12,20 +48,22 @@
#define ELF32_R_TYPE(info) ((unsigned char)(info)) #define ELF32_R_TYPE(info) ((unsigned char)(info))
/* Supported relocations */ /* Supported relocations */
#define R_ARM_ABS32 2 #define R_ARM_ABS32 2
#define R_ARM_THM_CALL 10 #define R_ARM_THM_CALL 10
/* Adapted from elfloader-arm.c */ /* Adapted from elfloader-arm.c */
/* word aligned */
static uint32_t datamemory_aligned[(ELFLOADER_DATAMEMORY_SIZE + 3) / 4];
static uint8_t *datamemory = (uint8_t *) datamemory_aligned;
static uint32_t datamemory_aligned[(ELFLOADER_DATAMEMORY_SIZE+3)/4]; //word aligned /* halfword aligned */
static uint8_t* datamemory = (uint8_t *)datamemory_aligned; VAR_AT_SEGMENT(static const uint16_t
VAR_AT_SEGMENT (static const uint16_t textmemory[ELFLOADER_TEXTMEMORY_SIZE/2],".elf_text") = {0}; //halfword aligned textmemory[ELFLOADER_TEXTMEMORY_SIZE / 2], ".elf_text") = {0};
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
void * void *
elfloader_arch_allocate_ram(int size) elfloader_arch_allocate_ram(int size)
{ {
if(size > sizeof(datamemory_aligned)){ if(size > sizeof(datamemory_aligned)) {
PRINTF("RESERVED RAM TOO SMALL\n"); PRINTF("RESERVED RAM TOO SMALL\n");
} }
return datamemory; return datamemory;
@ -34,7 +72,7 @@ elfloader_arch_allocate_ram(int size)
void * void *
elfloader_arch_allocate_rom(int size) elfloader_arch_allocate_rom(int size)
{ {
if(size > sizeof(textmemory)){ if(size > sizeof(textmemory)) {
PRINTF("RESERVED FLASH TOO SMALL\n"); PRINTF("RESERVED FLASH TOO SMALL\n");
} }
return (void *)textmemory; return (void *)textmemory;
@ -42,50 +80,43 @@ elfloader_arch_allocate_rom(int size)
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
#define READSIZE sizeof(datamemory_aligned) #define READSIZE sizeof(datamemory_aligned)
void elfloader_arch_write_rom(int fd, unsigned short textoff, unsigned int size, char *mem) void
elfloader_arch_write_rom(int fd, unsigned short textoff, unsigned int size,
char *mem)
{ {
int32u ptr; uint32_t ptr;
int nbytes; int nbytes;
cfs_seek(fd, textoff, CFS_SEEK_SET); cfs_seek(fd, textoff, CFS_SEEK_SET);
cfs_seek(fd, textoff, CFS_SEEK_SET); cfs_seek(fd, textoff, CFS_SEEK_SET);
for(ptr = 0; ptr < size; ptr += READSIZE) { for(ptr = 0; ptr < size; ptr += READSIZE) {
/* Read data from file into RAM. */ /* Read data from file into RAM. */
nbytes = cfs_read(fd, (unsigned char *)datamemory, READSIZE); nbytes = cfs_read(fd, (unsigned char *)datamemory, READSIZE);
/* Write data to flash. */ /* Write data to flash. */
stm32w_flash_write((int32u)mem, datamemory, nbytes); stm32w_flash_write((uint32_t) mem, datamemory, nbytes);
} }
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
void
elfloader_arch_relocate(int fd,
void elfloader_arch_relocate(int fd, unsigned int sectionoffset,
unsigned int sectionoffset, char *sectionaddr,
char *sectionaddr,
struct elf32_rela *rela, char *addr) struct elf32_rela *rela, char *addr)
{ {
unsigned int type; unsigned int type;
type = ELF32_R_TYPE(rela->r_info); type = ELF32_R_TYPE(rela->r_info);
cfs_seek(fd, sectionoffset + rela->r_offset, CFS_SEEK_SET); cfs_seek(fd, sectionoffset + rela->r_offset, CFS_SEEK_SET);
/* PRINTF("elfloader_arch_relocate: type %d\n", type); */ /* PRINTF("elfloader_arch_relocate: type %d\n", type); */
/* PRINTF("Addr: %p, Addend: %ld\n", addr, rela->r_addend); */ /* PRINTF("Addr: %p, Addend: %ld\n", addr, rela->r_addend); */
switch(type) { switch (type) {
case R_ARM_ABS32: case R_ARM_ABS32:
{ {
int32_t addend; int32_t addend;
cfs_read(fd, (char*)&addend, 4); cfs_read(fd, (char *)&addend, 4);
addr += addend; addr += addend;
cfs_seek(fd, -4, CFS_SEEK_CUR); cfs_seek(fd, -4, CFS_SEEK_CUR);
cfs_write(fd,&addr,4); cfs_write(fd, &addr, 4);
//elfloader_output_write_segment(output,(char*) &addr, 4); /* elfloader_output_write_segment(output,(char*) &addr, 4); */
PRINTF("%p: addr: %p\n", sectionaddr +rela->r_offset, PRINTF("%p: addr: %p\n", sectionaddr + rela->r_offset, addr);
addr);
} }
break; break;
case R_ARM_THM_CALL: case R_ARM_THM_CALL:
@ -93,49 +124,53 @@ void elfloader_arch_relocate(int fd,
uint16_t instr[2]; uint16_t instr[2];
int32_t offset; int32_t offset;
char *base; char *base;
cfs_read(fd, (char*)instr, 4); cfs_read(fd, (char *)instr, 4);
cfs_seek(fd, -4, CFS_SEEK_CUR); cfs_seek(fd, -4, CFS_SEEK_CUR);
/* Ignore the addend since it will be zero for calls to symbols,
and I can't think of a case when doing a relative call to
a non-symbol position */
base = sectionaddr + (rela->r_offset + 4);
if (((instr[1]) & 0xe800) == 0xe800) { /*
/* BL or BLX */ * Ignore the addend since it will be zero for calls to symbols,
if (((uint32_t)addr) & 0x1) { * and I can't think of a case when doing a relative call to
/* BL */ * a non-symbol position
instr[1] |= 0x1800; */
} else { base = sectionaddr + (rela->r_offset + 4);
if(((instr[1]) & 0xe800) == 0xe800) {
/* BL or BLX */
if(((uint32_t) addr) & 0x1) {
/* BL */
instr[1] |= 0x1800;
} else {
#if defined(__ARM_ARCH_4T__) #if defined(__ARM_ARCH_4T__)
return ELFLOADER_UNHANDLED_RELOC; return ELFLOADER_UNHANDLED_RELOC;
#else #else
/* BLX */ /* BLX */
instr[1] &= ~0x1800; instr[1] &= ~0x1800;
instr[1] |= 0x0800; instr[1] |= 0x0800;
#endif #endif
} }
} }
/* Adjust address for BLX */ /* Adjust address for BLX */
if ((instr[1] & 0x1800) == 0x0800) { if((instr[1] & 0x1800) == 0x0800) {
addr = (char*)((((uint32_t)addr) & 0xfffffffd) addr = (char *)((((uint32_t) addr) & 0xfffffffd) |
| (((uint32_t)base) & 0x00000002)); (((uint32_t) base) & 0x00000002));
} }
offset = addr - (sectionaddr + (rela->r_offset + 4)); offset = addr - (sectionaddr + (rela->r_offset + 4));
PRINTF("elfloader-arm.c: offset %d\n", (int)offset); PRINTF("elfloader-arm.c: offset %d\n", (int)offset);
if (offset < -(1<<22) || offset >= (1<<22)) { if(offset < -(1 << 22) || offset >= (1 << 22)) {
PRINTF("elfloader-arm.c: offset %d too large for relative call\n", PRINTF("elfloader-arm.c: offset %d too large for relative call\n",
(int)offset); (int)offset);
} }
/* PRINTF("%p: %04x %04x offset: %d addr: %p\n", sectionaddr +rela->r_offset, instr[0], instr[1], (int)offset, addr); */ /* PRINTF("%p: %04x %04x offset: %d addr: %p\n", sectionaddr +rela->r_offset, instr[0], instr[1], (int)offset, addr); */
instr[0] = (instr[0] & 0xf800) | ((offset>>12)&0x07ff); instr[0] = (instr[0] & 0xf800) | ((offset >> 12) & 0x07ff);
instr[1] = (instr[1] & 0xf800) | ((offset>>1)&0x07ff); instr[1] = (instr[1] & 0xf800) | ((offset >> 1) & 0x07ff);
cfs_write(fd,&instr,4); cfs_write(fd, &instr, 4);
//elfloader_output_write_segment(output, (char*)instr, 4); /* elfloader_output_write_segment(output, (char*)instr, 4); */
/* PRINTF("cfs_write: %04x %04x\n",instr[0], instr[1]); */ /* PRINTF("cfs_write: %04x %04x\n",instr[0], instr[1]); */
} }
break; break;
default: default:
PRINTF("elfloader-arm.c: unsupported relocation type %d\n", type); PRINTF("elfloader-arm.c: unsupported relocation type %d\n", type);
} }
} }
/** @} */

View file

@ -15,7 +15,7 @@
*/ */
#ifndef __STSTATUS_TYPE__ #ifndef __STSTATUS_TYPE__
#define __STSTATUS_TYPE__ #define __STSTATUS_TYPE__
typedef int8u StStatus; typedef uint8_t StStatus;
#endif //__STSTATUS_TYPE__ #endif //__STSTATUS_TYPE__
/** /**

View file

@ -37,7 +37,7 @@
#ifdef CORTEXM3_STM32W108 #ifdef CORTEXM3_STM32W108
// A type for the ADC User enumeration. // A type for the ADC User enumeration.
typedef int8u ADCUser; typedef uint8_t ADCUser;
enum enum
{ {
/** LQI User ID. */ /** LQI User ID. */
@ -55,7 +55,7 @@ enum
// A type for the reference enumeration. // A type for the reference enumeration.
typedef int8u ADCReferenceType; typedef uint8_t ADCReferenceType;
enum enum
{ {
/** AREF pin reference. */ /** AREF pin reference. */
@ -67,7 +67,7 @@ enum
}; };
// A type for the rate enumeration. // A type for the rate enumeration.
typedef int8u ADCRateType; typedef uint8_t ADCRateType;
enum enum
{ {
/** Rate 32 us, 5 effective bits in ADC_DATA[15:11] */ /** Rate 32 us, 5 effective bits in ADC_DATA[15:11] */
@ -173,7 +173,7 @@ enum
/** @brief A type for the channel enumeration /** @brief A type for the channel enumeration
* (such as ::ADC_SOURCE_ADC0_GND) * (such as ::ADC_SOURCE_ADC0_GND)
*/ */
typedef int8u ADCChannelType; typedef uint8_t ADCChannelType;
/** @brief Returns the ADC channel from a given GPIO. Its value can can be used /** @brief Returns the ADC channel from a given GPIO. Its value can can be used
* inside the ADC_SOURCE(P,N) macro to retrieve the input pair for * inside the ADC_SOURCE(P,N) macro to retrieve the input pair for
@ -184,7 +184,7 @@ typedef int8u ADCChannelType;
* *
* @return The ADC_MUX value connected to the given GPIO. * @return The ADC_MUX value connected to the given GPIO.
*/ */
int8u halGetADCChannelFromGPIO(int32u io); uint8_t halGetADCChannelFromGPIO(uint32_t io);
/** @brief Initializes and powers-up the ADC. /** @brief Initializes and powers-up the ADC.
@ -226,7 +226,7 @@ StStatus halStartAdcConversion(ADCUser id,
* *
* @param id An ADC user. * @param id An ADC user.
* *
* @param value Pointer to an int16u to be loaded with the new value. * @param value Pointer to an uint16_t to be loaded with the new value.
* *
* @return One of the following: * @return One of the following:
* - ::ST_ADC_CONVERSION_DONE if the conversion is complete. * - ::ST_ADC_CONVERSION_DONE if the conversion is complete.
@ -237,7 +237,7 @@ StStatus halStartAdcConversion(ADCUser id,
* - ::ST_ADC_NO_CONVERSION_PENDING if \c id does not have a pending * - ::ST_ADC_NO_CONVERSION_PENDING if \c id does not have a pending
* conversion. * conversion.
*/ */
StStatus halRequestAdcData(ADCUser id, int16u *value); StStatus halRequestAdcData(ADCUser id, uint16_t *value);
/** @brief Waits for the user's request to complete and then, /** @brief Waits for the user's request to complete and then,
@ -248,14 +248,14 @@ StStatus halRequestAdcData(ADCUser id, int16u *value);
* *
* @param id An ADC user. * @param id An ADC user.
* *
* @param value Pointer to an int16u to be loaded with the new value. * @param value Pointer to an uint16_t to be loaded with the new value.
* *
* @return One of the following: * @return One of the following:
* - ::ST_ADC_CONVERSION_DONE if the conversion is complete. * - ::ST_ADC_CONVERSION_DONE if the conversion is complete.
* - ::ST_ADC_NO_CONVERSION_PENDING if \c id does not have a pending * - ::ST_ADC_NO_CONVERSION_PENDING if \c id does not have a pending
* conversion. * conversion.
*/ */
StStatus halReadAdcBlocking(ADCUser id, int16u *value); StStatus halReadAdcBlocking(ADCUser id, uint16_t *value);
/** @brief Calibrates or recalibrates the ADC system. /** @brief Calibrates or recalibrates the ADC system.
@ -284,11 +284,11 @@ StStatus halAdcCalibrate(ADCUser id);
* *
* @appusage Use this function to get a human useful value. * @appusage Use this function to get a human useful value.
* *
* @param value An int16u to be converted. * @param value An uint16_t to be converted.
* *
* @return Volts as signed fixed point with units 10^-4 Volts. * @return Volts as signed fixed point with units 10^-4 Volts.
*/ */
int16s halConvertValueToVolts(int16u value); int16_t halConvertValueToVolts(uint16_t value);
/** @brief Calibrates Vref to be 1.2V +/-10mV. /** @brief Calibrates Vref to be 1.2V +/-10mV.

View file

@ -13,7 +13,7 @@
#define BUTTON_UNKNOWN 3 #define BUTTON_UNKNOWN 3
typedef int8u HalBoardButton; typedef uint8_t HalBoardButton;
/* Functions -----------------------------------------------------------------*/ /* Functions -----------------------------------------------------------------*/
@ -21,7 +21,7 @@ typedef int8u HalBoardButton;
void halInitButton(void); void halInitButton(void);
/** @brief Get button status */ /** @brief Get button status */
int8u halGetButtonStatus(HalBoardButton button); uint8_t halGetButtonStatus(HalBoardButton button);
#endif /* _BUTTON_H_ */ #endif /* _BUTTON_H_ */

View file

@ -10,18 +10,18 @@
#if (NUM_ADC_USERS > 8) #if (NUM_ADC_USERS > 8)
#error NUM_ADC_USERS must not be greater than 8, or int8u variables in adc.c must be changed #error NUM_ADC_USERS must not be greater than 8, or uint8_t variables in adc.c must be changed
#endif #endif
static int16u adcData; // conversion result written by DMA static uint16_t adcData; // conversion result written by DMA
static int8u adcPendingRequests; // bitmap of pending requests static uint8_t adcPendingRequests; // bitmap of pending requests
volatile static int8u adcPendingConversion; // id of pending conversion volatile static uint8_t adcPendingConversion; // id of pending conversion
static int8u adcReadingValid; // bitmap of valid adcReadings static uint8_t adcReadingValid; // bitmap of valid adcReadings
static int16u adcReadings[NUM_ADC_USERS]; static uint16_t adcReadings[NUM_ADC_USERS];
static int16u adcConfig[NUM_ADC_USERS]; static uint16_t adcConfig[NUM_ADC_USERS];
static boolean adcCalibrated; static boolean adcCalibrated;
static int16s Nvss; static int16_t Nvss;
static int16s Nvdd; static int16_t Nvdd;
/* Modified the original ADC driver for enabling the ADC extended range mode required for /* Modified the original ADC driver for enabling the ADC extended range mode required for
supporting the STLM20 temperature sensor. supporting the STLM20 temperature sensor.
NOTE: NOTE:
@ -30,10 +30,10 @@ static int16s Nvdd;
the temperature values the temperature values
*/ */
#ifdef ENABLE_ADC_EXTENDED_RANGE_BROKEN #ifdef ENABLE_ADC_EXTENDED_RANGE_BROKEN
static int16s Nvref; static int16_t Nvref;
static int16s Nvref2; static int16_t Nvref2;
#endif /* ENABLE_ADC_EXTENDED_RANGE_BROKEN */ #endif /* ENABLE_ADC_EXTENDED_RANGE_BROKEN */
static int16u adcStaticConfig; static uint16_t adcStaticConfig;
void halAdcSetClock(boolean slow) void halAdcSetClock(boolean slow)
{ {
@ -73,8 +73,8 @@ boolean halAdcGetRange(void)
void halAdcIsr(void) void halAdcIsr(void)
{ {
int8u i; uint8_t i;
int8u conversion = adcPendingConversion; //fix 'volatile' warning; costs no flash uint8_t conversion = adcPendingConversion; //fix 'volatile' warning; costs no flash
// make sure data is ready and the desired conversion is valid // make sure data is ready and the desired conversion is valid
if ( (INT_ADCFLAG & INT_ADCULDFULL) if ( (INT_ADCFLAG & INT_ADCULDFULL)
@ -105,7 +105,7 @@ void halAdcIsr(void)
// otherwise. // otherwise.
ADCUser startNextConversion() ADCUser startNextConversion()
{ {
int8u i; uint8_t i;
ATOMIC ( ATOMIC (
// start the next requested conversion if any // start the next requested conversion if any
@ -143,7 +143,7 @@ void halInternalInitAdc(void)
ADC_OFFSET = ADC_OFFSET_RESET; ADC_OFFSET = ADC_OFFSET_RESET;
ADC_GAIN = ADC_GAIN_RESET; ADC_GAIN = ADC_GAIN_RESET;
ADC_DMACFG = ADC_DMARST; ADC_DMACFG = ADC_DMARST;
ADC_DMABEG = (int32u)&adcData; ADC_DMABEG = (uint32_t)&adcData;
ADC_DMASIZE = 1; ADC_DMASIZE = 1;
ADC_DMACFG = (ADC_DMAAUTOWRAP | ADC_DMALOAD); ADC_DMACFG = (ADC_DMAAUTOWRAP | ADC_DMALOAD);
@ -186,7 +186,7 @@ StStatus halStartAdcConversion(ADCUser id,
return ST_ADC_CONVERSION_DEFERRED; return ST_ADC_CONVERSION_DEFERRED;
} }
StStatus halRequestAdcData(ADCUser id, int16u *value) StStatus halRequestAdcData(ADCUser id, uint16_t *value)
{ {
//Both the ADC interrupt and the global interrupt need to be enabled, //Both the ADC interrupt and the global interrupt need to be enabled,
//otherwise the ADC ISR cannot be serviced. //otherwise the ADC ISR cannot be serviced.
@ -220,7 +220,7 @@ StStatus halRequestAdcData(ADCUser id, int16u *value)
return stat; return stat;
} }
StStatus halReadAdcBlocking(ADCUser id, int16u *value) StStatus halReadAdcBlocking(ADCUser id, uint16_t *value)
{ {
StStatus stat; StStatus stat;
@ -250,13 +250,13 @@ StStatus halAdcCalibrate(ADCUser id)
ADC_SOURCE_VREF_VREF2, ADC_SOURCE_VREF_VREF2,
ADC_CONVERSION_TIME_US_4096); ADC_CONVERSION_TIME_US_4096);
stat = halReadAdcBlocking(id, (int16u *)(&Nvref)); stat = halReadAdcBlocking(id, (uint16_t *)(&Nvref));
if (stat == ST_ADC_CONVERSION_DONE) { if (stat == ST_ADC_CONVERSION_DONE) {
halStartAdcConversion(id, halStartAdcConversion(id,
ADC_REF_INT, ADC_REF_INT,
ADC_SOURCE_VREF2_VREF2, ADC_SOURCE_VREF2_VREF2,
ADC_CONVERSION_TIME_US_4096); ADC_CONVERSION_TIME_US_4096);
stat = halReadAdcBlocking(id, (int16u *)(&Nvref2)); stat = halReadAdcBlocking(id, (uint16_t *)(&Nvref2));
} }
if (stat == ST_ADC_CONVERSION_DONE) { if (stat == ST_ADC_CONVERSION_DONE) {
adcCalibrated = TRUE; adcCalibrated = TRUE;
@ -272,13 +272,13 @@ StStatus halAdcCalibrate(ADCUser id)
ADC_REF_INT, ADC_REF_INT,
ADC_SOURCE_GND_VREF2, ADC_SOURCE_GND_VREF2,
ADC_CONVERSION_TIME_US_4096); ADC_CONVERSION_TIME_US_4096);
stat = halReadAdcBlocking(id, (int16u *)(&Nvss)); stat = halReadAdcBlocking(id, (uint16_t *)(&Nvss));
if (stat == ST_ADC_CONVERSION_DONE) { if (stat == ST_ADC_CONVERSION_DONE) {
halStartAdcConversion(id, halStartAdcConversion(id,
ADC_REF_INT, ADC_REF_INT,
ADC_SOURCE_VREG2_VREF2, ADC_SOURCE_VREG2_VREF2,
ADC_CONVERSION_TIME_US_4096); ADC_CONVERSION_TIME_US_4096);
stat = halReadAdcBlocking(id, (int16u *)(&Nvdd)); stat = halReadAdcBlocking(id, (uint16_t *)(&Nvdd));
} }
if (stat == ST_ADC_CONVERSION_DONE) { if (stat == ST_ADC_CONVERSION_DONE) {
Nvdd -= Nvss; Nvdd -= Nvss;
@ -297,11 +297,11 @@ StStatus halAdcCalibrate(ADCUser id)
// FIXME: support high voltage range // FIXME: support high voltage range
// use Vref-Vref/2 to calibrate // use Vref-Vref/2 to calibrate
// FIXME: check for mfg token specifying measured VDD_PADSA // FIXME: check for mfg token specifying measured VDD_PADSA
int16s halConvertValueToVolts(int16u value) int16_t halConvertValueToVolts(uint16_t value)
{ {
int32s N; int32_t N;
int16s V; int16_t V;
int32s nvalue; int32_t nvalue;
if (!adcCalibrated) { if (!adcCalibrated) {
halAdcCalibrate(ADC_USER_LQI); halAdcCalibrate(ADC_USER_LQI);
@ -317,10 +317,10 @@ int16s halConvertValueToVolts(int16u value)
#ifdef ENABLE_ADC_EXTENDED_RANGE_BROKEN #ifdef ENABLE_ADC_EXTENDED_RANGE_BROKEN
if(halAdcGetRange()){ // High range. if(halAdcGetRange()){ // High range.
N = (((int32s)value + Nvref - 2*Nvref2) << 16)/(2*(Nvref-Nvref2)); N = (((int32_t)value + Nvref - 2*Nvref2) << 16)/(2*(Nvref-Nvref2));
// Calculate voltage with: V = (N * VREF) / (2^16) where VDD = 1.2 volts // Calculate voltage with: V = (N * VREF) / (2^16) where VDD = 1.2 volts
// Mutiplying by 1.2*10000 makes the result of this equation 100 uVolts // Mutiplying by 1.2*10000 makes the result of this equation 100 uVolts
V = (int16s)((N*12000L) >> 16); V = (int16_t)((N*12000L) >> 16);
if (V > 21000) { // VDD_PADS ? if (V > 21000) { // VDD_PADS ?
V = 21000; V = 21000;
} }
@ -336,7 +336,7 @@ int16s halConvertValueToVolts(int16u value)
// Mutiplying by0.9*10000 makes the result of this equation 100 uVolts // Mutiplying by0.9*10000 makes the result of this equation 100 uVolts
// (in fixed point E-4 which allows for 13.5 bits vs millivolts // (in fixed point E-4 which allows for 13.5 bits vs millivolts
// which is only 10.2 bits). // which is only 10.2 bits).
V = (int16s)((N*9000L) >> 16); V = (int16_t)((N*9000L) >> 16);
if (V > 12000) { if (V > 12000) {
V = 12000; V = 12000;
} }
@ -349,7 +349,7 @@ int16s halConvertValueToVolts(int16u value)
return V; return V;
} }
int8u halGetADCChannelFromGPIO(int32u io) uint8_t halGetADCChannelFromGPIO(uint32_t io)
{ {
switch(io) switch(io)
{ {

View file

@ -250,7 +250,7 @@ BoardResourcesType const *boardDescription = NULL;
void halBoardInit(void) void halBoardInit(void)
{ {
char boardName[16]; char boardName[16];
int8s i; int8_t i;
boardDescription = NULL; boardDescription = NULL;
#ifdef EMBERZNET_HAL #ifdef EMBERZNET_HAL
halCommonGetToken(boardName, TOKEN_MFG_BOARD_NAME); halCommonGetToken(boardName, TOKEN_MFG_BOARD_NAME);
@ -318,7 +318,7 @@ void halBoardPowerDown(void)
/* Configure GPIO for BUTTONSs */ /* Configure GPIO for BUTTONSs */
{ {
ButtonResourceType *buttons = (ButtonResourceType *) boardDescription->io->buttons; ButtonResourceType *buttons = (ButtonResourceType *) boardDescription->io->buttons;
int8u i; uint8_t i;
for (i = 0; i < boardDescription->buttons; i++) { for (i = 0; i < boardDescription->buttons; i++) {
halGpioConfig(PORTx_PIN(buttons[i].gpioPort, buttons[i].gpioPin), GPIOCFG_IN_PUD); halGpioConfig(PORTx_PIN(buttons[i].gpioPort, buttons[i].gpioPin), GPIOCFG_IN_PUD);
halGpioSet(PORTx_PIN(buttons[i].gpioPort, buttons[i].gpioPin), GPIOOUT_PULLUP); halGpioSet(PORTx_PIN(buttons[i].gpioPort, buttons[i].gpioPin), GPIOOUT_PULLUP);
@ -328,7 +328,7 @@ void halBoardPowerDown(void)
/* Configure GPIO for LEDs */ /* Configure GPIO for LEDs */
{ {
LedResourceType *leds = (LedResourceType *) boardDescription->io->leds; LedResourceType *leds = (LedResourceType *) boardDescription->io->leds;
int8u i; uint8_t i;
for (i = 0; i < boardDescription->leds; i++) { for (i = 0; i < boardDescription->leds; i++) {
/* LED default off */ /* LED default off */
halGpioConfig(PORTx_PIN(leds[i].gpioPort, leds[i].gpioPin), GPIOCFG_OUT); halGpioConfig(PORTx_PIN(leds[i].gpioPort, leds[i].gpioPin), GPIOCFG_OUT);
@ -394,7 +394,7 @@ void halBoardPowerUp(void)
/* Configure GPIO for LEDs */ /* Configure GPIO for LEDs */
{ {
LedResourceType *leds = (LedResourceType *) boardDescription->io->leds; LedResourceType *leds = (LedResourceType *) boardDescription->io->leds;
int8u i; uint8_t i;
for (i = 0; i < boardDescription->leds; i++) { for (i = 0; i < boardDescription->leds; i++) {
/* LED default off */ /* LED default off */
halGpioConfig(PORTx_PIN(leds[i].gpioPort, leds[i].gpioPin), GPIOCFG_OUT); halGpioConfig(PORTx_PIN(leds[i].gpioPort, leds[i].gpioPin), GPIOCFG_OUT);
@ -404,7 +404,7 @@ void halBoardPowerUp(void)
/* Configure GPIO for BUTTONSs */ /* Configure GPIO for BUTTONSs */
{ {
ButtonResourceType *buttons = (ButtonResourceType *) boardDescription->io->buttons; ButtonResourceType *buttons = (ButtonResourceType *) boardDescription->io->buttons;
int8u i; uint8_t i;
for (i = 0; i < boardDescription->buttons; i++) { for (i = 0; i < boardDescription->buttons; i++) {
halGpioConfig(PORTx_PIN(buttons[i].gpioPort, buttons[i].gpioPin), GPIOCFG_IN_PUD); halGpioConfig(PORTx_PIN(buttons[i].gpioPort, buttons[i].gpioPin), GPIOCFG_IN_PUD);
halGpioSet(PORTx_PIN(buttons[i].gpioPort, buttons[i].gpioPin), GPIOOUT_PULLUP); halGpioSet(PORTx_PIN(buttons[i].gpioPort, buttons[i].gpioPin), GPIOOUT_PULLUP);
@ -448,7 +448,7 @@ void printButtons (ButtonResourceType *buttons)
void boardPrintStringDescription(void) void boardPrintStringDescription(void)
{ {
int8u i = 0; uint8_t i = 0;
while (boardList[i] != NULL) { while (boardList[i] != NULL) {
if ((boardDescription == boardList[i]) || (boardDescription == NULL)) { if ((boardDescription == boardList[i]) || (boardDescription == NULL)) {

View file

@ -22,7 +22,7 @@
//------------------------------------------------------------------------------ //------------------------------------------------------------------------------
// Status values. // Status values.
typedef int32u FibStatus; typedef uint32_t FibStatus;
#define FIB_SUCCESS 0 #define FIB_SUCCESS 0
#define FIB_ERR_UNALIGNED 1 #define FIB_ERR_UNALIGNED 1
@ -36,7 +36,7 @@ typedef int32u FibStatus;
//------------------------------------------------------------------------------ //------------------------------------------------------------------------------
// Erase types. // Erase types.
typedef int32u FibEraseType; typedef uint32_t FibEraseType;
#define MFB_MASS_ERASE 0x01 #define MFB_MASS_ERASE 0x01
#define MFB_PAGE_ERASE 0x02 #define MFB_PAGE_ERASE 0x02
@ -48,9 +48,9 @@ typedef int32u FibEraseType;
//------------------------------------------------------------------------------ //------------------------------------------------------------------------------
// Shared flash functions. // Shared flash functions.
FibStatus fibFlashWrite(int32u address, int8u *data, FibStatus fibFlashWrite(uint32_t address, uint8_t *data,
int32u writeLength, int32u verifyLength); uint32_t writeLength, uint32_t verifyLength);
FibStatus fibFlashErase(FibEraseType eraseType, int32u address); FibStatus fibFlashErase(FibEraseType eraseType, uint32_t address);
#endif //__FIB_BOOTLOADER_H__ #endif //__FIB_BOOTLOADER_H__

View file

@ -12,7 +12,7 @@
void halInitButton(void) void halInitButton(void)
{ {
int8u i; uint8_t i;
/* Configure GPIO for BUTTONSs */ /* Configure GPIO for BUTTONSs */
ButtonResourceType *buttons = (ButtonResourceType *) boardDescription->io->buttons; ButtonResourceType *buttons = (ButtonResourceType *) boardDescription->io->buttons;
for (i = 0; i < boardDescription->buttons; i++) { for (i = 0; i < boardDescription->buttons; i++) {
@ -22,10 +22,10 @@ void halInitButton(void)
}/* end halInitButton() */ }/* end halInitButton() */
int8u halGetButtonStatus(HalBoardButton button) uint8_t halGetButtonStatus(HalBoardButton button)
{ {
int8u port = (button >> 3) & 0xf; uint8_t port = (button >> 3) & 0xf;
int8u pin = button & 0x7; uint8_t pin = button & 0x7;
if (button != DUMMY_BUTTON) if (button != DUMMY_BUTTON)
{ {

View file

@ -59,10 +59,10 @@
#define CLK1K_NUMERATOR 384000000 #define CLK1K_NUMERATOR 384000000
void halInternalCalibrateSlowRc( void ) void halInternalCalibrateSlowRc( void )
{ {
int8u i; uint8_t i;
int32u average=0; uint32_t average=0;
int16s delta; int16_t delta;
int32u period; uint32_t period;
CALDBG( CALDBG(
stSerialPrintf(ST_ASSERT_SERIAL_PORT, "halInternalCalibrateSlowRc:\r\n"); stSerialPrintf(ST_ASSERT_SERIAL_PORT, "halInternalCalibrateSlowRc:\r\n");
@ -85,7 +85,7 @@ void halInternalCalibrateSlowRc( void )
stSerialPrintf(ST_ASSERT_SERIAL_PORT, stSerialPrintf(ST_ASSERT_SERIAL_PORT,
"period: %u, ", CLK_PERIOD); "period: %u, ", CLK_PERIOD);
stSerialPrintf(ST_ASSERT_SERIAL_PORT, "%u Hz\r\n", stSerialPrintf(ST_ASSERT_SERIAL_PORT, "%u Hz\r\n",
((int16u)(((int32u)192000000)/((int32u)CLK_PERIOD)))); ((uint16_t)(((uint32_t)192000000)/((uint32_t)CLK_PERIOD))));
) )
//For 10kHz, the ideal CLK_PERIOD is 19200. Calculate the PERIOD delta. //For 10kHz, the ideal CLK_PERIOD is 19200. Calculate the PERIOD delta.
//It's possible for a chip's 10kHz source RC to be too far out of range //It's possible for a chip's 10kHz source RC to be too far out of range
@ -120,7 +120,7 @@ void halInternalCalibrateSlowRc( void )
stSerialPrintf(ST_ASSERT_SERIAL_PORT, stSerialPrintf(ST_ASSERT_SERIAL_PORT,
"period: %u, ", CLK_PERIOD); "period: %u, ", CLK_PERIOD);
stSerialPrintf(ST_ASSERT_SERIAL_PORT, "%u Hz\r\n", stSerialPrintf(ST_ASSERT_SERIAL_PORT, "%u Hz\r\n",
((int16u)(((int32u)192000000)/((int32u)CLK_PERIOD)))); ((uint16_t)(((uint32_t)192000000)/((uint32_t)CLK_PERIOD))));
) )
//The analog section should now be producing an output of ~10kHz //The analog section should now be producing an output of ~10kHz
@ -138,11 +138,11 @@ void halInternalCalibrateSlowRc( void )
average = (average+(SLOWRC_PERIOD_SAMPLES/2))/SLOWRC_PERIOD_SAMPLES; average = (average+(SLOWRC_PERIOD_SAMPLES/2))/SLOWRC_PERIOD_SAMPLES;
CALDBG( CALDBG(
stSerialPrintf(ST_ASSERT_SERIAL_PORT, "average: %u, %u Hz\r\n", stSerialPrintf(ST_ASSERT_SERIAL_PORT, "average: %u, %u Hz\r\n",
((int16u)average), ((int16u)(((int32u)192000000)/((int32u)average)))); ((uint16_t)average), ((uint16_t)(((uint32_t)192000000)/((uint32_t)average))));
) )
//using an average period sample, calculate the clk1k divisor //using an average period sample, calculate the clk1k divisor
CLK1K_CAL = (int16u)(CLK1K_NUMERATOR/average); CLK1K_CAL = (uint16_t)(CLK1K_NUMERATOR/average);
CALDBG( CALDBG(
stSerialPrintf(ST_ASSERT_SERIAL_PORT,"CLK1K_CAL=%2X\r\n",CLK1K_CAL); stSerialPrintf(ST_ASSERT_SERIAL_PORT,"CLK1K_CAL=%2X\r\n",CLK1K_CAL);
) )
@ -167,7 +167,7 @@ void halInternalCalibrateSlowRc( void )
// CLK_PERIOD // CLK_PERIOD
void halInternalCalibrateFastRc(void) void halInternalCalibrateFastRc(void)
{ {
int32s newTune = -16; int32_t newTune = -16;
CALDBG( CALDBG(
stSerialPrintf(ST_ASSERT_SERIAL_PORT, "halInternalCalibrateFastRc:\r\n"); stSerialPrintf(ST_ASSERT_SERIAL_PORT, "halInternalCalibrateFastRc:\r\n");
@ -188,7 +188,7 @@ void halInternalCalibrateFastRc(void)
stSerialPrintf(ST_ASSERT_SERIAL_PORT, stSerialPrintf(ST_ASSERT_SERIAL_PORT,
"period: %u, ", CLK_PERIOD); "period: %u, ", CLK_PERIOD);
stSerialPrintf(ST_ASSERT_SERIAL_PORT, "%u kHz\r\n", stSerialPrintf(ST_ASSERT_SERIAL_PORT, "%u kHz\r\n",
((int16u)((((int32u)3072000000)/((int32u)CLK_PERIOD))/1000))); ((uint16_t)((((uint32_t)3072000000)/((uint32_t)CLK_PERIOD))/1000)));
) )
//For 12MHz, the ideal CLK_PERIOD is 256. Tune the frequency down until //For 12MHz, the ideal CLK_PERIOD is 256. Tune the frequency down until
//the period is <= 256, which says the frequency is as close to 12MHz as //the period is <= 256, which says the frequency is as close to 12MHz as
@ -211,7 +211,7 @@ void halInternalCalibrateFastRc(void)
stSerialPrintf(ST_ASSERT_SERIAL_PORT, stSerialPrintf(ST_ASSERT_SERIAL_PORT,
"period: %u, ", CLK_PERIOD); "period: %u, ", CLK_PERIOD);
stSerialPrintf(ST_ASSERT_SERIAL_PORT, "%u kHz\r\n", stSerialPrintf(ST_ASSERT_SERIAL_PORT, "%u kHz\r\n",
((int16u)((((int32u)3072000000)/((int32u)CLK_PERIOD))/1000))); ((uint16_t)((((uint32_t)3072000000)/((uint32_t)CLK_PERIOD))/1000)));
) )
//The analog section should now be producing an output of 11.5MHz - 12.0MHz //The analog section should now be producing an output of 11.5MHz - 12.0MHz
@ -337,7 +337,7 @@ static boolean setBiasCheckLow(void)
void halInternalSearchForBiasTrim(void) void halInternalSearchForBiasTrim(void)
{ {
int8u bit; uint8_t bit;
//Enable the XTAL so we can search for the proper bias trim (NOTE: This //Enable the XTAL so we can search for the proper bias trim (NOTE: This
//will also forcefully ensure we're on the OSCHF so that we don't //will also forcefully ensure we're on the OSCHF so that we don't

View file

@ -18,6 +18,9 @@
#ifndef __GNU_H__ #ifndef __GNU_H__
#define __GNU_H__ #define __GNU_H__
#include <stdint.h>
#ifndef __GNUC__ #ifndef __GNUC__
#error Improper PLATFORM_HEADER #error Improper PLATFORM_HEADER
#endif #endif
@ -40,7 +43,7 @@
#include <stdarg.h> #include <stdarg.h>
#if defined (CORTEXM3_STM32W108) #if defined (CORTEXM3_STM32W108)
#include "micro/cortexm3/stm32w108/regs.h" #include "micro/cortexm3/stm32w108/regs.h"
#include "micro/cortexm3/stm32w108/stm32w108_type.h" #include "micro/cortexm3/stm32w108/stm32w108-type.h"
#else #else
#error Unknown CORTEXM3 micro #error Unknown CORTEXM3 micro
#endif #endif
@ -90,12 +93,12 @@
* @brief A typedef to make the size of the variable explicitly known. * @brief A typedef to make the size of the variable explicitly known.
*/ */
typedef unsigned char boolean; typedef unsigned char boolean;
typedef unsigned char int8u; //typedef unsigned char uint8_t;
typedef signed char int8s; //typedef signed char int8_t;
typedef unsigned short int16u; //typedef unsigned short uint16_t;
typedef signed short int16s; //typedef signed short int16_t;
typedef unsigned int int32u; //typedef unsigned int uint32_t;
typedef signed int int32s; //typedef signed int int32_t;
typedef unsigned int PointerType; typedef unsigned int PointerType;
//@} \\END MASTER VARIABLE TYPES //@} \\END MASTER VARIABLE TYPES
@ -363,7 +366,7 @@ void _executeBarrierInstructions(void);
* declarations section of any function which calls DISABLE_INTERRUPTS() * declarations section of any function which calls DISABLE_INTERRUPTS()
* or RESTORE_INTERRUPTS(). * or RESTORE_INTERRUPTS().
*/ */
#define DECLARE_INTERRUPT_STATE int8u _emIsrState #define DECLARE_INTERRUPT_STATE uint8_t _emIsrState
// Prototypes for the BASEPRI and PRIMASK access functions. They are very // Prototypes for the BASEPRI and PRIMASK access functions. They are very
// basic and instantiated in assembly code in the file spmr.s37 (since // basic and instantiated in assembly code in the file spmr.s37 (since
@ -372,13 +375,13 @@ void _executeBarrierInstructions(void);
// with a priority equal to or less than the BASEPRI value. // with a priority equal to or less than the BASEPRI value.
// Note that the priority values used by these functions are 5 bits and // Note that the priority values used by these functions are 5 bits and
// right-aligned // right-aligned
extern int8u _readBasePri(void); extern uint8_t _readBasePri(void);
extern void _writeBasePri(int8u priority); extern void _writeBasePri(uint8_t priority);
// Prototypes for BASEPRI functions used to disable and enable interrupts // Prototypes for BASEPRI functions used to disable and enable interrupts
// while still allowing enabled faults to trigger. // while still allowing enabled faults to trigger.
extern void _enableBasePri(void); extern void _enableBasePri(void);
extern int8u _disableBasePri(void); extern uint8_t _disableBasePri(void);
extern boolean _basePriIsDisabled(void); extern boolean _basePriIsDisabled(void);
// Prototypes for setting and clearing PRIMASK for global interrupt // Prototypes for setting and clearing PRIMASK for global interrupt

View file

@ -33,7 +33,7 @@
#include <stdarg.h> #include <stdarg.h>
#if defined (CORTEXM3_STM32W108) #if defined (CORTEXM3_STM32W108)
#include "micro/cortexm3/stm32w108/regs.h" #include "micro/cortexm3/stm32w108/regs.h"
#include "micro/cortexm3/stm32w108/stm32w108_type.h" #include "micro/cortexm3/stm32w108/stm32w108-type.h"
#elif defined (CORTEXM3_STM32F103) #elif defined (CORTEXM3_STM32F103)
#include "stm32f10x.h" #include "stm32f10x.h"
#else #else
@ -87,12 +87,12 @@
* @brief A typedef to make the size of the variable explicitly known. * @brief A typedef to make the size of the variable explicitly known.
*/ */
typedef unsigned char boolean; typedef unsigned char boolean;
typedef unsigned char int8u; typedef unsigned char uint8_t;
typedef signed char int8s; typedef signed char int8_t;
typedef unsigned short int16u; typedef unsigned short uint16_t;
typedef signed short int16s; typedef signed short int16_t;
typedef unsigned int int32u; typedef unsigned int uint32_t;
typedef signed int int32s; typedef signed int int32_t;
typedef unsigned int PointerType; typedef unsigned int PointerType;
//@} \\END MASTER VARIABLE TYPES //@} \\END MASTER VARIABLE TYPES
@ -359,7 +359,7 @@ void _executeBarrierInstructions(void);
* declarations section of any function which calls DISABLE_INTERRUPTS() * declarations section of any function which calls DISABLE_INTERRUPTS()
* or RESTORE_INTERRUPTS(). * or RESTORE_INTERRUPTS().
*/ */
#define DECLARE_INTERRUPT_STATE int8u _emIsrState #define DECLARE_INTERRUPT_STATE uint8_t _emIsrState
// Prototypes for the BASEPRI and PRIMASK access functions. They are very // Prototypes for the BASEPRI and PRIMASK access functions. They are very
// basic and instantiated in assembly code in the file spmr.s37 (since // basic and instantiated in assembly code in the file spmr.s37 (since
@ -368,13 +368,13 @@ void _executeBarrierInstructions(void);
// with a priority equal to or less than the BASEPRI value. // with a priority equal to or less than the BASEPRI value.
// Note that the priority values used by these functions are 5 bits and // Note that the priority values used by these functions are 5 bits and
// right-aligned // right-aligned
extern int8u _readBasePri(void); extern uint8_t _readBasePri(void);
extern void _writeBasePri(int8u priority); extern void _writeBasePri(uint8_t priority);
// Prototypes for BASEPRI functions used to disable and enable interrupts // Prototypes for BASEPRI functions used to disable and enable interrupts
// while still allowing enabled faults to trigger. // while still allowing enabled faults to trigger.
extern void _enableBasePri(void); extern void _enableBasePri(void);
extern int8u _disableBasePri(void); extern uint8_t _disableBasePri(void);
extern boolean _basePriIsDisabled(void); extern boolean _basePriIsDisabled(void);
// Prototypes for setting and clearing PRIMASK for global interrupt // Prototypes for setting and clearing PRIMASK for global interrupt

View file

@ -53,7 +53,7 @@ halPendSvSaveContext:
//------------------------------------------------------------------------------ //------------------------------------------------------------------------------
// int32u savedMSP // uint32_t savedMSP
// //
// Private storage to hold the saved stack pointer. This variable is only used // Private storage to hold the saved stack pointer. This variable is only used
// in this file and should not be extern'ed. In our current design we // in this file and should not be extern'ed. In our current design we

View file

@ -1,149 +0,0 @@
/**************************************************
*
* Part one of the system initialization code, contains low-level
* initialization, plain thumb variant.
*
* Customized by St Corporation for STM32W
*<!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*
**************************************************/
;
; The modules in this file are included in the libraries, and may be replaced
; by any user-defined modules that define the PUBLIC symbol _program_start or
; a user defined start symbol.
; To override the cstartup defined in the library, simply add your modified
; version to the workbench project.
;
; The vector table is normally located at address 0.
; When debugging in RAM, it can be located in RAM, aligned to at least 2^6.
; The name "__vector_table" has special meaning for C-SPY:
; it is where the SP start value is found, and the NVIC vector
; table register (VTOR) is initialized to this address if != 0.
;
; Cortex-M version
;
MODULE ?cstartup
;; Forward declaration of sections.
SECTION CSTACK:DATA:NOROOT(3)
SECTION .intvec:CODE:NOROOT(2)
EXTERN __iar_program_start
PUBLIC __vector_table
DATA
__vector_table
DCD sfe(CSTACK)
DCD __iar_program_start
;; Standard Cortex-M3 Vectors
DCD NMI_Handler ;;NMI Handler
DCD HardFault_Handler ;;Hard Fault Handler
DCD MemManage_Handler ;;Memory Fault Handler
DCD BusFault_Handler ;;Bus Fault Handler
DCD UsageFault_Handler ;;Usage Fault Handler
DCD 0 ;;Reserved
DCD 0 ;;Reserved
DCD 0 ;;Reserved
DCD 0 ;;Reserved
DCD SVC_Handler ;;SVCall Handler
DCD DebugMon_Handler ;;Debug Monitor Handler
DCD 0 ;;Reserved
DCD PendSV_Handler ;;PendSV Handler
DCD SysTick_Handler ;;SysTick Handler
;; STM32W Vectors
DCD halTimer1Isr ;;Timer 1 Handler
DCD halTimer2Isr ;;Timer 2 Handler
DCD halManagementIsr ;;Management Handler
DCD halBaseBandIsr ;;BaseBand Handler
DCD halSleepTimerIsr ;;Sleep Timer Handler
DCD halSc1Isr ;;SC1 Handler
DCD halSc2Isr ;;SC2 Handler
DCD halSecurityIsr ;;Security Handler
DCD halStackMacTimerIsr ;;MAC Timer Handler
DCD stmRadioTransmitIsr ;;MAC TX Handler
DCD stmRadioReceiveIsr ;;MAC RX Handler
DCD halAdcIsr ;;ADC Handler
DCD halIrqAIsr ;;GPIO IRQA Handler
DCD halIrqBIsr ;;GPIO IRQB Handler
DCD halIrqCIsr ;;GPIO IRQC Handler
DCD halIrqDIsr ;;GPIO IRQD Handler
DCD halDebugIsr ;;Debug Handler
;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;
;;
;; Default interrupt handlers.
;;
PUBWEAK NMI_Handler
PUBWEAK HardFault_Handler
PUBWEAK MemManage_Handler
PUBWEAK BusFault_Handler
PUBWEAK UsageFault_Handler
PUBWEAK SVC_Handler
PUBWEAK DebugMon_Handler
PUBWEAK PendSV_Handler
PUBWEAK SysTick_Handler
PUBWEAK halTimer1Isr
PUBWEAK halTimer2Isr
PUBWEAK halManagementIsr
PUBWEAK halBaseBandIsr
PUBWEAK halSleepTimerIsr
PUBWEAK halSc1Isr
PUBWEAK halSc2Isr
PUBWEAK halSecurityIsr
PUBWEAK halStackMacTimerIsr
PUBWEAK stmRadioTransmitIsr
PUBWEAK stmRadioReceiveIsr
PUBWEAK halAdcIsr
PUBWEAK halIrqAIsr
PUBWEAK halIrqBIsr
PUBWEAK halIrqCIsr
PUBWEAK halIrqDIsr
PUBWEAK halDebugIsr
SECTION .text:CODE:REORDER(1)
THUMB
NMI_Handler
HardFault_Handler
MemManage_Handler
BusFault_Handler
UsageFault_Handler
SVC_Handler
DebugMon_Handler
PendSV_Handler
SysTick_Handler
halTimer1Isr
halTimer2Isr
halManagementIsr
halBaseBandIsr
halSleepTimerIsr
halSc1Isr
halSc2Isr
halSecurityIsr
halStackMacTimerIsr
stmRadioTransmitIsr
stmRadioReceiveIsr
halAdcIsr
halIrqAIsr
halIrqBIsr
halIrqCIsr
halIrqDIsr
halDebugIsr
Default_Handler
B Default_Handler
END

View file

@ -85,10 +85,10 @@ static void disableFlitf(void)
FLASH_CTRL = FLASH_CTRL_LOCK; //lock the flash from further accesses FLASH_CTRL = FLASH_CTRL_LOCK; //lock the flash from further accesses
} }
static FibStatus fibFlashWrite(int32u address, int8u *data, int32u length, int32u dummy) static FibStatus fibFlashWrite(uint32_t address, uint8_t *data, uint32_t length, uint32_t dummy)
{ {
int32u i; uint32_t i;
int16u *ptr; uint16_t *ptr;
FibStatus status = FIB_SUCCESS; FibStatus status = FIB_SUCCESS;
// Address and length must be half-word aligned. // Address and length must be half-word aligned.
if ((address & 1) || (length & 1)) { if ((address & 1) || (length & 1)) {
@ -100,10 +100,10 @@ static FibStatus fibFlashWrite(int32u address, int8u *data, int32u length, int32
return FIB_ERR_INVALID_ADDRESS; return FIB_ERR_INVALID_ADDRESS;
} }
enableFlitf(); enableFlitf();
ptr = (int16u *)address; ptr = (uint16_t *)address;
for (i = 0; i < length; i += 2) { for (i = 0; i < length; i += 2) {
int16u currentData = *ptr; uint16_t currentData = *ptr;
int16u newData = HIGH_LOW_TO_INT(data[i + 1], data[i]); uint16_t newData = HIGH_LOW_TO_INT(data[i + 1], data[i]);
// Only program the data if it makes sense to do so. // Only program the data if it makes sense to do so.
if (currentData == newData) { if (currentData == newData) {
// If the new data matches the flash, don't bother doing anything. // If the new data matches the flash, don't bother doing anything.
@ -111,7 +111,7 @@ static FibStatus fibFlashWrite(int32u address, int8u *data, int32u length, int32
// If the flash is 0xFFFF we're allowed to write anything. // If the flash is 0xFFFF we're allowed to write anything.
// If the new data is 0x0000 it doesn't matter what the flash is. // If the new data is 0x0000 it doesn't matter what the flash is.
// OPTWREN must stay set to keep CIB unlocked. // OPTWREN must stay set to keep CIB unlocked.
if ((CIB_OB_BOTTOM <= (int32u)ptr) && ((int32u)ptr <= CIB_OB_TOP)) { if ((CIB_OB_BOTTOM <= (uint32_t)ptr) && ((uint32_t)ptr <= CIB_OB_TOP)) {
FLASH_CTRL = (FLASH_CTRL_OPTWREN | FLASH_CTRL_OPTPROG); FLASH_CTRL = (FLASH_CTRL_OPTWREN | FLASH_CTRL_OPTPROG);
} else { } else {
FLASH_CTRL = (FLASH_CTRL_OPTWREN | FLASH_CTRL_PROG); FLASH_CTRL = (FLASH_CTRL_OPTWREN | FLASH_CTRL_PROG);
@ -144,10 +144,10 @@ static FibStatus fibFlashWrite(int32u address, int8u *data, int32u length, int32
return status; return status;
} }
static FibStatus fibFlashWriteVerify(int32u address, int8u *data, int32u length) static FibStatus fibFlashWriteVerify(uint32_t address, uint8_t *data, uint32_t length)
{ {
int32u i; uint32_t i;
int8u *ptr = (int8u *)address; uint8_t *ptr = (uint8_t *)address;
for (i = 0; i < length; i++) { for (i = 0; i < length; i++) {
if (*ptr != data[i]) { if (*ptr != data[i]) {
return FIB_ERR_VERIFY_FAILED; return FIB_ERR_VERIFY_FAILED;
@ -157,26 +157,26 @@ static FibStatus fibFlashWriteVerify(int32u address, int8u *data, int32u length)
return FIB_SUCCESS; return FIB_SUCCESS;
} }
static FibStatus fibFlashErase(FibEraseType eraseType, int32u address) static FibStatus fibFlashErase(FibEraseType eraseType, uint32_t address)
{ {
int32u eraseOp; uint32_t eraseOp;
int32u *ptr; uint32_t *ptr;
int32u length; uint32_t length;
FibStatus status = FIB_SUCCESS; FibStatus status = FIB_SUCCESS;
if (BYTE_0(eraseType) == MFB_MASS_ERASE) { if (BYTE_0(eraseType) == MFB_MASS_ERASE) {
eraseOp = FLASH_CTRL_MASSERASE; eraseOp = FLASH_CTRL_MASSERASE;
ptr = (int32u *)MFB_BOTTOM; ptr = (uint32_t *)MFB_BOTTOM;
length = MFB_SIZE_W; length = MFB_SIZE_W;
} else if (BYTE_0(eraseType) == MFB_PAGE_ERASE) { } else if (BYTE_0(eraseType) == MFB_PAGE_ERASE) {
if (address < MFB_BOTTOM || address > MFB_TOP) { if (address < MFB_BOTTOM || address > MFB_TOP) {
return FIB_ERR_INVALID_ADDRESS; return FIB_ERR_INVALID_ADDRESS;
} }
eraseOp = FLASH_CTRL_PAGEERASE; eraseOp = FLASH_CTRL_PAGEERASE;
ptr = (int32u *)(address & MFB_PAGE_MASK_B); ptr = (uint32_t *)(address & MFB_PAGE_MASK_B);
length = MFB_PAGE_SIZE_W; length = MFB_PAGE_SIZE_W;
} else if (BYTE_0(eraseType) == CIB_ERASE) { } else if (BYTE_0(eraseType) == CIB_ERASE) {
eraseOp = FLASH_CTRL_OPTWREN | FLASH_CTRL_OPTERASE; eraseOp = FLASH_CTRL_OPTWREN | FLASH_CTRL_OPTERASE;
ptr = (int32u *)CIB_BOTTOM; ptr = (uint32_t *)CIB_BOTTOM;
length = CIB_SIZE_W; length = CIB_SIZE_W;
} else { } else {
return FIB_ERR_INVALID_TYPE; return FIB_ERR_INVALID_TYPE;
@ -203,7 +203,7 @@ static FibStatus fibFlashErase(FibEraseType eraseType, int32u address)
} }
if (status == FIB_SUCCESS if (status == FIB_SUCCESS
&& (eraseType & DO_VERIFY) != 0) { && (eraseType & DO_VERIFY) != 0) {
int32u i; uint32_t i;
for (i = 0; i < length; i++) { for (i = 0; i < length; i++) {
if (*ptr != 0xFFFFFFFF) { if (*ptr != 0xFFFFFFFF) {
return FIB_ERR_VERIFY_FAILED; return FIB_ERR_VERIFY_FAILED;
@ -228,7 +228,7 @@ static boolean verifyFib(void)
//The parameter 'eraseType' chooses which erasure will be performed while //The parameter 'eraseType' chooses which erasure will be performed while
//the 'address' parameter chooses the page to be erased during MFB page erase. //the 'address' parameter chooses the page to be erased during MFB page erase.
StStatus halInternalFlashErase(int8u eraseType, int32u address) StStatus halInternalFlashErase(uint8_t eraseType, uint32_t address)
{ {
FibStatus status; FibStatus status;
@ -239,10 +239,10 @@ StStatus halInternalFlashErase(int8u eraseType, int32u address)
// Always try to use the FIB bootloader if its present // Always try to use the FIB bootloader if its present
if(verifyFib()) { if(verifyFib()) {
status = halFixedAddressTable.fibFlashErase( status = halFixedAddressTable.fibFlashErase(
(((int32u)eraseType) | DO_ERASE), (((uint32_t)eraseType) | DO_ERASE),
address); address);
} else { } else {
status = fibFlashErase((((int32u)eraseType) | DO_ERASE), address); status = fibFlashErase((((uint32_t)eraseType) | DO_ERASE), address);
} }
#else #else
@ -250,7 +250,7 @@ StStatus halInternalFlashErase(int8u eraseType, int32u address)
assert(verifyFib()); assert(verifyFib());
status = halFixedAddressTable.fibFlashErase( status = halFixedAddressTable.fibFlashErase(
(((int32u)eraseType) | DO_ERASE), (((uint32_t)eraseType) | DO_ERASE),
address); address);
#endif #endif
) )
@ -270,14 +270,14 @@ StStatus halInternalFlashErase(int8u eraseType, int32u address)
// Always try to use the FIB bootloader if its present // Always try to use the FIB bootloader if its present
if(verifyFib()) { if(verifyFib()) {
status = halFixedAddressTable.fibFlashErase( status = halFixedAddressTable.fibFlashErase(
(((int32u)eraseType) | DO_VERIFY), (((uint32_t)eraseType) | DO_VERIFY),
address); address);
} else { } else {
status = fibFlashErase((((int32u)eraseType) | DO_VERIFY), address); status = fibFlashErase((((uint32_t)eraseType) | DO_VERIFY), address);
} }
#else #else
status = halFixedAddressTable.fibFlashErase( status = halFixedAddressTable.fibFlashErase(
(((int32u)eraseType) | DO_VERIFY), (((uint32_t)eraseType) | DO_VERIFY),
address); address);
#endif #endif
return fibToStStatus[status]; return fibToStStatus[status];
@ -291,7 +291,7 @@ StStatus halInternalFlashErase(int8u eraseType, int32u address)
//half-words contained in 'data' to be written to flash. //half-words contained in 'data' to be written to flash.
//NOTE: This function can NOT write the option bytes and will throw an error //NOTE: This function can NOT write the option bytes and will throw an error
//if that is attempted. //if that is attempted.
StStatus halInternalFlashWrite(int32u address, int16u * data, int32u length) StStatus halInternalFlashWrite(uint32_t address, uint16_t * data, uint32_t length)
{ {
FibStatus status; FibStatus status;
@ -303,11 +303,11 @@ StStatus halInternalFlashWrite(int32u address, int16u * data, int32u length)
// Always try to use the FIB bootloader if its present // Always try to use the FIB bootloader if its present
if(verifyFib()) { if(verifyFib()) {
status = halFixedAddressTable.fibFlashWrite(address, status = halFixedAddressTable.fibFlashWrite(address,
(int8u *)data, (uint8_t *)data,
length, length,
0); 0);
} else { } else {
status = fibFlashWrite(address, (int8u *)data, length, 0); status = fibFlashWrite(address, (uint8_t *)data, length, 0);
} }
#else #else
@ -316,7 +316,7 @@ StStatus halInternalFlashWrite(int32u address, int16u * data, int32u length)
// Ensure that a programmed FIB of a proper version is present // Ensure that a programmed FIB of a proper version is present
assert(verifyFib()); assert(verifyFib());
status = halFixedAddressTable.fibFlashWrite(address, status = halFixedAddressTable.fibFlashWrite(address,
(int8u *)data, (uint8_t *)data,
length, length,
0); 0);
#endif #endif
@ -331,15 +331,15 @@ StStatus halInternalFlashWrite(int32u address, int16u * data, int32u length)
// Always try to use the FIB bootloader if its present // Always try to use the FIB bootloader if its present
if(verifyFib()) { if(verifyFib()) {
status = halFixedAddressTable.fibFlashWrite(address, status = halFixedAddressTable.fibFlashWrite(address,
(int8u *)data, (uint8_t *)data,
0, 0,
length); length);
} else { } else {
status = fibFlashWriteVerify(address, (int8u *)data, length); status = fibFlashWriteVerify(address, (uint8_t *)data, length);
} }
#else #else
status = halFixedAddressTable.fibFlashWrite(address, status = halFixedAddressTable.fibFlashWrite(address,
(int8u *)data, (uint8_t *)data,
0, 0,
length); length);
#endif #endif
@ -352,9 +352,9 @@ StStatus halInternalFlashWrite(int32u address, int16u * data, int32u length)
//parameter can have a value of 0 through 7. 'data' is the 8bit value to be //parameter can have a value of 0 through 7. 'data' is the 8bit value to be
//programmed into the option byte since the hardware will calculate the //programmed into the option byte since the hardware will calculate the
//compliment and program the full 16bit option byte. //compliment and program the full 16bit option byte.
StStatus halInternalCibOptionByteWrite(int8u byte, int8u data) StStatus halInternalCibOptionByteWrite(uint8_t byte, uint8_t data)
{ {
int16u dataAndInverse = HIGH_LOW_TO_INT(~data, data); uint16_t dataAndInverse = HIGH_LOW_TO_INT(~data, data);
// There are only 8 option bytes, don't try to program more than that. // There are only 8 option bytes, don't try to program more than that.
if (byte > 7) { if (byte > 7) {
return ST_ERR_FLASH_PROG_FAIL; return ST_ERR_FLASH_PROG_FAIL;

View file

@ -65,7 +65,7 @@ boolean halFlashEraseIsActive(void);
* - ST_ERR_FLASH_VERIFY_FAILED if erase verification failed * - ST_ERR_FLASH_VERIFY_FAILED if erase verification failed
* - ST_SUCCESS if erasure completed and verified properly * - ST_SUCCESS if erasure completed and verified properly
*/ */
StStatus halInternalFlashErase(int8u eraseType, int32u address); StStatus halInternalFlashErase(uint8_t eraseType, uint32_t address);
/** @brief Writes a block of words to flash. A page is erased /** @brief Writes a block of words to flash. A page is erased
* to 0xFFFF at every address. Only two writes can be performed to the same * to 0xFFFF at every address. Only two writes can be performed to the same
@ -96,7 +96,7 @@ StStatus halInternalFlashErase(int8u eraseType, int32u address);
* - ST_ERR_FLASH_VERIFY_FAILED if write verification failed * - ST_ERR_FLASH_VERIFY_FAILED if write verification failed
* - ST_SUCCESS if writing completed and verified properly * - ST_SUCCESS if writing completed and verified properly
*/ */
StStatus halInternalFlashWrite(int32u address, int16u * data, int32u length); StStatus halInternalFlashWrite(uint32_t address, uint16_t * data, uint32_t length);
/** @brief Writes an option byte to the customer information block. Only /** @brief Writes an option byte to the customer information block. Only
* two writes can be performed to the same address between erasures and this * two writes can be performed to the same address between erasures and this
@ -116,7 +116,7 @@ StStatus halInternalFlashWrite(int32u address, int16u * data, int32u length);
* - ST_ERR_FLASH_VERIFY_FAILED if write verification failed * - ST_ERR_FLASH_VERIFY_FAILED if write verification failed
* - ST_SUCCESS if writing completed and verified properly * - ST_SUCCESS if writing completed and verified properly
*/ */
StStatus halInternalCibOptionByteWrite(int8u byte, int8u data); StStatus halInternalCibOptionByteWrite(uint8_t byte, uint8_t data);
#endif //DOXYGEN_SHOULD_SKIP_THIS #endif //DOXYGEN_SHOULD_SKIP_THIS

View file

@ -36,7 +36,7 @@ void halToggleLed(HalBoardLed led)
//purposes, we disable interrupts since this is a read-modify-write //purposes, we disable interrupts since this is a read-modify-write
ATOMIC( ATOMIC(
if(led/8 < 3) { if(led/8 < 3) {
*((volatile int32u *)(GPIO_PxOUT_BASE+(GPIO_Px_OFFSET*(led/8)))) ^= BIT(led&7); *((volatile uint32_t *)(GPIO_PxOUT_BASE+(GPIO_Px_OFFSET*(led/8)))) ^= BIT(led&7);
} }
) )
} }

View file

@ -29,9 +29,9 @@ typedef struct {
HalBootloaderAddressTableType *bootloaderAddressTable; HalBootloaderAddressTableType *bootloaderAddressTable;
void *startOfUnusedRam; void *startOfUnusedRam;
// ** pointers to shared functions ** // ** pointers to shared functions **
FibStatus (* fibFlashWrite)(int32u address, int8u *data, FibStatus (* fibFlashWrite)(uint32_t address, uint8_t *data,
int32u writeLength, int32u verifyLength); uint32_t writeLength, uint32_t verifyLength);
FibStatus (* fibFlashErase)(FibEraseType eraseType, int32u address); FibStatus (* fibFlashErase)(FibEraseType eraseType, uint32_t address);
} HalFixedAddressTableType; } HalFixedAddressTableType;
extern const HalFixedAddressTableType halFixedAddressTable; extern const HalFixedAddressTableType halFixedAddressTable;

View file

@ -53,8 +53,8 @@ typedef struct {
void (*resetVector)(void); void (*resetVector)(void);
void (*nmiHandler)(void); void (*nmiHandler)(void);
void (*hardFaultHandler)(void); void (*hardFaultHandler)(void);
int16u type; uint16_t type;
int16u version; uint16_t version;
const HalVectorTableType *vectorTable; const HalVectorTableType *vectorTable;
// Followed by more fields depending on the specific address table type // Followed by more fields depending on the specific address table type
} HalBaseAddressTableType; } HalBaseAddressTableType;

View file

@ -19,19 +19,19 @@
#define WAIT_TX_FIN() do{}while((SC2_TWISTAT&SC_TWITXFIN)!=SC_TWITXFIN) #define WAIT_TX_FIN() do{}while((SC2_TWISTAT&SC_TWITXFIN)!=SC_TWITXFIN)
#define WAIT_RX_FIN() do{}while((SC2_TWISTAT&SC_TWIRXFIN)!=SC_TWIRXFIN) #define WAIT_RX_FIN() do{}while((SC2_TWISTAT&SC_TWIRXFIN)!=SC_TWIRXFIN)
static int8u i2c_MEMS_Init (void); static uint8_t i2c_MEMS_Init (void);
static int8u i2c_MEMS_Read (t_mems_data *mems_data); static uint8_t i2c_MEMS_Read (t_mems_data *mems_data);
//extern void halInternalResetWatchDog(void); //extern void halInternalResetWatchDog(void);
static int8u i2c_Send_Frame (int8u DeviceAddress, int8u *pBuffer, int8u NoOfBytes); static uint8_t i2c_Send_Frame (uint8_t DeviceAddress, uint8_t *pBuffer, uint8_t NoOfBytes);
static int8u i2c_Send_Frame (int8u DeviceAddress, int8u *pBuffer, int8u NoOfBytes); static uint8_t i2c_Send_Frame (uint8_t DeviceAddress, uint8_t *pBuffer, uint8_t NoOfBytes);
int8u i2c_write_reg (int8u slave_addr, int8u reg_addr, int8u reg_value); uint8_t i2c_write_reg (uint8_t slave_addr, uint8_t reg_addr, uint8_t reg_value);
static int8u i2c_MEMS_Init (void); static uint8_t i2c_MEMS_Init (void);
static int8u i2c_MEMS_Read (t_mems_data *mems_data); static uint8_t i2c_MEMS_Read (t_mems_data *mems_data);
/* Functions -----------------------------------------------------------------*/ /* Functions -----------------------------------------------------------------*/
int8u mems_Init(void) uint8_t mems_Init(void)
{ {
int8u ret = 0; uint8_t ret = 0;
// GPIO assignments // GPIO assignments
// PA1: SC2SDA (Serial Data) // PA1: SC2SDA (Serial Data)
@ -60,9 +60,9 @@ int8u mems_Init(void)
return ret; return ret;
}/* end mems_Init */ }/* end mems_Init */
int8u mems_GetValue(t_mems_data *mems_data) uint8_t mems_GetValue(t_mems_data *mems_data)
{ {
int8u i; uint8_t i;
i = i2c_MEMS_Read(mems_data); i = i2c_MEMS_Read(mems_data);
return i; return i;
}/* end mems_GetValue() */ }/* end mems_GetValue() */
@ -79,9 +79,9 @@ int8u mems_GetValue(t_mems_data *mems_data)
* Output : None * Output : None
* Return : status * Return : status
*******************************************************************************/ *******************************************************************************/
static int8u i2c_Send_Frame (int8u DeviceAddress, int8u *pBuffer, int8u NoOfBytes) static uint8_t i2c_Send_Frame (uint8_t DeviceAddress, uint8_t *pBuffer, uint8_t NoOfBytes)
{ {
int8u i, data; uint8_t i, data;
SC2_TWICTRL1 |= SC_TWISTART; // send start SC2_TWICTRL1 |= SC_TWISTART; // send start
WAIT_CMD_FIN(); WAIT_CMD_FIN();
@ -115,9 +115,9 @@ static int8u i2c_Send_Frame (int8u DeviceAddress, int8u *pBuffer, int8u NoOfByte
* Output : buffer * Output : buffer
* Return : status * Return : status
*******************************************************************************/ *******************************************************************************/
static int8u i2c_Receive_Frame (int8u slave_addr, int8u reg_addr, int8u *pBuffer, int8u NoOfBytes) static uint8_t i2c_Receive_Frame (uint8_t slave_addr, uint8_t reg_addr, uint8_t *pBuffer, uint8_t NoOfBytes)
{ {
int8u i, addr = reg_addr; uint8_t i, addr = reg_addr;
if (NoOfBytes > 1) if (NoOfBytes > 1)
addr += REPETIR; addr += REPETIR;
@ -168,9 +168,9 @@ static int8u i2c_Receive_Frame (int8u slave_addr, int8u reg_addr, int8u *pBuffer
* Output : None * Output : None
* Return : I2C frame * Return : I2C frame
*******************************************************************************/ *******************************************************************************/
int8u i2c_write_reg (int8u slave_addr, int8u reg_addr, int8u reg_value) uint8_t i2c_write_reg (uint8_t slave_addr, uint8_t reg_addr, uint8_t reg_value)
{ {
int8u i2c_buffer[2]; uint8_t i2c_buffer[2];
i2c_buffer[0] = reg_addr; i2c_buffer[0] = reg_addr;
i2c_buffer[1] = reg_value; i2c_buffer[1] = reg_value;
@ -188,7 +188,7 @@ int8u i2c_write_reg (int8u slave_addr, int8u reg_addr, int8u reg_value)
* Output : None * Output : None
* Return : I2C frame * Return : I2C frame
*******************************************************************************/ *******************************************************************************/
int8u i2c_read_reg (int8u slave_addr, int8u reg_addr, int8u *pBuffer, int8u NoOfBytes) uint8_t i2c_read_reg (uint8_t slave_addr, uint8_t reg_addr, uint8_t *pBuffer, uint8_t NoOfBytes)
{ {
return i2c_Receive_Frame (slave_addr, reg_addr, pBuffer, NoOfBytes); return i2c_Receive_Frame (slave_addr, reg_addr, pBuffer, NoOfBytes);
}/* end i2c_read_reg() */ }/* end i2c_read_reg() */
@ -201,9 +201,9 @@ int8u i2c_read_reg (int8u slave_addr, int8u reg_addr, int8u *pBuffer, int8u NoOf
* Output : None * Output : None
* Return : status * Return : status
*******************************************************************************/ *******************************************************************************/
static int8u i2c_MEMS_Init (void) static uint8_t i2c_MEMS_Init (void)
{ {
int8u i = 0; uint8_t i = 0;
i += i2c_write_reg (kLIS3L02DQ_SLAVE_ADDR, STATUS_REG, 0x00); //no flag i += i2c_write_reg (kLIS3L02DQ_SLAVE_ADDR, STATUS_REG, 0x00); //no flag
i += i2c_write_reg (kLIS3L02DQ_SLAVE_ADDR, FF_WU_CFG, 0x00); // all off i += i2c_write_reg (kLIS3L02DQ_SLAVE_ADDR, FF_WU_CFG, 0x00); // all off
@ -224,9 +224,9 @@ static int8u i2c_MEMS_Init (void)
* Output : mems_data * Output : mems_data
* Return : I2C frame * Return : I2C frame
*******************************************************************************/ *******************************************************************************/
static int8u i2c_MEMS_Read (t_mems_data *mems_data) static uint8_t i2c_MEMS_Read (t_mems_data *mems_data)
{ {
int8u i, i2c_buffer[8]; uint8_t i, i2c_buffer[8];
/* Wait for new set of data to be available */ /* Wait for new set of data to be available */
while (1) { while (1) {

View file

@ -13,7 +13,7 @@
#define DEFINETOKENS #define DEFINETOKENS
#define TOKEN_MFG(name,creator,iscnt,isidx,type,arraysize,...) \ #define TOKEN_MFG(name,creator,iscnt,isidx,type,arraysize,...) \
const int16u TOKEN_##name = TOKEN_##name##_ADDRESS; const uint16_t TOKEN_##name = TOKEN_##name##_ADDRESS;
#include "hal/micro/cortexm3/token-manufacturing.h" #include "hal/micro/cortexm3/token-manufacturing.h"
#undef TOKEN_DEF #undef TOKEN_DEF
#undef TOKEN_MFG #undef TOKEN_MFG
@ -26,12 +26,12 @@
static const int8u nullEui[] = { 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF }; static const uint8_t nullEui[] = { 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF };
void halInternalGetMfgTokenData(void *data, int16u ID, int8u index, int8u len) void halInternalGetMfgTokenData(void *data, uint16_t ID, uint8_t index, uint8_t len)
{ {
int8u *ram = (int8u*)data; uint8_t *ram = (uint8_t*)data;
//0x7F is a non-indexed token. Remap to 0 for the address calculation //0x7F is a non-indexed token. Remap to 0 for the address calculation
index = (index==0x7F) ? 0 : index; index = (index==0x7F) ? 0 : index;
@ -53,8 +53,8 @@ void halInternalGetMfgTokenData(void *data, int16u ID, int8u index, int8u len)
//bottom 16bits of the token's actual address. Since the info blocks //bottom 16bits of the token's actual address. Since the info blocks
//exist in the range DATA_BIG_INFO_BASE-DATA_BIG_INFO_END, we need //exist in the range DATA_BIG_INFO_BASE-DATA_BIG_INFO_END, we need
//to OR the ID with DATA_BIG_INFO_BASE to get the real address. //to OR the ID with DATA_BIG_INFO_BASE to get the real address.
int32u realAddress = (DATA_BIG_INFO_BASE|ID) + (len*index); uint32_t realAddress = (DATA_BIG_INFO_BASE|ID) + (len*index);
int8u *flash = (int8u *)realAddress; uint8_t *flash = (uint8_t *)realAddress;
@ -74,12 +74,12 @@ void halInternalGetMfgTokenData(void *data, int16u ID, int8u index, int8u len)
} }
void halInternalSetMfgTokenData(int16u token, void *data, int8u len) void halInternalSetMfgTokenData(uint16_t token, void *data, uint8_t len)
{ {
StStatus flashStatus; StStatus flashStatus;
int32u realAddress = (DATA_BIG_INFO_BASE|token); uint32_t realAddress = (DATA_BIG_INFO_BASE|token);
int8u * flash = (int8u *)realAddress; uint8_t * flash = (uint8_t *)realAddress;
int32u i; uint32_t i;
//The flash library (and hardware) requires the address and length to both //The flash library (and hardware) requires the address and length to both
//be multiples of 16bits. Since this API is only valid for writing to //be multiples of 16bits. Since this API is only valid for writing to

View file

@ -26,7 +26,7 @@
* will be stored. This parameter is generated with a macro above. * will be stored. This parameter is generated with a macro above.
*/ */
#define TOKEN_MFG(name,creator,iscnt,isidx,type,arraysize,...) \ #define TOKEN_MFG(name,creator,iscnt,isidx,type,arraysize,...) \
extern const int16u TOKEN_##name; extern const uint16_t TOKEN_##name;
#include "hal/micro/cortexm3/token-manufacturing.h" #include "hal/micro/cortexm3/token-manufacturing.h"
#undef TOKEN_MFG #undef TOKEN_MFG
@ -125,7 +125,7 @@ enum {
* @param len: The length of the token being worked on. This value is * @param len: The length of the token being worked on. This value is
* automatically set by the API to be the size of the token. * automatically set by the API to be the size of the token.
*/ */
void halInternalGetMfgTokenData(void *data, int16u token, int8u index, int8u len); void halInternalGetMfgTokenData(void *data, uint16_t token, uint8_t index, uint8_t len);
/** /**
* @description Sets the value of a token in non-volatile storage. This is * @description Sets the value of a token in non-volatile storage. This is
@ -147,7 +147,7 @@ void halInternalGetMfgTokenData(void *data, int16u token, int8u index, int8u len
* @param len: The length of the token being worked on. This value is * @param len: The length of the token being worked on. This value is
* automatically set by the API to be the size of the token. * automatically set by the API to be the size of the token.
*/ */
void halInternalSetMfgTokenData(int16u token, void *data, int8u len); void halInternalSetMfgTokenData(uint16_t token, void *data, uint8_t len);
#define halCommonGetMfgToken( data, token ) \ #define halCommonGetMfgToken( data, token ) \
halInternalGetMfgTokenData(data, token, 0x7F, token##_SIZE) halInternalGetMfgTokenData(data, token, 0x7F, token##_SIZE)

View file

@ -54,8 +54,8 @@ void stCalibrateVref(void)
assert(FALSE); assert(FALSE);
} else { } else {
//The bias trim token is set, so use the trim directly //The bias trim token is set, so use the trim directly
int16u temp_value; uint16_t temp_value;
int16u mask = 0xFFFF; uint16_t mask = 0xFFFF;
// halClearLed(BOARDLED3); // halClearLed(BOARDLED3);
@ -95,11 +95,11 @@ void calDisableAdc(void) {
// These routines maintain the same signature as their hal- counterparts to // These routines maintain the same signature as their hal- counterparts to
// facilitate simple support between phys. // facilitate simple support between phys.
// It is assumed (hoped?) that the compiler will optimize out unused arguments. // It is assumed (hoped?) that the compiler will optimize out unused arguments.
StStatus calStartAdcConversion(int8u dummy1, // Not used. StStatus calStartAdcConversion(uint8_t dummy1, // Not used.
int8u dummy2, // Not used. uint8_t dummy2, // Not used.
int8u channel, uint8_t channel,
int8u rate, uint8_t rate,
int8u clock) { uint8_t clock) {
// Disable the Calibration ADC interrupt so that we can poll it. // Disable the Calibration ADC interrupt so that we can poll it.
INT_MGMTCFG &= ~INT_MGMTCALADC; INT_MGMTCFG &= ~INT_MGMTCALADC;
@ -118,14 +118,14 @@ StStatus calStartAdcConversion(int8u dummy1, // Not used.
} }
StStatus calReadAdcBlocking(int8u dummy, StStatus calReadAdcBlocking(uint8_t dummy,
int16u *value) { uint16_t *value) {
// Wait for conversion to complete. // Wait for conversion to complete.
while ( ! (INT_MGMTFLAG & INT_MGMTCALADC) ); while ( ! (INT_MGMTFLAG & INT_MGMTCALADC) );
// Clear the interrupt for this conversion. // Clear the interrupt for this conversion.
INT_MGMTFLAG = INT_MGMTCALADC; INT_MGMTFLAG = INT_MGMTCALADC;
// Get the result. // Get the result.
*value = (int16u)CAL_ADC_DATA; *value = (uint16_t)CAL_ADC_DATA;
return ST_SUCCESS; return ST_SUCCESS;
} }
@ -137,12 +137,12 @@ StStatus calReadAdcBlocking(int8u dummy,
//the fastest conversions with the greatest reasonable accuracy. Variation //the fastest conversions with the greatest reasonable accuracy. Variation
//across successive conversions appears to be +/-20mv of the average //across successive conversions appears to be +/-20mv of the average
//conversion. Overall function time is <150us. //conversion. Overall function time is <150us.
int16u stMeasureVddFast(void) uint16_t stMeasureVddFast(void)
{ {
int16u value; uint16_t value;
int32u Ngnd; uint32_t Ngnd;
int32u Nreg; uint32_t Nreg;
int32u Nvdd; uint32_t Nvdd;
tokTypeMfgRegVoltage1V8 vregOutTok; tokTypeMfgRegVoltage1V8 vregOutTok;
halCommonGetMfgToken(&vregOutTok, TOKEN_MFG_1V8_REG_VOLTAGE); halCommonGetMfgToken(&vregOutTok, TOKEN_MFG_1V8_REG_VOLTAGE);
@ -153,7 +153,7 @@ int16u stMeasureVddFast(void)
ADC_SAMPLE_CLOCKS_128, ADC_SAMPLE_CLOCKS_128,
ADC_6MHZ_CLOCK); ADC_6MHZ_CLOCK);
calReadAdcBlocking(DUMMY, &value); calReadAdcBlocking(DUMMY, &value);
Ngnd = (int32u)value; Ngnd = (uint32_t)value;
//Measure VREG_OUT/2 //Measure VREG_OUT/2
calStartAdcConversion(DUMMY, calStartAdcConversion(DUMMY,
@ -162,7 +162,7 @@ int16u stMeasureVddFast(void)
ADC_SAMPLE_CLOCKS_128, ADC_SAMPLE_CLOCKS_128,
ADC_6MHZ_CLOCK); ADC_6MHZ_CLOCK);
calReadAdcBlocking(DUMMY, &value); calReadAdcBlocking(DUMMY, &value);
Nreg = (int32u)value; Nreg = (uint32_t)value;
//Measure VDD_PADS/4 //Measure VDD_PADS/4
calStartAdcConversion(DUMMY, calStartAdcConversion(DUMMY,
@ -171,7 +171,7 @@ int16u stMeasureVddFast(void)
ADC_SAMPLE_CLOCKS_128, ADC_SAMPLE_CLOCKS_128,
ADC_6MHZ_CLOCK); ADC_6MHZ_CLOCK);
calReadAdcBlocking(DUMMY, &value); calReadAdcBlocking(DUMMY, &value);
Nvdd = (int32u)value; Nvdd = (uint32_t)value;
calDisableAdc(); calDisableAdc();
@ -202,8 +202,8 @@ void halCommonCalibratePads(void)
void halInternalSetRegTrim(boolean boostMode) void halInternalSetRegTrim(boolean boostMode)
{ {
tokTypeMfgRegTrim regTrim; tokTypeMfgRegTrim regTrim;
int8u trim1V2; uint8_t trim1V2;
int8u trim1V8; uint8_t trim1V8;
halCommonGetMfgToken(&regTrim, TOKEN_MFG_REG_TRIM); halCommonGetMfgToken(&regTrim, TOKEN_MFG_REG_TRIM);
// The compiler can optimize this function a bit more and keep the // The compiler can optimize this function a bit more and keep the
@ -247,9 +247,9 @@ void halInternalSetRegTrim(boolean boostMode)
// OSCHF, though, the clock speed is cut in half, so the input parameter // OSCHF, though, the clock speed is cut in half, so the input parameter
// is divided by two. With respect to accuracy, we're now limited by // is divided by two. With respect to accuracy, we're now limited by
// the accuracy of OSCHF (much lower than XTAL). // the accuracy of OSCHF (much lower than XTAL).
void halCommonDelayMicroseconds(int16u us) void halCommonDelayMicroseconds(uint16_t us)
{ {
int32u beginTime = ReadRegister(MAC_TIMER); uint32_t beginTime = ReadRegister(MAC_TIMER);
//If we're not using the XTAL, the MAC Timer is running off OSCHF, //If we're not using the XTAL, the MAC Timer is running off OSCHF,
//that means the clock is half speed, 6MHz. We need to halve our delay //that means the clock is half speed, 6MHz. We need to halve our delay
@ -281,7 +281,7 @@ void halCommonDelayMicroseconds(int16u us)
//necessary in some situations. If you have to burn more than 65ms of time, //necessary in some situations. If you have to burn more than 65ms of time,
//the halCommonDelayMicroseconds function becomes cumbersome, so this //the halCommonDelayMicroseconds function becomes cumbersome, so this
//function gives you millisecond granularity. //function gives you millisecond granularity.
void halCommonDelayMilliseconds(int16u ms) void halCommonDelayMilliseconds(uint16_t ms)
{ {
if(ms==0) { if(ms==0) {
return; return;

View file

@ -28,7 +28,7 @@ void halInternalResetWatchDog(void)
WDOG_RESET = 1; WDOG_RESET = 1;
} }
void halInternalDisableWatchDog(int8u magicKey) void halInternalDisableWatchDog(uint8_t magicKey)
{ {
if (magicKey == MICRO_DISABLE_WATCH_DOG_KEY) { if (magicKey == MICRO_DISABLE_WATCH_DOG_KEY) {
WDOG_KEY = 0xDEAD; WDOG_KEY = 0xDEAD;
@ -45,33 +45,33 @@ boolean halInternalWatchDogEnabled(void)
} }
} }
void halGpioConfig(int32u io, int32u config) void halGpioConfig(uint32_t io, uint32_t config)
{ {
static volatile int32u *const configRegs[] = static volatile uint32_t *const configRegs[] =
{ (volatile int32u *)GPIO_PACFGL_ADDR, { (volatile uint32_t *)GPIO_PACFGL_ADDR,
(volatile int32u *)GPIO_PACFGH_ADDR, (volatile uint32_t *)GPIO_PACFGH_ADDR,
(volatile int32u *)GPIO_PBCFGL_ADDR, (volatile uint32_t *)GPIO_PBCFGL_ADDR,
(volatile int32u *)GPIO_PBCFGH_ADDR, (volatile uint32_t *)GPIO_PBCFGH_ADDR,
(volatile int32u *)GPIO_PCCFGL_ADDR, (volatile uint32_t *)GPIO_PCCFGL_ADDR,
(volatile int32u *)GPIO_PCCFGH_ADDR }; (volatile uint32_t *)GPIO_PCCFGH_ADDR };
int32u portcfg; uint32_t portcfg;
portcfg = *configRegs[io/4]; // get current config portcfg = *configRegs[io/4]; // get current config
portcfg = portcfg & ~((0xF)<<((io&3)*4)); // mask out config of this pin portcfg = portcfg & ~((0xF)<<((io&3)*4)); // mask out config of this pin
*configRegs[io/4] = portcfg | (config <<((io&3)*4)); *configRegs[io/4] = portcfg | (config <<((io&3)*4));
} }
void halGpioSet(int32u gpio, boolean value) void halGpioSet(uint32_t gpio, boolean value)
{ {
if(gpio/8 < 3) { if(gpio/8 < 3) {
if (value) { if (value) {
*((volatile int32u *)(GPIO_PxSET_BASE+(GPIO_Px_OFFSET*(gpio/8)))) = BIT(gpio&7); *((volatile uint32_t *)(GPIO_PxSET_BASE+(GPIO_Px_OFFSET*(gpio/8)))) = BIT(gpio&7);
} else { } else {
*((volatile int32u *)(GPIO_PxCLR_BASE+(GPIO_Px_OFFSET*(gpio/8)))) = BIT(gpio&7); *((volatile uint32_t *)(GPIO_PxCLR_BASE+(GPIO_Px_OFFSET*(gpio/8)))) = BIT(gpio&7);
} }
} }
} }
int16u halInternalStartSystemTimer(void) uint16_t halInternalStartSystemTimer(void)
{ {
//Since the SleepTMR is the only timer maintained during deep sleep, it is //Since the SleepTMR is the only timer maintained during deep sleep, it is
//used as the System Timer (RTC). We maintain a 32 bit hardware timer //used as the System Timer (RTC). We maintain a 32 bit hardware timer

View file

@ -20,7 +20,7 @@
//This is necessary here because halSleepForQsWithOptions returns an //This is necessary here because halSleepForQsWithOptions returns an
//StStatus and not adding this typedef to this file breaks a //StStatus and not adding this typedef to this file breaks a
//whole lot of builds. //whole lot of builds.
typedef int8u StStatus; typedef uint8_t StStatus;
#endif //__STSTATUS_TYPE__ #endif //__STSTATUS_TYPE__
#endif // DOXYGEN_SHOULD_SKIP_THIS #endif // DOXYGEN_SHOULD_SKIP_THIS
@ -71,7 +71,7 @@ void halInternalResetWatchDog( void );
* @param config The configuration mode to use. * @param config The configuration mode to use.
* *
*/ */
void halGpioConfig(int32u io, int32u config); void halGpioConfig(uint32_t io, uint32_t config);
/** /**
* @brief Set/Clear single GPIO bit * @brief Set/Clear single GPIO bit
@ -81,7 +81,7 @@ void halGpioConfig(int32u io, int32u config);
* @param value A flag indicating whether to set or clear the io. * @param value A flag indicating whether to set or clear the io.
* *
*/ */
void halGpioSet(int32u io, boolean value); void halGpioSet(uint32_t io, boolean value);
/** /**
@ -111,7 +111,7 @@ void halInternalSetRegTrim(boolean boostMode);
* *
* @return A slow measurement of VDD_PADS in millivolts. * @return A slow measurement of VDD_PADS in millivolts.
*/ */
int16u stMeasureVddSlow(void); uint16_t stMeasureVddSlow(void);
/** @brief Takes a fast ADC measurement of VDD_PADS in millivolts. /** @brief Takes a fast ADC measurement of VDD_PADS in millivolts.
@ -121,7 +121,7 @@ int16u stMeasureVddSlow(void);
* *
* @return A fast measurement of VDD_PADS in millivolts. * @return A fast measurement of VDD_PADS in millivolts.
*/ */
int16u stMeasureVddFast(void); uint16_t stMeasureVddFast(void);
/** /**
@ -164,7 +164,7 @@ void halInternalSearchForBiasTrim(void);
* *
* @param ms The specified time, in milliseconds. * @param ms The specified time, in milliseconds.
*/ */
void halCommonDelayMilliseconds(int16u ms); void halCommonDelayMilliseconds(uint16_t ms);
/** @brief Puts the microcontroller to sleep in a specified mode, allows /** @brief Puts the microcontroller to sleep in a specified mode, allows
@ -183,7 +183,7 @@ void halCommonDelayMilliseconds(int16u ms);
* *
* @sa ::SleepModes * @sa ::SleepModes
*/ */
void halSleepWithOptions(SleepModes sleepMode, int32u gpioWakeBitMask); void halSleepWithOptions(SleepModes sleepMode, uint32_t gpioWakeBitMask);
/** /**
@ -218,7 +218,7 @@ void halSleepWithOptions(SleepModes sleepMode, int32u gpioWakeBitMask);
* @return An StStatus value indicating the success or * @return An StStatus value indicating the success or
* failure of the command. * failure of the command.
*/ */
StStatus halSleepForQsWithOptions(int32u *duration, int32u gpioWakeBitMask); StStatus halSleepForQsWithOptions(uint32_t *duration, uint32_t gpioWakeBitMask);
/** /**
* @brief Provides access to assembly code which triggers idle sleep. * @brief Provides access to assembly code which triggers idle sleep.
@ -262,7 +262,7 @@ void halInternalSleep(SleepModes sleepMode);
* *
* @return The events that caused the last wake from sleep. * @return The events that caused the last wake from sleep.
*/ */
int32u halGetWakeInfo(void); uint32_t halGetWakeInfo(void);
/** @brief Seeds the ::halCommonGetRandom() pseudorandom number /** @brief Seeds the ::halCommonGetRandom() pseudorandom number
@ -273,7 +273,7 @@ int32u halGetWakeInfo(void);
* *
* @param seed A seed for the pseudorandom number generator. * @param seed A seed for the pseudorandom number generator.
*/ */
void halCommonSeedRandom(int32u seed); void halCommonSeedRandom(uint32_t seed);
/** @brief Runs a standard LFSR to generate pseudorandom numbers. /** @brief Runs a standard LFSR to generate pseudorandom numbers.
* *
@ -283,7 +283,7 @@ void halCommonSeedRandom(int32u seed);
* ability to avoid collisions in large networks, but it is \b critical to * ability to avoid collisions in large networks, but it is \b critical to
* implement this function to return quickly. * implement this function to return quickly.
*/ */
int16u halCommonGetRandom(void); uint16_t halCommonGetRandom(void);
#endif //__STM32W108XX_MICRO_COMMON_H__ #endif //__STM32W108XX_MICRO_COMMON_H__

View file

@ -70,22 +70,22 @@ void halPowerUp(void)
halBoardPowerUp(); halBoardPowerUp();
} }
static int16u seed0 = 0xbeef; static uint16_t seed0 = 0xbeef;
static int16u seed1 = 0xface; static uint16_t seed1 = 0xface;
void halCommonSeedRandom(int32u seed) void halCommonSeedRandom(uint32_t seed)
{ {
seed0 = (int16u) seed; seed0 = (uint16_t) seed;
if (seed0 == 0) if (seed0 == 0)
seed0 = 0xbeef; seed0 = 0xbeef;
seed1 = (int16u) (seed >> 16); seed1 = (uint16_t) (seed >> 16);
if (seed1 == 0) if (seed1 == 0)
seed1 = 0xface; seed1 = 0xface;
} }
static int16u shift(int16u *val, int16u taps) static uint16_t shift(uint16_t *val, uint16_t taps)
{ {
int16u newVal = *val; uint16_t newVal = *val;
if (newVal & 0x8000) if (newVal & 0x8000)
newVal ^= taps; newVal ^= taps;
@ -93,44 +93,44 @@ static int16u shift(int16u *val, int16u taps)
return newVal; return newVal;
} }
int16u halCommonGetRandom(void) uint16_t halCommonGetRandom(void)
{ {
return (shift(&seed0, 0x0062) return (shift(&seed0, 0x0062)
^ shift(&seed1, 0x100B)); ^ shift(&seed1, 0x100B));
} }
void halCommonMemCopy(void *dest, const void *source, int8u bytes) void halCommonMemCopy(void *dest, const void *source, uint8_t bytes)
{ {
memcpy(dest, source, bytes); memcpy(dest, source, bytes);
} }
int8s halCommonMemCompare(const void *source0, const void *source1, int8u bytes) int8_t halCommonMemCompare(const void *source0, const void *source1, uint8_t bytes)
{ {
return memcmp(source0, source1, bytes); return memcmp(source0, source1, bytes);
} }
void halCommonMemSet(void *dest, int8u val, int16u bytes) void halCommonMemSet(void *dest, uint8_t val, uint16_t bytes)
{ {
memset(dest, val, bytes); memset(dest, val, bytes);
} }
#pragma pack(1) #pragma pack(1)
typedef struct appSwitchStruct { typedef struct appSwitchStruct {
int32u signature; uint32_t signature;
int8u mode; uint8_t mode;
int8u channel; uint8_t channel;
union { union {
int16u panID; uint16_t panID;
int16u offset; uint16_t offset;
} param; } param;
} appSwitchStructType; } appSwitchStructType;
#pragma pack() #pragma pack()
static appSwitchStructType *appSwitch = (appSwitchStructType *) RAM_BOTTOM; static appSwitchStructType *appSwitch = (appSwitchStructType *) RAM_BOTTOM;
StStatus halBootloaderStart(int8u mode, int8u channel, int16u panID) StStatus halBootloaderStart(uint8_t mode, uint8_t channel, uint16_t panID)
{ {
if (mode == IAP_BOOTLOADER_MODE_UART) { if (mode == IAP_BOOTLOADER_MODE_UART) {
int8u cut = *(volatile int8u *) 0x08040798; uint8_t cut = *(volatile uint8_t *) 0x08040798;
if (!( (halFixedAddressTable.baseTable.type == FIXED_ADDRESS_TABLE_TYPE) && if (!( (halFixedAddressTable.baseTable.type == FIXED_ADDRESS_TABLE_TYPE) &&
( ( (halFixedAddressTable.baseTable.version & FAT_MAJOR_VERSION_MASK) ( ( (halFixedAddressTable.baseTable.version & FAT_MAJOR_VERSION_MASK)
== 0x0000 ) && == 0x0000 ) &&
@ -140,7 +140,7 @@ StStatus halBootloaderStart(int8u mode, int8u channel, int16u panID)
return ST_ERR_FATAL; return ST_ERR_FATAL;
} else { } else {
/* Check that OTA bootloader is at the base of the flash */ /* Check that OTA bootloader is at the base of the flash */
if (*((int32u *) (MFB_BOTTOM + 28)) == IAP_BOOTLOADER_APP_SWITCH_SIGNATURE) { if (*((uint32_t *) (MFB_BOTTOM + 28)) == IAP_BOOTLOADER_APP_SWITCH_SIGNATURE) {
appSwitch->channel = ((channel >= 11) && (channel <= 26)) ? channel :IAP_BOOTLOADER_DEFAULT_CHANNEL; appSwitch->channel = ((channel >= 11) && (channel <= 26)) ? channel :IAP_BOOTLOADER_DEFAULT_CHANNEL;
appSwitch->param.panID = panID; appSwitch->param.panID = panID;
} else { } else {

View file

@ -13,7 +13,7 @@
#ifdef NVM_RAM_EMULATION #ifdef NVM_RAM_EMULATION
static int16u calibrationData[32+2]={ static uint16_t calibrationData[32+2]={
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF,
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF,
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF,
@ -21,14 +21,14 @@ static int16u calibrationData[32+2]={
0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF, 0xFFFF,
}; };
int8u halCommonReadFromNvm(void *data, int32u offset, int16u length) uint8_t halCommonReadFromNvm(void *data, uint32_t offset, uint16_t length)
{ {
halCommonMemCopy(data, ((int8u *) calibrationData) + offset, length); halCommonMemCopy(data, ((uint8_t *) calibrationData) + offset, length);
return ST_SUCCESS; return ST_SUCCESS;
} }
int8u halCommonWriteToNvm(const void *data, int32u offset, int16u length) uint8_t halCommonWriteToNvm(const void *data, uint32_t offset, uint16_t length)
{ {
halCommonMemCopy(((int8u *) calibrationData) + offset, data, length); halCommonMemCopy(((uint8_t *) calibrationData) + offset, data, length);
return ST_SUCCESS; return ST_SUCCESS;
} }
@ -50,14 +50,14 @@ int8u halCommonWriteToNvm(const void *data, int32u offset, int16u length)
//are not required to be continuous memory blocks so they can be define //are not required to be continuous memory blocks so they can be define
//separately. The linker is responsible for placing these storage containers //separately. The linker is responsible for placing these storage containers
//on flash page boundaries. //on flash page boundaries.
NO_STRIPPING __no_init VAR_AT_SEGMENT (const int8u nvmStorageLeft[NVM_DATA_SIZE_B], __NVM__); NO_STRIPPING __no_init VAR_AT_SEGMENT (const uint8_t nvmStorageLeft[NVM_DATA_SIZE_B], __NVM__);
NO_STRIPPING __no_init VAR_AT_SEGMENT (const int8u nvmStorageRight[NVM_DATA_SIZE_B], __NVM__); NO_STRIPPING __no_init VAR_AT_SEGMENT (const uint8_t nvmStorageRight[NVM_DATA_SIZE_B], __NVM__);
static int8u determineState(void) static uint8_t determineState(void)
{ {
int32u leftMgmt = *(int32u *)NVM_LEFT_PAGE; uint32_t leftMgmt = *(uint32_t *)NVM_LEFT_PAGE;
int32u rightMgmt = *(int32u *)NVM_RIGHT_PAGE; uint32_t rightMgmt = *(uint32_t *)NVM_RIGHT_PAGE;
int8u state=0; uint8_t state=0;
if((leftMgmt==0xFFFF0000) && (rightMgmt==0xFFFFFFFF)) { if((leftMgmt==0xFFFF0000) && (rightMgmt==0xFFFFFFFF)) {
//State 1 and state 4 use identical mgmt words. The function //State 1 and state 4 use identical mgmt words. The function
@ -95,12 +95,12 @@ static int8u determineState(void)
} }
int8u halCommonReadFromNvm(void *data, int32u offset, int16u length) uint8_t halCommonReadFromNvm(void *data, uint32_t offset, uint16_t length)
{ {
int16u i; uint16_t i;
int16u *flash; uint16_t *flash;
//Remember: all flash writes are 16bits. //Remember: all flash writes are 16bits.
int16u *ram = (int16u*)data; uint16_t *ram = (uint16_t*)data;
//The NVM data storage system cannot function if the LEFT and RIGHT //The NVM data storage system cannot function if the LEFT and RIGHT
//storage are not aligned to physical flash pages. //storage are not aligned to physical flash pages.
@ -121,7 +121,7 @@ int8u halCommonReadFromNvm(void *data, int32u offset, int16u length)
case 4: case 4:
case 9: case 9:
case 10: case 10:
flash = (int16u *)(NVM_LEFT_PAGE+offset); flash = (uint16_t *)(NVM_LEFT_PAGE+offset);
for(i=0;i<(length/2);i++) { for(i=0;i<(length/2);i++) {
ram[i] = flash[i]; ram[i] = flash[i];
} }
@ -130,7 +130,7 @@ int8u halCommonReadFromNvm(void *data, int32u offset, int16u length)
case 6: case 6:
case 7: case 7:
case 8: case 8:
flash = (int16u *)(NVM_RIGHT_PAGE+offset); flash = (uint16_t *)(NVM_RIGHT_PAGE+offset);
for(i=0;i<(length/2);i++) { for(i=0;i<(length/2);i++) {
ram[i] = flash[i]; ram[i] = flash[i];
} }
@ -155,9 +155,9 @@ int8u halCommonReadFromNvm(void *data, int32u offset, int16u length)
return ST_SUCCESS; return ST_SUCCESS;
} }
int16u *halCommonGetAddressFromNvm(int32u offset) uint16_t *halCommonGetAddressFromNvm(uint32_t offset)
{ {
int16u *flash; uint16_t *flash;
//The NVM data storage system cannot function if the LEFT and RIGHT //The NVM data storage system cannot function if the LEFT and RIGHT
//storage are not aligned to physical flash pages. //storage are not aligned to physical flash pages.
@ -174,22 +174,22 @@ int16u *halCommonGetAddressFromNvm(int32u offset)
case 4: case 4:
case 9: case 9:
case 10: case 10:
flash = (int16u *)(NVM_LEFT_PAGE+offset); flash = (uint16_t *)(NVM_LEFT_PAGE+offset);
break; break;
case 5: case 5:
case 6: case 6:
case 7: case 7:
case 8: case 8:
flash = (int16u *)(NVM_RIGHT_PAGE+offset); flash = (uint16_t *)(NVM_RIGHT_PAGE+offset);
break; break;
case 0: case 0:
default: default:
// Flash is in an invalid state // Flash is in an invalid state
// Fix it with a dummy write and then return the flash page left // Fix it with a dummy write and then return the flash page left
{ {
int16u dummy = 0xFFFF; uint16_t dummy = 0xFFFF;
halCommonWriteToNvm(&dummy, 0, 2); halCommonWriteToNvm(&dummy, 0, 2);
flash = (int16u *)(NVM_LEFT_PAGE+offset); flash = (uint16_t *)(NVM_LEFT_PAGE+offset);
} }
} }
@ -197,12 +197,12 @@ int16u *halCommonGetAddressFromNvm(int32u offset)
} }
static int8u erasePage(int32u page) static uint8_t erasePage(uint32_t page)
{ {
StStatus status; StStatus status;
int32u i, k; uint32_t i, k;
int32u address; uint32_t address;
int8u *flash; uint8_t *flash;
//Erasing a LEFT or RIGHT page requires erasing all of the flash pages. //Erasing a LEFT or RIGHT page requires erasing all of the flash pages.
//Since the mgmt bytes are stored at the bottom of a page, the flash pages //Since the mgmt bytes are stored at the bottom of a page, the flash pages
@ -211,7 +211,7 @@ static int8u erasePage(int32u page)
//words are still valid the next time determineState() is called. //words are still valid the next time determineState() is called.
for(i=NVM_FLASH_PAGE_COUNT;i>0;i--) { for(i=NVM_FLASH_PAGE_COUNT;i>0;i--) {
address = (page+((i-1)*MFB_PAGE_SIZE_B)); address = (page+((i-1)*MFB_PAGE_SIZE_B));
flash = (int8u *)address; flash = (uint8_t *)address;
//Scan the page to determine if it is fully erased already. //Scan the page to determine if it is fully erased already.
//If the flash is not erased, erase it. The purpose of scanning //If the flash is not erased, erase it. The purpose of scanning
//first is to save a little time if erasing is not required. //first is to save a little time if erasing is not required.
@ -248,7 +248,7 @@ static int8u erasePage(int32u page)
do { \ do { \
/*Copy all data below the new data from the srcPage to the destPage*/ \ /*Copy all data below the new data from the srcPage to the destPage*/ \
status = halInternalFlashWrite(destPage+NVM_MGMT_SIZE_B, \ status = halInternalFlashWrite(destPage+NVM_MGMT_SIZE_B, \
(int16u *)(srcPage+NVM_MGMT_SIZE_B), \ (uint16_t *)(srcPage+NVM_MGMT_SIZE_B), \
(offset-NVM_MGMT_SIZE_B)/2); \ (offset-NVM_MGMT_SIZE_B)/2); \
if(status != ST_SUCCESS) { return status; } \ if(status != ST_SUCCESS) { return status; } \
/*Write the new data*/ \ /*Write the new data*/ \
@ -258,7 +258,7 @@ static int8u erasePage(int32u page)
if(status != ST_SUCCESS) { return status; } \ if(status != ST_SUCCESS) { return status; } \
/*Copy all data above the new data from the srcPage to the destPage*/ \ /*Copy all data above the new data from the srcPage to the destPage*/ \
status = halInternalFlashWrite(destPage+offset+length, \ status = halInternalFlashWrite(destPage+offset+length, \
(int16u *)(srcPage+offset+length), \ (uint16_t *)(srcPage+offset+length), \
(NVM_DATA_SIZE_B- \ (NVM_DATA_SIZE_B- \
length-offset- \ length-offset- \
NVM_MGMT_SIZE_B)/2); \ NVM_MGMT_SIZE_B)/2); \
@ -269,7 +269,7 @@ static int8u erasePage(int32u page)
//the proper management address. //the proper management address.
#define WRITE_MGMT_16BITS(address, data) \ #define WRITE_MGMT_16BITS(address, data) \
do{ \ do{ \
int16u value = data; \ uint16_t value = data; \
status = halInternalFlashWrite((address), &value, 1); \ status = halInternalFlashWrite((address), &value, 1); \
if(status != ST_SUCCESS) { \ if(status != ST_SUCCESS) { \
return status; \ return status; \
@ -277,14 +277,14 @@ static int8u erasePage(int32u page)
} while(0) } while(0)
int8u halCommonWriteToNvm(const void *data, int32u offset, int16u length) uint8_t halCommonWriteToNvm(const void *data, uint32_t offset, uint16_t length)
{ {
StStatus status; StStatus status;
int8u state, exitState; uint8_t state, exitState;
int32u srcPage; uint32_t srcPage;
int32u destPage; uint32_t destPage;
//Remember: NVM data storage works on 16bit quantities. //Remember: NVM data storage works on 16bit quantities.
int16u *ram = (int16u*)data; uint16_t *ram = (uint16_t*)data;
//The NVM data storage system cannot function if the LEFT and RIGHT //The NVM data storage system cannot function if the LEFT and RIGHT
//storage are not aligned to physical flash pages. //storage are not aligned to physical flash pages.

View file

@ -137,7 +137,7 @@
* - Refer to nvm-def.h for a list of offset/length that define the data * - Refer to nvm-def.h for a list of offset/length that define the data
* stored in NVM storage space. * stored in NVM storage space.
* - All writes to flash are 16bit granularity and therefore the internal * - All writes to flash are 16bit granularity and therefore the internal
* flash writes cast the data to int16u. Length is also required to be * flash writes cast the data to uint16_t. Length is also required to be
* a multiple of 16bits. * a multiple of 16bits.
* - Flash page erase uses a granularity of a single flash page. The size * - Flash page erase uses a granularity of a single flash page. The size
* of a flash page depends on the chip and is defined in memmap.h with * of a flash page depends on the chip and is defined in memmap.h with
@ -198,7 +198,7 @@
* - ST_ERR_FATAL if the NVM storage management indicated an invalid * - ST_ERR_FATAL if the NVM storage management indicated an invalid
* state. The function will return entirely 0xFF in the data parameter. * state. The function will return entirely 0xFF in the data parameter.
*/ */
StStatus halCommonReadFromNvm(void *data, int32u offset, int16u length); StStatus halCommonReadFromNvm(void *data, uint32_t offset, uint16_t length);
/** /**
* @brief Return the address of the token in NVM * @brief Return the address of the token in NVM
@ -208,7 +208,7 @@ StStatus halCommonReadFromNvm(void *data, int32u offset, int16u length);
* *
* @return The address requested * @return The address requested
*/ */
int16u *halCommonGetAddressFromNvm(int32u offset); uint16_t *halCommonGetAddressFromNvm(uint32_t offset);
/** /**
* @brief Write the NVM data from the provided location RAM into flash. * @brief Write the NVM data from the provided location RAM into flash.
@ -226,7 +226,7 @@ int16u *halCommonGetAddressFromNvm(int32u offset);
* - Any other status value is an error code generated by the low level * - Any other status value is an error code generated by the low level
* flash erase and write API. Refer to flash.h for details. * flash erase and write API. Refer to flash.h for details.
*/ */
StStatus halCommonWriteToNvm(const void *data, int32u offset, int16u length); StStatus halCommonWriteToNvm(const void *data, uint32_t offset, uint16_t length);
/** /**
* @brief Define the number of physical flash pages that comprise a NVM page. * @brief Define the number of physical flash pages that comprise a NVM page.
@ -256,14 +256,14 @@ StStatus halCommonWriteToNvm(const void *data, int32u offset, int16u length);
* is defined by nvmStorageLeft[NVM_DATA_SIZE_B] and placed by the linker * is defined by nvmStorageLeft[NVM_DATA_SIZE_B] and placed by the linker
* using the segment "NVM". * using the segment "NVM".
*/ */
#define NVM_LEFT_PAGE ((int32u)nvmStorageLeft) #define NVM_LEFT_PAGE ((uint32_t)nvmStorageLeft)
/** /**
* @brief Define the absolute address of the RIGHT page. RIGHT page storage * @brief Define the absolute address of the RIGHT page. RIGHT page storage
* is defined by nvmStorageRight[NVM_DATA_SIZE_B] and placed by the linker * is defined by nvmStorageRight[NVM_DATA_SIZE_B] and placed by the linker
* using the segment "NVM". * using the segment "NVM".
*/ */
#define NVM_RIGHT_PAGE ((int32u)nvmStorageRight) #define NVM_RIGHT_PAGE ((uint32_t)nvmStorageRight)
/** /**
* @brief Define the number of bytes that comprise the NVM management bytes. * @brief Define the number of bytes that comprise the NVM management bytes.

View file

@ -117,9 +117,9 @@
//place in the halInternalWakeEvent variable //place in the halInternalWakeEvent variable
#define INTERNAL_WAKE_EVENT_BIT_SHIFT 20 #define INTERNAL_WAKE_EVENT_BIT_SHIFT 20
static int32u halInternalWakeEvent=0; static uint32_t halInternalWakeEvent=0;
int32u halGetWakeInfo(void) uint32_t halGetWakeInfo(void)
{ {
return halInternalWakeEvent; return halInternalWakeEvent;
} }
@ -129,7 +129,7 @@ void halInternalSleep(SleepModes sleepMode)
//Timer restoring always takes place during the wakeup sequence. We save //Timer restoring always takes place during the wakeup sequence. We save
//the state here in case SLEEPMODE_NOTIMER is invoked, which would disable //the state here in case SLEEPMODE_NOTIMER is invoked, which would disable
//the clocks. //the clocks.
int32u SLEEPTMR_CLKEN_SAVED = SLEEPTMR_CLKEN; uint32_t SLEEPTMR_CLKEN_SAVED = SLEEPTMR_CLKEN;
//This code assumes all wake source registers are properly configured. //This code assumes all wake source registers are properly configured.
//As such, it should be called from halSleepWithOptions() or from //As such, it should be called from halSleepWithOptions() or from
@ -138,7 +138,7 @@ void halInternalSleep(SleepModes sleepMode)
//The parameter gpioWakeSel is a bitfield composite of the GPIO wake //The parameter gpioWakeSel is a bitfield composite of the GPIO wake
//sources derived from the 3 ports, indicating which of the 24 GPIO //sources derived from the 3 ports, indicating which of the 24 GPIO
//are configured as a wake source. //are configured as a wake source.
int32u gpioWakeSel = (GPIO_PAWAKE<<0); uint32_t gpioWakeSel = (GPIO_PAWAKE<<0);
gpioWakeSel |= (GPIO_PBWAKE<<8); gpioWakeSel |= (GPIO_PBWAKE<<8);
gpioWakeSel |= (GPIO_PCWAKE<<16); gpioWakeSel |= (GPIO_PCWAKE<<16);
@ -248,38 +248,38 @@ deepSleepCore:
//MAC_TIMER_INT_MASK - reinitialized by stStackPowerUp() //MAC_TIMER_INT_MASK - reinitialized by stStackPowerUp()
//BB_INT_MASK - reinitialized by stStackPowerUp() //BB_INT_MASK - reinitialized by stStackPowerUp()
//SEC_INT_MASK - reinitialized by stStackPowerUp() //SEC_INT_MASK - reinitialized by stStackPowerUp()
int32u INT_SLEEPTMRCFG_SAVED = INT_SLEEPTMRCFG_REG; uint32_t INT_SLEEPTMRCFG_SAVED = INT_SLEEPTMRCFG_REG;
int32u INT_MGMTCFG_SAVED = INT_MGMTCFG_REG; uint32_t INT_MGMTCFG_SAVED = INT_MGMTCFG_REG;
//INT_TIM1CFG - reinitialized by halPowerUp() or similar //INT_TIM1CFG - reinitialized by halPowerUp() or similar
//INT_TIM2CFG - reinitialized by halPowerUp() or similar //INT_TIM2CFG - reinitialized by halPowerUp() or similar
//INT_SC1CFG - reinitialized by halPowerUp() or similar //INT_SC1CFG - reinitialized by halPowerUp() or similar
//INT_SC2CFG - reinitialized by halPowerUp() or similar //INT_SC2CFG - reinitialized by halPowerUp() or similar
//INT_ADCCFG - reinitialized by halPowerUp() or similar //INT_ADCCFG - reinitialized by halPowerUp() or similar
int32u GPIO_INTCFGA_SAVED = GPIO_INTCFGA_REG; uint32_t GPIO_INTCFGA_SAVED = GPIO_INTCFGA_REG;
int32u GPIO_INTCFGB_SAVED = GPIO_INTCFGB_REG; uint32_t GPIO_INTCFGB_SAVED = GPIO_INTCFGB_REG;
int32u GPIO_INTCFGC_SAVED = GPIO_INTCFGC_REG; uint32_t GPIO_INTCFGC_SAVED = GPIO_INTCFGC_REG;
int32u GPIO_INTCFGD_SAVED = GPIO_INTCFGD_REG; uint32_t GPIO_INTCFGD_SAVED = GPIO_INTCFGD_REG;
//SC1_INTMODE - reinitialized by halPowerUp() or similar //SC1_INTMODE - reinitialized by halPowerUp() or similar
//SC2_INTMODE - reinitialized by halPowerUp() or similar //SC2_INTMODE - reinitialized by halPowerUp() or similar
//----CM_LV //----CM_LV
int32u OSC24M_BIASTRIM_SAVED = OSC24M_BIASTRIM_REG; uint32_t OSC24M_BIASTRIM_SAVED = OSC24M_BIASTRIM_REG;
int32u OSCHF_TUNE_SAVED = OSCHF_TUNE_REG; uint32_t OSCHF_TUNE_SAVED = OSCHF_TUNE_REG;
int32u DITHER_DIS_SAVED = DITHER_DIS_REG; uint32_t DITHER_DIS_SAVED = DITHER_DIS_REG;
//OSC24M_CTRL - reinitialized by halPowerUp() or similar //OSC24M_CTRL - reinitialized by halPowerUp() or similar
//CPU_CLKSEL - reinitialized by halPowerUp() or similar //CPU_CLKSEL - reinitialized by halPowerUp() or similar
//TMR1_CLK_SEL - reinitialized by halPowerUp() or similar //TMR1_CLK_SEL - reinitialized by halPowerUp() or similar
//TMR2_CLK_SEL - reinitialized by halPowerUp() or similar //TMR2_CLK_SEL - reinitialized by halPowerUp() or similar
int32u PCTRACE_SEL_SAVED = PCTRACE_SEL_REG; uint32_t PCTRACE_SEL_SAVED = PCTRACE_SEL_REG;
//----RAM_CTRL //----RAM_CTRL
int32u MEM_PROT_0_SAVED = MEM_PROT_0_REG; uint32_t MEM_PROT_0_SAVED = MEM_PROT_0_REG;
int32u MEM_PROT_1_SAVED = MEM_PROT_1_REG; uint32_t MEM_PROT_1_SAVED = MEM_PROT_1_REG;
int32u MEM_PROT_2_SAVED = MEM_PROT_2_REG; uint32_t MEM_PROT_2_SAVED = MEM_PROT_2_REG;
int32u MEM_PROT_3_SAVED = MEM_PROT_3_REG; uint32_t MEM_PROT_3_SAVED = MEM_PROT_3_REG;
int32u MEM_PROT_4_SAVED = MEM_PROT_4_REG; uint32_t MEM_PROT_4_SAVED = MEM_PROT_4_REG;
int32u MEM_PROT_5_SAVED = MEM_PROT_5_REG; uint32_t MEM_PROT_5_SAVED = MEM_PROT_5_REG;
int32u MEM_PROT_6_SAVED = MEM_PROT_6_REG; uint32_t MEM_PROT_6_SAVED = MEM_PROT_6_REG;
int32u MEM_PROT_7_SAVED = MEM_PROT_7_REG; uint32_t MEM_PROT_7_SAVED = MEM_PROT_7_REG;
int32u MEM_PROT_EN_SAVED = MEM_PROT_EN_REG; uint32_t MEM_PROT_EN_SAVED = MEM_PROT_EN_REG;
//----AUX_ADC //----AUX_ADC
// reinitialized by halPowerUp() or similar // reinitialized by halPowerUp() or similar
//----CAL_ADC //----CAL_ADC
@ -295,14 +295,14 @@ deepSleepCore:
//----NVIC //----NVIC
//ST_CSR - fixed, restored by cstartup when exiting deep sleep //ST_CSR - fixed, restored by cstartup when exiting deep sleep
//ST_RVR - fixed, restored by cstartup when exiting deep sleep //ST_RVR - fixed, restored by cstartup when exiting deep sleep
int32u INT_CFGSET_SAVED = INT_CFGSET_REG; //mask against wake sources uint32_t INT_CFGSET_SAVED = INT_CFGSET_REG; //mask against wake sources
//INT_PENDSET - used below when overlapping interrupts and wake sources //INT_PENDSET - used below when overlapping interrupts and wake sources
//NVIC_IPR_3to0 - fixed, restored by cstartup when exiting deep sleep //NVIC_IPR_3to0 - fixed, restored by cstartup when exiting deep sleep
//NVIC_IPR_7to4 - fixed, restored by cstartup when exiting deep sleep //NVIC_IPR_7to4 - fixed, restored by cstartup when exiting deep sleep
//NVIC_IPR_11to8 - fixed, restored by cstartup when exiting deep sleep //NVIC_IPR_11to8 - fixed, restored by cstartup when exiting deep sleep
//NVIC_IPR_15to12 - fixed, restored by cstartup when exiting deep sleep //NVIC_IPR_15to12 - fixed, restored by cstartup when exiting deep sleep
//NVIC_IPR_19to16 - fixed, restored by cstartup when exiting deep sleep //NVIC_IPR_19to16 - fixed, restored by cstartup when exiting deep sleep
int32u SCS_VTOR_SAVED = SCS_VTOR_REG; uint32_t SCS_VTOR_SAVED = SCS_VTOR_REG;
//SCS_CCR - fixed, restored by cstartup when exiting deep sleep //SCS_CCR - fixed, restored by cstartup when exiting deep sleep
//SCS_SHPR_7to4 - fixed, restored by cstartup when exiting deep sleep //SCS_SHPR_7to4 - fixed, restored by cstartup when exiting deep sleep
//SCS_SHPR_11to8 - fixed, restored by cstartup when exiting deep sleep //SCS_SHPR_11to8 - fixed, restored by cstartup when exiting deep sleep
@ -320,7 +320,7 @@ deepSleepCore:
//up exactly which GPIO could have woken us up. //up exactly which GPIO could have woken us up.
//Reading the three IN registers is done separately to avoid warnings //Reading the three IN registers is done separately to avoid warnings
//about undefined order of volatile access. //about undefined order of volatile access.
int32u GPIO_IN_SAVED = GPIO_PAIN; uint32_t GPIO_IN_SAVED = GPIO_PAIN;
GPIO_IN_SAVED |= (GPIO_PBIN<<8); GPIO_IN_SAVED |= (GPIO_PBIN<<8);
GPIO_IN_SAVED |= (GPIO_PCIN<<16); GPIO_IN_SAVED |= (GPIO_PCIN<<16);
//reset the power up events by writing 1 to all bits. //reset the power up events by writing 1 to all bits.
@ -425,7 +425,7 @@ deepSleepCore:
//only propagate across deep sleep the interrupts that are both //only propagate across deep sleep the interrupts that are both
//enabled and possible wake sources //enabled and possible wake sources
{ {
int32u wakeSourceInterruptMask = 0; uint32_t wakeSourceInterruptMask = 0;
if(GPIO_PBWAKE&PB0) { if(GPIO_PBWAKE&PB0) {
wakeSourceInterruptMask |= INT_IRQA; wakeSourceInterruptMask |= INT_IRQA;
@ -513,7 +513,7 @@ deepSleepCore:
{ {
//Use a local copy of WAKE_SEL to avoid warnings from the compiler //Use a local copy of WAKE_SEL to avoid warnings from the compiler
//about order of volatile accesses //about order of volatile accesses
int32u wakeSel = WAKE_SEL; uint32_t wakeSel = WAKE_SEL;
//stall until a wake event or CSYSPWRUPREQ/ACK clears //stall until a wake event or CSYSPWRUPREQ/ACK clears
while( (CSYSPWRUPACK_STATUS) && (!(PWRUP_EVENT&wakeSel)) ) {} while( (CSYSPWRUPACK_STATUS) && (!(PWRUP_EVENT&wakeSel)) ) {}
//if there was a wake event, allow CSYSPWRUPACK and skip sleep //if there was a wake event, allow CSYSPWRUPACK and skip sleep
@ -630,14 +630,14 @@ deepSleepCore:
//Now that we're awake, normal interrupts are operational again //Now that we're awake, normal interrupts are operational again
//Take a snapshot of the new GPIO state and the EVENT register to //Take a snapshot of the new GPIO state and the EVENT register to
//record our wake event //record our wake event
int32u GPIO_IN_NEW = GPIO_PAIN; uint32_t GPIO_IN_NEW = GPIO_PAIN;
GPIO_IN_NEW |= (GPIO_PBIN<<8); GPIO_IN_NEW |= (GPIO_PBIN<<8);
GPIO_IN_NEW |= (GPIO_PCIN<<16); GPIO_IN_NEW |= (GPIO_PCIN<<16);
//Only operate on power up events that are also wake events. Power //Only operate on power up events that are also wake events. Power
//up events will always trigger like an interrupt flag, so we have //up events will always trigger like an interrupt flag, so we have
//to check them against events that are enabled for waking. (This is //to check them against events that are enabled for waking. (This is
//a two step process because we're accessing two volatile values.) //a two step process because we're accessing two volatile values.)
int32u powerUpEvents = PWRUP_EVENT; uint32_t powerUpEvents = PWRUP_EVENT;
powerUpEvents &= WAKE_SEL; powerUpEvents &= WAKE_SEL;
halInternalWakeEvent |= ((GPIO_IN_SAVED^GPIO_IN_NEW)&gpioWakeSel); halInternalWakeEvent |= ((GPIO_IN_SAVED^GPIO_IN_NEW)&gpioWakeSel);
//PWRUP_SC1 is PB2 which is bit 10 //PWRUP_SC1 is PB2 which is bit 10
@ -845,7 +845,7 @@ deepSleepCore:
} }
void halSleepWithOptions(SleepModes sleepMode, int32u gpioWakeBitMask) void halSleepWithOptions(SleepModes sleepMode, uint32_t gpioWakeBitMask)
{ {
//configure all GPIO wake sources //configure all GPIO wake sources
GPIO_PAWAKE = (gpioWakeBitMask>>0)&0xFF; GPIO_PAWAKE = (gpioWakeBitMask>>0)&0xFF;

View file

@ -35,7 +35,7 @@
__EXPORT__ _executeBarrierInstructions __EXPORT__ _executeBarrierInstructions
//------------------------------------------------------------------------------ //------------------------------------------------------------------------------
// int8u _readBasePri(void) // uint8_t _readBasePri(void)
// //
// Read and return the BASEPRI value. // Read and return the BASEPRI value.
// //
@ -50,7 +50,7 @@ _readBasePri:
__CFI__(EndBlock cfiBlock0) __CFI__(EndBlock cfiBlock0)
//------------------------------------------------------------------------------ //------------------------------------------------------------------------------
// void _writeBasePri(int8u priority) // void _writeBasePri(uint8_t priority)
// //
// Write BASEPRI with the passed value to obtain the proper preemptive priority // Write BASEPRI with the passed value to obtain the proper preemptive priority
// group masking. Note that the value passed must have been left shifted by 3 // group masking. Note that the value passed must have been left shifted by 3
@ -68,7 +68,7 @@ _writeBasePri:
__CFI__(EndBlock cfiBlock1) __CFI__(EndBlock cfiBlock1)
//------------------------------------------------------------------------------ //------------------------------------------------------------------------------
// int8u _disableBasePri(void) // uint8_t _disableBasePri(void)
// //
// Set BASEPRI to mask out interrupts but allow faults. It returns the value // Set BASEPRI to mask out interrupts but allow faults. It returns the value
// BASEPRI had when it was called. // BASEPRI had when it was called.

View file

@ -84,9 +84,9 @@ typedef struct LedResourceStruct {
/** Name of the LED as printed in the board */ /** Name of the LED as printed in the board */
char *name; char *name;
/** GPIO port associated with the LED */ /** GPIO port associated with the LED */
int8u gpioPort; uint8_t gpioPort;
/** GPIO pin associated with the LED */ /** GPIO pin associated with the LED */
int8u gpioPin; uint8_t gpioPin;
} LedResourceType; } LedResourceType;
typedef LedResourceType InfraRedLedResourceType; typedef LedResourceType InfraRedLedResourceType;
@ -98,9 +98,9 @@ typedef struct ButtonResourceStruct {
/** Name of the button as printed in the board */ /** Name of the button as printed in the board */
char *name; char *name;
/** GPIO port associated with the button */ /** GPIO port associated with the button */
int8u gpioPort; uint8_t gpioPort;
/** GPIO pin associated with the button */ /** GPIO pin associated with the button */
int8u gpioPin; uint8_t gpioPin;
} ButtonResourceType; } ButtonResourceType;
/** /**
@ -110,7 +110,7 @@ typedef struct MemsResourceStruct {
/** Name of the MEMS device */ /** Name of the MEMS device */
char *name; char *name;
/** Serial communication port associated with the MEMS */ /** Serial communication port associated with the MEMS */
int8u scPort; uint8_t scPort;
} MemsResourceType; } MemsResourceType;
/** /**
@ -120,9 +120,9 @@ typedef struct TempSensorResourceStruct {
/** Name of the temperature sensor device */ /** Name of the temperature sensor device */
char *name; char *name;
/** GPIO port associated with the sensor */ /** GPIO port associated with the sensor */
int8u gpioPort; uint8_t gpioPort;
/** GPIO pin associated with the sensor */ /** GPIO pin associated with the sensor */
int8u gpioPin; uint8_t gpioPin;
/** Flag to indicate whether the ADC range extension bug fix is implemented */ /** Flag to indicate whether the ADC range extension bug fix is implemented */
boolean adcFix; boolean adcFix;
} TempSensorResourceType; } TempSensorResourceType;
@ -167,11 +167,11 @@ typedef struct BoardIOStruct {
*/ */
typedef struct BoardResourcesStruct { typedef struct BoardResourcesStruct {
const char *name; const char *name;
const int32u flags; const uint32_t flags;
/** Number of buttons */ /** Number of buttons */
int8u buttons; uint8_t buttons;
/** Number of leds */ /** Number of leds */
int8u leds; uint8_t leds;
/** Board I/O description */ /** Board I/O description */
const BoardIOType *io; const BoardIOType *io;
/** Board infrared led description */ /** Board infrared led description */
@ -202,7 +202,7 @@ extern BoardResourcesType const *boardDescription;
/** Description buttons definition */ /** Description buttons definition */
#define BUTTON_Sn(n) (PORTx_PIN(boardDescription->io->buttons[n].gpioPort, boardDescription->io->buttons[n].gpioPin)) #define BUTTON_Sn(n) (PORTx_PIN(boardDescription->io->buttons[n].gpioPort, boardDescription->io->buttons[n].gpioPin))
#define BUTTON_Sn_WAKE_SOURCE(n) (1 << ((boardDescription->io->buttons[n].gpioPin) + (8 * (boardDescription->io->buttons[n].gpioPort >> 3)))) #define BUTTON_Sn_WAKE_SOURCE(n) (1 << ((boardDescription->io->buttons[n].gpioPin) + (8 * (boardDescription->io->buttons[n].gpioPort >> 3))))
#define BUTTON_INPUT_GPIO(port) *((volatile int32u *) (GPIO_PxIN_BASE + GPIO_Px_OFFSET * port)) #define BUTTON_INPUT_GPIO(port) *((volatile uint32_t *) (GPIO_PxIN_BASE + GPIO_Px_OFFSET * port))
#define DUMMY_BUTTON 0xff #define DUMMY_BUTTON 0xff
#define BUTTON_S1 (boardDescription->buttons>0 ? BUTTON_Sn(0): DUMMY_BUTTON) #define BUTTON_S1 (boardDescription->buttons>0 ? BUTTON_Sn(0): DUMMY_BUTTON)

View file

@ -139,8 +139,8 @@ void (* const g_pfnVectors[])(void) =
halDebugIsr, // 32 halDebugIsr, // 32
}; };
static void setStackPointer(int32u address) __attribute__((noinline)); static void setStackPointer(uint32_t address) __attribute__((noinline));
static void setStackPointer(int32u address) static void setStackPointer(uint32_t address)
{ {
// This code is needed to generate the instruction below // This code is needed to generate the instruction below
// that GNU ASM is refusing to add // that GNU ASM is refusing to add
@ -148,7 +148,7 @@ static void setStackPointer(int32u address)
asm(".short 0x4685"); asm(".short 0x4685");
} }
static const int16u blOffset[] = { static const uint16_t blOffset[] = {
0x0715 - 0x03ad - 0x68, 0x0715 - 0x03ad - 0x68,
0x0719 - 0x03ad - 0x6C 0x0719 - 0x03ad - 0x6C
}; };
@ -277,17 +277,17 @@ void Reset_Handler(void)
} }
//USART bootloader software activation check //USART bootloader software activation check
if ((*((int32u *)RAM_BOTTOM) == IAP_BOOTLOADER_APP_SWITCH_SIGNATURE) && (*((int8u *)(RAM_BOTTOM+4)) == IAP_BOOTLOADER_MODE_UART)){ if ((*((uint32_t *)RAM_BOTTOM) == IAP_BOOTLOADER_APP_SWITCH_SIGNATURE) && (*((uint8_t *)(RAM_BOTTOM+4)) == IAP_BOOTLOADER_MODE_UART)){
int8u cut = *(volatile int8u *) 0x08040798; uint8_t cut = *(volatile uint8_t *) 0x08040798;
int16u offset = 0; uint16_t offset = 0;
typedef void (*EntryPoint)(void); typedef void (*EntryPoint)(void);
offset = (halFixedAddressTable.baseTable.version == 3) ? blOffset[cut - 2] : 0; offset = (halFixedAddressTable.baseTable.version == 3) ? blOffset[cut - 2] : 0;
*((int32u *)RAM_BOTTOM) = 0; *((uint32_t *)RAM_BOTTOM) = 0;
if (offset) { if (offset) {
halInternalSwitchToXtal(); halInternalSwitchToXtal();
} }
EntryPoint entryPoint = (EntryPoint)(*(int32u *)(FIB_BOTTOM+4) - offset); EntryPoint entryPoint = (EntryPoint)(*(uint32_t *)(FIB_BOTTOM+4) - offset);
setStackPointer(*(int32u *)FIB_BOTTOM); setStackPointer(*(uint32_t *)FIB_BOTTOM);
entryPoint(); entryPoint();
} }

View file

@ -38,12 +38,12 @@ extern void halInternalSwitchToXtal(void);
__interwork int __low_level_init(void); __interwork int __low_level_init(void);
static void setStackPointer(int32u address) static void setStackPointer(uint32_t address)
{ {
asm("MOVS SP, r0"); asm("MOVS SP, r0");
} }
static const int16u blOffset[] = { static const uint16_t blOffset[] = {
0x0715 - 0x03ad - 0x68, 0x0715 - 0x03ad - 0x68,
0x0719 - 0x03ad - 0x6C 0x0719 - 0x03ad - 0x6C
}; };
@ -79,7 +79,7 @@ __interwork int __low_level_init(void)
////---- Always remap the vector table ----//// ////---- Always remap the vector table ----////
// We might be coming from a bootloader at the base of flash, or even in the // We might be coming from a bootloader at the base of flash, or even in the
// NULL_BTL case, the BAT/AAT will be at the beginning of the image // NULL_BTL case, the BAT/AAT will be at the beginning of the image
SCS_VTOR = (int32u)__vector_table; SCS_VTOR = (uint32_t)__vector_table;
////---- Always Configure Interrupt Priorities ----//// ////---- Always Configure Interrupt Priorities ----////
//The STM32W support 5 bits of priority configuration. //The STM32W support 5 bits of priority configuration.
@ -169,17 +169,17 @@ __interwork int __low_level_init(void)
} }
//USART bootloader software activation check //USART bootloader software activation check
if ((*((int32u *)RAM_BOTTOM) == IAP_BOOTLOADER_APP_SWITCH_SIGNATURE) && (*((int8u *)(RAM_BOTTOM+4)) == IAP_BOOTLOADER_MODE_UART)){ if ((*((uint32_t *)RAM_BOTTOM) == IAP_BOOTLOADER_APP_SWITCH_SIGNATURE) && (*((uint8_t *)(RAM_BOTTOM+4)) == IAP_BOOTLOADER_MODE_UART)){
int8u cut = *(volatile int8u *) 0x08040798; uint8_t cut = *(volatile uint8_t *) 0x08040798;
int16u offset = 0; uint16_t offset = 0;
typedef void (*EntryPoint)(void); typedef void (*EntryPoint)(void);
offset = (halFixedAddressTable.baseTable.version == 3) ? blOffset[cut - 2] : 0; offset = (halFixedAddressTable.baseTable.version == 3) ? blOffset[cut - 2] : 0;
*((int32u *)RAM_BOTTOM) = 0; *((uint32_t *)RAM_BOTTOM) = 0;
if (offset) { if (offset) {
halInternalSwitchToXtal(); halInternalSwitchToXtal();
} }
EntryPoint entryPoint = (EntryPoint)(*(int32u *)(FIB_BOTTOM+4) - offset); EntryPoint entryPoint = (EntryPoint)(*(uint32_t *)(FIB_BOTTOM+4) - offset);
setStackPointer(*(int32u *)FIB_BOTTOM); setStackPointer(*(uint32_t *)FIB_BOTTOM);
entryPoint(); entryPoint();
} }

View file

@ -46,12 +46,12 @@
#define FPEC_KEY2 0xCDEF89AB //magic key defined in hardware #define FPEC_KEY2 0xCDEF89AB //magic key defined in hardware
//Translation between page number and simee (word based) address //Translation between page number and simee (word based) address
#define SIMEE_ADDR_TO_PAGE(x) ((int8u)(((int16u)(x)) >> 9)) #define SIMEE_ADDR_TO_PAGE(x) ((uint8_t)(((uint16_t)(x)) >> 9))
#define PAGE_TO_SIMEE_ADDR(x) (((int16u)(x)) << 9) #define PAGE_TO_SIMEE_ADDR(x) (((uint16_t)(x)) << 9)
//Translation between page number and code addresses, used by bootloaders //Translation between page number and code addresses, used by bootloaders
#define PROG_ADDR_TO_PAGE(x) ((int8u)((((int32u)(x))&MFB_ADDR_MASK) >> 10)) #define PROG_ADDR_TO_PAGE(x) ((uint8_t)((((uint32_t)(x))&MFB_ADDR_MASK) >> 10))
#define PAGE_TO_PROG_ADDR(x) ((((int32u)(x)) << 10)|MFB_BOTTOM) #define PAGE_TO_PROG_ADDR(x) ((((uint32_t)(x)) << 10)|MFB_BOTTOM)
#endif //__STM32W108_MEMMAP_H__ #endif //__STM32W108_MEMMAP_H__

File diff suppressed because it is too large Load diff

View file

@ -1,5 +1,5 @@
/******************** (C) COPYRIGHT 2007 STMicroelectronics ******************** /******************** (C) COPYRIGHT 2007 STMicroelectronics ********************
* File Name : stm32w108_type.h * File Name : stm32w108-type.h
* Author : MCD Application Team * Author : MCD Application Team
* Version : V1.0 * Version : V1.0
* Date : 10/08/2009 * Date : 10/08/2009

View file

@ -32,14 +32,14 @@ static boolean sleepTimerInterruptOccurred = FALSE;
* a single clock tick occurs every 0.9769625 milliseconds, and a rollover * a single clock tick occurs every 0.9769625 milliseconds, and a rollover
* of the 16-bit timer occurs every 64 seconds. * of the 16-bit timer occurs every 64 seconds.
*/ */
int16u halCommonGetInt16uMillisecondTick(void) uint16_t halCommonGetInt16uMillisecondTick(void)
{ {
return (int16u)halCommonGetInt32uMillisecondTick(); return (uint16_t)halCommonGetInt32uMillisecondTick();
} }
int16u halCommonGetInt16uQuarterSecondTick(void) uint16_t halCommonGetInt16uQuarterSecondTick(void)
{ {
return (int16u)(halCommonGetInt32uMillisecondTick() >> 8); return (uint16_t)(halCommonGetInt32uMillisecondTick() >> 8);
} }
/** /**
@ -47,9 +47,9 @@ int16u halCommonGetInt16uQuarterSecondTick(void)
* a single clock tick occurs every 0.9769625 milliseconds, and a rollover * a single clock tick occurs every 0.9769625 milliseconds, and a rollover
* of the 32-bit timer occurs approximately every 48.5 days. * of the 32-bit timer occurs approximately every 48.5 days.
*/ */
int32u halCommonGetInt32uMillisecondTick(void) uint32_t halCommonGetInt32uMillisecondTick(void)
{ {
int32u time; uint32_t time;
time = SLEEPTMR_CNTH<<16; time = SLEEPTMR_CNTH<<16;
time |= SLEEPTMR_CNTL; time |= SLEEPTMR_CNTL;
@ -71,13 +71,13 @@ void halSleepTimerIsr(void)
#define CONVERT_TICKS_TO_QS(x) ((x) >> 8) #define CONVERT_TICKS_TO_QS(x) ((x) >> 8)
#define TIMER_MAX_QS 0x1000000 // = 4194304 seconds * 4 = 16777216 #define TIMER_MAX_QS 0x1000000 // = 4194304 seconds * 4 = 16777216
static StStatus internalSleepForQs(boolean useGpioWakeMask, static StStatus internalSleepForQs(boolean useGpioWakeMask,
int32u *duration, uint32_t *duration,
int32u gpioWakeBitMask) uint32_t gpioWakeBitMask)
{ {
StStatus status = ST_SUCCESS; StStatus status = ST_SUCCESS;
int32u sleepOverflowCount; uint32_t sleepOverflowCount;
int32u remainder; uint32_t remainder;
int32u startCount; uint32_t startCount;
//There is really no reason to bother with a duration of 0qs //There is really no reason to bother with a duration of 0qs
if(*duration==0) { if(*duration==0) {
@ -165,7 +165,7 @@ static StStatus internalSleepForQs(boolean useGpioWakeMask,
return status; return status;
} }
StStatus halSleepForQsWithOptions(int32u *duration, int32u gpioWakeBitMask) StStatus halSleepForQsWithOptions(uint32_t *duration, uint32_t gpioWakeBitMask)
{ {
return internalSleepForQs(TRUE, duration, gpioWakeBitMask); return internalSleepForQs(TRUE, duration, gpioWakeBitMask);
} }

View file

@ -1,4 +1,4 @@
/**@file temperature_sensor.c /**@file temperature-sensor.c
* @brief MB851 temperature sensor APIS * @brief MB851 temperature sensor APIS
* *
* *
@ -8,7 +8,7 @@
#include BOARD_HEADER #include BOARD_HEADER
#include "hal/hal.h" #include "hal/hal.h"
#include "hal/error.h" #include "hal/error.h"
#include "hal/micro/temperature_sensor.h" #include "hal/micro/temperature-sensor.h"
#include "hal/micro/adc.h" #include "hal/micro/adc.h"
void temperatureSensor_Init(void) void temperatureSensor_Init(void)
@ -29,10 +29,10 @@ void temperatureSensor_Init(void)
#endif /* ENABLE_ADC_EXTENDED_RANGE_BROKEN */ #endif /* ENABLE_ADC_EXTENDED_RANGE_BROKEN */
}/* end temperatureSensor_Init() */ }/* end temperatureSensor_Init() */
int32u temperatureSensor_GetValue(void) uint32_t temperatureSensor_GetValue(void)
{ {
static int16u ADCvalue; static uint16_t ADCvalue;
static int16s volts; static int16_t volts;
/* /*
NOTE: NOTE:
@ -47,6 +47,6 @@ int32u temperatureSensor_GetValue(void)
// 100 uVolts // 100 uVolts
volts = halConvertValueToVolts(ADCvalue); volts = halConvertValueToVolts(ADCvalue);
return ((18641 - (int32s)volts)*100)/1171; return ((18641 - (int32_t)volts)*100)/1171;
}/* end temperatureSensor_GetValue() */ }/* end temperatureSensor_GetValue() */

View file

@ -83,72 +83,72 @@
#ifndef __MFG_TYPES_DEFINED__ #ifndef __MFG_TYPES_DEFINED__
#define __MFG_TYPES_DEFINED__ #define __MFG_TYPES_DEFINED__
//--- Fixed Information Block --- //--- Fixed Information Block ---
typedef int8u tokTypeMfgChipData[24]; typedef uint8_t tokTypeMfgChipData[24];
typedef int8u tokTypeMfgPartData[6]; typedef uint8_t tokTypeMfgPartData[6];
typedef int8u tokTypeMfgTesterData[6]; typedef uint8_t tokTypeMfgTesterData[6];
typedef int8u tokTypeMfgStEui64[8]; typedef uint8_t tokTypeMfgStEui64[8];
typedef struct { typedef struct {
int16u iffilterL; uint16_t iffilterL;
int16u lna; uint16_t lna;
int16u ifamp; uint16_t ifamp;
int16u rxadcH; uint16_t rxadcH;
int16u prescalar; uint16_t prescalar;
int16u phdet; uint16_t phdet;
int16u vco; uint16_t vco;
int16u loopfilter; uint16_t loopfilter;
int16u pa; uint16_t pa;
int16u iqmixer; uint16_t iqmixer;
} tokTypeMfgAnalogueTrim; } tokTypeMfgAnalogueTrim;
typedef struct { typedef struct {
int16u iffilterH; uint16_t iffilterH;
int16u biasmaster; uint16_t biasmaster;
int16u moddac; uint16_t moddac;
int16u auxadc; uint16_t auxadc;
int16u caladc; uint16_t caladc;
} tokTypeMfgAnalogueTrimBoth; } tokTypeMfgAnalogueTrimBoth;
typedef struct { typedef struct {
int8u regTrim1V2; uint8_t regTrim1V2;
int8u regTrim1V8; uint8_t regTrim1V8;
} tokTypeMfgRegTrim; } tokTypeMfgRegTrim;
typedef int16u tokTypeMfgRegVoltage1V8; typedef uint16_t tokTypeMfgRegVoltage1V8;
typedef int16u tokTypeMfgAdcVrefVoltage; typedef uint16_t tokTypeMfgAdcVrefVoltage;
typedef int16u tokTypeMfgTempCal; typedef uint16_t tokTypeMfgTempCal;
typedef int16u tokTypeMfgFibVersion; typedef uint16_t tokTypeMfgFibVersion;
typedef int16u tokTypeMfgFibChecksum; typedef uint16_t tokTypeMfgFibChecksum;
typedef struct { typedef struct {
int16u ob2; uint16_t ob2;
int16u ob3; uint16_t ob3;
int16u ob0; uint16_t ob0;
int16u ob1; uint16_t ob1;
} tokTypeMfgFibObs; } tokTypeMfgFibObs;
//--- Customer Information Block --- //--- Customer Information Block ---
typedef struct { typedef struct {
int16u ob0; uint16_t ob0;
int16u ob1; uint16_t ob1;
int16u ob2; uint16_t ob2;
int16u ob3; uint16_t ob3;
int16u ob4; uint16_t ob4;
int16u ob5; uint16_t ob5;
int16u ob6; uint16_t ob6;
int16u ob7; uint16_t ob7;
} tokTypeMfgCibObs; } tokTypeMfgCibObs;
typedef int16u tokTypeMfgCustomVersion; typedef uint16_t tokTypeMfgCustomVersion;
typedef int8u tokTypeMfgCustomEui64[8]; typedef uint8_t tokTypeMfgCustomEui64[8];
typedef int8u tokTypeMfgString[16]; typedef uint8_t tokTypeMfgString[16];
typedef int8u tokTypeMfgBoardName[16]; typedef uint8_t tokTypeMfgBoardName[16];
typedef int16u tokTypeMfgManufId; typedef uint16_t tokTypeMfgManufId;
typedef int16u tokTypeMfgPhyConfig; typedef uint16_t tokTypeMfgPhyConfig;
typedef int8u tokTypeMfgBootloadAesKey[16]; typedef uint8_t tokTypeMfgBootloadAesKey[16];
typedef int8u tokTypeMfgEui64[8]; typedef uint8_t tokTypeMfgEui64[8];
typedef int8u tokTypeMfgEzspStorage[8]; typedef uint8_t tokTypeMfgEzspStorage[8];
typedef int16u tokTypeMfgAshConfig; typedef uint16_t tokTypeMfgAshConfig;
typedef struct { typedef struct {
int8u certificate[48]; uint8_t certificate[48];
int8u caPublicKey[22]; uint8_t caPublicKey[22];
int8u privateKey[21]; uint8_t privateKey[21];
// The bottom flag bit is 1 for uninitialized, 0 for initialized. // The bottom flag bit is 1 for uninitialized, 0 for initialized.
// The other flag bits should be set to 0 at initialization. // The other flag bits should be set to 0 at initialization.
int8u flags; uint8_t flags;
} tokTypeMfgCbkeData; } tokTypeMfgCbkeData;
typedef struct { typedef struct {
// The bottom flag bit is 1 for uninitialized, 0 for initialized. // The bottom flag bit is 1 for uninitialized, 0 for initialized.
@ -158,11 +158,11 @@ typedef struct {
// Special flags support. Due to a bug in the way some customers // Special flags support. Due to a bug in the way some customers
// had programmed the flags field, we will also examine the upper // had programmed the flags field, we will also examine the upper
// bits 9 and 10 for the size field. Those bits are also reserved. // bits 9 and 10 for the size field. Those bits are also reserved.
int16u flags; uint16_t flags;
int8u value[16]; uint8_t value[16];
int16u crc; uint16_t crc;
} tokTypeMfgInstallationCode; } tokTypeMfgInstallationCode;
typedef int16u tokTypeMfgOsc24mBiasTrim; typedef uint16_t tokTypeMfgOsc24mBiasTrim;
#endif //__MFG_TYPES_DEFINED__ #endif //__MFG_TYPES_DEFINED__

View file

@ -28,18 +28,18 @@ int putchar (int c)
#endif #endif
#define RECEIVE_QUEUE_SIZE (128) #define RECEIVE_QUEUE_SIZE (128)
int8u rxQ[RECEIVE_QUEUE_SIZE]; uint8_t rxQ[RECEIVE_QUEUE_SIZE];
int16u rxHead; uint16_t rxHead;
int16u rxTail; uint16_t rxTail;
int16u rxUsed; uint16_t rxUsed;
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// Initialization // Initialization
void uartInit(int32u baudrate, int8u databits, SerialParity parity, int8u stopbits) void uartInit(uint32_t baudrate, uint8_t databits, SerialParity parity, uint8_t stopbits)
{ {
int32u tempcfg; uint32_t tempcfg;
int32u tmp; uint32_t tmp;
assert( (baudrate >= 300) && (baudrate <=921600) ); assert( (baudrate >= 300) && (baudrate <=921600) );
@ -171,10 +171,10 @@ static void halInternalUart1RxIsr(void)
// data, processing any errors noted // data, processing any errors noted
// along the way. // along the way.
while ( SC1_UARTSTAT & SC_UARTRXVAL ) { while ( SC1_UARTSTAT & SC_UARTRXVAL ) {
int8u errors = SC1_UARTSTAT & (SC_UARTFRMERR | uint8_t errors = SC1_UARTSTAT & (SC_UARTFRMERR |
SC_UARTRXOVF | SC_UARTRXOVF |
SC_UARTPARERR ); SC_UARTPARERR );
int8u incoming = (int8u) SC1_DATA; uint8_t incoming = (uint8_t) SC1_DATA;
if ( (errors == 0) && (rxUsed < (RECEIVE_QUEUE_SIZE-1)) ) { if ( (errors == 0) && (rxUsed < (RECEIVE_QUEUE_SIZE-1)) ) {
rxQ[rxHead] = incoming; rxQ[rxHead] = incoming;
@ -194,7 +194,7 @@ static void halInternalUart1RxIsr(void)
void halSc1Isr(void) void halSc1Isr(void)
{ {
int32u interrupt; uint32_t interrupt;
//this read and mask is performed in two steps otherwise the compiler //this read and mask is performed in two steps otherwise the compiler
//will complain about undefined order of volatile access //will complain about undefined order of volatile access
@ -233,7 +233,7 @@ void halSc1Isr(void)
* Output : dataByte: buffer containing the read byte if any * Output : dataByte: buffer containing the read byte if any
* Return : TRUE if there is a data, FALSE otherwise * Return : TRUE if there is a data, FALSE otherwise
*******************************************************************************/ *******************************************************************************/
boolean __io_getcharNonBlocking(int8u *data) boolean __io_getcharNonBlocking(uint8_t *data)
{ {
if (__read(_LLIO_STDIN,data,1)) if (__read(_LLIO_STDIN,data,1))
return TRUE; return TRUE;

View file

@ -36,7 +36,7 @@ typedef enum
* @return stopbits The number of stop bits used for communication. * @return stopbits The number of stop bits used for communication.
* Valid values are 1 or 2 * Valid values are 1 or 2
*/ */
void uartInit(int32u baudrate, int8u databits, SerialParity parity, int8u stopbits); void uartInit(uint32_t baudrate, uint8_t databits, SerialParity parity, uint8_t stopbits);
#ifdef __ICCARM__ #ifdef __ICCARM__
/** /**
@ -63,7 +63,7 @@ size_t fflush(int handle);
/** /**
* @brief Read the input byte if any. * @brief Read the input byte if any.
*/ */
boolean __io_getcharNonBlocking(int8u *data); boolean __io_getcharNonBlocking(uint8_t *data);
void __io_putchar( char c ); void __io_putchar( char c );
int __io_getchar(void); int __io_getchar(void);
void __io_flush( void ); void __io_flush( void );

View file

@ -1,11 +1,5 @@
/** @file hal/micro/generic/compiler/platform-common.h /** \addtogroup platform_common
* See @ref platform_common for detailed documentation. * \brief Compiler and Platform specific definitions and typedefs common to
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
/** @addtogroup platform_common
* @brief Compiler and Platform specific definitions and typedefs common to
* all platforms. * all platforms.
* *
* platform-common.h provides PLATFORM_HEADER defaults and common definitions. * platform-common.h provides PLATFORM_HEADER defaults and common definitions.
@ -15,6 +9,13 @@
* See platform-common.h for source code. * See platform-common.h for source code.
*@{ *@{
*/ */
/** \file hal/micro/generic/compiler/platform-common.h
* See \ref platform_common for detailed documentation.
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
#ifndef PLATCOMMONOKTOINCLUDE #ifndef PLATCOMMONOKTOINCLUDE
// This header should only be included by a PLATFORM_HEADER // This header should only be included by a PLATFORM_HEADER
@ -36,23 +37,23 @@
*/ */
//@{ //@{
/** /**
* @brief Standard program memory delcaration. * \brief Standard program memory delcaration.
*/ */
#define PGM const #define PGM const
/** /**
* @brief Char pointer to program memory declaration. * \brief Char pointer to program memory declaration.
*/ */
#define PGM_P const char * #define PGM_P const char *
/** /**
* @brief Unsigned char pointer to program memory declaration. * \brief Unsigned char pointer to program memory declaration.
*/ */
#define PGM_PU const unsigned char * #define PGM_PU const unsigned char *
/** /**
* @brief Sometimes a second PGM is needed in a declaration. Having two * \brief Sometimes a second PGM is needed in a declaration. Having two
* 'const' declarations generates a warning so we have a second PGM that turns * 'const' declarations generates a warning so we have a second PGM that turns
* into nothing under gcc. * into nothing under gcc.
*/ */
@ -72,32 +73,32 @@
*/ */
//@{ //@{
/** /**
* @brief Provide a portable name for the int32u by int16u division * \brief Provide a portable name for the uint32_t by uint16_t division
* library function (which can perform the division with only a single * library function (which can perform the division with only a single
* assembly instruction on some platforms) * assembly instruction on some platforms)
*/ */
#define halCommonUDiv32By16(x, y) ((int16u) (((int32u) (x)) / ((int16u) (y)))) #define halCommonUDiv32By16(x, y) ((uint16_t) (((uint32_t) (x)) / ((uint16_t) (y))))
/** /**
* @brief Provide a portable name for the int32s by int16s division * \brief Provide a portable name for the int32_t by int16_t division
* library function (which can perform the division with only a single * library function (which can perform the division with only a single
* assembly instruction on some platforms) * assembly instruction on some platforms)
*/ */
#define halCommonSDiv32By16(x, y) ((int16s) (((int32s) (x)) / ((int16s) (y)))) #define halCommonSDiv32By16(x, y) ((int16_t) (((int32_t) (x)) / ((int16_t) (y))))
/** /**
* @brief Provide a portable name for the int32u by int16u modulo * \brief Provide a portable name for the uint32_t by uint16_t modulo
* library function (which can perform the division with only a single * library function (which can perform the division with only a single
* assembly instruction on some platforms) * assembly instruction on some platforms)
*/ */
#define halCommonUMod32By16(x, y) ((int16u) (((int32u) (x)) % ((int16u) (y)))) #define halCommonUMod32By16(x, y) ((uint16_t) (((uint32_t) (x)) % ((uint16_t) (y))))
/** /**
* @brief Provide a portable name for the int32s by int16s modulo * \brief Provide a portable name for the int32_t by int16_t modulo
* library function (which can perform the division with only a single * library function (which can perform the division with only a single
* assembly instruction on some platforms) * assembly instruction on some platforms)
*/ */
#define halCommonSMod32By16(x, y) ((int16s) (((int32s) (x)) % ((int16s) (y)))) #define halCommonSMod32By16(x, y) ((int16_t) (((int32_t) (x)) % ((int16_t) (y))))
//@} \\END DIVIDE and MODULUS OPERATIONS //@} \\END DIVIDE and MODULUS OPERATIONS
#endif //_HAL_USE_COMMON_DIVMOD_ #endif //_HAL_USE_COMMON_DIVMOD_
@ -118,25 +119,25 @@
//@{ //@{
/** /**
* @brief Refer to the C stdlib memcpy(). * \brief Refer to the C stdlib memcpy().
*/ */
void halCommonMemCopy(void *dest, const void *src, int8u bytes); void halCommonMemCopy(void *dest, const void *src, uint8_t bytes);
/** /**
* @brief Refer to the C stdlib memset(). * \brief Refer to the C stdlib memset().
*/ */
void halCommonMemSet(void *dest, int8u val, int16u bytes); void halCommonMemSet(void *dest, uint8_t val, uint16_t bytes);
/** /**
* @brief Refer to the C stdlib memcmp(). * \brief Refer to the C stdlib memcmp().
*/ */
int8s halCommonMemCompare(const void *source0, const void *source1, int8u bytes); int8_t halCommonMemCompare(const void *source0, const void *source1, uint8_t bytes);
/** /**
* @brief Friendly convenience macro pointing to the full HAL function. * \brief Friendly convenience macro pointing to the full HAL function.
*/ */
#define MEMSET(d,v,l) halCommonMemSet(d,v,l) #define MEMSET(d,v,l) halCommonMemSet(d,v,l)
#define MEMCOPY(d,s,l) halCommonMemCopy(d,s,l) #define MEMCOPY(d,s,l) halCommonMemCopy(d,s,l)
@ -165,18 +166,18 @@
*/ */
/** /**
* @brief An alias for one, used for clarity. * \brief An alias for one, used for clarity.
*/ */
#define TRUE 1 #define TRUE 1
/** /**
* @brief An alias for zero, used for clarity. * \brief An alias for zero, used for clarity.
*/ */
#define FALSE 0 #define FALSE 0
#ifndef NULL #ifndef NULL
/** /**
* @brief The null pointer. * \brief The null pointer.
*/ */
#define NULL ((void *)0) #define NULL ((void *)0)
#endif #endif
@ -190,50 +191,50 @@
//@{ //@{
/** /**
* @brief Useful to reference a single bit of a byte. * \brief Useful to reference a single bit of a byte.
*/ */
#define BIT(x) (1U << (x)) // Unsigned avoids compiler warnings re BIT(15) #define BIT(x) (1U << (x)) // Unsigned avoids compiler warnings re BIT(15)
/** /**
* @brief Useful to reference a single bit of an int32u type. * \brief Useful to reference a single bit of an uint32_t type.
*/ */
#define BIT32(x) (((int32u) 1) << (x)) #define BIT32(x) (((uint32_t) 1) << (x))
/** /**
* @brief Sets \c bit in the \c reg register or byte. * \brief Sets \c bit in the \c reg register or byte.
* @note Assuming \c reg is an IO register, some platforms * @note Assuming \c reg is an IO register, some platforms
* can implement this in a single atomic operation. * can implement this in a single atomic operation.
*/ */
#define SETBIT(reg, bit) reg |= BIT(bit) #define SETBIT(reg, bit) reg |= BIT(bit)
/** /**
* @brief Sets the bits in the \c reg register or the byte * \brief Sets the bits in the \c reg register or the byte
* as specified in the bitmask \c bits. * as specified in the bitmask \c bits.
* @note This is never a single atomic operation. * @note This is never a single atomic operation.
*/ */
#define SETBITS(reg, bits) reg |= (bits) #define SETBITS(reg, bits) reg |= (bits)
/** /**
* @brief Clears a bit in the \c reg register or byte. * \brief Clears a bit in the \c reg register or byte.
* @note Assuming \c reg is an IO register, some platforms (such as the AVR) * @note Assuming \c reg is an IO register, some platforms (such as the AVR)
* can implement this in a single atomic operation. * can implement this in a single atomic operation.
*/ */
#define CLEARBIT(reg, bit) reg &= ~(BIT(bit)) #define CLEARBIT(reg, bit) reg &= ~(BIT(bit))
/** /**
* @brief Clears the bits in the \c reg register or byte * \brief Clears the bits in the \c reg register or byte
* as specified in the bitmask \c bits. * as specified in the bitmask \c bits.
* @note This is never a single atomic operation. * @note This is never a single atomic operation.
*/ */
#define CLEARBITS(reg, bits) reg &= ~(bits) #define CLEARBITS(reg, bits) reg &= ~(bits)
/** /**
* @brief Returns the value of \c bit within the register or byte \c reg. * \brief Returns the value of \c bit within the register or byte \c reg.
*/ */
#define READBIT(reg, bit) (reg & (BIT(bit))) #define READBIT(reg, bit) (reg & (BIT(bit)))
/** /**
* @brief Returns the value of the bitmask \c bits within * \brief Returns the value of the bitmask \c bits within
* the register or byte \c reg. * the register or byte \c reg.
*/ */
#define READBITS(reg, bits) (reg & (bits)) #define READBITS(reg, bits) (reg & (bits))
@ -248,43 +249,43 @@
//@{ //@{
/** /**
* @brief Returns the low byte of the 16-bit value \c n as an \c int8u. * \brief Returns the low byte of the 16-bit value \c n as an \c uint8_t.
*/ */
#define LOW_BYTE(n) ((int8u)((n) & 0xFF)) #define LOW_BYTE(n) ((uint8_t)((n) & 0xFF))
/** /**
* @brief Returns the high byte of the 16-bit value \c n as an \c int8u. * \brief Returns the high byte of the 16-bit value \c n as an \c uint8_t.
*/ */
#define HIGH_BYTE(n) ((int8u)(LOW_BYTE((n) >> 8))) #define HIGH_BYTE(n) ((uint8_t)(LOW_BYTE((n) >> 8)))
/** /**
* @brief Returns the value built from the two \c int8u * \brief Returns the value built from the two \c uint8_t
* values \c high and \c low. * values \c high and \c low.
*/ */
#define HIGH_LOW_TO_INT(high, low) ( \ #define HIGH_LOW_TO_INT(high, low) ( \
(( (int16u) (high) ) << 8) + \ (( (uint16_t) (high) ) << 8) + \
( (int16u) ( (low) & 0xFF)) \ ( (uint16_t) ( (low) & 0xFF)) \
) )
/** /**
* @brief Returns the low byte of the 32-bit value \c n as an \c int8u. * \brief Returns the low byte of the 32-bit value \c n as an \c uint8_t.
*/ */
#define BYTE_0(n) ((int8u)((n) & 0xFF)) #define BYTE_0(n) ((uint8_t)((n) & 0xFF))
/** /**
* @brief Returns the second byte of the 32-bit value \c n as an \c int8u. * \brief Returns the second byte of the 32-bit value \c n as an \c uint8_t.
*/ */
#define BYTE_1(n) ((int8u)(BYTE_0((n) >> 8))) #define BYTE_1(n) ((uint8_t)(BYTE_0((n) >> 8)))
/** /**
* @brief Returns the third byte of the 32-bit value \c n as an \c int8u. * \brief Returns the third byte of the 32-bit value \c n as an \c uint8_t.
*/ */
#define BYTE_2(n) ((int8u)(BYTE_0((n) >> 16))) #define BYTE_2(n) ((uint8_t)(BYTE_0((n) >> 16)))
/** /**
* @brief Returns the high byte of the 32-bit value \c n as an \c int8u. * \brief Returns the high byte of the 32-bit value \c n as an \c uint8_t.
*/ */
#define BYTE_3(n) ((int8u)(BYTE_0((n) >> 24))) #define BYTE_3(n) ((uint8_t)(BYTE_0((n) >> 24)))
//@} \\END Byte manipulation macros //@} \\END Byte manipulation macros
@ -296,28 +297,28 @@
//@{ //@{
/** /**
* @brief Returns the elapsed time between two 8 bit values. * \brief Returns the elapsed time between two 8 bit values.
* Result may not be valid if the time samples differ by more than 127 * Result may not be valid if the time samples differ by more than 127
*/ */
#define elapsedTimeInt8u(oldTime, newTime) \ #define elapsedTimeInt8u(oldTime, newTime) \
((int8u) ((int8u)(newTime) - (int8u)(oldTime))) ((uint8_t) ((uint8_t)(newTime) - (uint8_t)(oldTime)))
/** /**
* @brief Returns the elapsed time between two 16 bit values. * \brief Returns the elapsed time between two 16 bit values.
* Result may not be valid if the time samples differ by more than 32767 * Result may not be valid if the time samples differ by more than 32767
*/ */
#define elapsedTimeInt16u(oldTime, newTime) \ #define elapsedTimeInt16u(oldTime, newTime) \
((int16u) ((int16u)(newTime) - (int16u)(oldTime))) ((uint16_t) ((uint16_t)(newTime) - (uint16_t)(oldTime)))
/** /**
* @brief Returns the elapsed time between two 32 bit values. * \brief Returns the elapsed time between two 32 bit values.
* Result may not be valid if the time samples differ by more than 2147483647 * Result may not be valid if the time samples differ by more than 2147483647
*/ */
#define elapsedTimeInt32u(oldTime, newTime) \ #define elapsedTimeInt32u(oldTime, newTime) \
((int32u) ((int32u)(newTime) - (int32u)(oldTime))) ((uint32_t) ((uint32_t)(newTime) - (uint32_t)(oldTime)))
/** /**
* @brief Returns TRUE if t1 is greater than t2. Can only account for 1 wrap * \brief Returns TRUE if t1 is greater than t2. Can only account for 1 wrap
* around of the variable before it is wrong. * around of the variable before it is wrong.
*/ */
#define MAX_INT8U_VALUE 0xFF #define MAX_INT8U_VALUE 0xFF
@ -325,7 +326,7 @@
(elapsedTimeInt8u(t2, t1) <= ((MAX_INT8U_VALUE + 1) / 2)) (elapsedTimeInt8u(t2, t1) <= ((MAX_INT8U_VALUE + 1) / 2))
/** /**
* @brief Returns TRUE if t1 is greater than t2. Can only account for 1 wrap * \brief Returns TRUE if t1 is greater than t2. Can only account for 1 wrap
* around of the variable before it is wrong. * around of the variable before it is wrong.
*/ */
#define MAX_INT16U_VALUE 0xFFFF #define MAX_INT16U_VALUE 0xFFFF
@ -333,7 +334,7 @@
(elapsedTimeInt16u(t2, t1) <= ((MAX_INT16U_VALUE + 1) / 2)) (elapsedTimeInt16u(t2, t1) <= ((MAX_INT16U_VALUE + 1) / 2))
/** /**
* @brief Returns TRUE if t1 is greater than t2. Can only account for 1 wrap * \brief Returns TRUE if t1 is greater than t2. Can only account for 1 wrap
* around of the variable before it is wrong. * around of the variable before it is wrong.
*/ */
#define MAX_INT32U_VALUE 0xFFFFFFFF #define MAX_INT32U_VALUE 0xFFFFFFFF

View file

@ -22,7 +22,7 @@ void halInitLed(void);
/** @brief Ensures that the definitions from the BOARD_HEADER /** @brief Ensures that the definitions from the BOARD_HEADER
* are always used as parameters to the LED functions. * are always used as parameters to the LED functions.
*/ */
typedef int8u HalBoardLed; typedef uint8_t HalBoardLed;
// Note: Even though many compilers will use 16 bits for an enum instead of 8, // Note: Even though many compilers will use 16 bits for an enum instead of 8,
// we choose to use an enum here. The possible compiler inefficiency does not // we choose to use an enum here. The possible compiler inefficiency does not
// affect stack-based parameters and local variables, which is the // affect stack-based parameters and local variables, which is the

View file

@ -1,4 +1,4 @@
/** @file hal/micro/mems_regs.h /** @file hal/micro/mems-regs.h
* @brief stm32w108 mems registers * @brief stm32w108 mems registers
* *
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. --> * <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
@ -112,14 +112,14 @@
//-reg_addr is the address of the register to be written--// //-reg_addr is the address of the register to be written--//
//-pBuffer is the storage destination for the read data---// //-pBuffer is the storage destination for the read data---//
//-NoOfBytes is the amount of data to read----------------// //-NoOfBytes is the amount of data to read----------------//
int8u i2c_read_reg (int8u slave_addr, int8u reg_addr, int8u *pBuffer, int8u NoOfBytes); uint8_t i2c_read_reg (uint8_t slave_addr, uint8_t reg_addr, uint8_t *pBuffer, uint8_t NoOfBytes);
//*********************i2c_write_reg**********************// //*********************i2c_write_reg**********************//
//----------Writes a register on the I2C target-----------// //----------Writes a register on the I2C target-----------//
//------slave addr is the is the I2C target device--------// //------slave addr is the is the I2C target device--------//
//-reg_addr is the address of the register to be written--// //-reg_addr is the address of the register to be written--//
//-reg_value is the value of the register to be written---// //-reg_value is the value of the register to be written---//
int8u i2c_write_reg (int8u slave_addr, int8u reg_addr, int8u reg_value); uint8_t i2c_write_reg (uint8_t slave_addr, uint8_t reg_addr, uint8_t reg_value);
#endif /* _MEMS_REGS_H_ */ #endif /* _MEMS_REGS_H_ */

View file

@ -8,29 +8,29 @@
#ifndef _MEMS_H_ #ifndef _MEMS_H_
#define _MEMS_H_ #define _MEMS_H_
#include "hal/micro/mems_regs.h" #include "hal/micro/mems-regs.h"
/** @brief Mems data type: three acceleration values each related to a specific direction /** @brief Mems data type: three acceleration values each related to a specific direction
Watch out: only lower data values (e.g. those terminated by the _l) are Watch out: only lower data values (e.g. those terminated by the _l) are
currently used by the device */ currently used by the device */
typedef struct { typedef struct {
int8u outx_l; uint8_t outx_l;
int8u outx_h; uint8_t outx_h;
int8u outy_l; uint8_t outy_l;
int8u outy_h; uint8_t outy_h;
int8u outz_l; uint8_t outz_l;
int8u outz_h; uint8_t outz_h;
} t_mems_data; } t_mems_data;
/** @brief Mems Initialization function /** @brief Mems Initialization function
*/ */
int8u mems_Init(void); uint8_t mems_Init(void);
/** @brief Get mems acceleration values /** @brief Get mems acceleration values
*/ */
int8u mems_GetValue(t_mems_data *mems_data); uint8_t mems_GetValue(t_mems_data *mems_data);
#endif /* _MEMS_H_ */ #endif /* _MEMS_H_ */

View file

@ -21,7 +21,7 @@
//This is necessary here because halSleepForQsWithOptions returns an //This is necessary here because halSleepForQsWithOptions returns an
//StStatus and not adding this typedef to this file breaks a //StStatus and not adding this typedef to this file breaks a
//whole lot of builds. //whole lot of builds.
typedef int8u StStatus; typedef uint8_t StStatus;
#endif //__STSTATUS_TYPE__ #endif //__STSTATUS_TYPE__
#endif // DOXYGEN_SHOULD_SKIP_THIS #endif // DOXYGEN_SHOULD_SKIP_THIS
@ -58,7 +58,7 @@ void halInternalEnableWatchDog(void);
* *
* @param magicKey A value (::MICRO_DISABLE_WATCH_DOG_KEY) that enables the function. * @param magicKey A value (::MICRO_DISABLE_WATCH_DOG_KEY) that enables the function.
*/ */
void halInternalDisableWatchDog(int8u magicKey); void halInternalDisableWatchDog(uint8_t magicKey);
/** @brief Determines whether the watchdog has been enabled or disabled. /** @brief Determines whether the watchdog has been enabled or disabled.
* *
@ -90,7 +90,7 @@ boolean halInternalWatchDogEnabled( void );
*/ */
enum SleepModes enum SleepModes
#else #else
typedef int8u SleepModes; typedef uint8_t SleepModes;
enum enum
#endif #endif
{ {
@ -116,7 +116,7 @@ enum
* @param us The specified time, in microseconds. * @param us The specified time, in microseconds.
Values should be between 1 and 65535 microseconds. Values should be between 1 and 65535 microseconds.
*/ */
void halCommonDelayMicroseconds(int16u us); void halCommonDelayMicroseconds(uint16_t us);
/** @brief Request the appplication to enter in bootloader mode /** @brief Request the appplication to enter in bootloader mode
* *
@ -132,7 +132,7 @@ void halCommonDelayMicroseconds(int16u us);
* default panID (only vaild for RF mode). * default panID (only vaild for RF mode).
* @return An error code or it will never return. * @return An error code or it will never return.
*/ */
StStatus halBootloaderStart(int8u mode, int8u channel, int16u panId); StStatus halBootloaderStart(uint8_t mode, uint8_t channel, uint16_t panId);
#ifdef CORTEXM3_STM32F103 #ifdef CORTEXM3_STM32F103
#include "micro/cortexm3/stm32f103ret/micro-specific.h" #include "micro/cortexm3/stm32f103ret/micro-specific.h"

View file

@ -38,7 +38,7 @@
* @return Time to update the async registers after RTC is started (units of 100 * @return Time to update the async registers after RTC is started (units of 100
* microseconds). * microseconds).
*/ */
int16u halInternalStartSystemTimer(void); uint16_t halInternalStartSystemTimer(void);
/** /**
@ -48,7 +48,7 @@ int16u halInternalStartSystemTimer(void);
* @return The least significant 16 bits of the current system time, in system * @return The least significant 16 bits of the current system time, in system
* ticks. * ticks.
*/ */
int16u halCommonGetInt16uMillisecondTick(void); uint16_t halCommonGetInt16uMillisecondTick(void);
/** /**
* @brief Returns the current system time in system ticks, as a 32-bit * @brief Returns the current system time in system ticks, as a 32-bit
@ -59,7 +59,7 @@ int16u halCommonGetInt16uMillisecondTick(void);
* @return The least significant 32 bits of the current system time, in * @return The least significant 32 bits of the current system time, in
* system ticks. * system ticks.
*/ */
int32u halCommonGetInt32uMillisecondTick(void); uint32_t halCommonGetInt32uMillisecondTick(void);
/** /**
* @brief Returns the current system time in quarter second ticks, as a * @brief Returns the current system time in quarter second ticks, as a
@ -70,7 +70,7 @@ int32u halCommonGetInt32uMillisecondTick(void);
* @return The least significant 16 bits of the current system time, in system * @return The least significant 16 bits of the current system time, in system
* ticks multiplied by 256. * ticks multiplied by 256.
*/ */
int16u halCommonGetInt16uQuarterSecondTick(void); uint16_t halCommonGetInt16uQuarterSecondTick(void);
#endif //__SYSTEM_TIMER_H__ #endif //__SYSTEM_TIMER_H__

View file

@ -1,4 +1,4 @@
/** @file temperature_sensor.h /** @file temperature-sensor.h
* @brief Header for temperature sensor driver * @brief Header for temperature sensor driver
* *
* *
@ -21,7 +21,7 @@ void temperatureSensor_Init(void);
/** @brief Get temperature sensor value /** @brief Get temperature sensor value
*/ */
int32u temperatureSensor_GetValue(void); uint32_t temperatureSensor_GetValue(void);
#endif /* _TEMP_SENSOR_H_ */ #endif /* _TEMP_SENSOR_H_ */

View file

@ -18,10 +18,10 @@
#ifdef DEFINETYPES #ifdef DEFINETYPES
typedef struct { typedef struct {
int8u vcoAtLna; // the VCO tune value at the time LNA value was calculated. uint8_t vcoAtLna; // the VCO tune value at the time LNA value was calculated.
int8u modDac; // msb : cal needed , bit 0-5 : value uint8_t modDac; // msb : cal needed , bit 0-5 : value
int8u filter; // msb : cal needed , bit 0-4 : value uint8_t filter; // msb : cal needed , bit 0-4 : value
int8u lna; // msb : cal needed , bit 0-5 : value uint8_t lna; // msb : cal needed , bit 0-5 : value
} tokTypeStackCalData; } tokTypeStackCalData;
#endif #endif

View file

@ -1,3 +1,9 @@
/**
* \addtogroup mb851-platform
*
* @{
*/
/* /*
* Copyright (c) 2010, STMicroelectronics. * Copyright (c) 2010, STMicroelectronics.
* All rights reserved. * All rights reserved.
@ -27,17 +33,14 @@
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
* *
* This file is part of the Contiki OS
*
*/ */
/*---------------------------------------------------------------------------*/
/** /**
* \file * \file
* Leds. * Leds.
* \author * \author
* Salvatore Pitrulli <salvopitru@users.sourceforge.net> * Salvatore Pitrulli <salvopitru@users.sourceforge.net>
*/ */
/*---------------------------------------------------------------------------*/
#include PLATFORM_HEADER #include PLATFORM_HEADER
#include BOARD_HEADER #include BOARD_HEADER
@ -46,32 +49,30 @@
#include "hal/micro/micro-common.h" #include "hal/micro/micro-common.h"
#include "hal/micro/cortexm3/micro-common.h" #include "hal/micro/cortexm3/micro-common.h"
#define LEDS_PORT *((volatile int32u *)(GPIO_PxOUT_BASE+(GPIO_Px_OFFSET*(LEDS_CONF_PORT/8)))) #define LEDS_PORT *((volatile uint32_t *)(GPIO_PxOUT_BASE+(GPIO_Px_OFFSET*(LEDS_CONF_PORT/8))))
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
void void
leds_arch_init(void) leds_arch_init(void)
{ {
halGpioConfig(PORTx_PIN(LEDS_CONF_PORT,LEDS_CONF_RED_PIN),GPIOCFG_OUT); halGpioConfig(PORTx_PIN(LEDS_CONF_PORT, LEDS_CONF_RED_PIN), GPIOCFG_OUT);
halGpioConfig(PORTx_PIN(LEDS_CONF_PORT,LEDS_CONF_GREEN_PIN),GPIOCFG_OUT); halGpioConfig(PORTx_PIN(LEDS_CONF_PORT, LEDS_CONF_GREEN_PIN), GPIOCFG_OUT);
LEDS_PORT |= (LEDS_CONF_RED | LEDS_CONF_GREEN); LEDS_PORT |= (LEDS_CONF_RED | LEDS_CONF_GREEN);
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
unsigned char unsigned char
leds_arch_get(void) leds_arch_get(void)
{ {
return ((LEDS_PORT & LEDS_CONF_RED) ? 0 : LEDS_RED) return ((LEDS_PORT & LEDS_CONF_RED) ? 0 : LEDS_RED) |
| ((LEDS_PORT & LEDS_CONF_GREEN) ? 0 : LEDS_GREEN); ((LEDS_PORT & LEDS_CONF_GREEN) ? 0 : LEDS_GREEN);
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
void void
leds_arch_set(unsigned char leds) leds_arch_set(unsigned char leds)
{ {
LEDS_PORT = (LEDS_PORT & ~(LEDS_CONF_RED | LEDS_CONF_GREEN)) |
LEDS_PORT = (LEDS_PORT & ~(LEDS_CONF_RED|LEDS_CONF_GREEN)) ((leds & LEDS_RED) ? 0 : LEDS_CONF_RED) |
| ((leds & LEDS_RED) ? 0 : LEDS_CONF_RED) ((leds & LEDS_GREEN) ? 0 : LEDS_CONF_GREEN);
| ((leds & LEDS_GREEN) ? 0 : LEDS_CONF_GREEN);
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
/** @} */

View file

@ -1,5 +1,42 @@
/**
* \addtogroup mb851-platform
*
* @{
*/
/* /*
* Implementation of multithreading in ARM Cortex-M3. To be done. * Copyright (c) 2010, STMicroelectronics.
* All rights reserved.
*
* 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.
* 3. The name of the author may not be used to endorse or promote
* products derived from this software without specific prior
* written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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.
*
*/
/*
* Implementation of multithreading in ARM Cortex-M3. To do.
*/ */
@ -10,4 +47,5 @@ struct mtarch_thread {
short mt_thread; short mt_thread;
}; };
#endif /* __MTARCH_H__ */ #endif /* __MTARCH_H__ */
/** @} */

View file

@ -1,3 +1,9 @@
/**
* \addtogroup mb851-platform
*
* @{
*/
/* /*
* Copyright (c) 2010, STMicroelectronics. * Copyright (c) 2010, STMicroelectronics.
* All rights reserved. * All rights reserved.
@ -27,17 +33,14 @@
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
* *
* This file is part of the Contiki OS
*
*/ */
/*---------------------------------------------------------------------------*/
/** /**
* \file * \file
* Random number functions for STM32W. * Random number functions for STM32W.
* \author * \author
* Salvatore Pitrulli <salvopitru@users.sourceforge.net> * Salvatore Pitrulli <salvopitru@users.sourceforge.net>
*/ */
/*---------------------------------------------------------------------------*/
#include "dev/stm32w-radio.h" #include "dev/stm32w-radio.h"
#include "lib/random.h" #include "lib/random.h"
@ -46,18 +49,20 @@
#warning "RANDOM_RAND_MAX is not defined as 65535." #warning "RANDOM_RAND_MAX is not defined as 65535."
#endif #endif
int rand(void) /*--------------------------------------------------------------------------*/
int
rand(void)
{ {
uint16_t rand_num; uint16_t rand_num;
ST_RadioGetRandomNumbers(&rand_num, 1);
ST_RadioGetRandomNumbers(&rand_num, 1); return (int)rand_num;
return (int)rand_num;
} }
/*--------------------------------------------------------------------------*/
/* /*
* It does nothing, since the rand already generates true random numbers. * It does nothing, since the rand already generates true random numbers.
*/ */
void srand(unsigned int seed) void
srand(unsigned int seed)
{ {
} }
/** @} */

View file

@ -1,3 +1,9 @@
/**
* \addtogroup mb851-platform
*
* @{
*/
/* /*
* Copyright (c) 2010, STMicroelectronics. * Copyright (c) 2010, STMicroelectronics.
* All rights reserved. * All rights reserved.
@ -27,23 +33,18 @@
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
* *
* This file is part of the Contiki OS
*
*/ */
/*---------------------------------------------------------------------------*/
/** /**
* \file * \file
* Real-timer specific implementation for STM32W. * Real-timer specific implementation for STM32W.
* \author * \author
* Salvatore Pitrulli <salvopitru@users.sourceforge.net> * Salvatore Pitrulli <salvopitru@users.sourceforge.net>
*/ */
/*---------------------------------------------------------------------------*/
#include "sys/energest.h" #include "sys/energest.h"
#include "sys/rtimer.h" #include "sys/rtimer.h"
#define DEBUG 0 #define DEBUG 0
#if DEBUG #if DEBUG
#include <stdio.h> #include <stdio.h>
@ -52,123 +53,116 @@
#define PRINTF(...) #define PRINTF(...)
#endif #endif
static uint16_t saved_TIM1CFG;
static uint32_t time_msb = 0; /* Most significant bits of the current time. */
/* time of the next rtimer event. Initially is set to the max
static uint32_t time_msb = 0; // Most significant bits of the current time. value. */
// time of the next rtimer event. Initially is set to the max value.
static rtimer_clock_t next_rtimer_time = 0; static rtimer_clock_t next_rtimer_time = 0;
static uint16_t saved_TIM1CFG;
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
void halTimer1Isr(void){ void
halTimer1Isr(void)
{
if(INT_TIM1FLAG & INT_TIMUIF){ // Overflow event. if(INT_TIM1FLAG & INT_TIMUIF) {
rtimer_clock_t now, clock_to_wait;
//PRINTF("O %4x.\r\n", TIM1_CNT); /* Overflow event. */
//printf("OV "); /* PRINTF("O %4x.\r\n", TIM1_CNT); */
/* printf("OV "); */
time_msb++; time_msb++;
rtimer_clock_t now = ((rtimer_clock_t)time_msb << 16)|TIM1_CNT; now = ((rtimer_clock_t) time_msb << 16) | TIM1_CNT;
clock_to_wait = next_rtimer_time - now;
rtimer_clock_t clock_to_wait = next_rtimer_time - now;
if(clock_to_wait <= 0x10000 && clock_to_wait > 0) {
if(clock_to_wait <= 0x10000 && clock_to_wait > 0){ // We must set now the Timer Compare Register. /* We must now set the Timer Compare Register. */
TIM1_CCR1 = (uint16_t) clock_to_wait;
TIM1_CCR1 = (int16u)clock_to_wait;
INT_TIM1FLAG = INT_TIMCC1IF; INT_TIM1FLAG = INT_TIMCC1IF;
INT_TIM1CFG |= INT_TIMCC1IF; // Compare 1 interrupt enable. INT_TIM1CFG |= INT_TIMCC1IF; /* Compare 1 interrupt enable. */
} }
INT_TIM1FLAG = INT_TIMUIF; INT_TIM1FLAG = INT_TIMUIF;
} else {
if(INT_TIM1FLAG & INT_TIMCC1IF) {
/* Compare event. */
INT_TIM1CFG &= ~INT_TIMCC1IF; /* Disable the next compare interrupt */
PRINTF("\nCompare event %4x\r\n", TIM1_CNT);
PRINTF("INT_TIM1FLAG %2x\r\n", INT_TIM1FLAG);
ENERGEST_ON(ENERGEST_TYPE_IRQ);
rtimer_run_next();
ENERGEST_OFF(ENERGEST_TYPE_IRQ);
INT_TIM1FLAG = INT_TIMCC1IF;
}
} }
else if(INT_TIM1FLAG & INT_TIMCC1IF){ // Compare event.
INT_TIM1CFG &= ~INT_TIMCC1IF; // Disable the next compare interrupt
PRINTF("\nCompare event %4x\r\n", TIM1_CNT);
PRINTF("INT_TIM1FLAG %2x\r\n", INT_TIM1FLAG);
ENERGEST_ON(ENERGEST_TYPE_IRQ);
rtimer_run_next();
ENERGEST_OFF(ENERGEST_TYPE_IRQ);
INT_TIM1FLAG = INT_TIMCC1IF;
}
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
void void
rtimer_arch_init(void) rtimer_arch_init(void)
{ {
TIM1_CR1 = 0; TIM1_CR1 = 0;
TIM1_PSC = RTIMER_ARCH_PRESCALER;
TIM1_PSC = RT_PRESCALER;
/* Counting from 0 to the maximum value. */
TIM1_ARR = 0xffff; // Counting from 0 to the maximum value. TIM1_ARR = 0xffff;
// Bits of TIMx_CCMR1 as default. /* Bits of TIMx_CCMR1 as default. */
/* Update Generation. */
TIM1_EGR = TIM_UG; // Update Generation. TIM1_EGR = TIM_UG;
INT_TIM1FLAG = 0xffff; INT_TIM1FLAG = 0xffff;
INT_TIM1CFG = INT_TIMUIF; // Update interrupt enable (interrupt on overflow). /* Update interrupt enable (interrupt on overflow).*/
INT_TIM1CFG = INT_TIMUIF;
TIM1_CR1 = TIM_CEN; // Counter enable.
/* Counter enable. */
INT_CFGSET = INT_TIM1; // Enable top level interrupt. TIM1_CR1 = TIM_CEN;
/* Enable top level interrupt. */
INT_CFGSET = INT_TIM1;
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
void rtimer_arch_disable_irq(void) void
rtimer_arch_disable_irq(void)
{ {
ATOMIC( ATOMIC(saved_TIM1CFG = INT_TIM1CFG; INT_TIM1CFG = 0;)
saved_TIM1CFG = INT_TIM1CFG;
INT_TIM1CFG = 0;
)
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
void rtimer_arch_enable_irq(void) void
rtimer_arch_enable_irq(void)
{ {
INT_TIM1CFG = saved_TIM1CFG; INT_TIM1CFG = saved_TIM1CFG;
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
rtimer_clock_t rtimer_arch_now(void) rtimer_clock_t
rtimer_arch_now(void)
{ {
return ((rtimer_clock_t)time_msb << 16)|TIM1_CNT; rtimer_clock_t t;
ATOMIC(t = ((rtimer_clock_t) time_msb << 16) | TIM1_CNT;)
return t;
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
void void
rtimer_arch_schedule(rtimer_clock_t t) rtimer_arch_schedule(rtimer_clock_t t)
{ {
rtimer_clock_t now, clock_to_wait;
PRINTF("rtimer_arch_schedule time %4x\r\n", /*((uint32_t*)&t)+1,*/(uint32_t)t); PRINTF("rtimer_arch_schedule time %4x\r\n", /*((uint32_t*)&t)+1, */
(uint32_t)t);
next_rtimer_time = t; next_rtimer_time = t;
now = rtimer_arch_now();
rtimer_clock_t now = rtimer_arch_now(); clock_to_wait = t - now;
rtimer_clock_t clock_to_wait = t - now;
PRINTF("now %2x\r\n", TIM1_CNT); PRINTF("now %2x\r\n", TIM1_CNT);
PRINTF("clock_to_wait %4x\r\n", clock_to_wait); PRINTF("clock_to_wait %4x\r\n", clock_to_wait);
if(clock_to_wait <= 0x10000){ // We must set now the Timer Compare Register. if(clock_to_wait <= 0x10000) {
/* We must now set the Timer Compare Register. */
TIM1_CCR1 = (int16u)now + (int16u)clock_to_wait; TIM1_CCR1 = (uint16_t)now + (uint16_t)clock_to_wait;
INT_TIM1FLAG = INT_TIMCC1IF; INT_TIM1FLAG = INT_TIMCC1IF;
INT_TIM1CFG |= INT_TIMCC1IF; // Compare 1 interrupt enable. INT_TIM1CFG |= INT_TIMCC1IF; /* Compare 1 interrupt enable. */
PRINTF("2-INT_TIM1FLAG %2x\r\n", INT_TIM1FLAG); PRINTF("2-INT_TIM1FLAG %2x\r\n", INT_TIM1FLAG);
} }
// else compare register will be set at overflow interrupt closer to the rtimer event. /* else compare register will be set at overflow interrupt closer to
the rtimer event. */
} }
/*---------------------------------------------------------------------------*/
/** @} */

View file

@ -1,3 +1,9 @@
/**
* \addtogroup mb851-platform
*
* @{
*/
/* /*
* Copyright (c) 2010, STMicroelectronics. * Copyright (c) 2010, STMicroelectronics.
* All rights reserved. * All rights reserved.
@ -27,8 +33,6 @@
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
* *
* This file is part of the Contiki OS
*
*/ */
/** /**
@ -41,43 +45,53 @@
#ifndef __RTIMER_ARCH_H__ #ifndef __RTIMER_ARCH_H__
#define __RTIMER_ARCH_H__ #define __RTIMER_ARCH_H__
#define RTIMER_ARCH_RES_341US 0
#define RTIMER_ARCH_RES_171US 1
#define RTIMER_ARCH_RES_85US 2
#include "contiki-conf.h" #include "contiki-conf.h"
#include "sys/clock.h" #include "sys/clock.h"
#ifdef RTIMER_ARCH_CONF_RESOLUTION
#define RTIMER_ARCH_RESOLUTION RTIMER_ARCH_CONF_RESOLUTION
#else /* RTIMER_ARCH_CONF_RESOLUTION */
#define RTIMER_ARCH_RESOLUTION RTIMER_ARCH_RES_171US
#endif /* RTIMER_ARCH_CONF_RESOLUTION */
//#define RT_RESOLUTION RES_85US /*
#ifdef RT_CONF_RESOLUTION * If it was possible to define a custom size for the rtimer_clock_t
#define RT_RESOLUTION RT_CONF_RESOLUTION * type: typedef unsigned long long rtimer_clock_t; Only 48 bit are
#else * used. It's enough for hundreds of years.
#define RT_RESOLUTION RES_171US */
#endif #if RTIMER_ARCH_RESOLUTION == RTIMER_ARCH_RES_341US
/* CK_CNT = PCLK/4096 = 12 MHz/4096 = 2929.6875 Hz */
#define RTIMER_ARCH_PRESCALER 12
/* One tick: 341.33 us. Using this value we will delay about 9.22 sec
after a day. */
#define RTIMER_ARCH_SECOND 2930
#endif /* RTIMER_ARCH_RESOLUTION == RTIMER_ARCH_RES_341US */
#define RES_341US 0 #if RTIMER_ARCH_RESOLUTION == RTIMER_ARCH_RES_171US
#define RES_171US 1 /* CK_CNT = PCLK/2048 = 12 MHz/2048 = 5859.375 Hz */
#define RES_85US 2 #define RTIMER_ARCH_PRESCALER 11
/* One tick: 170.66 us. Using this value we will advance about 5.53
sec after a day. */
#define RTIMER_ARCH_SECOND 5859
#endif /* RTIMER_ARCH_RESOLUTION == RTIMER_ARCH_RES_171US */
// If it was possible to define a custom size for the rtimer_clock_t type: #if RTIMER_ARCH_RESOLUTION == RTIMER_ARCH_RES_85US
//typedef unsigned long long rtimer_clock_t; // Only 48 bit are used. It's enough for hundreds of years. /* CK_CNT = PCLK/2048 = 12 MHz/2048 = 5859.375 Hz */
#define RTIMER_ARCH__PRESCALER 10
#if RT_RESOLUTION == RES_341US /* One tick: 85.33 us. Using this value we will delay about 1.84 sec
#define RT_PRESCALER 12 // CK_CNT = PCLK/4096 = 12 MHz/4096 = 2929.6875 Hz after a day. */
#define RTIMER_ARCH_SECOND 2930 // One tick: 341.33 us. Using this value we will delay about 9.22 sec after a day. #define RTIMER_ARCH_SECOND 11719
#endif /* RT_RESOLUTION == RES_341US */ #endif /* RTIMER_ARCH_RESOLUTION == RTIMER_ARCH_RES_85US */
#if RT_RESOLUTION == RES_171US
#define RT_PRESCALER 11 // CK_CNT = PCLK/2048 = 12 MHz/2048 = 5859.375 Hz
#define RTIMER_ARCH_SECOND 5859 // One tick: 170.66 us. Using this value we will advance about 5.53 sec after a day.
#endif /* RT_RESOLUTION == RES_171US */
#if RT_RESOLUTION == RES_85US
#define RT_PRESCALER 10 // CK_CNT = PCLK/2048 = 12 MHz/2048 = 5859.375 Hz
#define RTIMER_ARCH_SECOND 11719 // One tick: 85.33 us. Using this value we will delay about 1.84 sec after a day.
#endif /* RT_RESOLUTION == RES_85US */
rtimer_clock_t rtimer_arch_now(void); rtimer_clock_t rtimer_arch_now(void);
//#define rtimer_arch_now() clock_time()
void rtimer_arch_disable_irq(void); void rtimer_arch_disable_irq(void);
void rtimer_arch_enable_irq(void); void rtimer_arch_enable_irq(void);
#endif /* __RTIMER_ARCH_H__ */ #endif /* __RTIMER_ARCH_H__ */
/** @} */

View file

@ -1,10 +0,0 @@
/* Enter system in deep sleep 1 (core power domain is fully
* powered down and sleep timer is active).
* Execution is suspended for a given number of seconds.
*
* Pay attention! All system peripherals (including sensors) have
* to be reinitialized before being used again. UART, LEDs and
* real timers are automatically reinitialized. */
void sleep_seconds(int seconds);

View file

@ -1,3 +1,9 @@
/**
* \addtogroup mb851-platform
*
* @{
*/
/* /*
* Copyright (c) 2010, STMicroelectronics. * Copyright (c) 2010, STMicroelectronics.
* All rights reserved. * All rights reserved.
@ -27,35 +33,30 @@
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
* *
* This file is part of the Contiki OS
*
*/ */
/*---------------------------------------------------------------------------*/
/** /**
* \file * \file
* Machine dependent STM32W SLIP routines for UART1. * Machine dependent STM32W SLIP routines for UART1.
* \author * \author
* Salvatore Pitrulli <salvopitru@users.sourceforge.net> * Salvatore Pitrulli <salvopitru@users.sourceforge.net>
*/ */
/*---------------------------------------------------------------------------*/
#include <stdio.h> #include <stdio.h>
#include "contiki.h" #include "contiki.h"
#include "dev/slip.h" #include "dev/slip.h"
#include "dev/uart1.h" #include "dev/uart1.h"
/*--------------------------------------------------------------------------*/
void void
slip_arch_init(unsigned long ubr) slip_arch_init(unsigned long ubr)
{ {
uart1_set_input(slip_input_byte); uart1_set_input(slip_input_byte);
} }
/*--------------------------------------------------------------------------*/
void void
slip_arch_writeb(unsigned char c) slip_arch_writeb(unsigned char c)
{ {
uart1_writeb(c); uart1_writeb(c);
} }
/** @} */

View file

@ -1,33 +1,20 @@
CC = arm-none-eabi-gcc CC = arm-none-eabi-gcc
AR = arm-none-eabi-ar AR = arm-none-eabi-ar
CFLAGS = -mthumb -mcpu=cortex-m3 -I "." -I "C:/Program\ Files/Raisonance/Ride/Lib/ARM/include" \ CFLAGS = -mthumb -mcpu=cortex-m3 -I "." -I "C:/Program\ Files/Raisonance/Ride/Lib/ARM/include" \
-fsigned-char -D _SMALL_PRINTF -D INTEGER_ONLY -Os -ffunction-sections -mlittle-endian -fsigned-char -D _SMALL_PRINTF -D INTEGER_ONLY -Os -ffunction-sections -mlittle-endian
AROPTS = cq AROPTS = cq
SOURCE_FILES = sp-printf.c sp-puts.c sp-sprintf.c sp-snprintf.c sp-vfprintf.c
SOURCE_FILES = _SP_printf.c _SP_puts.c _SP_sprintf.c _SP_snprintf.c _SP_vfprintf.c
SOURCE_OBJS = ${patsubst %.c,%.o,$(SOURCE_FILES)} SOURCE_OBJS = ${patsubst %.c,%.o,$(SOURCE_FILES)}
LIB = smallprintf_thumb2.a LIB = smallprintf_thumb2.a
all: clean $(LIB) all: clean $(LIB)
clean: clean:
rm -f $(LIB) rm -f $(LIB)
%.a: $(SOURCE_OBJS) %.a: $(SOURCE_OBJS)
$(AR) $(AROPTS) $@ $^ $(AR) $(AROPTS) $@ $^
%.o: %.c %.o: %.c
$(CC) $(CFLAGS) -c $< -o $@ $(CC) $(CFLAGS) -c $< -o $@

View file

@ -0,0 +1,84 @@
/**
* \addtogroup stm32w-cpu
*
* @{
*/
#ifdef INTEGER_ONLY
#define _vfprintf_r _vfiprintf_r
#define _vfprintf _vfiprintf
#define vfprintf vfiprintf
#endif /* INTEGER_ONLY */
#include <_ansi.h>
#include <stdio.h>
#ifndef _SMALL_PRINTF
#include "local.h"
#endif /* _SMALL_PRINTF */
#ifdef _HAVE_STDC
#include <stdarg.h>
#else /* _HAVE_STDC */
#include <varargs.h>
#endif /* _HAVE_STDC */
/*--------------------------------------------------------------------------*/
#ifndef _SMALL_PRINTF
#ifdef _HAVE_STDC
int
_printf_r (struct _reent *ptr, const char *fmt, ...)
#else /* _HAVE_STDC */
int
_printf_r (ptr, fmt, va_alist)
struct _reent *ptr;
char *fmt;
va_dcl
#endif /* _HAVE_STDC */
{
int ret;
va_list ap;
//_REENT_SMALL_CHECK_INIT(_stdout_r (ptr));
#ifdef _HAVE_STDC
va_start (ap, fmt);
#else /* _HAVE_STDC */
va_start (ap);
#endif /* _HAVE_STDC */
ret = _vfprintf_r (ptr, _stdout_r (ptr), fmt, ap);
va_end (ap);
return ret;
}
#endif /* _SMALL_PRINTF */
/*--------------------------------------------------------------------------*/
#ifndef _REENT_ONLY
#ifdef _HAVE_STDC
int
printf (const char *fmt, ...)
#else /* _HAVE_STDC */
int
printf (fmt, va_alist)
char *fmt;
va_dcl
#endif /* _HAVE_STDC */
{
int ret;
va_list ap;
//_REENT_SMALL_CHECK_INIT(_stdout_r (_REENT));
#ifdef _HAVE_STDC
va_start (ap, fmt);
#else /* _HAVE_STDC */
va_start (ap);
#endif /* _HAVE_STDC */
#ifndef _SMALL_PRINTF
ret = vfprintf (_stdout_r (_REENT), fmt, ap);
#else /* _SMALL_PRINTF */
ret = vfprintf (0, fmt, ap);
#endif /* _SMALL_PRINTF */
va_end (ap);
return ret;
}
#endif /* _REENT_ONLY */
/** @} */

View file

@ -0,0 +1,39 @@
/**
* \addtogroup stm32w-cpu
*
* @{
*/
#include <stdio.h>
#include <string.h>
void __io_putchar (char);
/*--------------------------------------------------------------------------*/
void
_SMALL_PRINTF_puts(const char *ptr, int len, FILE *fp)
{
/* No file => sprintf */
if (fp && (fp->_file == -1) && (fp->_flags & (__SWR | __SSTR))) {
char *str = fp->_p;
for (; len ; len--) {
*str ++ = *ptr++;
}
fp->_p = str;
} else {
/* file => printf */
for (; len ; len--) {
__io_putchar (*ptr++);
}
}
}
/*--------------------------------------------------------------------------*/
int
puts(const char *str)
{
int len = strlen (str);
_SMALL_PRINTF_puts(str, len, 0) ;
__io_putchar ('\n');
return len;
}
/** @} */

View file

@ -1,3 +1,9 @@
/**
* \addtogroup stm32w-cpu
*
* @{
*/
/* /*
* Copyright (c) 1990 The Regents of the University of California. * Copyright (c) 1990 The Regents of the University of California.
* All rights reserved. * All rights reserved.
@ -14,8 +20,9 @@
* IMPLIED WARRANTIES, INCLUDING, WITHOUT LIMITATION, THE IMPLIED * IMPLIED WARRANTIES, INCLUDING, WITHOUT LIMITATION, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
*/ */
/* doc in _SP_sprintf.c */
/* This code created by modifying _SP_sprintf.c so copyright inherited. */ /* doc in sp-sprintf.c */
/* This code created by modifying sp-sprintf.c so copyright inherited. */
#include <stdio.h> #include <stdio.h>
#ifdef _HAVE_STDC #ifdef _HAVE_STDC
@ -121,4 +128,4 @@ snprintf (str, size, fmt, va_alist)
} }
#endif #endif
/** @} */

View file

@ -1,3 +1,9 @@
/**
* \addtogroup stm32w-cpu
*
* @{
*/
/* /*
* Copyright (c) 1990 The Regents of the University of California. * Copyright (c) 1990 The Regents of the University of California.
* All rights reserved. * All rights reserved.
@ -386,4 +392,4 @@ sprintf (str, fmt, va_alist)
} }
#endif #endif
/** @} */

View file

@ -1,3 +1,9 @@
/**
* \addtogroup stm32w-cpu
*
* @{
*/
/* /*
FUNCTION FUNCTION
<<vprintf>>, <<vfprintf>>, <<vsprintf>>---format argument list <<vprintf>>, <<vfprintf>>, <<vsprintf>>---format argument list
@ -1765,10 +1771,14 @@ get_arg (struct _reent *data, int n, char *fmt, va_list *ap,
} }
} }
/* alter the global numargs value and keep a reference to the last bit of the fmt /*
string we processed here because the caller will continue processing where we started */ * alter the global numargs value and keep a reference to the last bit of the
* fmt string we processed here because the caller will continue processing
* where we started
*/
*numargs_p = numargs; *numargs_p = numargs;
*last_fmt = fmt; *last_fmt = fmt;
return &args[n]; return &args[n];
} }
#endif /* !_NO_POS_ARGS */ #endif /* !_NO_POS_ARGS */
/** @} */

View file

@ -1,3 +1,9 @@
/**
* \addtogroup stm32w-cpu
*
* @{
*/
/**************************************************************** /****************************************************************
* *
* The author of this software is David M. Gay. * The author of this software is David M. Gay.
@ -26,8 +32,13 @@
dmg@research.att.com or research!dmg dmg@research.att.com or research!dmg
*/ */
/* This header file is a modification of mprec.h that only contains floating #ifndef __VFIEEEFP_H__
point union code. */ #define __VFIEEEFP_H__
/*
* This header file is a modification of mprec.h that only contains floating
* point union code.
*/
#include <ieeefp.h> #include <ieeefp.h>
#include <math.h> #include <math.h>
@ -58,11 +69,12 @@ Exactly one of IEEE_8087, IEEE_MC68k, VAX, or IBM should be defined.
#endif #endif
#ifdef WANT_IO_LONG_DBL #ifdef WANT_IO_LONG_DBL
/* If we are going to examine or modify specific bits in a long double using /*
the lword0 or lwordx macros, then we must wrap the long double inside * If we are going to examine or modify specific bits in a long double using
a union. This is necessary to avoid undefined behavior according to * the lword0 or lwordx macros, then we must wrap the long double inside
the ANSI C spec. */ * a union. This is necessary to avoid undefined behavior according to
* the ANSI C spec.
*/
#ifdef IEEE_8087 #ifdef IEEE_8087
#if LDBL_MANT_DIG == 24 #if LDBL_MANT_DIG == 24
struct ldieee struct ldieee
@ -136,10 +148,12 @@ struct ldieee
#endif /* !IEEE_8087 */ #endif /* !IEEE_8087 */
#endif /* WANT_IO_LONG_DBL */ #endif /* WANT_IO_LONG_DBL */
/* If we are going to examine or modify specific bits in a double using /*
the word0 and/or word1 macros, then we must wrap the double inside * If we are going to examine or modify specific bits in a double using
a union. This is necessary to avoid undefined behavior according to * the word0 and/or word1 macros, then we must wrap the double inside
the ANSI C spec. */ * a union. This is necessary to avoid undefined behavior according to
* the ANSI C spec.
*/
union double_union union double_union
{ {
double d; double d;
@ -281,4 +295,5 @@ union double_union
#endif #endif
#endif #endif
#endif /* __VFIEEEFP_H__ */
/** @} */

View file

@ -1,78 +0,0 @@
#ifdef INTEGER_ONLY
#define _vfprintf_r _vfiprintf_r
#define _vfprintf _vfiprintf
#define vfprintf vfiprintf
#endif
#include <_ansi.h>
#include <stdio.h>
#ifndef _SMALL_PRINTF
#include "local.h"
#endif
#ifdef _HAVE_STDC
#include <stdarg.h>
#else
#include <varargs.h>
#endif
#ifndef _SMALL_PRINTF
#ifdef _HAVE_STDC
int
_printf_r (struct _reent *ptr, const char *fmt, ...)
#else
int
_printf_r (ptr, fmt, va_alist)
struct _reent *ptr;
char *fmt;
va_dcl
#endif
{
int ret;
va_list ap;
//_REENT_SMALL_CHECK_INIT(_stdout_r (ptr));
#ifdef _HAVE_STDC
va_start (ap, fmt);
#else
va_start (ap);
#endif
ret = _vfprintf_r (ptr, _stdout_r (ptr), fmt, ap);
va_end (ap);
return ret;
}
#endif
#ifndef _REENT_ONLY
#ifdef _HAVE_STDC
int
printf (const char *fmt, ...)
#else
int
printf (fmt, va_alist)
char *fmt;
va_dcl
#endif
{
int ret;
va_list ap;
//_REENT_SMALL_CHECK_INIT(_stdout_r (_REENT));
#ifdef _HAVE_STDC
va_start (ap, fmt);
#else
va_start (ap);
#endif
#ifndef _SMALL_PRINTF
ret = vfprintf (_stdout_r (_REENT), fmt, ap);
#else
ret = vfprintf (0, fmt, ap);
#endif
va_end (ap);
return ret;
}
#endif /* ! _REENT_ONLY */

View file

@ -1,34 +0,0 @@
#include <stdio.h>
#include <string.h>
void __io_putchar ( char );
void _SMALL_PRINTF_puts(const char *ptr, int len, FILE *fp)
{
if ( fp && ( fp->_file == -1 ) /* No file => sprintf */
&& (fp->_flags & (__SWR | __SSTR) ) )
{
char *str = fp->_p;
for ( ; len ; len-- )
{
*str ++ = *ptr++;
}
fp->_p = str;
}
else /* file => printf */
{
for ( ; len ; len-- )
__io_putchar ( *ptr++ );
}
}
int puts(const char *str)
{
int len = strlen ( str );
_SMALL_PRINTF_puts(str, len, 0) ;
__io_putchar ( '\n' );
return len;
}

View file

@ -1,3 +1,9 @@
/**
* \addtogroup mb851-platform
*
* @{
*/
/* /*
* Copyright (c) 2010, STMicroelectronics. * Copyright (c) 2010, STMicroelectronics.
* All rights reserved. * All rights reserved.
@ -27,40 +33,34 @@
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
* *
* This file is part of the uIP TCP/IP stack.
*
*/ */
/*---------------------------------------------------------------------------*/
/** /**
* \file * \file
* uip_arch.c * uip-arch.c
* \author * \author
* Salvatore Pitrulli <salvopitru@users.sourceforge.net> * Salvatore Pitrulli <salvopitru@users.sourceforge.net>
*/ */
/*---------------------------------------------------------------------------*/
#include "net/uip.h" #include "net/uip.h"
#include "net/uip_arch.h" #include "net/uip_arch.h"
/*-----------------------------------------------------------------------------------*/
#if UIP_TCP #if UIP_TCP
void void
uip_add32(uint8_t *op32, uint16_t op16) uip_add32(uint8_t * op32, uint16_t op16)
{ {
uint32_t op32_align, uip_acc32_align; uint32_t op32_align, uip_acc32_align;
op32_align = ((uint32_t)op32[0])<<24 | ((uint32_t)op32[1])<<16 | ((uint16_t)op32[2])<<8 | op32[3]; op32_align =
((uint32_t) op32[0]) << 24 | ((uint32_t) op32[1]) << 16 |
((uint16_t) op32[2]) << 8 | op32[3];
uip_acc32_align = op32_align + op16; uip_acc32_align = op32_align + op16;
uip_acc32[3] = uip_acc32_align; uip_acc32[3] = uip_acc32_align;
uip_acc32[2] = uip_acc32_align>>8; uip_acc32[2] = uip_acc32_align >> 8;
uip_acc32[1] = uip_acc32_align>>16; uip_acc32[1] = uip_acc32_align >> 16;
uip_acc32[0] = uip_acc32_align>>24; uip_acc32[0] = uip_acc32_align >> 24;
} }
#endif #endif
/*-----------------------------------------------------------------------------------*/ /*-----------------------------------------------------------------------------------*/
/** @} */

View file

@ -1,3 +1,9 @@
/**
* \addtogroup mb851-platform
*
* @{
*/
/* /*
* Copyright (c) 2010, STMicroelectronics. * Copyright (c) 2010, STMicroelectronics.
* All rights reserved. * All rights reserved.
@ -27,27 +33,21 @@
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
* *
* This file is part of the Contiki OS
*
*/ */
/*---------------------------------------------------------------------------*/
/** /**
* \file * \file
* Watchdog * Watchdog
* \author * \author
* Salvatore Pitrulli <salvopitru@users.sourceforge.net> * Salvatore Pitrulli <salvopitru@users.sourceforge.net>
*/ */
/*---------------------------------------------------------------------------*/
#include <stdio.h> #include <stdio.h>
#include "dev/watchdog.h" #include "dev/watchdog.h"
#include PLATFORM_HEADER #include PLATFORM_HEADER
#include "hal/error.h" #include "hal/error.h"
#include "hal/hal.h" #include "hal/hal.h"
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
void void
watchdog_init(void) watchdog_init(void)
@ -58,16 +58,17 @@ watchdog_init(void)
void void
watchdog_start(void) watchdog_start(void)
{ {
/* We setup the watchdog to reset the device after 2.048 seconds, /*
unless watchdog_periodic() is called. */ * We setup the watchdog to reset the device after 2.048 seconds,
* unless watchdog_periodic() is called.
*/
halInternalEnableWatchDog(); halInternalEnableWatchDog();
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
void void
watchdog_periodic(void) watchdog_periodic(void)
{ {
/* This function is called periodically to restart the watchdog /* This function is called periodically to restart the watchdog timer. */
timer. */
halResetWatchdog(); halResetWatchdog();
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
@ -83,3 +84,4 @@ watchdog_reboot(void)
halReboot(); halReboot();
} }
/*---------------------------------------------------------------------------*/ /*---------------------------------------------------------------------------*/
/** @} */

View file

@ -1,6 +1,3 @@
# $Id: Makefile.mb851,v 1.2 2010/12/15 11:18:09 salvopitru Exp $
ARCH= irq.c sensors.c acc-sensor.c button-sensor.c temperature-sensor.c mems.c ARCH= irq.c sensors.c acc-sensor.c button-sensor.c temperature-sensor.c mems.c
CONTIKI_TARGET_DIRS = . dev CONTIKI_TARGET_DIRS = . dev

Some files were not shown because too many files have changed in this diff Show more