New Contiki port to STM32W108.

This commit is contained in:
salvopitru 2010-10-25 09:03:38 +00:00
parent 324796cd1a
commit ec5e3ce0d7
130 changed files with 43157 additions and 0 deletions

View file

@ -0,0 +1,178 @@
.SUFFIXES:
ifdef IAR
${info Using IAR...}
#IAR_PATH = C:/Program\ Files/IAR\ Systems/Embedded\ Workbench\ 5.4\ Evaluation
ifeq ($(IAR_PATH),)
${error IAR_PATH not defined! You must specify IAR root directory}
endif
endif
### Define the CPU directory
CONTIKI_CPU=$(CONTIKI)/cpu/stm32w108
### Define the source files we have in the STM32W port
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 \
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
STM32W_S = spmr.s79 context-switch.s79
ifdef IAR
STM32W_C += low_level_init.c
STM32W_S += cstartup_M.s
else
STM32W_C += crt_stm32w108.c
endif
# .s and .s79 not specified here because in Makefile.include only .c and .S suffixes are replaced with .o.
CONTIKI_TARGET_SOURCEFILES += $(STM32W_C) \
$(SYSAPPS) $(ELFLOADER) \
$(TARGETLIBS)
CONTIKI_SOURCEFILES += $(CONTIKI_TARGET_SOURCEFILES)
ifdef IAR
TARGET_LIBFILES = $(CONTIKI_CPU)/simplemac/library/simplemac-library.a
else
ifdef PRINTF_FLOAT
TARGET_LIBFILES = $(CONTIKI_CPU)/simplemac/library/simplemac-library.a $(CONTIKI_CPU)/hal/micro/cortexm3/e_stdio_thumb2.a
else
TARGET_LIBFILES = $(CONTIKI_CPU)/simplemac/library/simplemac-library.a $(CONTIKI_CPU)/hal/micro/cortexm3/e_stdio_intonly_thumb2.a
endif
endif
# `$(CC) -print-file-name=thumb2/libc.a` `$(CC) -print-file-name=thumb2/libgcc.a`
### Compiler definitions
ifdef IAR
CC = iccarm
LD = ilinkarm
AS = iasmarm
AR = iarchive
OBJCOPY = ielftool
STRIP = strip
OPTI = -Ohz --no_unroll
CFLAGSNO = --endian=little --cpu=Cortex-M3 -e --diag_suppress Pa050 -D BOARD_HEADER=\"board.h\" \
-D BOARD_MB851 -D "PLATFORM_HEADER=\"hal/micro/cortexm3/compiler/iar.h\"" -D CORTEXM3 \
-D CORTEXM3_STM32W108 -D PHY_STM32W108XX -D DISABLE_WATCHDOG -D ENABLE_ADC_EXTENDED_RANGE_BROKEN \
-D __SOURCEFILE__=\"$*.c\" -lC $(OBJECTDIR) \
-I $(IAR_PATH)/arm/inc --dlib_config=DLib_Config_Normal.h
CFLAGS += $(CFLAGSNO) $(OPTI)
AROPTS = --create
ASFLAGS = -s+ -w+ --cpu Cortex-M3 -L$(OBJECTDIR)
LDFLAGS += --redirect _Printf=_PrintfSmall --redirect _Scanf=_ScanfSmall --map=contiki-$(TARGET).map \
--config $(CONTIKI_CPU)/hal/micro/cortexm3/stm32w108/iar-cfg.icf
OBJOPTS = --bin
else
CC = arm-none-eabi-gcc
LD = arm-none-eabi-gcc
AS = arm-none-eabi-gcc
AR = arm-none-eabi-ar
OBJCOPY = arm-none-eabi-objcopy
STRIP = arm-none-eabi-strip
SIZE = arm-none-eabi-size
OPTI = -Os -ffunction-sections -fshort-enums
CFLAGSNO = -mthumb -mcpu=cortex-m3 -fsigned-char -D "PLATFORM_HEADER=\"hal/micro/cortexm3/compiler/gnu.h\"" \
-D BOARD_HEADER=\"board.h\" -g -Wall -Wno-strict-aliasing -mlittle-endian \
-D BOARD_MB851 -D CORTEXM3 -D CORTEXM3_STM32W108 -D PHY_STM32W108XX -D DISABLE_WATCHDOG -D ENABLE_ADC_EXTENDED_RANGE_BROKEN \
-D __SOURCEFILE__=\"$*.c\"
CFLAGS += $(CFLAGSNO) $(OPTI)
ASFLAGS = -mthumb -mcpu=cortex-m3 -fsigned-char -c -g -Wall -Os -ffunction-sections \
-mlittle-endian -fshort-enums -x assembler-with-cpp -Wa,-EL
LDFLAGS += -mcpu=cortex-m3 \
-mthumb \
-Wl,-T -Xlinker $(CONTIKI_CPU)/hal/micro/cortexm3/stm32w108/gnu.ld \
-Wl,-static \
-u Default_Handler \
-nostartfiles \
-Wl,-Map -Xlinker contiki-$(TARGET).map \
-Wl,--gc-sections
SIZEFLAGS = -A
OBJOPTS = -O binary
endif
FLASHER = $(CONTIKI)/tools/stm32w/stm32w_flasher/linux/stm32w_flasher
# Check if we are running under Windows
ifdef OS
ifneq (,$(findstring Windows,$(OS)))
FLASHER = $(CONTIKI)/tools/stm32w/stm32w_flasher/win/stm32w_flasher
endif
endif
ifndef PORT
# Flash with jlink
FLASHEROPTS = -f -r
else
# Flash on serial port with on-board bootloader
FLASHEROPTS = -f -i rs232 -p $(PORT) -r
endif
### Custom rules
OBJECTDIR = obj_$(TARGET)
ssubst = ${patsubst %.s,%.o,${patsubst %.s79,%.o,$(1)}}
CONTIKI_OBJECTFILES += ${addprefix $(OBJECTDIR)/,${call ssubst, $(STM32W_S)}}
vpath %.s79 $(CONTIKI_CPU)/hal/micro/cortexm3
vpath %.s $(CONTIKI_CPU)/hal/micro/cortexm3
ifdef IAR
# Check if we are in cygwin environment, so we must have paths like /cygdrive/c/... (checking TERM doesn't always work.)
ifneq ($(shell ls /cygdrive 2>/dev/null),)
${info Cygwin detected.}
SEDCOMMAND = sed -e '1s,\($(OBJECTDIR)\\$*\)\.o: \(.\):,\1.o : /cygdrive/\l\2,g' -e '1!s,\($(OBJECTDIR)\\$*\)\.o: \(.\):, /cygdrive/\l\2,g' -e 's,\\\([^ ]\),/\1,g' -e 's,$$, \\,' -e '$$s, \\$$,,' < $(@:.o=.P) > $(@:.o=.d)
else
SEDCOMMAND = sed -e '1s,\($(OBJECTDIR)\\$*\)\.o:,\1.o : ,g' -e '1!s,\($(OBJECTDIR)\\$*\)\.o:, ,g' -e 's,\\\([^ ]\),/\1,g' -e 's,$$, \\,' -e '$$s, \\$$,,' < $(@:.o=.P) > $(@:.o=.d)
endif
CUSTOM_RULE_C_TO_OBJECTDIR_O = 1
$(OBJECTDIR)/%.o: %.c
$(CC) $(CFLAGS) $< --dependencies=m $(@:.o=.P) -o $@
@$(SEDCOMMAND); rm -f $(@:.o=.P)
@$(FINALIZE_DEPENDENCY)
CUSTOM_RULE_C_TO_CO = 1
%.co: %.c
$(CC) $(CFLAGS) -DAUTOSTART_ENABLE $< -o $@
else #IAR
CUSTOM_RULE_LINK = 1
%.$(TARGET): %.co $(PROJECT_OBJECTFILES) $(PROJECT_LIBRARIES) contiki-$(TARGET).a
$(LD) $(LDFLAGS) $(TARGET_STARTFILES) ${filter-out %.a,$^} -Wl,-\( ${filter %.a,$^} $(TARGET_LIBFILES) -Wl,-\) -o $@
@echo >> contiki-$(TARGET).map
@$(SIZE) $(SIZEFLAGS) $@ >> contiki-$(TARGET).map
#%.$(TARGET): %.co $(PROJECT_OBJECTFILES) $(PROJECT_LIBRARIES) $(CONTIKI_OBJECTFILES)
# $(LD) $(LDFLAGS) $(TARGET_STARTFILES) ${filter-out %.a,$^} ${filter %.a,$^} $(TARGET_LIBFILES) -o $@
# @echo "\n" >> contiki-$(TARGET).map
# @$(SIZE) $(SIZEFLAGS) $@ >> contiki-$(TARGET).map
endif #IAR
$(OBJECTDIR)/%.o: %.s79
$(AS) $(ASFLAGS) -o $@ $<
$(OBJECTDIR)/%.o: %.s
$(AS) $(ASFLAGS) -o $@ $<
%.bin: %.$(TARGET)
$(OBJCOPY) $(OBJOPTS) $< $@
%.flash: %.bin
$(FLASHER) $(FLASHEROPTS) $<

130
cpu/stm32w108/clock.c Normal file
View file

@ -0,0 +1,130 @@
/*
* 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.
*
* This file is part of the Contiki OS
*
* $Id: clock.c,v 1.1 2010/10/25 09:03:38 salvopitru Exp $
*/
/*---------------------------------------------------------------------------*/
/**
* \file
* Clock.
* \author
* Salvatore Pitrulli <salvopitru@users.sourceforge.net>
*/
/*---------------------------------------------------------------------------*/
#include PLATFORM_HEADER
#include "hal/error.h"
#include "hal/hal.h"
#include "dev/stm32w_systick.h"
#include "sys/clock.h"
#include "sys/etimer.h"
// The value that will be load in the SysTick value register.
#define RELOAD_VALUE 24000-1 // 1 ms with a 24 MHz clock
static volatile clock_time_t count;
static volatile unsigned long current_seconds = 0;
static unsigned int second_countdown = CLOCK_SECOND;
/*---------------------------------------------------------------------------*/
void SysTick_Handler(void)
{
count++;
if(etimer_pending()) {
etimer_request_poll();
}
if (--second_countdown == 0) {
current_seconds++;
second_countdown = CLOCK_SECOND;
}
}
/*---------------------------------------------------------------------------*/
void clock_init(void)
{
INTERRUPTS_OFF();
//Counts the number of ticks.
count = 0;
SysTick_CLKSourceConfig(SysTick_CLKSource_HCLK);
SysTick_SetReload(RELOAD_VALUE);
SysTick_ITConfig(ENABLE);
SysTick_CounterCmd(SysTick_Counter_Enable);
INTERRUPTS_ON();
}
/*---------------------------------------------------------------------------*/
clock_time_t clock_time(void)
{
return count;
}
/*---------------------------------------------------------------------------*/
/**
* Delay the CPU for a multiple of TODO
*/
void clock_delay(unsigned int i)
{
for (; i > 0; i--) { /* Needs fixing XXX */
unsigned j;
for (j = 50; j > 0; j--)
asm ("nop");
}
}
/*---------------------------------------------------------------------------*/
/**
* Wait for a multiple of 1 ms.
*
*/
void clock_wait(int i)
{
clock_time_t start;
start = clock_time();
while(clock_time() - start < (clock_time_t)i);
}
/*---------------------------------------------------------------------------*/
unsigned long clock_seconds(void)
{
return current_seconds;
}

View file

@ -0,0 +1,53 @@
/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
* File Name : cortexm3_macro.h
* Author : MCD Application Team
* Version : V2.0.3
* Date : 09/22/2008
* Description : Header file for cortexm3_macro.s.
********************************************************************************
* 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 __CORTEXM3_MACRO_H
#define __CORTEXM3_MACRO_H
/* Includes ------------------------------------------------------------------*/
#include "stm32w_type.h"
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
void __WFI(void);
void __WFE(void);
void __SEV(void);
void __ISB(void);
void __DSB(void);
void __DMB(void);
void __SVC(void);
u32 __MRS_CONTROL(void);
void __MSR_CONTROL(u32 Control);
u32 __MRS_PSP(void);
void __MSR_PSP(u32 TopOfProcessStack);
u32 __MRS_MSP(void);
void __MSR_MSP(u32 TopOfMainStack);
void __RESETPRIMASK(void);
void __SETPRIMASK(void);
u32 __READ_PRIMASK(void);
void __RESETFAULTMASK(void);
void __SETFAULTMASK(void);
u32 __READ_FAULTMASK(void);
void __BASEPRICONFIG(u32 NewPriority);
u32 __GetBASEPRI(void);
u16 __REV_HalfWord(u16 Data);
u32 __REV_Word(u32 Data);
#endif /* __CORTEXM3_MACRO_H */
/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/

View file

@ -0,0 +1,596 @@
/*
* 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.
*
* This file is part of the Contiki OS
*
*/
/*---------------------------------------------------------------------------*/
/**
* \file
* Machine dependent STM32W radio code.
* \author
* Salvatore Pitrulli
*/
/*---------------------------------------------------------------------------*/
#include PLATFORM_HEADER
#include "hal/error.h"
#include "hal/hal.h"
#include "contiki.h"
#include "net/mac/frame802154.h"
#include "dev/stm32w-radio.h"
#include "net/netstack.h"
#include "net/packetbuf.h"
#include "net/rime/rimestats.h"
#define DEBUG 0
#include "dev/leds.h"
#define LED_ACTIVITY 0
#if DEBUG > 0
#include <stdio.h>
#define PRINTF(...) printf(__VA_ARGS__)
#else
#define PRINTF(...) do {} while (0)
#endif
#if LED_ACTIVITY
#define LED_TX_ON() leds_on(LEDS_GREEN)
#define LED_TX_OFF() leds_off(LEDS_GREEN)
#define LED_RX_ON() leds_on(LEDS_RED)
#define LED_RX_OFF() leds_off(LEDS_RED)
#else
#define LED_TX_ON()
#define LED_TX_OFF()
#define LED_RX_ON()
#define LED_RX_OFF()
#endif
#ifndef MAC_RETRIES
#define MAC_RETRIES 1
#endif
#if MAC_RETRIES
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 RETRY_CNT_GTZ() (mac_retries_left > 0)
#else
#define INIT_RETRY_CNT()
#define DEC_RETRY_CNT()
#define RETRY_CNT_GTZ() 0
#endif
/* 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. */
#ifndef RADIO_WAIT_FOR_PACKET_SENT
#define RADIO_WAIT_FOR_PACKET_SENT 1
#endif
#define TO_PREV_STATE() { \
if(onoroff == OFF){ \
ST_RadioSleep(); \
ENERGEST_OFF(ENERGEST_TYPE_LISTEN); \
} \
}
const RadioTransmitConfig radioTransmitConfig = {
TRUE, // waitForAck;
TRUE, // checkCca; // Set to FALSE with low-power MACs.
4, // ccaAttemptMax;
2, // backoffExponentMin;
6, // backoffExponentMax;
TRUE // appendCrc;
};
/*
* The buffers which hold incoming data.
*/
#ifndef RADIO_RXBUFS
#define RADIO_RXBUFS 1
#endif
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.
#if RADIO_RXBUFS > 1
static volatile int8_t first = -1, last=0;
#else
static const int8_t first=0, last=0;
#endif
#if RADIO_RXBUFS > 1
#define CLEAN_RXBUFS() do{first = -1; last = 0;}while(0)
#define RXBUFS_EMPTY() (first == -1)
int RXBUFS_FULL(){
int8_t first_tmp = first;
return first_tmp == last;
}
#else /* RADIO_RXBUFS > 1 */
#define CLEAN_RXBUFS() (stm32w_rxbufs[0][0] = 0)
#define RXBUFS_EMPTY() (stm32w_rxbufs[0][0] == 0)
#define RXBUFS_FULL() (stm32w_rxbufs[0][0] != 0)
#endif /* RADIO_RXBUFS > 1 */
static uint8_t __attribute__(( aligned(2) )) stm32w_txbuf[STM32W_MAX_PACKET_LEN+1];
#define CLEAN_TXBUF() (stm32w_txbuf[0] = 0)
#define TXBUF_EMPTY() (stm32w_txbuf[0] == 0)
#define CHECKSUM_LEN 2
/*
* The transceiver state.
*/
#define ON 0
#define OFF 1
static volatile uint8_t onoroff = OFF;
static uint8_t receiving_packet = 0;
static s8 last_rssi;
static volatile StStatus last_tx_status;
/*---------------------------------------------------------------------------*/
PROCESS(stm32w_radio_process, "STM32W radio driver");
/*---------------------------------------------------------------------------*/
static int stm32w_radio_init(void);
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_send(const void *data, unsigned short len);
static int stm32w_radio_read(void *buf, unsigned short bufsize);
static int stm32w_radio_channel_clear(void);
static int stm32w_radio_receiving_packet(void);
static int stm32w_radio_pending_packet(void);
static int stm32w_radio_on(void);
static int stm32w_radio_off(void);
static int add_to_rxbuf(uint8_t * src);
static int read_from_rxbuf(void * dest, unsigned short len);
const struct radio_driver stm32w_radio_driver =
{
stm32w_radio_init,
stm32w_radio_prepare,
stm32w_radio_transmit,
stm32w_radio_send,
stm32w_radio_read,
stm32w_radio_channel_clear,
stm32w_radio_receiving_packet,
stm32w_radio_pending_packet,
stm32w_radio_on,
stm32w_radio_off,
};
/*---------------------------------------------------------------------------*/
static int stm32w_radio_init(void)
{
// A channel needs also to be setted.
ST_RadioSetChannel(RF_CHANNEL);
// Initialize radio (analog section, digital baseband and MAC).
// Leave radio powered up in non-promiscuous rx mode.
ST_RadioInit(ST_RADIO_POWER_MODE_OFF);
onoroff = OFF;
ST_RadioSetNodeId(STM32W_NODE_ID); // To be deleted.
ST_RadioSetPanId(IEEE802154_PANID);
ST_RadioEnableAutoAck(TRUE);
CLEAN_RXBUFS();
CLEAN_TXBUF();
process_start(&stm32w_radio_process, NULL);
return 0;
}
/*---------------------------------------------------------------------------*/
int stm32w_radio_set_channel(u8_t channel)
{
if (ST_RadioSetChannel(channel) == ST_SUCCESS)
return 0;
else
return 1;
}
/*---------------------------------------------------------------------------*/
static int wait_for_tx(void){
struct timer t;
timer_set(&t, CLOCK_SECOND/10);
while(!TXBUF_EMPTY()){
if(timer_expired(&t)){
PRINTF("stm32w: tx buffer full.\r\n");
return 1;
}
/* Put CPU in sleep mode. */
halSleepWithOptions(SLEEPMODE_IDLE,0);
}
return 0;
}
/*---------------------------------------------------------------------------*/
static int stm32w_radio_prepare(const void *payload, unsigned short payload_len)
{
if(payload_len > STM32W_MAX_PACKET_LEN){
PRINTF("stm32w: payload length=%d is too long.\r\n", payload_len);
return RADIO_TX_ERR;
}
#if !RADIO_WAIT_FOR_PACKET_SENT
/* 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().
*/
if(wait_for_tx()){
PRINTF("stm32w: tx buffer full.\r\n");
return RADIO_TX_ERR;
}
#endif /* RADIO_WAIT_FOR_PACKET_SENT */
/* Copy to the txbuf.
* The first byte must be the packet length.
*/
CLEAN_TXBUF();
memcpy(stm32w_txbuf + 1, payload, payload_len);
return RADIO_TX_OK;
}
/*---------------------------------------------------------------------------*/
static int stm32w_radio_transmit(unsigned short payload_len)
{
stm32w_txbuf[0] = payload_len + CHECKSUM_LEN;
INIT_RETRY_CNT();
if(onoroff == OFF){
PRINTF("stm32w: Radio is off, turning it on.\r\n");
ST_RadioWake();
ENERGEST_ON(ENERGEST_TYPE_LISTEN);
}
LED_TX_ON();
if(ST_RadioTransmit(stm32w_txbuf)==ST_SUCCESS){
ENERGEST_OFF(ENERGEST_TYPE_LISTEN);
ENERGEST_ON(ENERGEST_TYPE_TRANSMIT);
PRINTF("stm32w: sending %d bytes\r\n", payload_len);
#if DEBUG > 1
for(u8_t c=1; c <= stm32w_txbuf[0]-2; c++){
PRINTF("%x:",stm32w_txbuf[c]);
}
PRINTF("\r\n");
#endif
#if RADIO_WAIT_FOR_PACKET_SENT
if(wait_for_tx()){
PRINTF("stm32w: unknown tx error.\r\n");
TO_PREV_STATE();
LED_TX_OFF();
return RADIO_TX_ERR;
}
TO_PREV_STATE();
if(last_tx_status == ST_SUCCESS || last_tx_status == ST_PHY_ACK_RECEIVED){
return RADIO_TX_OK;
}
LED_TX_OFF();
return RADIO_TX_ERR;
#else /* RADIO_WAIT_FOR_PACKET_SENT */
TO_PREV_STATE();
LED_TX_OFF();
return RADIO_TX_OK;
#endif /* RADIO_WAIT_FOR_PACKET_SENT */
}
TO_PREV_STATE();
PRINTF("stm32w: transmission never started.\r\n");
/* TODO: Do we have to retransmit? */
CLEAN_TXBUF();
LED_TX_OFF();
return RADIO_TX_ERR;
}
/*---------------------------------------------------------------------------*/
static int stm32w_radio_send(const void *payload, unsigned short payload_len)
{
if(stm32w_radio_prepare(payload, payload_len) == RADIO_TX_ERR)
return RADIO_TX_ERR;
return stm32w_radio_transmit(payload_len);
}
/*---------------------------------------------------------------------------*/
static int stm32w_radio_channel_clear(void)
{
return ST_RadioChannelIsClear();
}
/*---------------------------------------------------------------------------*/
static int stm32w_radio_receiving_packet(void)
{
return receiving_packet;
}
/*---------------------------------------------------------------------------*/
static int stm32w_radio_pending_packet(void)
{
return !RXBUFS_EMPTY();
}
/*---------------------------------------------------------------------------*/
static int stm32w_radio_off(void)
{
/* Any transmit or receive packets in progress are aborted.
* Waiting for end of transmission or reception have to be done.
*/
if(onoroff == ON){
ST_RadioSleep();
onoroff = OFF;
CLEAN_TXBUF();
CLEAN_RXBUFS();
ENERGEST_OFF(ENERGEST_TYPE_LISTEN);
}
return 1;
}
/*---------------------------------------------------------------------------*/
static int stm32w_radio_on(void)
{
if(onoroff == OFF){
ST_RadioWake();
onoroff = ON;
ENERGEST_ON(ENERGEST_TYPE_LISTEN);
}
return 1;
}
/*---------------------------------------------------------------------------*/
void ST_RadioReceiveIsrCallback(u8 *packet,
boolean ackFramePendingSet,
u32 time,
u16 errors,
s8 rssi)
{
LED_RX_ON();
receiving_packet = 0;
/* Copy packet into the buffer. It is better to do this here. */
if(add_to_rxbuf(packet)){
process_poll(&stm32w_radio_process);
last_rssi = rssi;
}
LED_RX_OFF();
}
void ST_RadioTransmitCompleteIsrCallback(StStatus status,
u32 txSyncTime,
boolean framePending)
{
ENERGEST_OFF(ENERGEST_TYPE_TRANSMIT);
ENERGEST_ON(ENERGEST_TYPE_LISTEN);
LED_TX_OFF();
last_tx_status = status;
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();
}
}
/* Debug outputs. */
if(status == ST_SUCCESS || status == ST_PHY_ACK_RECEIVED){
PRINTF("TX_END");
}
else if (status == ST_MAC_NO_ACK_RECEIVED){
PRINTF("TX_END_NOACK!!!");
}
else if (status == ST_PHY_TX_CCA_FAIL){
PRINTF("TX_END_CCA!!!");
}
else if(status == ST_PHY_TX_UNDERFLOW){
PRINTF("TX_END_UFL!!!");
}
else {
PRINTF("TX_END_INCOMPL!!!");
}
}
boolean ST_RadioDataPendingShortIdIsrCallback(int16u shortId) {
receiving_packet = 1;
return FALSE;
}
boolean ST_RadioDataPendingLongIdIsrCallback(int8u* longId) {
receiving_packet = 1;
return FALSE;
}
/*---------------------------------------------------------------------------*/
PROCESS_THREAD(stm32w_radio_process, ev, data)
{
int len;
PROCESS_BEGIN();
PRINTF("stm32w_radio_process: started\r\n");
while(1) {
PROCESS_YIELD_UNTIL(ev == PROCESS_EVENT_POLL);
PRINTF("stm32w_radio_process: calling receiver callback\r\n");
#if DEBUG > 1
for(u8_t c=1; c <= RCVD_PACKET_LEN; c++){
PRINTF("%x",stm32w_rxbuf[c]);
}
PRINTF("\r\n");
#endif
packetbuf_clear();
len = stm32w_radio_read(packetbuf_dataptr(), PACKETBUF_SIZE);
if(len > 0) {
packetbuf_set_datalen(len);
NETSTACK_RDC.input();
}
if(!RXBUFS_EMPTY()){
// Some data packet still in rx buffer (this appens because process_poll doesn't queue requests),
// so stm32w_radio_process need to be called again.
process_poll(&stm32w_radio_process);
}
}
PROCESS_END();
}
/*---------------------------------------------------------------------------*/
static int stm32w_radio_read(void *buf, unsigned short bufsize)
{
return read_from_rxbuf(buf,bufsize);
}
/*---------------------------------------------------------------------------*/
void ST_RadioOverflowIsrCallback(void)
{
PRINTF("OVERFLOW\r\n");
}
/*---------------------------------------------------------------------------*/
void ST_RadioSfdSentIsrCallback(u32 sfdSentTime)
{
}
/*---------------------------------------------------------------------------*/
void ST_RadioMacTimerCompareIsrCallback(void)
{
}
/*---------------------------------------------------------------------------*/
static int add_to_rxbuf(uint8_t * src)
{
if(RXBUFS_FULL()){
return 0;
}
memcpy(stm32w_rxbufs[last], src, src[0] + 1);
#if RADIO_RXBUFS > 1
last = (last + 1) % RADIO_RXBUFS;
if(first == -1){
first = 0;
}
#endif
return 1;
}
/*---------------------------------------------------------------------------*/
static int read_from_rxbuf(void * dest, unsigned short len)
{
if(RXBUFS_EMPTY()){ // Buffers are all empty
return 0;
}
if(stm32w_rxbufs[first][0] > len){ // Too large packet for dest.
len = 0;
}
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
ATOMIC(
first = (first + 1) % RADIO_RXBUFS;
int first_tmp = first;
if(first_tmp == last){
CLEAN_RXBUFS();
}
)
#else
CLEAN_RXBUFS();
#endif
return len;
}
/*---------------------------------------------------------------------------*/
short last_packet_rssi(){
return last_rssi;
}

View file

@ -0,0 +1,57 @@
/*
* Copyright (c) 2007, 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.
*
* This file is part of the Contiki operating system.
*
* $Id: stm32w-radio.h,v 1.1 2010/10/25 09:03:39 salvopitru Exp $
*/
/**
* \file
* STM32W radio driver header file
* \author
* Adam Dunkels <adam@sics.se>
*/
#ifndef __STM32W_H__
#define __STM32W_H__
#include "contiki.h"
#include "dev/radio.h"
#include "hal/hal.h"
#include "simplemac/include/phy-library.h"
int stm32w_radio_set_channel(u8_t channel);
short last_packet_rssi();
#define STM32W_MAX_PACKET_LEN 127
extern const struct radio_driver stm32w_radio_driver;
#endif /* __STM32W_H__ */

View file

@ -0,0 +1,174 @@
/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
* File Name : stm32f10x_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 "stm32w_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

@ -0,0 +1,181 @@
/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
* File Name : stm32f10x_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

@ -0,0 +1,109 @@
/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
* File Name : stm32f10x_systick.h
* Author : MCD Application Team
* Version : V2.0.3
* Date : 09/22/2008
* Description : This file contains all the functions prototypes for the
* SysTick firmware library.
********************************************************************************
* 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 __STM32W_SYSTICK_H
#define __STM32W_SYSTICK_H
#include "stm32w_type.h"
#include "stm32w_conf.h"
#ifndef EXT
#define EXT extern
#endif /* EXT */
typedef struct
{
vu32 CTRL;
vu32 LOAD;
vu32 VAL;
vuc32 CALIB;
} SysTick_TypeDef;
/* System Control Space memory map */
#define SCS_BASE ((u32)0xE000E000)
#define SysTick_BASE (SCS_BASE + 0x0010)
#define NVIC_BASE (SCS_BASE + 0x0100)
#define SCB_BASE (SCS_BASE + 0x0D00)
#ifdef _SysTick
#define SysTick ((SysTick_TypeDef *) SysTick_BASE)
#endif /*_SysTick */
/***************** Bit definition for SysTick_CTRL register *****************/
#define SysTick_CTRL_ENABLE ((u32)0x00000001) /* Counter enable */
#define SysTick_CTRL_TICKINT ((u32)0x00000002) /* Counting down to 0 pends the SysTick handler */
#define SysTick_CTRL_CLKSOURCE ((u32)0x00000004) /* Clock source */
#define SysTick_CTRL_COUNTFLAG ((u32)0x00010000) /* Count Flag */
/***************** 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 */
/***************** Bit definition for SysTick_VAL register ******************/
#define SysTick_VAL_CURRENT ((u32)0x00FFFFFF) /* Current value at the time the register is accessed */
/***************** Bit definition for SysTick_CALIB register ****************/
#define SysTick_CALIB_TENMS ((u32)0x00FFFFFF) /* Reload value to use for 10ms timing */
#define SysTick_CALIB_SKEW ((u32)0x40000000) /* Calibration value is not exactly 10 ms */
#define SysTick_CALIB_NOREF ((u32)0x80000000) /* The reference clock is not provided */
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* SysTick clock source */
#define SysTick_CLKSource_HCLK_Div8 ((u32)0xFFFFFFFB)
#define SysTick_CLKSource_HCLK ((u32)0x00000004)
#define IS_SYSTICK_CLK_SOURCE(SOURCE) (((SOURCE) == SysTick_CLKSource_HCLK) || \
((SOURCE) == SysTick_CLKSource_HCLK_Div8))
/* SysTick counter state */
#define SysTick_Counter_Disable ((u32)0xFFFFFFFE)
#define SysTick_Counter_Enable ((u32)0x00000001)
#define SysTick_Counter_Clear ((u32)0x00000000)
#define IS_SYSTICK_COUNTER(COUNTER) (((COUNTER) == SysTick_Counter_Disable) || \
((COUNTER) == SysTick_Counter_Enable) || \
((COUNTER) == SysTick_Counter_Clear))
/* SysTick Flag */
#define SysTick_FLAG_COUNT ((u32)0x00000010)
#define SysTick_FLAG_SKEW ((u32)0x0000001E)
#define SysTick_FLAG_NOREF ((u32)0x0000001F)
#define IS_SYSTICK_FLAG(FLAG) (((FLAG) == SysTick_FLAG_COUNT) || \
((FLAG) == SysTick_FLAG_SKEW) || \
((FLAG) == SysTick_FLAG_NOREF))
#define IS_SYSTICK_RELOAD(RELOAD) (((RELOAD) > 0) && ((RELOAD) <= 0xFFFFFF))
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
void SysTick_CLKSourceConfig(u32 SysTick_CLKSource);
void SysTick_SetReload(u32 Reload);
void SysTick_CounterCmd(u32 SysTick_Counter);
void SysTick_ITConfig(FunctionalState NewState);
u32 SysTick_GetCounter(void);
FlagStatus SysTick_GetFlagStatus(u8 SysTick_FLAG);
#endif /* __STM32F10x_SYSTICK_H */
/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/

View file

@ -0,0 +1,80 @@
/******************** (C) COPYRIGHT 2008 STMicroelectronics ********************
* File Name : stm32f10x_type.h
* Author : MCD Application Team
* Version : V2.0.3
* Date : 09/22/2008
* Description : This file contains all the common data types used for the
* STM32F10x firmware library.
********************************************************************************
* 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_TYPE_H
#define __STM32F10x_TYPE_H
/* Includes ------------------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
typedef signed long s32;
typedef signed short s16;
typedef signed char s8;
typedef signed long const sc32; /* Read Only */
typedef signed short const sc16; /* Read Only */
typedef signed char const sc8; /* Read Only */
typedef volatile signed long vs32;
typedef volatile signed short vs16;
typedef volatile signed char vs8;
typedef volatile signed long const vsc32; /* Read Only */
typedef volatile signed short const vsc16; /* Read Only */
typedef volatile signed char const vsc8; /* Read Only */
typedef unsigned long u32;
typedef unsigned short u16;
typedef unsigned char u8;
typedef unsigned long const uc32; /* Read Only */
typedef unsigned short const uc16; /* Read Only */
typedef unsigned char const uc8; /* Read Only */
typedef volatile unsigned long vu32;
typedef volatile unsigned short vu16;
typedef volatile unsigned char vu8;
typedef volatile unsigned long const vuc32; /* Read Only */
typedef volatile unsigned short const vuc16; /* Read Only */
typedef volatile unsigned char const vuc8; /* Read Only */
//typedef enum {FALSE = 0, TRUE = !FALSE} bool;
typedef enum {RESET = 0, SET = !RESET} FlagStatus, ITStatus;
typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;
#define IS_FUNCTIONAL_STATE(STATE) (((STATE) == DISABLE) || ((STATE) == ENABLE))
typedef enum {ERROR = 0, SUCCESS = !ERROR} ErrorStatus;
#define U8_MAX ((u8)255)
#define S8_MAX ((s8)127)
#define S8_MIN ((s8)-128)
#define U16_MAX ((u16)65535u)
#define S16_MAX ((s16)32767)
#define S16_MIN ((s16)-32768)
#define U32_MAX ((u32)4294967295uL)
#define S32_MAX ((s32)2147483647)
#define S32_MIN ((s32)-2147483648)
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
#endif /* __STM32F10x_TYPE_H */
/******************* (C) COPYRIGHT 2008 STMicroelectronics *****END OF FILE****/

View file

@ -0,0 +1,67 @@
#include <stdio.h>
#include "dev/uart1.h"
#include PLATFORM_HEADER
#include "hal/micro/micro-common.h"
#include "hal/micro/cortexm3/micro-common.h"
//#include "uart.h"
#ifdef __GNUC__
# define _LLIO_STDIN ((int) stdin)
# define _LLIO_STDOUT ((int) stdout)
# define _LLIO_STDERR ((int) stderr)
# define _LLIO_ERROR (-1)
#else
# ifdef __ICCARM__
# include <yfuns.h>
# endif
#endif
void __io_putchar(char c)
{
uart1_writeb(c);
}
#undef putchar
int putchar(int c)
{
__io_putchar((char) c);
return c;
}
size_t _write(int handle, const unsigned char * buffer, size_t size)
{
size_t nChars = 0;
if (handle != _LLIO_STDOUT && handle != _LLIO_STDERR) {
return _LLIO_ERROR;
}
if (buffer == 0) {
// This means that we should flush internal buffers.
//spin until TX complete (TX is idle)
while ((SC1_UARTSTAT&SC_UARTTXIDLE)!=SC_UARTTXIDLE) {}
return 0;
}
// ensure port is configured for UART
if(SC1_MODE != SC1_MODE_UART) {
return _LLIO_ERROR;
}
while(size--) {
__io_putchar(*buffer++);
++nChars;
}
return nChars;
}
size_t _read(int handle, unsigned char * buffer, size_t size)
{
return 0;
}

225
cpu/stm32w108/dev/uart1.c Normal file
View file

@ -0,0 +1,225 @@
/*
* 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.
*
* This file is part of the Contiki OS
*
*/
/*---------------------------------------------------------------------------*/
/**
* \file
* Machine dependent STM32W UART1 code.
* \author
* Salvatore Pitrulli
* \version
* 0.1
* \since
* 03.04.2010
*/
/*---------------------------------------------------------------------------*/
#include <stdio.h>
#include <stdlib.h>
//#include <io.h>
//#include <signal.h>
#include "sys/energest.h"
#include "dev/uart1.h"
#include "dev/watchdog.h"
#include "lib/ringbuf.h"
#include "dev/leds.h"
static int (*uart1_input_handler)(unsigned char c);
static volatile uint8_t transmitting;
#ifdef UART1_CONF_TX_WITH_INTERRUPT
#define TX_WITH_INTERRUPT UART1_CONF_TX_WITH_INTERRUPT
#else /* UART1_CONF_TX_WITH_INTERRUPT */
#define TX_WITH_INTERRUPT 1
#endif /* UART1_CONF_TX_WITH_INTERRUPT */
#if TX_WITH_INTERRUPT
#ifdef UART1_CONF_TX_BUFSIZE
#define UART1_TX_BUFSIZE UART1_CONF_TX_BUFSIZE
#else /* UART1_CONF_TX_BUFSIZE */
#define UART1_TX_BUFSIZE 64
#endif /* UART1_CONF_TX_BUFSIZE */
static struct ringbuf txbuf;
static uint8_t txbuf_data[UART1_TX_BUFSIZE];
#endif /* TX_WITH_INTERRUPT */
/*---------------------------------------------------------------------------*/
//uint8_t
//uart1_active(void)
//{
// return ((~ UTCTL1) & TXEPT) | transmitting;
//}
/*---------------------------------------------------------------------------*/
void
uart1_set_input(int (*input)(unsigned char c))
{
uart1_input_handler = input;
}
/*---------------------------------------------------------------------------*/
void
uart1_writeb(unsigned char c)
{
watchdog_periodic();
#if TX_WITH_INTERRUPT
/* 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
until it is possible to put it there. */
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(transmitting == 0) {
transmitting = 1;
SC1_DATA = ringbuf_get(&txbuf);
INT_SC1FLAG = INT_SCTXFREE;
INT_SC1CFG |= INT_SCTXFREE;
}
#else /* TX_WITH_INTERRUPT */
/* Loop until the transmission buffer is available. */
while((INT_SC1FLAG & INT_SCTXFREE) == 0);
/* Transmit the data. */
SC1_DATA = c;
INT_SC1FLAG = INT_SCTXFREE;
#endif /* TX_WITH_INTERRUPT */
}
/*---------------------------------------------------------------------------*/
#if ! WITH_UIP /* If WITH_UIP is defined, putchar() is defined by the SLIP driver */
#endif /* ! WITH_UIP */
/*---------------------------------------------------------------------------*/
/**
* Initalize the RS232 port.
*
*/
void
uart1_init(unsigned long ubr)
{
GPIO_PBCFGL &= 0xF00F;
GPIO_PBCFGL |= 0x0490;
u16_t uartper = (u32_t)24e6/(2*ubr);
u32_t rest = (u32_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
transmitting = 0;
#if TX_WITH_INTERRUPT
ringbuf_init(&txbuf, txbuf_data, sizeof(txbuf_data));
#endif /* TX_WITH_INTERRUPT */
INT_SC1FLAG = 0xFFFF;
INT_CFGSET = INT_SC1;
}
/*---------------------------------------------------------------------------*/
void uart1_rx_interrupt(void);
void uart1_tx_interrupt(void);
void halSc1Isr(void)
{
ENERGEST_ON(ENERGEST_TYPE_IRQ);
if(INT_SC1FLAG & INT_SCRXVAL){
uart1_rx_interrupt();
INT_SC1FLAG = INT_SCRXVAL;
}
#if TX_WITH_INTERRUPT
else if(INT_SC1FLAG & INT_SCTXFREE){
uart1_tx_interrupt();
INT_SC1FLAG = INT_SCTXFREE;
}
#endif /* TX_WITH_INTERRUPT */
ENERGEST_OFF(ENERGEST_TYPE_IRQ);
}
void uart1_rx_interrupt(void)
{
uint8_t c;
c = SC1_DATA;
if(uart1_input_handler != NULL) {
uart1_input_handler(c);
}
}
/*---------------------------------------------------------------------------*/
#if TX_WITH_INTERRUPT
void uart1_tx_interrupt(void)
{
if(ringbuf_elements(&txbuf) == 0) {
transmitting = 0;
INT_SC1CFG &= ~INT_SCTXFREE;
} else {
SC1_DATA = ringbuf_get(&txbuf);
}
}
#endif /* TX_WITH_INTERRUPT */
/*---------------------------------------------------------------------------*/

53
cpu/stm32w108/dev/uart1.h Normal file
View file

@ -0,0 +1,53 @@
/*
* Copyright (c) 2007, 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.
*
* This file is part of the Contiki operating system.
*
* $Id: uart1.h,v 1.1 2010/10/25 09:03:39 salvopitru Exp $
*/
/**
* \file
* A brief description of what this file is.
* \author
* Adam Dunkels <adam@sics.se>
*/
#ifndef __UART1_H__
#define __UART1_H__
//#include "msp430.h"
//
//#define UART1_BAUD2UBR(baud) ((MSP430_CPU_SPEED)/(baud))
void uart1_set_input(int (*input)(unsigned char c));
void uart1_writeb(unsigned char c);
void uart1_init(unsigned long ubr);
//uint8_t uart1_active(void);
#endif /* __UART1_H__ */

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,18 @@
<hr size="1">
<table border="0" cellspacing="0" cellpadding="0" width=100%>
<tr>
<td><address><small>
$projectname. <br>
$projectnumber.
</small></address>
</td>
<td align="right">
<address><small>
Copyright &copy; 2009 by STMicrolectronics. All rights reserved.<br>
Generated $datetime with <a href="http://www.doxygen.org/index.html">Doxygen</a> $doxygenversion.
</small></address>
</td>
</tr>
</table>
</body>
</html>

View file

@ -0,0 +1,16 @@
<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN">
<html><head><meta http-equiv="Content-Type" content="text/html;charset=iso-8859-1">
<title>$title</title>
<LINK HREF="doxygen.css" REL="stylesheet" TYPE="text/css">
</head><body>
<table border="0" cellspacing="0" cellpadding="0" width=100%>
<tr>
<td><img src="ST_Logo.gif"></td>
<td> <div class="qindex">
<a class="qindex" href="index.html">Home</a>&nbsp;
| &nbsp;<a class="qindex" href="modules.html">Modules</a>&nbsp;
| &nbsp;<a class="qindex" href="annotated.html">Data Structures</a>&nbsp;
| &nbsp;<a class="qindex" href="files.html">File List</a>&nbsp;
| &nbsp;<a class="qindex" href="globals.html">Index</a></div>
</td>
</table>

Binary file not shown.

After

Width:  |  Height:  |  Size: 1.1 KiB

View file

@ -0,0 +1,5 @@
all:
doxygen Doxygen_Release
cp ST_Logo.gif html
clean:
- rm -fr html

File diff suppressed because it is too large Load diff

56
cpu/stm32w108/hal/error.h Normal file
View file

@ -0,0 +1,56 @@
/**
* @file error.h
* @brief Return codes for API functions and module definitions.
*
* See @ref status_codes for documentation.
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
#ifndef __ERRORS_H__
#define __ERRORS_H__
/**
* @brief Return type for St functions.
*/
#ifndef __STSTATUS_TYPE__
#define __STSTATUS_TYPE__
typedef int8u StStatus;
#endif //__STSTATUS_TYPE__
/**
* @addtogroup status_codes
* @{
*/
/**
* @brief Macro used by error-def.h to define all of the return codes.
*
* @param symbol The name of the constant being defined. All St returns
* begin with ST_. For example, ::ST_CONNECTION_OPEN.
*
* @param value The value of the return code. For example, 0x61.
*/
#define DEFINE_ERROR(symbol, value) \
ST_ ## symbol = value,
enum {
#ifndef DOXYGEN_SHOULD_SKIP_THIS
#include "error-def.h"
#endif //DOXYGEN_SHOULD_SKIP_THIS
/** Gets defined as a count of all the possible return codes in the
* StZNet stack API.
*/
ST_ERROR_CODE_COUNT
};
#undef DEFINE_ERROR
#endif // __ERRORS_H__
/**@} // End of addtogroup
*/

43
cpu/stm32w108/hal/hal.h Normal file
View file

@ -0,0 +1,43 @@
/** @file hal/hal.h
* @brief Generic set of HAL includes for all platforms.
*
* See also @ref hal for more documentation.
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
/** @addtogroup hal
* @if STM32W10XX
* <center><h1>STM32W108xx Microprocessors</h1></center>
* @endif
*
* HAL function names have the following conventions:
*
* <b>HAL which SimpleMAC library depends upon:</b> API that is required for proper operation of the SimpleMAC library. As with all of the HAL, it is provided as source and it is possible for the end customer to modify this code. However, unlike other portions of the HAL, if the customer does modify this code, it must ensure that equivalent functionality is still provided to ensure proper operation of the SimpleMAC library.
*
*
* <b>HAL for other chip capabilities:</b> API which SimpleMAC does not directly depend on. However, much of this functionality may be required for proper operation of all features of the chip.
*
* <b>Additional HAL for sample applications:</b> API which is included to assist the development of the included sample applications. This functionality may be very useful, but is not required for proper operation of the chip. This code and functionality may be freely modified by the end customer.
*
* <br><br>
*
* See also hal.h.
*/
#ifndef __HAL_H__
#define __HAL_H__
// Keep micro first for specifics used by other headers
#include "micro/micro-common.h"
#include "micro/cortexm3/micro-common.h"
#include "micro/led.h"
#include "micro/button.h"
#include "micro/system-timer.h"
#include "micro/cortexm3/nvm.h"
#include "hal/micro/cortexm3/uart.h"
#endif //__HAL_H__

View file

@ -0,0 +1,303 @@
/** @file /hal/micro/adc.h
* @brief Header for A/D converter.
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
/** @addtogroup adc
* Sample A/D converter driver.
*
* See adc.h for source code.
*
* @note Stm32w108xx ADC driver support is preliminary and essentailly untested -
* please do not attempt to use this ADC driver on this platform.
*
* @note Except for the Stm32w108xx, the StZNet stack does use these functions.
*
* To use the ADC system, include this file and ensure that
* ::halInternalInitAdc() is called whenever the microcontroller is
* started. Call ::halInternalSleepAdc() to sleep the module and
* ::halInternalInitAdc() to wake up the module.
*
* A "user" is a separate thread of execution and usage. That is,
* internal St code is one user and clients are a different user.
* But a client that is calling the ADC in two different functions
* constitutes only one user, as long as the ADC access is not
* interleaved.
*
* @note This code does not allow access to the continuous reading mode of
* the ADC, which some clients may require.
*
* Many functions in this file return an ::StStatus value. See
* error-def.h for definitions of all ::StStatus return values.
*
*@{
*/
#ifndef __ADC_H__
#define __ADC_H__
// A type for the ADC User enumeration.
typedef int8u ADCUser;
enum
{
/** LQI User ID. */
ADC_USER_LQI = 0,
/** Application User ID */
ADC_USER_APP = 1,
/** Application User ID */
ADC_USER_APP2 = 2
};
/** @brief Be sure to update ::NUM_ADC_USERS if additional users are added
* to the ::ADCUser list.
*/
#define NUM_ADC_USERS 3 // make sure to update if the above is adjusted
// A type for the reference enumeration.
typedef int8u ADCReferenceType;
enum
{
/** AREF pin reference. */
ADC_REF_AREF = 0x00,
/** AVCC pin reference. */
ADC_REF_AVCC = 0x40,
/** Internal reference. */
ADC_REF_INT = 0xC0
};
// A type for the rate enumeration.
typedef int8u ADCRateType;
enum
{
/** Rate 32 us, 5 effective bits in ADC_DATA[15:11] */
ADC_CONVERSION_TIME_US_32 = 0x0,
/** Rate 64 us, 6 effective bits in ADC_DATA[15:10] */
ADC_CONVERSION_TIME_US_64 = 0x1,
/** Rate 128 us, 7 effective bits in ADC_DATA[15:9] */
ADC_CONVERSION_TIME_US_128 = 0x2,
/** Rate 256 us, 8 effective bits in ADC_DATA[15:8] */
ADC_CONVERSION_TIME_US_256 = 0x3,
/** Rate 512 us, 9 effective bits in ADC_DATA[15:7] */
ADC_CONVERSION_TIME_US_512 = 0x4,
/** Rate 1024 us, 10 effective bits in ADC_DATA[15:6] */
ADC_CONVERSION_TIME_US_1024 = 0x5,
/** Rate 2048 us, 11 effective bits in ADC_DATA[15:5] */
ADC_CONVERSION_TIME_US_2048 = 0x6,
/** Rate 4096 us, 12 effective bits in ADC_DATA[15:4] */
ADC_CONVERSION_TIME_US_4096 = 0x7,
};
#if defined (CORTEXM3)
/** Channel 0 : ADC0 on PB5 */
#define ADC_MUX_ADC0 0x0
/** Channel 1 : ADC0 on PB6 */
#define ADC_MUX_ADC1 0x1
/** Channel 2 : ADC0 on PB7 */
#define ADC_MUX_ADC2 0x2
/** Channel 3 : ADC0 on PC1 */
#define ADC_MUX_ADC3 0x3
/** Channel 4 : ADC0 on PA4 */
#define ADC_MUX_ADC4 0x4
/** Channel 5 : ADC0 on PA5 */
#define ADC_MUX_ADC5 0x5
/** Channel 8 : VSS (0V) - not for high voltage range */
#define ADC_MUX_GND 0x8
/** Channel 9 : VREF/2 (0.6V) */
#define ADC_MUX_VREF2 0x9
/** Channel A : VREF (1.2V)*/
#define ADC_MUX_VREF 0xA
/** Channel B : Regulator/2 (0.9V) - not for high voltage range */
#define ADC_MUX_VREG2 0xB
// ADC_SOURCE_<pos>_<neg> selects <pos> as the positive input and <neg> as
// the negative input.
enum
{
ADC_SOURCE_ADC0_VREF2 = ((ADC_MUX_ADC0 <<ADC_MUXN_BITS) + ADC_MUX_VREF2),
ADC_SOURCE_ADC0_GND = ((ADC_MUX_ADC0 <<ADC_MUXN_BITS) + ADC_MUX_GND),
ADC_SOURCE_ADC1_VREF2 = ((ADC_MUX_ADC1 <<ADC_MUXN_BITS) + ADC_MUX_VREF2),
ADC_SOURCE_ADC1_GND = ((ADC_MUX_ADC1 <<ADC_MUXN_BITS) + ADC_MUX_GND),
ADC_SOURCE_ADC2_VREF2 = ((ADC_MUX_ADC2 <<ADC_MUXN_BITS) + ADC_MUX_VREF2),
ADC_SOURCE_ADC2_GND = ((ADC_MUX_ADC2 <<ADC_MUXN_BITS) + ADC_MUX_GND),
ADC_SOURCE_ADC3_VREF2 = ((ADC_MUX_ADC3 <<ADC_MUXN_BITS) + ADC_MUX_VREF2),
ADC_SOURCE_ADC3_GND = ((ADC_MUX_ADC3 <<ADC_MUXN_BITS) + ADC_MUX_GND),
ADC_SOURCE_ADC4_VREF2 = ((ADC_MUX_ADC4 <<ADC_MUXN_BITS) + ADC_MUX_GND),
ADC_SOURCE_ADC5_VREF2 = ((ADC_MUX_ADC5 <<ADC_MUXN_BITS) + ADC_MUX_GND),
ADC_SOURCE_ADC1_ADC0 = ((ADC_MUX_ADC1 <<ADC_MUXN_BITS) + ADC_MUX_ADC0),
ADC_SOURCE_ADC0_ADC1 = ((ADC_MUX_ADC1 <<ADC_MUXN_BITS) + ADC_MUX_ADC0),
ADC_SOURCE_ADC3_ADC2 = ((ADC_MUX_ADC3 <<ADC_MUXN_BITS) + ADC_MUX_ADC2),
ADC_SOURCE_ADC2_ADC3 = ((ADC_MUX_ADC3 <<ADC_MUXN_BITS) + ADC_MUX_ADC2),
ADC_SOURCE_ADC5_ADC4 = ((ADC_MUX_ADC5 <<ADC_MUXN_BITS) + ADC_MUX_ADC4),
ADC_SOURCE_GND_VREF2 = ((ADC_MUX_GND <<ADC_MUXN_BITS) + ADC_MUX_VREF2),
ADC_SOURCE_VGND = ((ADC_MUX_GND <<ADC_MUXN_BITS) + ADC_MUX_GND),
ADC_SOURCE_VREF_VREF2 = ((ADC_MUX_VREF <<ADC_MUXN_BITS) + ADC_MUX_VREF2),
ADC_SOURCE_VREF = ((ADC_MUX_VREF <<ADC_MUXN_BITS) + ADC_MUX_GND),
/* Modified the original ADC driver for enabling the ADC extended range mode required for
supporting the STLM20 temperature sensor.
NOTE:
The ADC extended range is inaccurate due to the high voltage mode bug of the general purpose ADC
(see STM32W108 errata). As consequence, it is not reccomended to use this ADC driver for getting
the temperature values
*/
#ifdef ENABLE_ADC_EXTENDED_RANGE_BROKEN
ADC_SOURCE_VREF2_VREF2 = ((ADC_MUX_VREF2 <<ADC_MUXN_BITS) + ADC_MUX_VREF2),
ADC_SOURCE_VREF2 = ((ADC_MUX_VREF2 <<ADC_MUXN_BITS) + ADC_MUX_GND),
#endif /* ENABLE_ADC_EXTENDED_RANGE_BROKEN */
ADC_SOURCE_VREG2_VREF2 = ((ADC_MUX_VREG2 <<ADC_MUXN_BITS) + ADC_MUX_VREF2),
ADC_SOURCE_VDD_GND = ((ADC_MUX_VREG2 <<ADC_MUXN_BITS) + ADC_MUX_GND)
};
#endif // defined (CORTEXM3)
/** @brief A type for the channel enumeration
* (such as ::ADC_SOURCE_ADC0_GND)
*/
typedef int8u ADCChannelType;
/** @brief Initializes and powers-up the ADC.
*/
void halInternalInitAdc(void);
/** @brief Shuts down the voltage reference and ADC system to
* minimize power consumption in sleep.
*/
void halInternalSleepAdc(void);
/** @brief Starts an ADC conversion for the user specified by \c id.
*
* @appusage The application must set \c reference to the voltage
* reference desired (see the ADC references enum),
* set \c channel to the channel number
* required (see the ADC channel enum), and set \c rate to reflect the
* number of bits of accuracy desired (see the ADC rates enum)
*
* @param id An ADC user.
*
* @param reference Voltage reference to use, chosen from enum
*
* @param channel Microprocessor channel number.
*
* @param rate rate number (see the ADC rate enum).
*
* @return One of the following:
* - ADC_CONVERSION_DEFERRED if the conversion is still waiting
* to start.
* - ADC_CONVERSION_BUSY if the conversion is currently taking
* place.
* - ST_ERR_FATAL if a passed parameter is invalid.
*/
StStatus halStartAdcConversion(ADCUser id,
ADCReferenceType reference,
ADCChannelType channel,
ADCRateType rate);
/** @brief Returns the status of a pending conversion
* previously started by ::halStartAdcConversion(). If the conversion
* is complete, writes the raw register value of the conversion (the unaltered
* value taken directly from the ADC's data register) into \c value.
*
* @param id An ADC user.
*
* @param value Pointer to an int16u to be loaded with the new value.
*
* @return One of the following:
* - ::ST_ADC_CONVERSION_DONE if the conversion is complete.
* - ::ST_ADC_CONVERSION_DEFERRED if the conversion is still waiting
* to start.
* - ::ST_ADC_CONVERSION_BUSY if the conversion is currently taking
* place.
* - ::ST_ADC_NO_CONVERSION_PENDING if \c id does not have a pending
* conversion.
*/
StStatus halRequestAdcData(ADCUser id, int16u *value);
/** @brief Waits for the user's request to complete and then,
* if a conversion was done, writes the raw register value of the conversion
* (the unaltered value taken directly from the ADC's data register) into
* \c value and returns ::ADC_CONVERSION_DONE, or immediately
* returns ::ADC_NO_CONVERSION_PENDING.
*
* @param id An ADC user.
*
* @param value Pointer to an int16u to be loaded with the new value.
*
* @return One of the following:
* - ::ST_ADC_CONVERSION_DONE if the conversion is complete.
* - ::ST_ADC_NO_CONVERSION_PENDING if \c id does not have a pending
* conversion.
*/
StStatus halReadAdcBlocking(ADCUser id, int16u *value);
/** @brief Calibrates or recalibrates the ADC system.
*
* @appusage Use this function to (re)calibrate as needed. This function is
* intended for the microcontroller, which requires proper calibration to calculate
* a human readible value (a value in volts). If the app does not call this
* function, the first time (and only the first time) the function
* ::halConvertValueToVolts() is called, this function is invoked. To
* maintain accurate volt calculations, the application should call this
* whenever it expects the temperature of the micro to change.
*
* @param id An ADC user.
*
* @return One of the following:
* - ::ST_ADC_CONVERSION_DONE if the calibration is complete.
* - ::ST_ERR_FATAL if the calibration failed.
*/
StStatus halAdcCalibrate(ADCUser id);
/** @brief Convert the raw register value (the unaltered value taken
* directly from the ADC's data register) into a signed fixed point value with
* units 10^-4 Volts. The returned value will be in the range -12000 to
* +12000 (-1.2000 volts to +1.2000 volts).
*
* @appusage Use this function to get a human useful value.
*
* @param value An int16u to be converted.
*
* @return Volts as signed fixed point with units 10^-4 Volts.
*/
int16s halConvertValueToVolts(int16u value);
/** @brief Calibrates Vref to be 1.2V +/-10mV.
*
* @appusage This function must be called from halInternalInitAdc() before
* making ADC readings. This function is not intended to be called from any
* function other than halInternalInitAdc(). This function ensures that the
* master cell voltage and current bias values are calibrated before
* calibrating Vref.
*/
void stCalibrateVref(void);
#ifdef CORTEXM3
void halAdcSetClock(boolean fast);
void halAdcSetRange(boolean high);
boolean halAdcGetClock(void);
boolean halAdcGetRange(void);
#endif
#endif // __ADC_H__
/** @} // END addtogroup
*/

View file

@ -0,0 +1,28 @@
/** @file /hal/micro/button.h
* @brief Header for button driver
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
#ifndef _BUTTON_H_
#define _BUTTON_H_
/* button status */
#define BUTTON_PRESSED 0
#define BUTTON_RELEASED 1
#define BUTTON_UNKNOWN 3
typedef int8u HalBoardButton;
/* Functions -----------------------------------------------------------------*/
/** @brief Init buttons */
void halInitButton(void);
/** @brief Get button status */
int8u halGetButtonStatus(HalBoardButton button);
#endif /* _BUTTON_H_ */
/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/

View file

@ -0,0 +1,349 @@
/** @file adc.c
* @brief ADC HAL functions
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
#include PLATFORM_HEADER
#include "hal/error.h"
#include "hal/hal.h"
#include "hal/micro/adc.h"
#if (NUM_ADC_USERS > 8)
#error NUM_ADC_USERS must not be greater than 8, or int8u variables in adc.c must be changed
#endif
static int16u adcData; // conversion result written by DMA
static int8u adcPendingRequests; // bitmap of pending requests
volatile static int8u adcPendingConversion; // id of pending conversion
static int8u adcReadingValid; // bitmap of valid adcReadings
static int16u adcReadings[NUM_ADC_USERS];
static int16u adcConfig[NUM_ADC_USERS];
static boolean adcCalibrated;
static int16s Nvss;
static int16s Nvdd;
/* Modified the original ADC driver for enabling the ADC extended range mode required for
supporting the STLM20 temperature sensor.
NOTE:
The ADC extended range is inaccurate due to the high voltage mode bug of the general purpose ADC
(see STM32W108 errata). As consequence, it is not reccomended to use this ADC driver for getting
the temperature values
*/
#ifdef ENABLE_ADC_EXTENDED_RANGE_BROKEN
static int16s Nvref;
static int16s Nvref2;
#endif /* ENABLE_ADC_EXTENDED_RANGE_BROKEN */
static int16u adcStaticConfig;
void halAdcSetClock(boolean slow)
{
if (slow) {
adcStaticConfig |= ADC_1MHZCLK_MASK;
} else {
adcStaticConfig &= ~ADC_1MHZCLK_MASK;
}
}
void halAdcSetRange(boolean high)
{
if (high) {
adcStaticConfig |= (ADC_HVSELP_MASK | ADC_HVSELN_MASK);
} else {
adcStaticConfig &= ~(ADC_HVSELP_MASK | ADC_HVSELN_MASK);
}
}
boolean halAdcGetClock(void)
{
/* Fix original function code */
return (adcStaticConfig & ADC_1MHZCLK_MASK) ? TRUE : FALSE;
}
boolean halAdcGetRange(void)
{
/* Fix original function code */
return (adcStaticConfig & ((ADC_HVSELP_MASK | ADC_HVSELN_MASK))) ? TRUE : FALSE;
}
// Define a channel field that combines ADC_MUXP and ADC_MUXN
#define ADC_CHAN (ADC_MUXP | ADC_MUXN)
#define ADC_CHAN_BIT ADC_MUXN_BIT
void halAdcIsr(void)
{
int8u i;
int8u conversion = adcPendingConversion; //fix 'volatile' warning; costs no flash
// make sure data is ready and the desired conversion is valid
if ( (INT_ADCFLAG & INT_ADCULDFULL)
&& (conversion < NUM_ADC_USERS) ) {
adcReadings[conversion] = adcData;
adcReadingValid |= BIT(conversion); // mark the reading as valid
// setup the next conversion if any
if (adcPendingRequests) {
for (i = 0; i < NUM_ADC_USERS; i++) {
if (BIT(i) & adcPendingRequests) {
adcPendingConversion = i; // set pending conversion
adcPendingRequests ^= BIT(i); //clear request: conversion is starting
ADC_CFG = adcConfig[i];
break; //conversion started, so we're done here (only one at a time)
}
}
} else { // no conversion to do
ADC_CFG = 0; // disable adc
adcPendingConversion = NUM_ADC_USERS; //nothing pending, so go "idle"
}
}
INT_ADCFLAG = 0xFFFF;
asm("DMB");
}
// An internal support routine called from functions below.
// Returns the user number of the started conversion, or NUM_ADC_USERS
// otherwise.
ADCUser startNextConversion()
{
int8u i;
ATOMIC (
// start the next requested conversion if any
if (adcPendingRequests && !(ADC_CFG & ADC_ENABLE)) {
for (i = 0; i < NUM_ADC_USERS; i++) {
if ( BIT(i) & adcPendingRequests) {
adcPendingConversion = i; // set pending conversion
adcPendingRequests ^= BIT(i); // clear request
ADC_CFG = adcConfig[i]; // set the configuration to desired
INT_ADCFLAG = 0xFFFF;
INT_CFGSET = INT_ADC;
}
}
} else {
i = NUM_ADC_USERS;
}
)
return i;
}
void halInternalInitAdc(void)
{
// reset the state variables
adcPendingRequests = 0;
adcPendingConversion = NUM_ADC_USERS;
adcCalibrated = FALSE;
adcStaticConfig = ADC_1MHZCLK | ADC_ENABLE; // init config: 1MHz, low voltage
// set all adcReadings as invalid
adcReadingValid = 0;
// turn off the ADC
ADC_CFG = 0; // disable ADC, turn off HV buffers
ADC_OFFSET = ADC_OFFSET_RESET;
ADC_GAIN = ADC_GAIN_RESET;
ADC_DMACFG = ADC_DMARST;
ADC_DMABEG = (int32u)&adcData;
ADC_DMASIZE = 1;
ADC_DMACFG = (ADC_DMAAUTOWRAP | ADC_DMALOAD);
// clear the ADC interrupts and enable
INT_ADCCFG = INT_ADCULDFULL;
INT_ADCFLAG = 0xFFFF;
INT_CFGSET = INT_ADC;
stCalibrateVref();
}
StStatus halStartAdcConversion(ADCUser id,
ADCReferenceType reference,
ADCChannelType channel,
ADCRateType rate)
{
if(reference != ADC_REF_INT)
return ST_ERR_FATAL;
// save the chosen configuration for this user
adcConfig[id] = ( ((rate << ADC_PERIOD_BIT) & ADC_PERIOD)
| ((channel << ADC_CHAN_BIT) & ADC_CHAN)
| adcStaticConfig);
// if the user already has a pending request, overwrite params
if (adcPendingRequests & BIT(id)) {
return ST_ADC_CONVERSION_DEFERRED;
}
ATOMIC (
// otherwise, queue the transaction
adcPendingRequests |= BIT(id);
// try and start the conversion if there is not one happening
adcReadingValid &= ~BIT(id);
)
if (startNextConversion() == id)
return ST_ADC_CONVERSION_BUSY;
else
return ST_ADC_CONVERSION_DEFERRED;
}
StStatus halRequestAdcData(ADCUser id, int16u *value)
{
//Both the ADC interrupt and the global interrupt need to be enabled,
//otherwise the ADC ISR cannot be serviced.
boolean intsAreOff = ( INTERRUPTS_ARE_OFF()
|| !(INT_CFGSET & INT_ADC)
|| !(INT_ADCCFG & INT_ADCULDFULL) );
StStatus stat;
ATOMIC (
// If interupts are disabled but the flag is set,
// manually run the isr...
//FIXME -= is this valid???
if( intsAreOff
&& ( (INT_CFGSET & INT_ADC) && (INT_ADCCFG & INT_ADCULDFULL) )) {
halAdcIsr();
}
// check if we are done
if (BIT(id) & adcReadingValid) {
*value = adcReadings[id];
adcReadingValid ^= BIT(id);
stat = ST_ADC_CONVERSION_DONE;
} else if (adcPendingRequests & BIT(id)) {
stat = ST_ADC_CONVERSION_DEFERRED;
} else if (adcPendingConversion == id) {
stat = ST_ADC_CONVERSION_BUSY;
} else {
stat = ST_ADC_NO_CONVERSION_PENDING;
}
)
return stat;
}
StStatus halReadAdcBlocking(ADCUser id, int16u *value)
{
StStatus stat;
do {
stat = halRequestAdcData(id, value);
if (stat == ST_ADC_NO_CONVERSION_PENDING)
break;
} while(stat != ST_ADC_CONVERSION_DONE);
return stat;
}
StStatus halAdcCalibrate(ADCUser id)
{
StStatus stat;
/* Modified the original ADC driver for enabling the ADC extended range mode required for
supporting the STLM20 temperature sensor.
NOTE:
The ADC extended range is inaccurate due to the high voltage mode bug of the general purpose ADC
(see STM32W108 errata). As consequence, it is not reccomended to use this ADC driver for getting
the temperature values
*/
#ifdef ENABLE_ADC_EXTENDED_RANGE_BROKEN
if(halAdcGetRange()){
halStartAdcConversion(id,
ADC_REF_INT,
ADC_SOURCE_VREF_VREF2,
ADC_CONVERSION_TIME_US_4096);
stat = halReadAdcBlocking(id, (int16u *)(&Nvref));
if (stat == ST_ADC_CONVERSION_DONE) {
halStartAdcConversion(id,
ADC_REF_INT,
ADC_SOURCE_VREF2_VREF2,
ADC_CONVERSION_TIME_US_4096);
stat = halReadAdcBlocking(id, (int16u *)(&Nvref2));
}
if (stat == ST_ADC_CONVERSION_DONE) {
adcCalibrated = TRUE;
} else {
adcCalibrated = FALSE;
stat = ST_ERR_FATAL;
}
return stat;
}
#endif /* ENABLE_ADC_EXTENDED_RANGE_BROKEN */
halStartAdcConversion(id,
ADC_REF_INT,
ADC_SOURCE_GND_VREF2,
ADC_CONVERSION_TIME_US_4096);
stat = halReadAdcBlocking(id, (int16u *)(&Nvss));
if (stat == ST_ADC_CONVERSION_DONE) {
halStartAdcConversion(id,
ADC_REF_INT,
ADC_SOURCE_VREG2_VREF2,
ADC_CONVERSION_TIME_US_4096);
stat = halReadAdcBlocking(id, (int16u *)(&Nvdd));
}
if (stat == ST_ADC_CONVERSION_DONE) {
Nvdd -= Nvss;
adcCalibrated = TRUE;
} else {
adcCalibrated = FALSE;
stat = ST_ERR_FATAL;
}
return stat;
}
// Use the ratio of the sample reading to the of VDD_PADSA/2, known to be 900mV,
// to convert to 100uV units.
// FIXME: support external Vref
// use #define of Vref, ignore VDD_PADSA
// FIXME: support high voltage range
// use Vref-Vref/2 to calibrate
// FIXME: check for mfg token specifying measured VDD_PADSA
int16s halConvertValueToVolts(int16u value)
{
int32s N;
int16s V;
int32s nvalue;
if (!adcCalibrated) {
halAdcCalibrate(ADC_USER_LQI);
}
if (adcCalibrated) {
/* Modified the original ADC driver for enabling the ADC extended range mode required for
supporting the STLM20 temperature sensor.
NOTE:
The ADC extended range is inaccurate due to the high voltage mode bug of the general purpose ADC
(see STM32W108 errata). As consequence, it is not reccomended to use this ADC driver for getting
the temperature values
*/
#ifdef ENABLE_ADC_EXTENDED_RANGE_BROKEN
if(halAdcGetRange()){ // High range.
N = (((int32s)value + Nvref - 2*Nvref2) << 16)/(2*(Nvref-Nvref2));
// 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
V = (int16s)((N*12000L) >> 16);
if (V > 21000) { // VDD_PADS ?
V = 21000;
}
}
else {
#endif /* ENABLE_ADC_EXTENDED_RANGE_BROKEN */
assert(Nvdd);
nvalue = value - Nvss;
// Convert input value (minus ground) to a fraction of VDD/2.
N = ((nvalue << 16) + Nvdd/2) / Nvdd;
// Calculate voltage with: V = (N * VDD/2) / (2^16) where VDD/2 = 0.9 volts
// 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
// which is only 10.2 bits).
V = (int16s)((N*9000L) >> 16);
if (V > 12000) {
V = 12000;
}
#ifdef ENABLE_ADC_EXTENDED_RANGE_BROKEN
}
#endif /* ENABLE_ADC_EXTENDED_RANGE_BROKEN */
} else {
V = -32768;
}
return V;
}

View file

@ -0,0 +1,56 @@
/** @file hal/micro/cortexm3/bootloader/fib-bootloader.h
* @brief Definition and description of FIB bootloader shared functions.
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
#ifndef __FIB_BOOTLOADER_H__
#define __FIB_BOOTLOADER_H__
//------------------------------------------------------------------------------
// Reset signatures.
#define FIB_RESET_GO_ZERO 0xF00F0100
// Reset signatures 0xF00F0100 to 0xF00F010F can be chosen using the go command.
#define FIB_RESET_GO_JUMP 0xF00F0110
#define FIB_RESET_BAUD_RATE 0xF00F0111
#define FIB_RESET_READ_UNPROTECT 0xF00F0112
#define FIB_RESET_GPIO_BOOTMODE 0xF00F0113
#define FIB_RESET_PART_DATA 0xF00F0114
#define FIB_RESET_NMI_HARD_FAULT 0xF00F0115
//------------------------------------------------------------------------------
// Status values.
typedef int32u FibStatus;
#define FIB_SUCCESS 0
#define FIB_ERR_UNALIGNED 1
#define FIB_ERR_INVALID_ADDRESS 2
#define FIB_ERR_INVALID_TYPE 3
#define FIB_ERR_WRITE_PROTECTED 4
#define FIB_ERR_WRITE_FAILED 5
#define FIB_ERR_ERASE_REQUIRED 6
#define FIB_ERR_VERIFY_FAILED 7
//------------------------------------------------------------------------------
// Erase types.
typedef int32u FibEraseType;
#define MFB_MASS_ERASE 0x01
#define MFB_PAGE_ERASE 0x02
#define CIB_ERASE 0x03
#define DO_ERASE 0x0100
#define DO_VERIFY 0x0200
//------------------------------------------------------------------------------
// Shared flash functions.
FibStatus fibFlashWrite(int32u address, int8u *data,
int32u writeLength, int32u verifyLength);
FibStatus fibFlashErase(FibEraseType eraseType, int32u address);
#endif //__FIB_BOOTLOADER_H__

View file

@ -0,0 +1,29 @@
/** @file /hal/micro/cortexm3/button.c
* @brief button APIs
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
#include PLATFORM_HEADER
#include BOARD_HEADER
#include "hal/micro/button.h"
#include "hal/micro/micro-common.h"
#include "hal/micro/cortexm3/micro-common.h"
void halInitButton(void)
{
/* Set GPIO pin to PUD (input pull-up or pull-down) for button S1 */
halGpioConfig(BUTTON_S1,GPIOCFG_IN_PUD);
/* Set the button S1 gpio pin to pull-up */
BUTTON_S1_OUTPUT_GPIO |= GPIOOUT_PULLUP << BUTTON_S1_GPIO_PIN;
}/* end halInitButton() */
int8u halGetButtonStatus(HalBoardButton button)
{
if (button == BUTTON_S1)
return (BUTTON_S1_INPUT_GPIO & (1<<BUTTON_S1_GPIO_PIN)) ? BUTTON_RELEASED : BUTTON_PRESSED;
else
return BUTTON_UNKNOWN;
}/* end halGetButtonStatus()*/

View file

@ -0,0 +1,473 @@
/*
* File: clocks.c
* Description: STM32W108 internal, clock specific HAL functions
* This file is provided for completeness and it should not be modified
* by customers as it comtains code very tightly linked to undocumented
* device features
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
#include PLATFORM_HEADER
#include "error.h"
#include "hal/hal.h"
#include "hal/micro/cortexm3/mpu.h"
#include "hal/micro/cortexm3/mfg-token.h"
//Provide a simple means for enabling calibration debug output
#define CALDBG(x)
//#define CALDBG(x) x
//The slowest frequency for the 10kHz RC source is 8kHz (125us). The PERIOD
//register updates every 16 cycles, so to be safe 17 cycles = 2125us. But,
//we need twice this maximum time because the period measurement runs
//asynchronously, and the value of CLKRC_TUNE is changed immediately before
//the delay.
#define SLOWRC_PERIOD_SETTLE_TIME 4250
//The CLK_PERIOD register measures the number of 12MHz clock cycles that
//occur in 16 cycles of the SlowRC clock. This is meant to smooth out the the
//noise inherently present in the analog RC source. While these 16 cycles
//smooths out most noise, there is still some jitter in the bottom bits of
//CLK_PERIOD. To further smooth out the noise, we take several readings of
//CLK_PERIOD and average them out. Testing has shown that the bottom 3 and 4
//bits of CLK_PERIOD contain most of the jitter. Averaging 8 samples will
//smooth out 3 bits of jitter and provide a realiable and stable reading useful
//in the calculations, while taking much less time than 16 or 32 samples.
#define SLOWRC_PERIOD_SAMPLES 8
//The register CLK1K_CAL is a fractional divider that divides the 10kHz analog
//source with the goal of generating a 1024Hz, clk1k output.
// 10000Hz / CLK1K_CAL = 1024Hz.
//Since the CLK_PERIOD register measures the number of 12MHz cycles in 16
//cycles of the RC:
// 16 * 12000000
// ------------- = ~10kHz
// CLK_PERIOD
//and
// ~10kHz / 1024 = X
//where X is the fractional number that belongs in CLK1K_CAL. Since the
//integer portion of CLK1K_CAL is bits 15:11 and the fractional is 10:0,
//multiplying X by 2048 (bit shift left by 11) generates the proper CLK1K_CAL
//register value.
//
//Putting this all together:
// 16 * 12000000 * 2048 384000000
// -------------------- = ------------ = CLK1K_CAL
// CLK_PERIOD * 1024 CLK_PERIOD
//
#define CLK1K_NUMERATOR 384000000
void halInternalCalibrateSlowRc( void )
{
int8u i;
int32u average=0;
int16s delta;
int32u period;
CALDBG(
stSerialPrintf(ST_ASSERT_SERIAL_PORT, "halInternalCalibrateSlowRc:\r\n");
)
////---- STEP 1: coarsely tune SlowRC in analog section to ~10kHz ----////
//To operate properly across the full temperature and voltage range,
//the RC source in the analog section needs to be first coarsely tuned
//to 10kHz. The CLKRC_TUNE register, which is 2's compliment, provides 16
//steps at ~400Hz per step yielding approximate frequences of 8kHz at 7
//and 15kHz at -8.
//Start with our reset values for TUNE and CAL
CLK_PERIODMODE = 0; //measure SlowRC
CLKRC_TUNE = CLKRC_TUNE_RESET;
CLK1K_CAL = CLK1K_CAL_RESET;
//wait for the PERIOD register to properly update
halCommonDelayMicroseconds(SLOWRC_PERIOD_SETTLE_TIME);
//Measure the current CLK_PERIOD to obtain a baseline
CALDBG(
stSerialPrintf(ST_ASSERT_SERIAL_PORT,
"period: %u, ", CLK_PERIOD);
stSerialPrintf(ST_ASSERT_SERIAL_PORT, "%u Hz\r\n",
((int16u)(((int32u)192000000)/((int32u)CLK_PERIOD))));
)
//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
//for the CLKRC_TUNE to bring it back to 10kHz. Therefore, we have to
//ensure that our delta correction does not exceed the tune range so
//tune has to be capped to the end of the vailable range so it does not
//wrap. Even if we cannot achieve 10kHz, the 1kHz calibration can still
//properly correct to 1kHz.
//Each CLKRC_TUNE step yields a CLK_PERIOD delta of *approximately* 800.
//Calculate how many steps we are off. While dividing by 800 may seem
//like an ugly calculation, the precision of the result is worth the small
//bit of code and time needed to do a divide.
period = CLK_PERIOD;
//Round to the nearest integer
delta = (19200+400) - period;
delta /= 800;
//CLKRC_TUNE is a 4 bit signed number. cap the delta to 7/-8
if(delta > 7) {
delta = 7;
}
if(delta < -8) {
delta = -8;
}
CALDBG(
stSerialPrintf(ST_ASSERT_SERIAL_PORT, "TUNE steps delta: %d\r\n",
delta);
)
CLKRC_TUNE = delta;
//wait for PERIOD to update before taking another sample
halCommonDelayMicroseconds(SLOWRC_PERIOD_SETTLE_TIME);
CALDBG(
stSerialPrintf(ST_ASSERT_SERIAL_PORT,
"period: %u, ", CLK_PERIOD);
stSerialPrintf(ST_ASSERT_SERIAL_PORT, "%u Hz\r\n",
((int16u)(((int32u)192000000)/((int32u)CLK_PERIOD))));
)
//The analog section should now be producing an output of ~10kHz
////---- STEP 2: fine tune the SlowRC to 1024Hz ----////
//Our goal is to generate a 1024Hz source. The register CLK1K_CAL is a
//fractional divider that divides the 10kHz analog source and generates
//the clk1k output. At reset, the default value is 0x5000 which yields a
//division of 10.000. By averaging several samples of CLK_PERIOD, we
//can then calculate the proper divisor need for CLK1K_CAL to make 1024Hz.
for(i=0;i<SLOWRC_PERIOD_SAMPLES;i++) {
halCommonDelayMicroseconds(SLOWRC_PERIOD_SETTLE_TIME);
average += CLK_PERIOD;
}
//calculate the average, with proper rounding
average = (average+(SLOWRC_PERIOD_SAMPLES/2))/SLOWRC_PERIOD_SAMPLES;
CALDBG(
stSerialPrintf(ST_ASSERT_SERIAL_PORT, "average: %u, %u Hz\r\n",
((int16u)average), ((int16u)(((int32u)192000000)/((int32u)average))));
)
//using an average period sample, calculate the clk1k divisor
CLK1K_CAL = (int16u)(CLK1K_NUMERATOR/average);
CALDBG(
stSerialPrintf(ST_ASSERT_SERIAL_PORT,"CLK1K_CAL=%2X\r\n",CLK1K_CAL);
)
//The SlowRC timer is now producing a 1024Hz tick (+/-2Hz).
CALDBG(
stSerialPrintf(ST_ASSERT_SERIAL_PORT, "DONE\r\n");
)
}
//The slowest frequency for the FastRC source is 4MHz (250ns). The PERIOD
//register updates every 256 cycles, so to be safe 257 cycles = 64us. But,
//we need twice this maximum time because the period measurement runs
//asynchronously, and the value of OSCHF_TUNE is changed immediately before
//the delay.
#define FASTRC_PERIOD_SETTLE_TIME 128
//The CLK_PERIOD register measures the number of 12MHz cycles in 256
//cycles of OSCHF:
// 256 * 12000000
// ------------- = ~12MHz
// CLK_PERIOD
void halInternalCalibrateFastRc(void)
{
int32s newTune = -16;
CALDBG(
stSerialPrintf(ST_ASSERT_SERIAL_PORT, "halInternalCalibrateFastRc:\r\n");
)
////---- coarsely tune FastRC in analog section to ~12MHz ----////
//The RC source in the analog section needs to be coarsely tuned
//to 12MHz. The OSCHF_TUNE register, which is 2's compliment, provides 32
//steps at ~0.5MHz per step yielding approximate frequences of 4MHz at 15
//and 20MHz at -16.
CLK_PERIODMODE = 1; //measure FastRC
CALDBG(
//start at the fastest possible frequency
OSCHF_TUNE = newTune;
//wait for the PERIOD register to properly update
halCommonDelayMicroseconds(FASTRC_PERIOD_SETTLE_TIME);
//Measure the current CLK_PERIOD to obtain a baseline
stSerialPrintf(ST_ASSERT_SERIAL_PORT,
"period: %u, ", CLK_PERIOD);
stSerialPrintf(ST_ASSERT_SERIAL_PORT, "%u kHz\r\n",
((int16u)((((int32u)3072000000)/((int32u)CLK_PERIOD))/1000)));
)
//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
//possible (without going over 12MHz)
//Start at the fastest possible frequency (-16) and increase to the slowest
//possible (15). When CLK_PERIOD is <=256 or we run out of tune values,
//we're done.
for(;newTune<16;newTune++) {
//decrease frequency by one step (by increasing tune value)
OSCHF_TUNE = newTune;
//wait for the PERIOD register to properly update
halCommonDelayMicroseconds(FASTRC_PERIOD_SETTLE_TIME);
//kickout if we're tuned
if(CLK_PERIOD>=256) {
break;
}
}
CALDBG(
//Measure the current CLK_PERIOD to show the final result
stSerialPrintf(ST_ASSERT_SERIAL_PORT,
"period: %u, ", CLK_PERIOD);
stSerialPrintf(ST_ASSERT_SERIAL_PORT, "%u kHz\r\n",
((int16u)((((int32u)3072000000)/((int32u)CLK_PERIOD))/1000)));
)
//The analog section should now be producing an output of 11.5MHz - 12.0MHz
}
#define OSC24M_BIASTRIM_OFFSET (0x2)
#define OSC24M_BIASTRIM_MIN (0+OSC24M_BIASTRIM_OFFSET)
#define OSC24M_BIASTRIM_MAX OSC24M_BIASTRIM_OSC24M_BIAS_TRIM_MASK
#define OSC24M_BIASTRIM_MSB (1 << (OSC24M_BIASTRIM_OSC24M_BIAS_TRIM_BITS-1))
#define OSC24M_BIASTRIM_UNINIT (0xFFFF)
tokTypeMfgOsc24mBiasTrim biasTrim=OSC24M_BIASTRIM_UNINIT;
//This function is intended to be called periodically, from the stack and
//application, to check the XTAL bias trim is within appropriate levels
//and adjust if not. This function is *not* designed to be used before
//halInternalSwitchToXtal has been called.
void halCommonCheckXtalBiasTrim(void)
{
//HI is set indicating the trim value is too high. Decrement the trim.
if((OSC24M_COMP & OSC24M_HI) == OSC24M_HI) {
biasTrim--;
}
//LO is cleared indicating the trim value is too low. Inrement the trim.
if((OSC24M_COMP & OSC24M_LO) != OSC24M_LO) {
biasTrim++;
//Add an offset to the bias trim as a factor of safety.
if(biasTrim < (OSC24M_BIASTRIM_MAX - OSC24M_BIASTRIM_OFFSET)) {
biasTrim += OSC24M_BIASTRIM_OFFSET;
} else {
biasTrim = OSC24M_BIASTRIM_MAX;
}
}
//Don't allow bias trim to dip below the offset regardless of LO.
if(biasTrim<OSC24M_BIASTRIM_OFFSET) {
biasTrim = OSC24M_BIASTRIM_OFFSET;
}
OSC24M_BIASTRIM = biasTrim;
}
static boolean setBiasCheckLow(void)
{
OSC24M_BIASTRIM = biasTrim;
halCommonDelayMicroseconds(1500);
return ((OSC24M_COMP & OSC24M_LO) == OSC24M_LO);
}
void halInternalSearchForBiasTrim(void)
{
int8u bit;
//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
//accidentally trip the NMI while searching.)
OSC24M_CTRL = OSC24M_CTRL_OSC24M_EN;
//Do a binary search of the 4-bit bias trim values to find
//smallest bias trim value for which LO = 1.
biasTrim = 0;
bit = (OSC24M_BIASTRIM_MSB << 1);
do {
bit >>= 1;
biasTrim += bit;
//Set trim and wait for 1.5ms to allow the oscillator to stabilize.
if(setBiasCheckLow()) {
biasTrim -= bit;
}
} while(bit);
//If the last bias value went too low, increment it.
if((OSC24M_COMP & OSC24M_LO) != OSC24M_LO) {
biasTrim++;
}
//Add an offset to the bias trim as a factor of safety.
if(biasTrim < (OSC24M_BIASTRIM_MAX - OSC24M_BIASTRIM_OFFSET)) {
biasTrim += OSC24M_BIASTRIM_OFFSET;
} else {
biasTrim = OSC24M_BIASTRIM_MAX;
}
//Using the shadow variable, the clock switch logic will take over from here,
//enabling, verifying, and tweaking as needed.
}
//This function configures the flash access controller for optimal
//current consumption when FCLK is operating at 24MHz. By providing
//this function the calling code does not have to be aware of the
//details of setting FLASH_ACCESS.
static void halInternalConfigXtal24MhzFlashAccess(void)
{
ATOMIC(
BYPASS_MPU(
#if defined(CORTEXM3_STM32W108)
FLASH_ACCESS = (FLASH_ACCESS_PREFETCH_EN |
(1<<FLASH_ACCESS_CODE_LATENCY_BIT));
#endif
)
)
}
//NOTE: The global "shadow" variable biasTrim will be set by either:
// A) TOKEN_MFG_OSC24M_BIAS_TRIM when booting fresh
// B) searchForBiasTrim() when booting fresh and the token is not valid
// C) halInternalSwitchToXtal() if halInternalSwitchToXtal() already ran
void halInternalSwitchToXtal(void)
{
boolean loSet;
boolean hiSet;
boolean setTrimOneLastTime = FALSE;
//If it hasn't yet been initialized,
//preload our biasTrim shadow variable from the token. If the token is
//not set, then run a search to find an initial value. The bias trim
//algorithm/clock switch logic will always use the biasTrim shadow
//variable as the starting point for finding the bias, and then
//save that new bias to the shadow variable.
if(biasTrim == OSC24M_BIASTRIM_UNINIT) {
halCommonGetMfgToken(&biasTrim, TOKEN_MFG_OSC24M_BIAS_TRIM);
if(biasTrim == 0xFFFF) {
halInternalSearchForBiasTrim();
}
}
//Ensure the XTAL is enabled (with the side effect of ensuring we're
//still on OSCHF).
OSC24M_CTRL = OSC24M_CTRL_OSC24M_EN;
do {
//Set trim to our shadow variable and wait for 1.5ms to allow the
//oscillator to stabilize.
loSet = setBiasCheckLow();
hiSet = (OSC24M_COMP & OSC24M_HI) == OSC24M_HI;
//The bias is too low, so we need to increment the bias trim.
if(!loSet) {
biasTrim++;
}
//The bias is too high, so we need to decrement the bias trim.
if(hiSet) {
//but don't trim below our min value
if(biasTrim>OSC24M_BIASTRIM_MIN) {
biasTrim--;
setTrimOneLastTime = TRUE;
}
}
//Kickout when HI=0 and LO=1 or we've hit the MAX or the MIN
} while( (hiSet || !loSet) &&
(biasTrim<OSC24M_BIASTRIM_MAX) &&
(biasTrim>OSC24M_BIASTRIM_MIN) );
//The LO bit being cleared means we've corrected up from the bottom and
//therefore need to apply the offset. Additionally, if our trim value
//is below the offset, we still need to apply the offset. And, when
//applying the offset respect the max possible value of the trim.
if(!loSet || (biasTrim<OSC24M_BIASTRIM_OFFSET)){
if(biasTrim < (OSC24M_BIASTRIM_MAX - OSC24M_BIASTRIM_OFFSET)) {
biasTrim += OSC24M_BIASTRIM_OFFSET;
} else {
biasTrim = OSC24M_BIASTRIM_MAX;
}
setTrimOneLastTime = TRUE;
}
if(setTrimOneLastTime) {
setBiasCheckLow();
}
//We've found a valid trim value and we've waited for the oscillator
//to stabalize, it's now safe to select the XTAL
OSC24M_CTRL |= OSC24M_CTRL_OSC24M_SEL;
//If the XTAL switch failed, the NMI ISR will trigger, creeping the bias
//trim up higher, and if max bias is reached the ISR will trigger a reset.
//Our standard mode of operation is 24MHz (CPU/FCLK is sourced from SYSCLK)
CPU_CLKSEL = CPU_CLKSEL_FIELD;
//Configure flash access for optimal current consumption at 24MHz
halInternalConfigXtal24MhzFlashAccess();
}

View file

@ -0,0 +1,57 @@
#ifndef __ASM_H__
#define __ASM_H__
#ifdef __IAR_SYSTEMS_ASM__
// IAR V5 Definitions.
#define __END__ END
#define __EXPORT__ EXPORT
#define __IMPORT__ IMPORT
#define __SPACE__ DS8
#define __EQU__(a, b) a EQU b
#define __WEAK__ PUBWEAK
#define __THUMB__ THUMB
#if __VER__ >= 5000000
// IAR V5 Definitions.
RSEG RESETINFO:DATA
RSEG CSTACK:DATA
#define __CODE__ SECTION .text:CODE:REORDER:NOROOT(2)
#define __BSS__ SECTION .bss:DATA:NOROOT(2)
#define __BEGIN_RESETINFO__(offset) SFB(RESETINFO + offset)
#define __END_RESETINFO__(offset) SFE(RESETINFO + offset)
#define __BEGIN_STACK__(offset) SFB(CSTACK + offset)
#define __END_STACK__(offset) SFE(CSTACK + offset)
#define __CFI__(x)
#else // __VER__
#error IAR versions less that 5.xx are not supported
#endif // __VER__
#endif // __IAR_SYSTEMS_ASM__
#ifdef __GNUC__
// GCC Definitions.
.syntax unified
.thumb
#define __CODE__ .text
#define __THUMB__ .thumb_func
#define __BSS__ .bss
#define __END__ .end
#define __EXPORT__ .global
#define __IMPORT__ .extern
#define __SPACE__ .space
#define __EQU__(a, b) .equ a, b
#define __WEAK__ .weak
#define __BEGIN_NVDATA__(offset) (_noinit + offset)
#define __BEGIN_STACK__(offset) (_stack + offset)
#define __END_STACK__(offset) (_estack + offset)
#define __CFI__(x)
#endif // __GNUC__
#endif // __ASM_H__

View file

@ -0,0 +1,521 @@
/** @file hal/micro/cortexm3/compiler/gnu.h
* See @ref gnu for detailed documentation.
*
*/
/** @addtogroup gnu
* @brief Compiler and Platform specific definitions and typedefs for the
* GNU C ARM compiler.
*
* @note gnu.h should be included first in all source files by setting the
* preprocessor macro PLATFORM_HEADER to point to it. gnu.h automatically
* includes platform-common.h.
*
* See gnu.h and platform-common.h for source code.
*@{
*/
#ifndef __GNU_H__
#define __GNU_H__
#ifndef __GNUC__
#error Improper PLATFORM_HEADER
#endif
#define GCC_VERSION (__GNUC__ * 10000 \
+ __GNUC_MINOR__ * 100 \
+ __GNUC_PATCHLEVEL__)
#if GCC_VERSION < 40302
#error Only GNU C version later than 4.3.2 are supported
#endif
#ifndef DOXYGEN_SHOULD_SKIP_THIS
//#include <intrinsics.h>
#include <stdarg.h>
#if defined (CORTEXM3_STM32W108)
#include "micro/cortexm3/stm32w108/regs.h"
#else
#error Unknown CORTEXM3 micro
#endif
//Provide a default NVIC configuration file. The build process can
//override this if it needs to.
#ifndef NVIC_CONFIG
#define NVIC_CONFIG "hal/micro/cortexm3/nvic-config.h"
#endif
//[[
#ifdef EMU_TEST
#ifdef I_AM_AN_EMULATOR
// This register is defined for both the chip and the emulator with
// with distinct reset values. Need to undefine to avoid preprocessor
// collision.
#undef DATA_EMU_REGS_BASE
#undef DATA_EMU_REGS_END
#undef DATA_EMU_REGS_SIZE
#undef I_AM_AN_EMULATOR
#undef I_AM_AN_EMULATOR_REG
#undef I_AM_AN_EMULATOR_ADDR
#undef I_AM_AN_EMULATOR_RESET
#undef I_AM_AN_EMULATOR_I_AM_AN_EMULATOR
#undef I_AM_AN_EMULATOR_I_AM_AN_EMULATOR_MASK
#undef I_AM_AN_EMULATOR_I_AM_AN_EMULATOR_BIT
#undef I_AM_AN_EMULATOR_I_AM_AN_EMULATOR_BITS
#endif//I_AM_AN_EMULATOR
#error MICRO currently not supported for emulator builds.
#endif//EMU_TEST
//]]
// suppress warnings about unknown pragmas
// (as they may be pragmas known to other platforms)
//#pragma diag_suppress = pe161
#endif // DOXYGEN_SHOULD_SKIP_THIS
// Define that the minimal hal is being used.
#define MINIMAL_HAL
/** \name Master Variable Types
* These are a set of typedefs to make the size of all variable declarations
* explicitly known.
*/
//@{
/**
* @brief A typedef to make the size of the variable explicitly known.
*/
typedef unsigned char boolean;
typedef unsigned char int8u;
typedef signed char int8s;
typedef unsigned short int16u;
typedef signed short int16s;
typedef unsigned int int32u;
typedef signed int int32s;
typedef unsigned int PointerType;
//@} \\END MASTER VARIABLE TYPES
/**
* @brief Use the Master Program Memory Declarations from platform-common.h
*/
#define _HAL_USE_COMMON_PGM_
////////////////////////////////////////////////////////////////////////////////
/** \name Miscellaneous Macros
*/
////////////////////////////////////////////////////////////////////////////////
//@{
/**
* @brief A convenient method for code to know what endiannes processor
* it is running on. For the Cortex-M3, we are little endian.
*/
#define BIGENDIAN_CPU FALSE
/**
* @brief A friendlier name for the compiler's intrinsic for not
* stripping.
*/
#define NO_STRIPPING /* __root ??? */
#define __no_init /*__attribute__((section (".noinit")))*/
/**
* @brief A friendlier name for the compiler's intrinsic for eeprom
* reference.
*/
#define EEPROM errorerror
#ifndef __SOURCEFILE__
/**
* @brief The __SOURCEFILE__ macro is used by asserts to list the
* filename if it isn't otherwise defined, set it to the compiler intrinsic
* which specifies the whole filename and path of the sourcefile
*/
#define __SOURCEFILE__ __FILE__
#endif
//#include <assert.h>
#undef assert
#define assert(condition) do { if (! (condition)) {while (1); }} while(0)
#if 0
do { if (! (condition)) { \
printf ("Assert failed %s %d\r\n",__SOURCEFILE__, __LINE__); }} while(0)
#endif
#ifndef BOOTLOADER
#undef __delay_cycles
/**
* @brief __delay_cycles() is an intrinsic IAR call; however, we
* have explicity disallowed it since it is too specific to the system clock.
* \note Please use halCommonDelayMicroseconds() instead, because it correctly
* accounts for various system clock speeds.
*/
#define __delay_cycles(x) please_use_halCommonDelayMicroseconds_instead_of_delay_cycles
#endif
/**
* @brief Set debug level based on whether or DEBUG is defined.
* basic debugging support is included if DEBUG is not defined.
*/
#ifndef DEBUG_LEVEL
#ifdef DEBUG
#define DEBUG_LEVEL FULL_DEBUG
#else
#define DEBUG_LEVEL BASIC_DEBUG
#endif
#endif
/**
* @brief Macro to reset the watchdog timer. Note: be very very
* careful when using this as you can easily get into an infinite loop if you
* are not careful.
*/
void halInternalResetWatchDog(void);
#define halResetWatchdog() halInternalResetWatchDog()
/**
* @brief Define __attribute__ to nothing since it isn't handled by IAR.
*/
/**
* @brief Declare a variable as unused to avoid a warning. Has no effect
* in IAR builds
*/
#define UNUSED
/**
* @brief Some platforms need to cast enum values that have the high bit set.
*/
#define SIGNED_ENUM
/**
* @brief Define the magic value that is interpreted by IAR C-SPY's Stack View.
*/
#define STACK_FILL_VALUE 0xCDCDCDCD
/**
* @brief Define a generic RAM function identifier to a compiler specific one.
*/
#ifdef RAMEXE
//If the whole build is running out of RAM, as chosen by the RAMEXE build
//define, then define RAMFUNC to nothing since it's not needed.
#define RAMFUNC
#else //RAMEXE
#define RAMFUNC __ramfunc
#endif //RAMEXE
/**
* @brief Define a generic no operation identifier to a compiler specific one.
*/
#define NO_OPERATION() __no_operation()
/**
* @brief A convenience macro that makes it easy to change the field of a
* register to any value.
*/
#define SET_REG_FIELD(reg, field, value) \
do{ \
reg = ((reg & (~field##_MASK)) | (value << field##_BIT)); \
}while(0)
/**
* @brief Stub for code not running in simulation.
*/
#define simulatedTimePasses()
/**
* @brief Stub for code not running in simulation.
*/
#define simulatedTimePassesMs(x)
/**
* @brief Stub for code not running in simulation.
*/
#define simulatedSerialTimePasses()
/**
* @brief Use the Divide and Modulus Operations from platform-common.h
*/
#define _HAL_USE_COMMON_DIVMOD_
/**
* @brief Provide a portable way to specify the segment where a variable
* lives.
*/
#define VAR_AT_SEGMENT(__variableDeclaration, __segmentName) \
__variableDeclaration __attribute__ ((section (__segmentName)))
////////////////////////////////////////////////////////////////////////////////
//@} // end of Miscellaneous Macros
////////////////////////////////////////////////////////////////////////////////
/** @name Portable segment names
*@{
*/
/**
* @brief Portable segment names
*/
#define __NO_INIT__ ".noinit"
#define __INTVEC__ ".intvec"
#define __CSTACK__ "CSTACK"
#define __DATA_INIT__ ".data_init"
#define __DATA__ ".data"
#define __BSS__ ".bss"
#define __CONST__ ".rodata"
#define __TEXT__ ".text"
#define __TEXTRW_INIT__ ".textrw_init"
#define __TEXTRW__ ".textrw"
#define __FAT__ "FAT" // Fixed address table
#define __NVM__ "NVM" //Non-Volatile Memory data storage
//=============================================================================
// The '#pragma segment=' declaration must be used before attempting to access
// the segments so the compiler properly handles the __segment_*() functions.
//
// The segment names used here are the default segment names used by IAR. Refer
// to the IAR Compiler Reference Guide for a proper description of these
// segments.
//=============================================================================
#if 0
#pragma segment=__NO_INIT__
#pragma segment=__INTVEC__
#pragma segment=__CSTACK__
#pragma segment=__DATA_INIT__
#pragma segment=__DATA__
#pragma segment=__BSS__
#pragma segment=__CONST__
#pragma segment=__TEXT__
#pragma segment=__TEXTRW_INIT__
#pragma segment=__TEXTRW__
#pragma segment=__FAT__
#pragma segment=__NVM__
#endif
/**@} */
//A utility function for inserting barrier instructions. These
//instructions should be used whenever the MPU is enabled or disabled so
//that all memory/instruction accesses can complete before the MPU changes
//state.
void _executeBarrierInstructions(void);
////////////////////////////////////////////////////////////////////////////////
/** \name Global Interrupt Manipulation Macros
*
* \b Note: The special purpose BASEPRI register is used to enable and disable
* interrupts while permitting faults.
* When BASEPRI is set to 1 no interrupts can trigger. The configurable faults
* (usage, memory management, and bus faults) can trigger if enabled as well as
* the always-enabled exceptions (reset, NMI and hard fault).
* When BASEPRI is set to 0, it is disabled, so any interrupt can triggger if
* its priority is higher than the current priority.
*/
////////////////////////////////////////////////////////////////////////////////
//@{
#define ATOMIC_LITE(blah) ATOMIC(blah)
#define DECLARE_INTERRUPT_STATE_LITE DECLARE_INTERRUPT_STATE
#define DISABLE_INTERRUPTS_LITE() DISABLE_INTERRUPTS()
#define RESTORE_INTERRUPTS_LITE() RESTORE_INTERRUPTS()
#ifdef BOOTLOADER
#ifndef DOXYGEN_SHOULD_SKIP_THIS
// The bootloader does not use interrupts
#define DECLARE_INTERRUPT_STATE
#define DISABLE_INTERRUPTS() do { } while(0)
#define RESTORE_INTERRUPTS() do { } while(0)
#define INTERRUPTS_ON() do { } while(0)
#define INTERRUPTS_OFF() do { } while(0)
#define INTERRUPTS_ARE_OFF() (FALSE)
#define ATOMIC(blah) { blah }
#define HANDLE_PENDING_INTERRUPTS() do { } while(0)
#define SET_BASE_PRIORITY_LEVEL(basepri) do { } while(0)
#endif // DOXYGEN_SHOULD_SKIP_THIS
#else // BOOTLOADER
#ifndef DOXYGEN_SHOULD_SKIP_THIS
/**
* @brief This macro should be called in the local variable
* declarations section of any function which calls DISABLE_INTERRUPTS()
* or RESTORE_INTERRUPTS().
*/
#define DECLARE_INTERRUPT_STATE int8u _emIsrState
// Prototypes for the BASEPRI and PRIMASK access functions. They are very
// basic and instantiated in assembly code in the file spmr.s37 (since
// there are no C functions that cause the compiler to emit code to access
// the BASEPRI/PRIMASK). This will inhibit the core from taking interrupts
// with a priority equal to or less than the BASEPRI value.
// Note that the priority values used by these functions are 5 bits and
// right-aligned
extern int8u _readBasePri(void);
extern void _writeBasePri(int8u priority);
// Prototypes for BASEPRI functions used to disable and enable interrupts
// while still allowing enabled faults to trigger.
extern void _enableBasePri(void);
extern int8u _disableBasePri(void);
extern boolean _basePriIsDisabled(void);
// Prototypes for setting and clearing PRIMASK for global interrupt
// enable/disable.
extern void _setPriMask(void);
extern void _clearPriMask(void);
#endif // DOXYGEN_SHOULD_SKIP_THIS
//The core Global Interrupt Manipulation Macros start here.
/**
* @brief Disable interrupts, saving the previous state so it can be
* later restored with RESTORE_INTERRUPTS().
* \note Do not fail to call RESTORE_INTERRUPTS().
* \note It is safe to nest this call.
*/
#define DISABLE_INTERRUPTS() \
do { \
_emIsrState = _disableBasePri(); \
} while(0)
/**
* @brief Restore the global interrupt state previously saved by
* DISABLE_INTERRUPTS()
* \note Do not call without having first called DISABLE_INTERRUPTS()
* to have saved the state.
* \note It is safe to nest this call.
*/
#define RESTORE_INTERRUPTS() \
do { \
_writeBasePri(_emIsrState); \
} while(0)
/**
* @brief Enable global interrupts without regard to the current or
* previous state.
*/
#define INTERRUPTS_ON() \
do { \
_enableBasePri(); \
} while(0)
/**
* @brief Disable global interrupts without regard to the current or
* previous state.
*/
#define INTERRUPTS_OFF() \
do { \
(void)_disableBasePri(); \
} while(0)
/**
* @returns TRUE if global interrupts are disabled.
*/
#define INTERRUPTS_ARE_OFF() ( _basePriIsDisabled() )
/**
* @returns TRUE if global interrupt flag was enabled when
* ::DISABLE_INTERRUPTS() was called.
*/
#define INTERRUPTS_WERE_ON() (_emIsrState == 0)
/**
* @brief A block of code may be made atomic by wrapping it with this
* macro. Something which is atomic cannot be interrupted by interrupts.
*/
#define ATOMIC(blah) \
{ \
DECLARE_INTERRUPT_STATE; \
DISABLE_INTERRUPTS(); \
{ blah } \
RESTORE_INTERRUPTS(); \
}
/**
* @brief Allows any pending interrupts to be executed. Usually this
* would be called at a safe point while interrupts are disabled (such as
* within an ISR).
*
* Takes no action if interrupts are already enabled.
*/
#define HANDLE_PENDING_INTERRUPTS() \
do { \
if (INTERRUPTS_ARE_OFF()) { \
INTERRUPTS_ON(); \
INTERRUPTS_OFF(); \
} \
} while (0)
/**
* @brief Sets the base priority mask (BASEPRI) to the value passed,
* bit shifted up by PRIGROUP_POSITION+1. This will inhibit the core from
* taking all interrupts with a preemptive priority equal to or less than
* the BASEPRI mask. This macro is dependent on the value of
* PRIGROUP_POSITION in nvic-config.h. Note that the value 0 disables the
* the base priority mask.
*
* Refer to the "PRIGROUP" table in nvic-config.h to know the valid values
* for this macro depending on the value of PRIGROUP_POSITION. With respect
* to the table, this macro can only take the preemptive priority group
* numbers denoted by the parenthesis.
*/
#define SET_BASE_PRIORITY_LEVEL(basepri) \
do { \
_writeBasePri(basepri); \
} while(0)
#endif // BOOTLOADER
////////////////////////////////////////////////////////////////////////////////
//@} // end of Global Interrupt Manipulation Macros
////////////////////////////////////////////////////////////////////////////////
/**
* @brief Use the C Standard Library Memory Utilities from platform-common.h
*/
#define _HAL_USE_COMMON_MEMUTILS_
////////////////////////////////////////////////////////////////////////////////
/** \name External Declarations
* These are routines that are defined in certain header files that we don't
* want to include, e.g. stdlib.h
*/
////////////////////////////////////////////////////////////////////////////////
//@{
/**
* @brief Returns the absolute value of I (also called the magnitude of I).
* That is, if I is negative, the result is the opposite of I, but if I is
* nonnegative the result is I.
*
* @param I An integer.
*
* @return A nonnegative integer.
*/
int abs(int I);
////////////////////////////////////////////////////////////////////////////////
//@} // end of External Declarations
////////////////////////////////////////////////////////////////////////////////
/**
* @brief Include platform-common.h last to pick up defaults and common definitions.
*/
#define PLATCOMMONOKTOINCLUDE
#include "hal/micro/generic/compiler/platform-common.h"
#undef PLATCOMMONOKTOINCLUDE
#endif // __GNU_H__
/** @} END addtogroup */

View file

@ -0,0 +1,516 @@
/** @file hal/micro/cortexm3/compiler/iar.h
* @brief iar for detailed documentation.
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
/** @addtogroup iar
* @brief Compiler and Platform specific definitions and typedefs for the
* IAR ARM C compiler.
*
* @note iar.h should be included first in all source files by setting the
* preprocessor macro PLATFORM_HEADER to point to it. iar.h automatically
* includes platform-common.h.
*
* See iar.h and platform-common.h for source code.
*@{
*/
#ifndef __IAR_H__
#define __IAR_H__
#ifndef __ICCARM__
#error Improper PLATFORM_HEADER
#endif
#if (__VER__ < 5040005)
#error Only IAR EWARM versions later than 5.40.5 are supported
#endif // __VER__
#ifndef DOXYGEN_SHOULD_SKIP_THIS
#include <intrinsics.h>
#include <stdarg.h>
#if defined (CORTEXM3_STM32W108)
#include "micro/cortexm3/stm32w108/regs.h"
#else
#error Unknown CORTEXM3 micro
#endif
//Provide a default NVIC configuration file. The build process can
//override this if it needs to.
#ifndef NVIC_CONFIG
#define NVIC_CONFIG "hal/micro/cortexm3/nvic-config.h"
#endif
//[[
#ifdef ST_EMU_TEST
#ifdef I_AM_AN_EMULATOR
// This register is defined for both the chip and the emulator with
// with distinct reset values. Need to undefine to avoid preprocessor
// collision.
#undef DATA_EMU_REGS_BASE
#undef DATA_EMU_REGS_END
#undef DATA_EMU_REGS_SIZE
#undef I_AM_AN_EMULATOR
#undef I_AM_AN_EMULATOR_REG
#undef I_AM_AN_EMULATOR_ADDR
#undef I_AM_AN_EMULATOR_RESET
#undef I_AM_AN_EMULATOR_I_AM_AN_EMULATOR
#undef I_AM_AN_EMULATOR_I_AM_AN_EMULATOR_MASK
#undef I_AM_AN_EMULATOR_I_AM_AN_EMULATOR_BIT
#undef I_AM_AN_EMULATOR_I_AM_AN_EMULATOR_BITS
#endif//I_AM_AN_EMULATOR
#error MICRO currently not supported for emulator builds.
#endif//ST_EMU_TEST
//]]
// suppress warnings about unknown pragmas
// (as they may be pragmas known to other platforms)
#pragma diag_suppress = pe161
#endif // DOXYGEN_SHOULD_SKIP_THIS
// Define that the minimal hal is being used.
#define MINIMAL_HAL
/** \name Master Variable Types
* These are a set of typedefs to make the size of all variable declarations
* explicitly known.
*/
//@{
/**
* @brief A typedef to make the size of the variable explicitly known.
*/
typedef unsigned char boolean;
typedef unsigned char int8u;
typedef signed char int8s;
typedef unsigned short int16u;
typedef signed short int16s;
typedef unsigned int int32u;
typedef signed int int32s;
typedef unsigned int PointerType;
//@} \\END MASTER VARIABLE TYPES
/**
* @brief Use the Master Program Memory Declarations from platform-common.h
*/
#define _HAL_USE_COMMON_PGM_
////////////////////////////////////////////////////////////////////////////////
/** \name Miscellaneous Macros
*/
////////////////////////////////////////////////////////////////////////////////
//@{
/**
* @brief A convenient method for code to know what endiannes processor
* it is running on. For the Cortex-M3, we are little endian.
*/
#define BIGENDIAN_CPU FALSE
/**
* @brief A friendlier name for the compiler's intrinsic for not
* stripping.
*/
#define NO_STRIPPING __root
/**
* @brief A friendlier name for the compiler's intrinsic for eeprom
* reference.
*/
#define EEPROM errorerror
#ifndef __SOURCEFILE__
/**
* @brief The __SOURCEFILE__ macro is used by asserts to list the
* filename if it isn't otherwise defined, set it to the compiler intrinsic
* which specifies the whole filename and path of the sourcefile
*/
#define __SOURCEFILE__ __FILE__
#endif
#include <assert.h>
#ifndef BOOTLOADER
#undef __delay_cycles
/**
* @brief __delay_cycles() is an intrinsic IAR call; however, we
* have explicity disallowed it since it is too specific to the system clock.
* \note Please use halCommonDelayMicroseconds() instead, because it correctly
* accounts for various system clock speeds.
*/
#define __delay_cycles(x) please_use_halCommonDelayMicroseconds_instead_of_delay_cycles
#endif
/**
* @brief Set debug level based on whether or DEBUG is defined.
* For the STM32W108xx, basic debugging support is included if DEBUG is not defined.
*/
#ifndef DEBUG_LEVEL
#ifdef DEBUG
#define DEBUG_LEVEL FULL_DEBUG
#else
#define DEBUG_LEVEL BASIC_DEBUG
#endif
#endif
/**
* @brief Macro to reset the watchdog timer. Note: be very very
* careful when using this as you can easily get into an infinite loop if you
* are not careful.
*/
void halInternalResetWatchDog(void);
#define halResetWatchdog() halInternalResetWatchDog()
/**
* @brief Define __attribute__ to nothing since it isn't handled by IAR.
*/
#define __attribute__(nothing)
/**
* @brief Declare a variable as unused to avoid a warning. Has no effect
* in IAR builds
*/
#define UNUSED
/**
* @brief Some platforms need to cast enum values that have the high bit set.
*/
#define SIGNED_ENUM
/**
* @brief Define the magic value that is interpreted by IAR C-SPY's Stack View.
*/
#define STACK_FILL_VALUE 0xCDCDCDCD
/**
* @brief Define a generic RAM function identifier to a compiler specific one.
*/
#ifdef RAMEXE
//If the whole build is running out of RAM, as chosen by the RAMEXE build
//define, then define RAMFUNC to nothing since it's not needed.
#define RAMFUNC
#else //RAMEXE
#define RAMFUNC __ramfunc
#endif //RAMEXE
/**
* @brief Define a generic no operation identifier to a compiler specific one.
*/
#define NO_OPERATION() __no_operation()
/**
* @brief A convenience macro that makes it easy to change the field of a
* register to any value.
*/
#define SET_REG_FIELD(reg, field, value) \
do{ \
reg = ((reg & (~field##_MASK)) | (value << field##_BIT)); \
}while(0)
/**
* @brief Stub for code not running in simulation.
*/
#define simulatedTimePasses()
/**
* @brief Stub for code not running in simulation.
*/
#define simulatedTimePassesMs(x)
/**
* @brief Stub for code not running in simulation.
*/
#define simulatedSerialTimePasses()
/**
* @brief Use the Divide and Modulus Operations from platform-common.h
*/
#define _HAL_USE_COMMON_DIVMOD_
/**
* @brief Provide a portable way to specify the segment where a variable
* lives.
*/
#define VAR_AT_SEGMENT(__variableDeclaration, __segmentName) \
__variableDeclaration @ __segmentName
////////////////////////////////////////////////////////////////////////////////
//@} // end of Miscellaneous Macros
////////////////////////////////////////////////////////////////////////////////
/** @name Portable segment names
*@{
*/
/**
* @brief Portable segment names
*/
#define __NO_INIT__ ".noinit"
#define __INTVEC__ ".intvec"
#define __CSTACK__ "CSTACK"
#define __DATA_INIT__ ".data_init"
#define __DATA__ ".data"
#define __BSS__ ".bss"
#define __CONST__ ".rodata"
#define __TEXT__ ".text"
#define __TEXTRW_INIT__ ".textrw_init"
#define __TEXTRW__ ".textrw"
#define __FAT__ "FAT" // Fixed address table
#define __NVM__ "NVM" //Non-Volatile Memory data storage
//=============================================================================
// The '#pragma segment=' declaration must be used before attempting to access
// the segments so the compiler properly handles the __segment_*() functions.
//
// The segment names used here are the default segment names used by IAR. Refer
// to the IAR Compiler Reference Guide for a proper description of these
// segments.
//=============================================================================
#pragma segment=__NO_INIT__
#pragma segment=__INTVEC__
#pragma segment=__CSTACK__
#pragma segment=__DATA_INIT__
#pragma segment=__DATA__
#pragma segment=__BSS__
#pragma segment=__CONST__
#pragma segment=__TEXT__
#pragma segment=__TEXTRW_INIT__
#pragma segment=__TEXTRW__
#pragma segment=__FAT__
#pragma segment=__NVM__
/**@} */
//A utility function for inserting barrier instructions. These
//instructions should be used whenever the MPU is enabled or disabled so
//that all memory/instruction accesses can complete before the MPU changes
//state.
void _executeBarrierInstructions(void);
// MPU is unused with this platform header variant
#define _HAL_MPU_UNUSED_
////////////////////////////////////////////////////////////////////////////////
/** \name Global Interrupt Manipulation Macros
*
* \b Note: The special purpose BASEPRI register is used to enable and disable
* interrupts while permitting faults.
* When BASEPRI is set to 1 no interrupts can trigger. The configurable faults
* (usage, memory management, and bus faults) can trigger if enabled as well as
* the always-enabled exceptions (reset, NMI and hard fault).
* When BASEPRI is set to 0, it is disabled, so any interrupt can triggger if
* its priority is higher than the current priority.
*/
////////////////////////////////////////////////////////////////////////////////
//@{
#define ATOMIC_LITE(blah) ATOMIC(blah)
#define DECLARE_INTERRUPT_STATE_LITE DECLARE_INTERRUPT_STATE
#define DISABLE_INTERRUPTS_LITE() DISABLE_INTERRUPTS()
#define RESTORE_INTERRUPTS_LITE() RESTORE_INTERRUPTS()
#ifdef BOOTLOADER
#ifndef DOXYGEN_SHOULD_SKIP_THIS
// The bootloader does not use interrupts
#define DECLARE_INTERRUPT_STATE
#define DISABLE_INTERRUPTS() do { } while(0)
#define RESTORE_INTERRUPTS() do { } while(0)
#define INTERRUPTS_ON() do { } while(0)
#define INTERRUPTS_OFF() do { } while(0)
#define INTERRUPTS_ARE_OFF() (FALSE)
#define ATOMIC(blah) { blah }
#define HANDLE_PENDING_INTERRUPTS() do { } while(0)
#define SET_BASE_PRIORITY_LEVEL(basepri) do { } while(0)
#endif // DOXYGEN_SHOULD_SKIP_THIS
#else // BOOTLOADER
#ifndef DOXYGEN_SHOULD_SKIP_THIS
/**
* @brief This macro should be called in the local variable
* declarations section of any function which calls DISABLE_INTERRUPTS()
* or RESTORE_INTERRUPTS().
*/
#define DECLARE_INTERRUPT_STATE int8u _emIsrState
// Prototypes for the BASEPRI and PRIMASK access functions. They are very
// basic and instantiated in assembly code in the file spmr.s37 (since
// there are no C functions that cause the compiler to emit code to access
// the BASEPRI/PRIMASK). This will inhibit the core from taking interrupts
// with a priority equal to or less than the BASEPRI value.
// Note that the priority values used by these functions are 5 bits and
// right-aligned
extern int8u _readBasePri(void);
extern void _writeBasePri(int8u priority);
// Prototypes for BASEPRI functions used to disable and enable interrupts
// while still allowing enabled faults to trigger.
extern void _enableBasePri(void);
extern int8u _disableBasePri(void);
extern boolean _basePriIsDisabled(void);
// Prototypes for setting and clearing PRIMASK for global interrupt
// enable/disable.
extern void _setPriMask(void);
extern void _clearPriMask(void);
#endif // DOXYGEN_SHOULD_SKIP_THIS
//The core Global Interrupt Manipulation Macros start here.
/**
* @brief Disable interrupts, saving the previous state so it can be
* later restored with RESTORE_INTERRUPTS().
* \note Do not fail to call RESTORE_INTERRUPTS().
* \note It is safe to nest this call.
*/
#define DISABLE_INTERRUPTS() \
do { \
_emIsrState = _disableBasePri(); \
} while(0)
/**
* @brief Restore the global interrupt state previously saved by
* DISABLE_INTERRUPTS()
* \note Do not call without having first called DISABLE_INTERRUPTS()
* to have saved the state.
* \note It is safe to nest this call.
*/
#define RESTORE_INTERRUPTS() \
do { \
_writeBasePri(_emIsrState); \
} while(0)
/**
* @brief Enable global interrupts without regard to the current or
* previous state.
*/
#define INTERRUPTS_ON() \
do { \
_enableBasePri(); \
} while(0)
/**
* @brief Disable global interrupts without regard to the current or
* previous state.
*/
#define INTERRUPTS_OFF() \
do { \
(void)_disableBasePri(); \
} while(0)
/**
* @returns TRUE if global interrupts are disabled.
*/
#define INTERRUPTS_ARE_OFF() ( _basePriIsDisabled() )
/**
* @returns TRUE if global interrupt flag was enabled when
* ::DISABLE_INTERRUPTS() was called.
*/
#define INTERRUPTS_WERE_ON() (_emIsrState == 0)
/**
* @brief A block of code may be made atomic by wrapping it with this
* macro. Something which is atomic cannot be interrupted by interrupts.
*/
#define ATOMIC(blah) \
{ \
DECLARE_INTERRUPT_STATE; \
DISABLE_INTERRUPTS(); \
{ blah } \
RESTORE_INTERRUPTS(); \
}
/**
* @brief Allows any pending interrupts to be executed. Usually this
* would be called at a safe point while interrupts are disabled (such as
* within an ISR).
*
* Takes no action if interrupts are already enabled.
*/
#define HANDLE_PENDING_INTERRUPTS() \
do { \
if (INTERRUPTS_ARE_OFF()) { \
INTERRUPTS_ON(); \
INTERRUPTS_OFF(); \
} \
} while (0)
/**
* @brief Sets the base priority mask (BASEPRI) to the value passed,
* bit shifted up by PRIGROUP_POSITION+1. This will inhibit the core from
* taking all interrupts with a preemptive priority equal to or less than
* the BASEPRI mask. This macro is dependent on the value of
* PRIGROUP_POSITION in nvic-config.h. Note that the value 0 disables the
* the base priority mask.
*
* Refer to the "PRIGROUP" table in nvic-config.h to know the valid values
* for this macro depending on the value of PRIGROUP_POSITION. With respect
* to the table, this macro can only take the preemptive priority group
* numbers denoted by the parenthesis.
*/
#define SET_BASE_PRIORITY_LEVEL(basepri) \
do { \
_writeBasePri(basepri); \
} while(0)
#endif // BOOTLOADER
////////////////////////////////////////////////////////////////////////////////
//@} // end of Global Interrupt Manipulation Macros
////////////////////////////////////////////////////////////////////////////////
/**
* @brief Use the C Standard Library Memory Utilities from platform-common.h
*/
#define _HAL_USE_COMMON_MEMUTILS_
////////////////////////////////////////////////////////////////////////////////
/** \name External Declarations
* These are routines that are defined in certain header files that we don't
* want to include, e.g. stdlib.h
*/
////////////////////////////////////////////////////////////////////////////////
//@{
/**
* @brief Returns the absolute value of I (also called the magnitude of I).
* That is, if I is negative, the result is the opposite of I, but if I is
* nonnegative the result is I.
*
* @param I An integer.
*
* @return A nonnegative integer.
*/
int abs(int I);
////////////////////////////////////////////////////////////////////////////////
//@} // end of External Declarations
////////////////////////////////////////////////////////////////////////////////
/**
* @brief Include platform-common.h last to pick up defaults and common definitions.
*/
#define PLATCOMMONOKTOINCLUDE
#include "hal/micro/generic/compiler/platform-common.h"
#undef PLATCOMMONOKTOINCLUDE
#endif // __IAR_H__
/** @} END addtogroup */

View file

@ -0,0 +1,158 @@
//------------------------------------------------------------------------------
// @file hal/micro/cortexm3/context-switch.s79
// @brief Context save/restore for deep sleep using the PendSV exception.
//
// This file also contains a simple halInternalIdleSleep() function that
// executes just the WFI instruction for idle sleeping.
//
// When the STM32W108XX enters deep sleep, the hardware will actually remove power
// from the Cortex-M3 core (in Deep Sleep 0, power is not removed but the core
// is held in reset). Since this will clear the internal state of the core, it
// must be properly restored such that execution can resume from the sleep code.
// The simplest and most secure mechanism to do this is to perform a context save
// and restore. Context save/restore is almost identical to a context switch
// used in multi-threaded systems with the main difference being only one stack
// pointer is used and the save/restore operations are disjoint.
//
// When an interrupt is triggered in the STM32W108XX, the core automatically saves 8
// of the 16 CPU registers on the stack. The ISR then only needs to save the
// other 8 registers and store the resulting stack pointer. Restoring is the
// reverse operation where 8 registers are manually copied back with the other 8
// being restored on the return from interrupt.
//
// As its last act, the deep sleep code will trigger the PendSV exception to
// perform a context save. When the core is booted upon deep sleep exit, the
// RESET_EVENT register informs cstartup if the chip just exited deep sleep.
// Cstartup will then trigger halTriggerContextRestore which sets up the stack
// pointer and trigger the PendSV exception to perform a restore. When PendSV
// returns from interrupt context the system will be back at the same point it
// was before deep sleep.
//
//
// <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
//------------------------------------------------------------------------------
#include "compiler/asm.h"
//------------------------------------------------------------------------------
// boolean halPendSvSaveContext
//
// A simple boolean flag used to indicate if a context save or a context restore
// should be performed. Since context switching is handled with the PendSV
// interrupt, parameters cannot be passed into the ISR and as such this boolean
// flag is used. If this flag is zero, PendSV should perform a context restore.
// If this flag is non-zero, PendSV should perform a context save.
// Note: The smallest unit of storage is a single byte.
//
// NOTE: This flag must be set before PendSV is triggered!
//------------------------------------------------------------------------------
__BSS__
__EXPORT__ halPendSvSaveContext
halPendSvSaveContext:
__SPACE__ 1
//------------------------------------------------------------------------------
// int32u savedMSP
//
// 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
// do not use real context switching, but only context saving and restoring.
// As such, we only need to keep track of the Main Stack Pointer (MSP). This
// variable is used to hold the MSP between a save and a restore.
//------------------------------------------------------------------------------
__BSS__
__EXPORT__ savedMSP
savedMSP:
__SPACE__ 4
//------------------------------------------------------------------------------
// void halPendSvIsr(void)
//
// This ISR is installed by cstartup in the vector table for the PendSV
// exception. The purpose of this ISR is to either save the current context
// and trigger sleeping through the 'WFI' instruction, or restore a
// previous context. The variable halPendSvSaveContext is used to
// decide if a save or a restore is performed. Since entering/exiting interrupt
// context automatically saves/restores 8 of the 16 CPU registers on the stack
// we need to manually save the other 8 onto the stack as well.
//
// When a context save is complete, the stack will have been expanded by 16
// words with the current Stack Pointer stored in savedMSP.
//
// When a context restore is complete, the stack will have been shrunk by 16
// words with the old context restored after the return instruction.
//
// NOTE: The IAR default handler name for PendSV, PendSV_Handler, is also
// instantiated here so it routes to the same code as the St
// name halPendSvIsr.
//------------------------------------------------------------------------------
__CODE__
__THUMB__
__EXPORT__ PendSV_Handler
__EXPORT__ halPendSvIsr
PendSV_Handler:
halPendSvIsr:
LDR R0, =halPendSvSaveContext //load the variable's address
LDRB R0, [R0] //get the value in the variable
CBZ R0, contextRestore //if variable is zero, branch to contextRestore
contextSave:
MRS R0, MSP //load the main stack pointer into R0
SUB R0, R0, #0x20 //make room on the stack for 8 words (32 bytes)
MSR MSP, R0 //load new MSP from adjusted stack pointer
STM R0, {R4-R11} //store R4-R11 (8 words) onto the stack
LDR R1, =savedMSP //load address of savedMSP into R1
STR R0, [R1] //store the MSP into savedMSP
WFI //all saved, trigger deep sleep
// Even if we fall through the WFI instruction, we will immediately
// execute a context restore and end up where we left off with no
// ill effects. Normally at this point the core will either be
// powered off or reset (depending on the deep sleep level).
contextRestore:
LDR R0, =savedMSP //load address of savedMSP into R0
LDR R0, [R0] //load the MSP from savedMSP
LDM R0, {R4-R11} //load R4-R11 (8 words) from the stack
ADD R0, R0, #0x20 //eliminate the 8 words (32 bytes) from the stack
MSR MSP, R0 //restore the MSP from R0
BX LR //return to the old context
//------------------------------------------------------------------------------
// void halTriggerContextRestore(void)
//
// Cstartup is responsible for triggering a context restore based upon the
// RESET_EVENT register. Since the stack pointer sits at the top of memory
// after the core boots, cstartup cannot simply trigger a PendSV to restore
// context as this will cause existing stack data to be over written. Cstartup
// disables interrupts, pends PendSV, and then calls this function. This
// function simply configures the Stack Pointer to be past the previous data
// such that when interrupts are enabled and PendSV fires it wont corrupt
// previous data.
//------------------------------------------------------------------------------
__CODE__
__THUMB__
__EXPORT__ halTriggerContextRestore
halTriggerContextRestore:
LDR R0, =savedMSP //load address of savedMSP into R0
LDR R0, [R0] //load the MSP from savedMSP
MSR MSP, R0 //restore the MSP from R0
CPSIE i //enable interrupts and let PendSV fire
BX LR //this return should never be triggered
//------------------------------------------------------------------------------
// void halInternalIdleSleep(void)
//
// A simple internal function call (to be called from halSleep) for executing
// the WFI instruction and entering the simple, idle sleep state.
//------------------------------------------------------------------------------
__CODE__
__THUMB__
__EXPORT__ halInternalIdleSleep
halInternalIdleSleep:
WFI //trigger idle sleep
BX LR //return
__END__

View file

@ -0,0 +1,149 @@
/**************************************************
*
* 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

@ -0,0 +1,42 @@
CC = arm-none-eabi-gcc
AR = arm-none-eabi-ar
CFLAGS = -mthumb -mcpu=cortex-m3 -I "." -I "C:/Program\ Files/Raisonance/Ride/Lib/ARM/include" \
-fsigned-char -D SMALL_SCANF -D _SMALL_PRINTF -D INTEGER_ONLY -Os -ffunction-sections -mlittle-endian
#
AROPTS = cq
SOURCE_DIR = src
SOURCE_FILES = small_mprec.c syscalls.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 \
scanf.c small_vfsscanf.c sscanf.c small_strtod.c
vpath %.c $(SOURCE_DIR)
SOURCE_OBJS = ${patsubst %.c,%.o,$(SOURCE_FILES)}
LIB = e_stdio_intonly_thumb2.a
all: clean $(LIB)
clean:
rm -f $(SOURCE_OBJS) $(LIB)
%.a: $(SOURCE_OBJS)
$(AR) $(AROPTS) $@ $^
%.o: %.c
$(CC) $(CFLAGS) -c $< -o $@

View file

@ -0,0 +1,80 @@
#define _SMALL_PRINFT
#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

@ -0,0 +1,43 @@
#include <stdio.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)
{
#if 1 //VC090825: cleaner and faster version
int len = 0;
while ( str && (*str) )
{
__io_putchar ( *(str++) );
len++;
}
#else //VC090825: cleaner, lighter and faster version
int len = strlen ( str );
_SMALL_PRINTF_puts(str, len, 0) ;
#endif //VC090825: cleaner, lighter and faster version
__io_putchar ( '\n' );
return len;
}

View file

@ -0,0 +1,124 @@
/*
* Copyright (c) 1990 The Regents of the University of California.
* All rights reserved.
*
* Redistribution and use in source and binary forms are permitted
* provided that the above copyright notice and this paragraph are
* duplicated in all such forms and that any documentation,
* advertising materials, and other materials related to such
* distribution and use acknowledge that the software was developed
* by the University of California, Berkeley. The name of the
* University may not be used to endorse or promote products derived
* from this software without specific prior written permission.
* THIS SOFTWARE IS PROVIDED ``AS IS'' AND WITHOUT ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, WITHOUT LIMITATION, THE IMPLIED
* 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. */
#include <stdio.h>
#ifdef _HAVE_STDC
#include <stdarg.h>
#else
#include <varargs.h>
#endif
#include <limits.h>
#include <errno.h>
#include <_ansi.h>
#ifndef _SMALL_PRINTF
#include "local.h"
#else
#ifdef INTEGER_ONLY
#define _vfprintf_r _vfiprintf_r
#endif
#endif
#ifndef _SMALL_PRINTF
int
#ifdef _HAVE_STDC
_DEFUN (_snprintf_r, (ptr, str, size, fmt), struct _reent *ptr _AND char *str _AND size_t size _AND _CONST char *fmt _DOTS)
#else
_snprintf_r (ptr, str, size, fmt, va_alist)
struct _reent *ptr;
char *str;
size_t size;
_CONST char *fmt;
va_dcl
#endif
{
int ret;
va_list ap;
FILE f;
if (size > INT_MAX)
{
ptr->_errno = EOVERFLOW;
return EOF;
}
f._flags = __SWR | __SSTR;
f._bf._base = f._p = (unsigned char *) str;
f._bf._size = f._w = (size > 0 ? size - 1 : 0);
f._file = -1; /* No file. */
#ifdef _HAVE_STDC
va_start (ap, fmt);
#else
va_start (ap);
#endif
ret = _vfprintf_r (ptr, &f, fmt, ap);
va_end (ap);
if (ret < EOF)
ptr->_errno = EOVERFLOW;
if (size > 0)
*f._p = 0;
return (ret);
}
#endif
#ifndef _REENT_ONLY
int
#ifdef _HAVE_STDC
_DEFUN (snprintf, (str, size, fmt), char *str _AND size_t size _AND _CONST char *fmt _DOTS)
#else
snprintf (str, size, fmt, va_alist)
char *str;
size_t size;
_CONST char *fmt;
va_dcl
#endif
{
int ret;
va_list ap;
FILE f;
struct _reent *ptr = _REENT;
if (size > INT_MAX)
{
ptr->_errno = EOVERFLOW;
return EOF;
}
f._flags = __SWR | __SSTR;
f._bf._base = f._p = (unsigned char *) str;
f._bf._size = f._w = (size > 0 ? size - 1 : 0);
f._file = -1; /* No file. */
#ifdef _HAVE_STDC
va_start (ap, fmt);
#else
va_start (ap);
#endif
ret = _vfprintf_r (ptr, &f, fmt, ap);
va_end (ap);
if (ret < EOF)
ptr->_errno = EOVERFLOW;
if (size > 0)
*f._p = 0;
return (ret);
}
#endif

View file

@ -0,0 +1,393 @@
/*
* Copyright (c) 1990 The Regents of the University of California.
* All rights reserved.
*
* Redistribution and use in source and binary forms are permitted
* provided that the above copyright notice and this paragraph are
* duplicated in all such forms and that any documentation,
* advertising materials, and other materials related to such
* distribution and use acknowledge that the software was developed
* by the University of California, Berkeley. The name of the
* University may not be used to endorse or promote products derived
* from this software without specific prior written permission.
* THIS SOFTWARE IS PROVIDED ``AS IS'' AND WITHOUT ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, WITHOUT LIMITATION, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
*/
/*
FUNCTION
<<printf>>, <<fprintf>>, <<asprintf>>, <<sprintf>>, <<snprintf>>---format output
INDEX
fprintf
INDEX
printf
INDEX
asprintf
INDEX
sprintf
INDEX
snprintf
ANSI_SYNOPSIS
#include <stdio.h>
int printf(const char *<[format]> [, <[arg]>, ...]);
int fprintf(FILE *<[fd]>, const char *<[format]> [, <[arg]>, ...]);
int sprintf(char *<[str]>, const char *<[format]> [, <[arg]>, ...]);
int asprintf(char **<[strp]>, const char *<[format]> [, <[arg]>, ...]);
int snprintf(char *<[str]>, size_t <[size]>, const char *<[format]> [, <[arg]>, ...]);
TRAD_SYNOPSIS
#include <stdio.h>
int printf(<[format]> [, <[arg]>, ...])
char *<[format]>;
int fprintf(<[fd]>, <[format]> [, <[arg]>, ...]);
FILE *<[fd]>;
char *<[format]>;
int asprintf(<[strp]>, <[format]> [, <[arg]>, ...]);
char **<[strp]>;
char *<[format]>;
int sprintf(<[str]>, <[format]> [, <[arg]>, ...]);
char *<[str]>;
char *<[format]>;
int snprintf(<[str]>, size_t <[size]>, <[format]> [, <[arg]>, ...]);
char *<[str]>;
size_t <[size]>;
char *<[format]>;
DESCRIPTION
<<printf>> accepts a series of arguments, applies to each a
format specifier from <<*<[format]>>>, and writes the
formatted data to <<stdout>>, terminated with a null character.
The behavior of <<printf>> is undefined if there are not enough
arguments for the format.
<<printf>> returns when it reaches the end of the format string.
If there are more arguments than the format requires, excess
arguments are ignored.
<<fprintf>>, <<asprintf>>, <<sprintf>> and <<snprintf>> are identical
to <<printf>>, other than the destination of the formatted output:
<<fprintf>> sends the output to a specified file <[fd]>, while
<<asprintf>> stores the output in a dynamically allocated buffer,
while <<sprintf>> stores the output in the specified char array
<[str]> and <<snprintf>> limits number of characters written to
<[str]> to at most <[size]> (including terminating <<0>>). For
<<sprintf>> and <<snprintf>>, the behavior is undefined if the
output <<*<[str]>>> overlaps with one of the arguments. For
<<asprintf>>, <[strp]> points to a pointer to char which is filled
in with the dynamically allocated buffer. <[format]> is a pointer
to a charater string containing two types of objects: ordinary
characters (other than <<%>>), which are copied unchanged to the
output, and conversion specifications, each of which is introduced
by <<%>>. (To include <<%>> in the output, use <<%%>> in the format
string.) A conversion specification has the following form:
. %[<[flags]>][<[width]>][.<[prec]>][<[size]>][<[type]>]
The fields of the conversion specification have the following meanings:
O+
o <[flags]>
an optional sequence of characters which control
output justification, numeric signs, decimal points,
trailing zeroes, and octal and hex prefixes.
The flag characters are minus (<<->>), plus (<<+>>),
space ( ), zero (<<0>>), and sharp (<<#>>). They can
appear in any combination.
o+
o -
The result of the conversion is left justified, and the right is
padded with blanks. If you do not use this flag, the result is right
justified, and padded on the left.
o +
The result of a signed conversion (as determined by <[type]>)
will always begin with a plus or minus sign. (If you do not use
this flag, positive values do not begin with a plus sign.)
o " " (space)
If the first character of a signed conversion specification
is not a sign, or if a signed conversion results in no
characters, the result will begin with a space. If the
space ( ) flag and the plus (<<+>>) flag both appear,
the space flag is ignored.
o 0
If the <[type]> character is <<d>>, <<i>>, <<o>>, <<u>>,
<<x>>, <<X>>, <<e>>, <<E>>, <<f>>, <<g>>, or <<G>>: leading zeroes,
are used to pad the field width (following any indication of sign or
base); no spaces are used for padding. If the zero (<<0>>) and
minus (<<->>) flags both appear, the zero (<<0>>) flag will
be ignored. For <<d>>, <<i>>, <<o>>, <<u>>, <<x>>, and <<X>>
conversions, if a precision <[prec]> is specified, the zero (<<0>>)
flag is ignored.
Note that <<0>> is interpreted as a flag, not as the beginning
of a field width.
o #
The result is to be converted to an alternative form, according
to the next character:
o+
o 0
increases precision to force the first digit
of the result to be a zero.
o x
a non-zero result will have a <<0x>> prefix.
o X
a non-zero result will have a <<0X>> prefix.
o e, E or f
The result will always contain a decimal point
even if no digits follow the point.
(Normally, a decimal point appears only if a
digit follows it.) Trailing zeroes are removed.
o g or G
same as <<e>> or <<E>>, but trailing zeroes
are not removed.
o all others
undefined.
o-
o-
o <[width]>
<[width]> is an optional minimum field width. You can either
specify it directly as a decimal integer, or indirectly by
using instead an asterisk (<<*>>), in which case an <<int>>
argument is used as the field width. Negative field widths
are not supported; if you attempt to specify a negative field
width, it is interpreted as a minus (<<->>) flag followed by a
positive field width.
o <[prec]>
an optional field; if present, it is introduced with `<<.>>'
(a period). This field gives the maximum number of
characters to print in a conversion; the minimum number of
digits of an integer to print, for conversions with <[type]>
<<d>>, <<i>>, <<o>>, <<u>>, <<x>>, and <<X>>; the maximum number of
significant digits, for the <<g>> and <<G>> conversions;
or the number of digits to print after the decimal
point, for <<e>>, <<E>>, and <<f>> conversions. You can specify
the precision either directly as a decimal integer or
indirectly by using an asterisk (<<*>>), in which case
an <<int>> argument is used as the precision. Supplying a negative
precision is equivalent to omitting the precision.
If only a period is specified the precision is zero.
If a precision appears with any other conversion <[type]>
than those listed here, the behavior is undefined.
o <[size]>
<<h>>, <<l>>, and <<L>> are optional size characters which
override the default way that <<printf>> interprets the
data type of the corresponding argument. <<h>> forces
the following <<d>>, <<i>>, <<o>>, <<u>>, <<x>> or <<X>> conversion
<[type]> to apply to a <<short>> or <<unsigned short>>. <<h>> also
forces a following <<n>> <[type]> to apply to
a pointer to a <<short>>. Similarily, an
<<l>> forces the following <<d>>, <<i>>, <<o>>, <<u>>,
<<x>> or <<X>> conversion <[type]> to apply to a <<long>> or
<<unsigned long>>. <<l>> also forces a following <<n>> <[type]> to
apply to a pointer to a <<long>>. <<l>> with <<c>>, <<s>> is
equivalent to <<C>>, <<S>> respectively. If an <<h>>
or an <<l>> appears with another conversion
specifier, the behavior is undefined. <<L>> forces a
following <<e>>, <<E>>, <<f>>, <<g>> or <<G>> conversion <[type]> to
apply to a <<long double>> argument. If <<L>> appears with
any other conversion <[type]>, the behavior is undefined.
o <[type]>
<[type]> specifies what kind of conversion <<printf>> performs.
Here is a table of these:
o+
o %
prints the percent character (<<%>>)
o c
prints <[arg]> as single character
o C
prints wchar_t <[arg]> as single multibyte character
o s
prints characters until precision is reached or a null terminator
is encountered; takes a string pointer
o S
converts wchar_t characters to multibyte output characters until
precision is reached or a null wchar_t terminator
is encountered; takes a wchar_t pointer
o d
prints a signed decimal integer; takes an <<int>> (same as <<i>>)
o i
prints a signed decimal integer; takes an <<int>> (same as <<d>>)
o o
prints a signed octal integer; takes an <<int>>
o u
prints an unsigned decimal integer; takes an <<int>>
o x
prints an unsigned hexadecimal integer (using <<abcdef>> as
digits beyond <<9>>); takes an <<int>>
o X
prints an unsigned hexadecimal integer (using <<ABCDEF>> as
digits beyond <<9>>); takes an <<int>>
o f
prints a signed value of the form <<[-]9999.9999>>; takes
a floating-point number
o e
prints a signed value of the form <<[-]9.9999e[+|-]999>>; takes a
floating-point number
o E
prints the same way as <<e>>, but using <<E>> to introduce the
exponent; takes a floating-point number
o g
prints a signed value in either <<f>> or <<e>> form, based on given
value and precision---trailing zeros and the decimal point are
printed only if necessary; takes a floating-point number
o G
prints the same way as <<g>>, but using <<E>> for the exponent if an
exponent is needed; takes a floating-point number
o n
stores (in the same object) a count of the characters written;
takes a pointer to <<int>>
o p
prints a pointer in an implementation-defined format.
This implementation treats the pointer as an
<<unsigned long>> (same as <<Lu>>).
o-
O-
RETURNS
<<sprintf>> and <<asprintf>> return the number of bytes in the output string,
save that the concluding <<NULL>> is not counted.
<<printf>> and <<fprintf>> return the number of characters transmitted.
If an error occurs, <<printf>> and <<fprintf>> return <<EOF>> and
<<asprintf>> returns -1. No error returns occur for <<sprintf>>.
PORTABILITY
The ANSI C standard specifies that implementations must
support at least formatted output of up to 509 characters.
Supporting OS subroutines required: <<close>>, <<fstat>>, <<isatty>>,
<<lseek>>, <<read>>, <<sbrk>>, <<write>>.
*/
#include <stdio.h>
#ifdef _HAVE_STDC
#include <stdarg.h>
#else
#include <varargs.h>
#endif
#include <limits.h>
#include <_ansi.h>
#ifndef _SMALL_PRINTF
#include "local.h"
#else
#ifdef INTEGER_ONLY
#define _vfprintf_r _vfiprintf_r
#endif
#endif
#ifndef _SMALL_PRINTF
int
#ifdef _HAVE_STDC
_DEFUN (_sprintf_r, (ptr, str, fmt), struct _reent *ptr _AND char *str _AND _CONST char *fmt _DOTS)
#else
_sprintf_r (ptr, str, fmt, va_alist)
struct _reent *ptr;
char *str;
_CONST char *fmt;
va_dcl
#endif
{
int ret;
va_list ap;
FILE f;
f._flags = __SWR | __SSTR;
f._bf._base = f._p = (unsigned char *) str;
f._bf._size = f._w = INT_MAX;
f._file = -1; /* No file. */
#ifdef _HAVE_STDC
va_start (ap, fmt);
#else
va_start (ap);
#endif
ret = _vfprintf_r (ptr, &f, fmt, ap);
va_end (ap);
*f._p = 0;
return (ret);
}
#endif
#ifndef _REENT_ONLY
int
#ifdef _HAVE_STDC
_DEFUN (sprintf, (str, fmt), char *str _AND _CONST char *fmt _DOTS)
#else
sprintf (str, fmt, va_alist)
char *str;
_CONST char *fmt;
va_dcl
#endif
{
int ret;
va_list ap;
FILE f;
f._flags = __SWR | __SSTR;
f._bf._base = f._p = (unsigned char *) str;
f._bf._size = f._w = INT_MAX;
f._file = -1; /* No file. */
#ifdef _HAVE_STDC
va_start (ap, fmt);
#else
va_start (ap);
#endif
ret = _vfprintf_r (_REENT, &f, fmt, ap);
va_end (ap);
*f._p = 0;
return (ret);
}
#endif

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,32 @@
/*
* Copyright (c) 1990 The Regents of the University of California.
* All rights reserved.
*
* Redistribution and use in source and binary forms are permitted
* provided that the above copyright notice and this paragraph are
* duplicated in all such forms and that any documentation,
* advertising materials, and other materials related to such
* distribution and use acknowledge that the software was developed
* by the University of California, Berkeley. The name of the
* University may not be used to endorse or promote products derived
* from this software without specific prior written permission.
* THIS SOFTWARE IS PROVIDED ``AS IS'' AND WITHOUT ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, WITHOUT LIMITATION, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
*
* %W% (Berkeley) %G%
*/
/*
* Floating point scanf/printf (input/output) definitions.
*/
#ifdef _NO_LONGDBL
/* 11-bit exponent (VAX G floating point) is 308 decimal digits */
#define MAXEXP 308
#else /* !_NO_LONGDBL */
/* 15-bit exponent (Intel extended floating point) is 4932 decimal digits */
#define MAXEXP 4932
#endif /* !_NO_LONGDBL */
/* 128 bit fraction takes up 39 decimal digits; max reasonable precision */
#define MAXFRACT 39

View file

@ -0,0 +1,38 @@
/*
* Copyright (c) 1990 The Regents of the University of California.
* All rights reserved.
*
* Redistribution and use in source and binary forms are permitted
* provided that the above copyright notice and this paragraph are
* duplicated in all such forms and that any documentation,
* advertising materials, and other materials related to such
* distribution and use acknowledge that the software was developed
* by the University of California, Berkeley. The name of the
* University may not be used to endorse or promote products derived
* from this software without specific prior written permission.
* THIS SOFTWARE IS PROVIDED ``AS IS'' AND WITHOUT ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, WITHOUT LIMITATION, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
*/
/* %W% (Berkeley) %G% */
#include <_ansi.h>
/*
* I/O descriptors for __sfvwrite().
*/
struct __siov {
_CONST _PTR iov_base;
size_t iov_len;
};
struct __suio {
struct __siov *uio_iov;
int uio_iovcnt;
int uio_resid;
};
extern int _EXFUN(__sfvwrite,(FILE *, struct __suio *));
extern int _EXFUN(__swsetup,(FILE *));

View file

@ -0,0 +1,89 @@
/*
* Copyright (c) 1990 The Regents of the University of California.
* All rights reserved.
*
* Redistribution and use in source and binary forms are permitted
* provided that the above copyright notice and this paragraph are
* duplicated in all such forms and that any documentation,
* advertising materials, and other materials related to such
* distribution and use acknowledge that the software was developed
* by the University of California, Berkeley. The name of the
* University may not be used to endorse or promote products derived
* from this software without specific prior written permission.
* THIS SOFTWARE IS PROVIDED ``AS IS'' AND WITHOUT ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, WITHOUT LIMITATION, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
*
* %W% (UofMD/Berkeley) %G%
*/
/*
* Information local to this implementation of stdio,
* in particular, macros and private variables.
*/
#include <_ansi.h>
#include <stdarg.h>
#include <reent.h>
#include <unistd.h>
extern int _EXFUN(__svfscanf_r,(struct _reent *,FILE *, _CONST char *,va_list));
extern FILE *_EXFUN(__sfp,(struct _reent *));
extern int _EXFUN(__sflags,(struct _reent *,_CONST char*, int*));
extern int _EXFUN(__srefill,(FILE *));
extern _READ_WRITE_RETURN_TYPE _EXFUN(__sread,(void *, char *, int));
extern _READ_WRITE_RETURN_TYPE _EXFUN(__swrite,(void *, char const *, int));
extern _fpos_t _EXFUN(__sseek,(void *, _fpos_t, int));
extern int _EXFUN(__sclose,(void *));
extern int _EXFUN(__stextmode,(int));
extern void _EXFUN(__sinit,(struct _reent *));
extern void _EXFUN(_cleanup_r,(struct _reent *));
extern void _EXFUN(__smakebuf,(FILE *));
extern int _EXFUN(_fwalk,(struct _reent *, int (*)(FILE *)));
struct _glue * _EXFUN(__sfmoreglue,(struct _reent *,int n));
extern int _EXFUN(__srefill,(FILE *fp));
/* Called by the main entry point fns to ensure stdio has been initialized. */
#define CHECK_INIT(fp) \
do \
{ \
if (!_REENT->__sdidinit) \
__sinit (_REENT); \
} \
while (0)
/* Return true iff the given FILE cannot be written now. */
#define cantwrite(fp) \
((((fp)->_flags & __SWR) == 0 || (fp)->_bf._base == NULL) && \
__swsetup(fp))
/* Test whether the given stdio file has an active ungetc buffer;
release such a buffer, without restoring ordinary unread data. */
#define HASUB(fp) ((fp)->_ub._base != NULL)
#define FREEUB(fp) { \
if ((fp)->_ub._base != (fp)->_ubuf) \
_free_r(_REENT, (char *)(fp)->_ub._base); \
(fp)->_ub._base = NULL; \
}
/* Test for an fgetline() buffer. */
#define HASLB(fp) ((fp)->_lb._base != NULL)
#define FREELB(fp) { _free_r(_REENT,(char *)(fp)->_lb._base); (fp)->_lb._base = NULL; }
/* WARNING: _dcvt is defined in the stdlib directory, not here! */
char *_EXFUN(_dcvt,(struct _reent *, char *, double, int, int, char, int));
char *_EXFUN(_sicvt,(char *, short, char));
char *_EXFUN(_icvt,(char *, int, char));
char *_EXFUN(_licvt,(char *, long, char));
#ifdef __GNUC__
char *_EXFUN(_llicvt,(char *, long long, char));
#endif
#define CVT_BUF_SIZE 128
#define NDYNAMIC 4 /* add four more whenever necessary */

View file

@ -0,0 +1,20 @@
#ifndef _MBCTYPE_H_
#define _MBCTYPE_H_
/* escape character used for JIS encoding */
#define ESC_CHAR 0x1b
/* functions used to support SHIFT_JIS, EUC-JP, and JIS multibyte encodings */
int _EXFUN(_issjis1, (int c));
int _EXFUN(_issjis2, (int c));
int _EXFUN(_iseucjp, (int c));
int _EXFUN(_isjis, (int c));
#define _issjis1(c) (((c) >= 0x81 && (c) <= 0x9f) || ((c) >= 0xe0 && (c) <= 0xef))
#define _issjis2(c) (((c) >= 0x40 && (c) <= 0x7e) || ((c) >= 0x80 && (c) <= 0xfc))
#define _iseucjp(c) ((c) >= 0xa1 && (c) <= 0xfe)
#define _isjis(c) ((c) >= 0x21 && (c) <= 0x7e)
#endif /* _MBCTYPE_H_ */

View file

@ -0,0 +1,79 @@
/*
* Copyright (c) 1990 The Regents of the University of California.
* All rights reserved.
*
* Redistribution and use in source and binary forms are permitted
* provided that the above copyright notice and this paragraph are
* duplicated in all such forms and that any documentation,
* advertising materials, and other materials related to such
* distribution and use acknowledge that the software was developed
* by the University of California, Berkeley. The name of the
* University may not be used to endorse or promote products derived
* from this software without specific prior written permission.
* THIS SOFTWARE IS PROVIDED ``AS IS'' AND WITHOUT ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, WITHOUT LIMITATION, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
*/
#include <_ansi.h>
#include <stdio.h>
#include "local.h"
#ifdef _HAVE_STDC
#include <stdarg.h>
#else
#include <varargs.h>
#endif
#ifndef _REENT_ONLY
int
#ifdef _HAVE_STDC
scanf (const char *fmt, ...)
#else
scanf (fmt, va_alist)
char *fmt;
va_dcl
#endif
{
int ret;
va_list ap;
//_REENT_SMALL_CHECK_INIT(_stdin_r (_REENT));
#ifdef _HAVE_STDC
va_start (ap, fmt);
#else
va_start (ap);
#endif
ret = __svfscanf_r (_REENT, _stdin_r (_REENT), fmt, ap);
va_end (ap);
return ret;
}
#endif /* !_REENT_ONLY */
int
#ifdef _HAVE_STDC
_scanf_r (struct _reent *ptr, const char *fmt, ...)
#else
_scanf_r (ptr, fmt, va_alist)
struct _reent *ptr;
char *fmt;
va_dcl
#endif
{
int ret;
va_list ap;
//_REENT_SMALL_CHECK_INIT(_stdin_r (ptr));
#ifdef _HAVE_STDC
va_start (ap, fmt);
#else
va_start (ap);
#endif
ret = __svfscanf_r (ptr, _stdin_r (ptr), fmt, ap);
va_end (ap);
return (ret);
}

File diff suppressed because it is too large Load diff

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,383 @@
/****************************************************************
*
* The author of this software is David M. Gay.
*
* Copyright (c) 1991 by AT&T.
*
* Permission to use, copy, modify, and distribute this software for any
* purpose without fee is hereby granted, provided that this entire notice
* is included in all copies of any software which is or includes a copy
* or modification of this software and in all copies of the supporting
* documentation for such software.
*
* THIS SOFTWARE IS BEING PROVIDED "AS IS", WITHOUT ANY EXPRESS OR IMPLIED
* WARRANTY. IN PARTICULAR, NEITHER THE AUTHOR NOR AT&T MAKES ANY
* REPRESENTATION OR WARRANTY OF ANY KIND CONCERNING THE MERCHANTABILITY
* OF THIS SOFTWARE OR ITS FITNESS FOR ANY PARTICULAR PURPOSE.
*
***************************************************************/
/* Please send bug reports to
David M. Gay
AT&T Bell Laboratories, Room 2C-463
600 Mountain Avenue
Murray Hill, NJ 07974-2070
U.S.A.
dmg@research.att.com or research!dmg
*/
#include <ieeefp.h>
#include <math.h>
#include <float.h>
#include <errno.h>
#include <sys/config.h>
#include <sys/types.h>
#ifdef __IEEE_LITTLE_ENDIAN
#define IEEE_8087
#endif
#ifdef __IEEE_BIG_ENDIAN
#define IEEE_MC68k
#endif
#ifdef __Z8000__
#define Just_16
#endif
#ifdef DEBUG
#include "stdio.h"
#define Bug(x) {fprintf(stderr, "%s\n", x); exit(1);}
#endif
#ifdef Unsigned_Shifts
#define Sign_Extend(a,b) if (b < 0) a |= (__uint32_t)0xffff0000;
#else
#define Sign_Extend(a,b) /*no-op*/
#endif
#if defined(IEEE_8087) + defined(IEEE_MC68k) + defined(VAX) + defined(IBM) != 1
Exactly one of IEEE_8087, IEEE_MC68k, VAX, or IBM should be defined.
#endif
/* 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
a union. This is necessary to avoid undefined behavior according to
the ANSI C spec. */
union double_union
{
double d;
__uint32_t i[2];
};
#ifdef IEEE_8087
#define word0(x) (x.i[1])
#define word1(x) (x.i[0])
#else
#define word0(x) (x.i[0])
#define word1(x) (x.i[1])
#endif
/* The following definition of Storeinc is appropriate for MIPS processors.
* An alternative that might be better on some machines is
* #define Storeinc(a,b,c) (*a++ = b << 16 | c & 0xffff)
*/
#if defined (__IEEE_BYTES_LITTLE_ENDIAN) + defined (IEEE_8087) + defined (VAX)
#define Storeinc(a,b,c) (((unsigned short *)a)[1] = (unsigned short)b, \
((unsigned short *)a)[0] = (unsigned short)c, a++)
#else
#define Storeinc(a,b,c) (((unsigned short *)a)[0] = (unsigned short)b, \
((unsigned short *)a)[1] = (unsigned short)c, a++)
#endif
/* #define P DBL_MANT_DIG */
/* Ten_pmax = floor(P*log(2)/log(5)) */
/* Bletch = (highest power of 2 < DBL_MAX_10_EXP) / 16 */
/* Quick_max = floor((P-1)*log(FLT_RADIX)/log(10) - 1) */
/* Int_max = floor(P*log(FLT_RADIX)/log(10) - 1) */
#if defined(IEEE_8087) + defined(IEEE_MC68k)
#if defined (_DOUBLE_IS_32BITS)
#define Exp_shift 23
#define Exp_shift1 23
#define Exp_msk1 ((__uint32_t)0x00800000L)
#define Exp_msk11 ((__uint32_t)0x00800000L)
#define Exp_mask ((__uint32_t)0x7f800000L)
#define P 24
#define Bias 127
#if 0
#define IEEE_Arith /* it is, but the code doesn't handle IEEE singles yet */
#endif
#define Emin (-126)
#define Exp_1 ((__uint32_t)0x3f800000L)
#define Exp_11 ((__uint32_t)0x3f800000L)
#define Ebits 8
#define Frac_mask ((__uint32_t)0x007fffffL)
#define Frac_mask1 ((__uint32_t)0x007fffffL)
#define Ten_pmax 10
#define Sign_bit ((__uint32_t)0x80000000L)
#define Ten_pmax 10
#define Bletch 2
#define Bndry_mask ((__uint32_t)0x007fffffL)
#define Bndry_mask1 ((__uint32_t)0x007fffffL)
#define LSB 1
#define Sign_bit ((__uint32_t)0x80000000L)
#define Log2P 1
#define Tiny0 0
#define Tiny1 1
#define Quick_max 5
#define Int_max 6
#define Infinite(x) (word0(x) == ((__uint32_t)0x7f800000L))
#undef word0
#undef word1
#define word0(x) (x.i[0])
#define word1(x) 0
#else
#define Exp_shift 20
#define Exp_shift1 20
#define Exp_msk1 ((__uint32_t)0x100000L)
#define Exp_msk11 ((__uint32_t)0x100000L)
#define Exp_mask ((__uint32_t)0x7ff00000L)
#define P 53
#define Bias 1023
#define IEEE_Arith
#define Emin (-1022)
#define Exp_1 ((__uint32_t)0x3ff00000L)
#define Exp_11 ((__uint32_t)0x3ff00000L)
#define Ebits 11
#define Frac_mask ((__uint32_t)0xfffffL)
#define Frac_mask1 ((__uint32_t)0xfffffL)
#define Ten_pmax 22
#define Bletch 0x10
#define Bndry_mask ((__uint32_t)0xfffffL)
#define Bndry_mask1 ((__uint32_t)0xfffffL)
#define LSB 1
#define Sign_bit ((__uint32_t)0x80000000L)
#define Log2P 1
#define Tiny0 0
#define Tiny1 1
#define Quick_max 14
#define Int_max 14
#define Infinite(x) (word0(x) == ((__uint32_t)0x7ff00000L)) /* sufficient test for here */
#endif
#else
#undef Sudden_Underflow
#define Sudden_Underflow
#ifdef IBM
#define Exp_shift 24
#define Exp_shift1 24
#define Exp_msk1 ((__uint32_t)0x1000000L)
#define Exp_msk11 ((__uint32_t)0x1000000L)
#define Exp_mask ((__uint32_t)0x7f000000L)
#define P 14
#define Bias 65
#define Exp_1 ((__uint32_t)0x41000000L)
#define Exp_11 ((__uint32_t)0x41000000L)
#define Ebits 8 /* exponent has 7 bits, but 8 is the right value in b2d */
#define Frac_mask ((__uint32_t)0xffffffL)
#define Frac_mask1 ((__uint32_t)0xffffffL)
#define Bletch 4
#define Ten_pmax 22
#define Bndry_mask ((__uint32_t)0xefffffL)
#define Bndry_mask1 ((__uint32_t)0xffffffL)
#define LSB 1
#define Sign_bit ((__uint32_t)0x80000000L)
#define Log2P 4
#define Tiny0 ((__uint32_t)0x100000L)
#define Tiny1 0
#define Quick_max 14
#define Int_max 15
#else /* VAX */
#define Exp_shift 23
#define Exp_shift1 7
#define Exp_msk1 0x80
#define Exp_msk11 ((__uint32_t)0x800000L)
#define Exp_mask ((__uint32_t)0x7f80L)
#define P 56
#define Bias 129
#define Exp_1 ((__uint32_t)0x40800000L)
#define Exp_11 ((__uint32_t)0x4080L)
#define Ebits 8
#define Frac_mask ((__uint32_t)0x7fffffL)
#define Frac_mask1 ((__uint32_t)0xffff007fL)
#define Ten_pmax 24
#define Bletch 2
#define Bndry_mask ((__uint32_t)0xffff007fL)
#define Bndry_mask1 ((__uint32_t)0xffff007fL)
#define LSB ((__uint32_t)0x10000L)
#define Sign_bit ((__uint32_t)0x8000L)
#define Log2P 1
#define Tiny0 0x80
#define Tiny1 0
#define Quick_max 15
#define Int_max 15
#endif
#endif
#ifndef IEEE_Arith
#define ROUND_BIASED
#endif
#ifdef RND_PRODQUOT
#define rounded_product(a,b) a = rnd_prod(a, b)
#define rounded_quotient(a,b) a = rnd_quot(a, b)
#ifdef KR_headers
extern double rnd_prod(), rnd_quot();
#else
extern double rnd_prod(double, double), rnd_quot(double, double);
#endif
#else
#define rounded_product(a,b) a *= b
#define rounded_quotient(a,b) a /= b
#endif
#define Big0 (Frac_mask1 | Exp_msk1*(DBL_MAX_EXP+Bias-1))
#define Big1 ((__uint32_t)0xffffffffL)
#ifndef Just_16
/* When Pack_32 is not defined, we store 16 bits per 32-bit long.
* This makes some inner loops simpler and sometimes saves work
* during multiplications, but it often seems to make things slightly
* slower. Hence the default is now to store 32 bits per long.
*/
#ifndef Pack_32
#define Pack_32
#endif
#endif
#ifdef __cplusplus
extern "C" double strtod(const char *s00, char **se);
extern "C" char *dtoa(double d, int mode, int ndigits,
int *decpt, int *sign, char **rve);
#endif
typedef struct _Bigint _Bigint;
#if (defined (_SMALL_PRINTF) || defined(SMALL_SCANF) )
#define SMALL_LIB
#endif
#ifdef SMALL_LIB
#define small_Balloc _small_Balloc
#define small_Bfree _small_Bfree
#define small_multadd _small_multadd
#define small_s2b _small_s2b
#define small_lo0bits _small_lo0bits
#define small_hi0bits _small_hi0bits
#define small_i2b _small_i2b
#define small_mult _small_multiply
#define small_pow5mult _small_pow5mult
#define small_lshift _small_lshift
#define small_cmp __small_mcmp
#define small_diff __small_mdiff
#define small_ulp _small_ulp
#define small_b2d _small_b2d
#define small_d2b _small_d2b
#define small_ratio _small_ratio
#define small_tens __small_mprec_tens
#define small_bigtens __small_mprec_bigtens
#define small_tinytens __small_mprec_tinytens
struct _reent ;
double _EXFUN(small_ulp,(double x));
double _EXFUN(small_b2d,(_Bigint *a , int *e));
_Bigint * _EXFUN(small_multadd,(struct _reent *p, _Bigint *, int, int,_Bigint tab[]));
_Bigint * _EXFUN(small_s2b,(struct _reent *, const char*, int, int, __ULong,_Bigint tab[]));
_Bigint * _EXFUN(small_i2b,(struct _reent *,int,_Bigint tab[]));
_Bigint * _EXFUN(small_mult, (struct _reent *, _Bigint *, _Bigint *,_Bigint tab[]));
_Bigint * _EXFUN(small_pow5mult, (struct _reent *, _Bigint *, int k,_Bigint tab[]));
int _EXFUN(small_hi0bits,(__ULong));
int _EXFUN(small_lo0bits,(__ULong *));
_Bigint * _EXFUN(small_d2b,(struct _reent *p, double d, int *e, int *bits,_Bigint tab[]));
_Bigint * _EXFUN(small_lshift,(struct _reent *p, _Bigint *b, int k,_Bigint tab[]));
_Bigint * _EXFUN(small_diff,(struct _reent *p, _Bigint *a, _Bigint *b,_Bigint tab[]));
int _EXFUN(small_cmp,(_Bigint *a, _Bigint *b));
double _EXFUN(small_ratio,(_Bigint *a, _Bigint *b));
#define Bcopy(x,y) memcpy((char *)&x->_sign, (char *)&y->_sign, y->_wds*sizeof(__Long) + 2*sizeof(int))
#if defined(_DOUBLE_IS_32BITS) && defined(__v800)
#define n_bigtens 2
#else
#define n_bigtens 5
#endif
extern _CONST double small_tinytens[];
extern _CONST double small_bigtens[];
extern _CONST double small_tens[];
double _EXFUN(_small_mprec_log10,(int));
#else // NO SMALL_LIB
#define Balloc _Balloc
#define Bfree _Bfree
#define multadd _multadd
#define s2b _s2b
#define lo0bits _lo0bits
#define hi0bits _hi0bits
#define i2b _i2b
#define mult _multiply
#define pow5mult _pow5mult
#define lshift _lshift
#define cmp __mcmp
#define diff __mdiff
#define ulp _ulp
#define b2d _b2d
#define d2b _d2b
#define ratio _ratio
#define tens __mprec_tens
#define bigtens __mprec_bigtens
#define tinytens __mprec_tinytens
struct _reent ;
double _EXFUN(ulp,(double x));
double _EXFUN(b2d,(_Bigint *a , int *e));
_Bigint * _EXFUN(Balloc,(struct _reent *p, int k));
void _EXFUN(Bfree,(struct _reent *p, _Bigint *v));
_Bigint * _EXFUN(multadd,(struct _reent *p, _Bigint *, int, int));
_Bigint * _EXFUN(s2b,(struct _reent *, const char*, int, int, __ULong));
_Bigint * _EXFUN(i2b,(struct _reent *,int));
_Bigint * _EXFUN(mult, (struct _reent *, _Bigint *, _Bigint *));
_Bigint * _EXFUN(pow5mult, (struct _reent *, _Bigint *, int k));
int _EXFUN(hi0bits,(__ULong));
int _EXFUN(lo0bits,(__ULong *));
_Bigint * _EXFUN(d2b,(struct _reent *p, double d, int *e, int *bits));
_Bigint * _EXFUN(lshift,(struct _reent *p, _Bigint *b, int k));
_Bigint * _EXFUN(diff,(struct _reent *p, _Bigint *a, _Bigint *b));
int _EXFUN(cmp,(_Bigint *a, _Bigint *b));
double _EXFUN(ratio,(_Bigint *a, _Bigint *b));
#define Bcopy(x,y) memcpy((char *)&x->_sign, (char *)&y->_sign, y->_wds*sizeof(__Long) + 2*sizeof(int))
#if defined(_DOUBLE_IS_32BITS) && defined(__v800)
#define n_bigtens 2
#else
#define n_bigtens 5
#endif
extern _CONST double tinytens[];
extern _CONST double bigtens[];
extern _CONST double tens[];
double _EXFUN(_mprec_log10,(int));
#endif

View file

@ -0,0 +1,936 @@
/*
FUNCTON
<<strtod>>, <<strtof>>---string to double or float
INDEX
strtod
INDEX
_strtod_r
INDEX
strtof
ANSI_SYNOPSIS
#include <stdlib.h>
double strtod(const char *<[str]>, char **<[tail]>);
float strtof(const char *<[str]>, char **<[tail]>);
double _strtod_r(void *<[reent]>,
const char *<[str]>, char **<[tail]>);
TRAD_SYNOPSIS
#include <stdlib.h>
double strtod(<[str]>,<[tail]>)
char *<[str]>;
char **<[tail]>;
float strtof(<[str]>,<[tail]>)
char *<[str]>;
char **<[tail]>;
double _strtod_r(<[reent]>,<[str]>,<[tail]>)
char *<[reent]>;
char *<[str]>;
char **<[tail]>;
DESCRIPTION
The function <<strtod>> parses the character string <[str]>,
producing a substring which can be converted to a double
value. The substring converted is the longest initial
subsequence of <[str]>, beginning with the first
non-whitespace character, that has the format:
.[+|-]<[digits]>[.][<[digits]>][(e|E)[+|-]<[digits]>]
The substring contains no characters if <[str]> is empty, consists
entirely of whitespace, or if the first non-whitespace
character is something other than <<+>>, <<->>, <<.>>, or a
digit. If the substring is empty, no conversion is done, and
the value of <[str]> is stored in <<*<[tail]>>>. Otherwise,
the substring is converted, and a pointer to the final string
(which will contain at least the terminating null character of
<[str]>) is stored in <<*<[tail]>>>. If you want no
assignment to <<*<[tail]>>>, pass a null pointer as <[tail]>.
<<strtof>> is identical to <<strtod>> except for its return type.
This implementation returns the nearest machine number to the
input decimal string. Ties are broken by using the IEEE
round-even rule.
The alternate function <<_strtod_r>> is a reentrant version.
The extra argument <[reent]> is a pointer to a reentrancy structure.
RETURNS
<<strtod>> returns the converted substring value, if any. If
no conversion could be performed, 0 is returned. If the
correct value is out of the range of representable values,
plus or minus <<HUGE_VAL>> is returned, and <<ERANGE>> is
stored in errno. If the correct value would cause underflow, 0
is returned and <<ERANGE>> is stored in errno.
Supporting OS subroutines required: <<close>>, <<fstat>>, <<isatty>>,
<<lseek>>, <<read>>, <<sbrk>>, <<write>>.
*/
/****************************************************************
*
* The author of this software is David M. Gay.
*
* Copyright (c) 1991 by AT&T.
*
* Permission to use, copy, modify, and distribute this software for any
* purpose without fee is hereby granted, provided that this entire notice
* is included in all copies of any software which is or includes a copy
* or modification of this software and in all copies of the supporting
* documentation for such software.
*
* THIS SOFTWARE IS BEING PROVIDED "AS IS", WITHOUT ANY EXPRESS OR IMPLIED
* WARRANTY. IN PARTICULAR, NEITHER THE AUTHOR NOR AT&T MAKES ANY
* REPRESENTATION OR WARRANTY OF ANY KIND CONCERNING THE MERCHANTABILITY
* OF THIS SOFTWARE OR ITS FITNESS FOR ANY PARTICULAR PURPOSE.
*
***************************************************************/
/* Please send bug reports to
David M. Gay
AT&T Bell Laboratories, Room 2C-463
600 Mountain Avenue
Murray Hill, NJ 07974-2070
U.S.A.
dmg@research.att.com or research!dmg
*/
/* Scanf and printf call both the small_mprec.c file if small_scanf
* has not been specfied optimizations concerning small_mprec.c and
* call of balloc will be performed anyway for scanf.
*/
#ifdef _SMALL_PRINTF
#ifndef SMALL_SCANF
#define SMALL_SCANF
#endif
#endif
#include <_ansi.h>
#include <reent.h>
#include <string.h>
#include "small_mprec.h"
double
_DEFUN (_strtod_r, (ptr, s00, se),
struct _reent *ptr _AND
_CONST char *s00 _AND
char **se)
{
int bb2, bb5, bbe, bd2, bd5, bbbits, bs2, c, dsign, e1, esign, i, j,
k, nd, nd0, nf, nz, nz0, sign;
long e;
_CONST char *s, *s0, *s1;
double aadj, aadj1, adj;
long L;
unsigned long z;
__ULong y;
union double_union rv, rv0;
_Bigint *bb, *bb1, *bd, *bd0, *bs, *delta;
#ifdef SMALL_SCANF
/*
* For the SMALL_SCANF implementation for floating points numbers :
* - To avoid the call of allocator we defined a buffer for each variable : instead of taking the adress
* 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
* buffer that has not been used at the moment
* - This buffers are used in the call of function declared in small_mprec.h
* To have more informations look at small_mprec.c
*/
#define BUF_SIZE 32
#define BUF_LSHIFT_SIZE 40
_Bigint tab_bb[BUF_LSHIFT_SIZE],tab_bb1[BUF_SIZE],tab_bd[BUF_SIZE],tab_bd0[BUF_SIZE],tab_bs[BUF_LSHIFT_SIZE], tab_delta[BUF_LSHIFT_SIZE];
_Bigint tab_bblshift[BUF_LSHIFT_SIZE],tab_bslshift[BUF_LSHIFT_SIZE], tab_deltalshift[BUF_LSHIFT_SIZE],tab_bdlshift[BUF_LSHIFT_SIZE];
#endif
sign = nz0 = nz = 0;
rv.d = 0.;
for (s = s00;; s++)
switch (*s)
{
case '-':
sign = 1;
/* no break */
case '+':
if (*++s)
goto break2;
/* no break */
case 0:
s = s00;
goto ret;
case '\t':
case '\n':
case '\v':
case '\f':
case '\r':
case ' ':
continue;
default:
goto break2;
}
break2:
if (*s == '0')
{
nz0 = 1;
while (*++s == '0');
if (!*s)
goto ret;
}
s0 = s;
y = z = 0;
for (nd = nf = 0; (c = *s) >= '0' && c <= '9'; nd++, s++)
if (nd < 9)
y = 10 * y + c - '0';
else if (nd < 16)
z = 10 * z + c - '0';
nd0 = nd;
if (c == '.')
{
c = *++s;
if (!nd)
{
for (; c == '0'; c = *++s)
nz++;
if (c > '0' && c <= '9')
{
s0 = s;
nf += nz;
nz = 0;
goto have_dig;
}
goto dig_done;
}
for (; c >= '0' && c <= '9'; c = *++s)
{
have_dig:
nz++;
if (c -= '0')
{
nf += nz;
for (i = 1; i < nz; i++)
if (nd++ < 9)
y *= 10;
else if (nd <= DBL_DIG + 1)
z *= 10;
if (nd++ < 9)
y = 10 * y + c;
else if (nd <= DBL_DIG + 1)
z = 10 * z + c;
nz = 0;
}
}
}
dig_done:
e = 0;
if (c == 'e' || c == 'E')
{
if (!nd && !nz && !nz0)
{
s = s00;
goto ret;
}
s00 = s;
esign = 0;
switch (c = *++s)
{
case '-':
esign = 1;
case '+':
c = *++s;
}
if (c >= '0' && c <= '9')
{
while (c == '0')
c = *++s;
if (c > '0' && c <= '9')
{
e = c - '0';
s1 = s;
while ((c = *++s) >= '0' && c <= '9')
e = 10 * e + c - '0';
if (s - s1 > 8)
/* Avoid confusion from exponents
* so large that e might overflow.
*/
e = 9999999L;
if (esign)
e = -e;
}
else
e = 0;
}
else
s = s00;
}
if (!nd)
{
if (!nz && !nz0)
s = s00;
goto ret;
}
e1 = e -= nf;
/* Now we have nd0 digits, starting at s0, followed by a
* decimal point, followed by nd-nd0 digits. The number we're
* after is the integer represented by those digits times
* 10**e */
if (!nd0)
nd0 = nd;
k = nd < DBL_DIG + 1 ? nd : DBL_DIG + 1;
rv.d = y;
if (k > 9)
#ifndef SMALL_SCANF
rv.d = tens[k - 9] * rv.d + z;
#else
rv.d = small_tens[k - 9] * rv.d + z;
#endif
bd0 = 0;
if (nd <= DBL_DIG
#ifndef RND_PRODQUOT
&& FLT_ROUNDS == 1
#endif
)
{
if (!e)
goto ret;
if (e > 0)
{
if (e <= Ten_pmax)
{
#ifdef VAX
goto vax_ovfl_check;
#else
#ifndef SMALL_SCANF
/* rv.d = */ rounded_product (rv.d, tens[e]);
#else
rounded_product (rv.d, small_tens[e]);
#endif
goto ret;
#endif
}
i = DBL_DIG - nd;
if (e <= Ten_pmax + i)
{
/* A fancier test would sometimes let us do
* this for larger i values.
*/
e -= i;
#ifndef SMALL_SCANF
rv.d *= tens[i];
#else
rv.d *= small_tens[i];
#endif
#ifdef VAX
/* VAX exponent range is so narrow we must
* worry about overflow here...
*/
vax_ovfl_check:
word0 (rv) -= P * Exp_msk1;
#ifndef SMALL_SCANF
/* rv.d = */ rounded_product (rv.d, tens[e]);
#else
/* rv.d = */ rounded_product (rv.d, small_tens[e]);
#endif
if ((word0 (rv) & Exp_mask)
> Exp_msk1 * (DBL_MAX_EXP + Bias - 1 - P))
goto ovfl;
word0 (rv) += P * Exp_msk1;
#else
#ifndef SMALL_SCANF
/* rv.d = */ rounded_product (rv.d, tens[e]);
#else
/* rv.d = */ rounded_product (rv.d, small_tens[e]);
#endif
#endif
goto ret;
}
}
#ifndef Inaccurate_Divide
else if (e >= -Ten_pmax)
{
#ifndef SMALL_SCANF
/* rv.d = */ rounded_quotient (rv.d, tens[-e]);
#else
/* rv.d = */ rounded_quotient (rv.d, small_tens[-e]);
#endif
goto ret;
}
#endif
}
e1 += nd - k;
/* Get starting approximation = rv.d * 10**e1 */
if (e1 > 0)
{
if ((i = e1 & 15) != 0)
#ifndef SMALL_SCANF
rv.d *= tens[i];
#else
rv.d *= small_tens[i];
#endif
if (e1 &= ~15)
{
if (e1 > DBL_MAX_10_EXP)
{
ovfl:
ptr->_errno = ERANGE;
#ifdef _HAVE_STDC
rv.d = HUGE_VAL;
#else
/* Can't trust HUGE_VAL */
#ifdef IEEE_Arith
word0 (rv) = Exp_mask;
#ifndef _DOUBLE_IS_32BITS
word1 (rv) = 0;
#endif
#else
word0 (rv) = Big0;
#ifndef _DOUBLE_IS_32BITS
word1 (rv) = Big1;
#endif
#endif
#endif
if (bd0)
goto retfree;
goto ret;
}
if (e1 >>= 4)
{
for (j = 0; e1 > 1; j++, e1 >>= 1)
if (e1 & 1)
#ifndef SMALL_SCANF
rv.d *= bigtens[j];
#else
rv.d *= small_bigtens[j];
#endif
/* The last multiplication could overflow. */
word0 (rv) -= P * Exp_msk1;
#ifndef SMALL_SCANF
rv.d *= bigtens[j];
#else
rv.d *= small_bigtens[j];
#endif
if ((z = word0 (rv) & Exp_mask)
> Exp_msk1 * (DBL_MAX_EXP + Bias - P))
goto ovfl;
if (z > Exp_msk1 * (DBL_MAX_EXP + Bias - 1 - P))
{
/* set to largest number */
/* (Can't trust DBL_MAX) */
word0 (rv) = Big0;
#ifndef _DOUBLE_IS_32BITS
word1 (rv) = Big1;
#endif
}
else
word0 (rv) += P * Exp_msk1;
}
}
}
else if (e1 < 0)
{
e1 = -e1;
if ((i = e1 & 15) != 0)
#ifndef SMALL_SCANF
rv.d /= tens[i];
#else
rv.d /= small_tens[i];
#endif
if (e1 &= ~15)
{
e1 >>= 4;
if (e1 >= 1 << n_bigtens)
goto undfl;
for (j = 0; e1 > 1; j++, e1 >>= 1)
if (e1 & 1)
#ifndef SMALL_SCANF
rv.d *= tinytens[j];
/* The last multiplication could underflow. */
rv0.d = rv.d;
rv.d *=tinytens[j];
#else
rv.d *= small_tinytens[j];
/* The last multiplication could underflow. */
rv0.d = rv.d;
rv.d *= small_tinytens[j];
#endif
if (!rv.d)
{
rv.d = 2. * rv0.d;
#ifndef SMALL_SCANF
rv.d *= tinytens[j];
#else
rv.d *= small_tinytens[j];
#endif
if (!rv.d)
{
undfl:
rv.d = 0.;
ptr->_errno = ERANGE;
if (bd0)
goto retfree;
goto ret;
}
#ifndef _DOUBLE_IS_32BITS
word0 (rv) = Tiny0;
word1 (rv) = Tiny1;
#else
word0 (rv) = Tiny1;
#endif
/* The refinement below will clean
* this approximation up.
*/
}
}
}
/* Now the hard part -- adjusting rv to the correct value.*/
/* Put digits into bd: true value = bd * 10^e */
#ifndef SMALL_SCANF
bd0 = s2b (ptr, s0, nd0, nd, y);
#else
bd0 = small_s2b(ptr,s0, nd0, nd, y, &tab_bd0[0]);
#endif
for (;;)
{
#ifndef SMALL_SCANF
bd = Balloc (ptr, bd0->_k);
#else
bd = &tab_bd[0];
bd->_k = bd0->_k;
bd->_maxwds = 1 << (bd0->_k);
bd->_sign = bd->_wds =0;
#endif
Bcopy (bd, bd0);
#ifndef SMALL_SCANF
bb = d2b (ptr, rv.d, &bbe, &bbbits); /* rv.d = bb * 2^bbe */
bs = i2b (ptr, 1);
#else
bb = small_d2b (ptr, rv.d, &bbe, &bbbits, &tab_bb[0]); /* rv.d = bb * 2^bbe */
bs = small_i2b (ptr, 1, &tab_bs[0]);
#endif
if (e >= 0)
{
bb2 = bb5 = 0;
bd2 = bd5 = e;
}
else
{
bb2 = bb5 = -e;
bd2 = bd5 = 0;
}
if (bbe >= 0)
bb2 += bbe;
else
bd2 -= bbe;
bs2 = bb2;
#ifdef Sudden_Underflow
#ifdef IBM
j = 1 + 4 * P - 3 - bbbits + ((bbe + bbbits - 1) & 3);
#else
j = P + 1 - bbbits;
#endif
#else
i = bbe + bbbits - 1; /* logb(rv.d) */
if (i < Emin) /* denormal */
j = bbe + (P - Emin);
else
j = P + 1 - bbbits;
#endif
bb2 += j;
bd2 += j;
i = bb2 < bd2 ? bb2 : bd2;
if (i > bs2)
i = bs2;
if (i > 0)
{
bb2 -= i;
bd2 -= i;
bs2 -= i;
}
if (bb5 > 0)
{
#ifndef SMALL_SCANF
bs = pow5mult (ptr, bs, bb5);
bb1 = mult (ptr, bs, bb);
Bfree (ptr, bb);
bb = bb1;
#else
if (bs == &tab_bs[0]){
bs = small_pow5mult (ptr, bs, bb5,&tab_bslshift[0]);
}
else{
bs = small_pow5mult (ptr, bs, bb5,&tab_bs[0]);
}
bb1 = small_mult (ptr, bs, bb,&tab_bb1[0]);
bb = bb1;
#endif
}
#ifndef SMALL_SCANF
if (bb2 > 0)
bb = lshift (ptr, bb, bb2);
if (bd5 > 0)
bd = pow5mult (ptr, bd, bd5);
if (bd2 > 0)
bd = lshift (ptr, bd, bd2);
if (bs2 > 0)
bs = lshift (ptr, bs, bs2);
delta = diff (ptr, bb, bd);
dsign = delta->_sign;
delta->_sign = 0;
i = cmp (delta, bs);
#else
if (bb2 > 0){
if (bb == &tab_bb[0] ){
bb = small_lshift (ptr, bb, bb2,&tab_bblshift[0]);
}
else {
bb = small_lshift (ptr, bb, bb2,&tab_bblshift[0]);
}
}
if (bd5 > 0){
if (bd == &tab_bd[0]){
bd = small_pow5mult (ptr, bd, bd5, &tab_bdlshift[0]);
}
else{
bd = small_pow5mult (ptr, bd, bd5, &tab_bd[0]);
}
}
if (bd2 > 0){
if (bd == &tab_bd[0] ){
bd = small_lshift (ptr, bb, bd2,&tab_bdlshift[0]);
}
else {
bd = small_lshift (ptr, bd, bd2,&tab_bd[0]);
}
}
if (bs2 > 0){
if ( bs == &tab_bs[0] ){
bs = small_lshift (ptr, bs, bs2,&tab_bslshift[0]);
}
else{
bs = small_lshift (ptr, bs, bs2,&tab_bs[0]);
}
}
delta = small_diff (ptr, bb, bd,&tab_delta[0]);
dsign = delta->_sign;
delta->_sign = 0;
i = small_cmp (delta, bs);
#endif
if (i < 0)
{
/* Error is less than half an ulp -- check for
* special case of mantissa a power of two.
*/
if (dsign || word1 (rv) || word0 (rv) & Bndry_mask)
break;
#ifndef SMALL_SCANF
delta = lshift (ptr, delta, Log2P);
if (cmp (delta, bs) > 0)
goto drop_down;
#else
if (delta == &tab_delta[0]){
delta = small_lshift (ptr, delta, Log2P,&tab_deltalshift[0]);
}
else{
delta = small_lshift (ptr, delta, Log2P,&tab_delta[0]);
}
if (small_cmp (delta, bs) > 0)
goto drop_down;
#endif
break;
}
if (i == 0)
{
/* exactly half-way between */
if (dsign)
{
if ((word0 (rv) & Bndry_mask1) == Bndry_mask1
&& word1 (rv) == 0xffffffff)
{
/*boundary case -- increment exponent*/
word0 (rv) = (word0 (rv) & Exp_mask)
+ Exp_msk1
#ifdef IBM
| Exp_msk1 >> 4
#endif
;
#ifndef _DOUBLE_IS_32BITS
word1 (rv) = 0;
#endif
break;
}
}
else if (!(word0 (rv) & Bndry_mask) && !word1 (rv))
{
drop_down:
/* boundary case -- decrement exponent */
#ifdef Sudden_Underflow
L = word0 (rv) & Exp_mask;
#ifdef IBM
if (L < Exp_msk1)
#else
if (L <= Exp_msk1)
#endif
goto undfl;
L -= Exp_msk1;
#else
L = (word0 (rv) & Exp_mask) - Exp_msk1;
#endif
word0 (rv) = L | Bndry_mask1;
#ifndef _DOUBLE_IS_32BITS
word1 (rv) = 0xffffffff;
#endif
#ifdef IBM
goto cont;
#else
break;
#endif
}
#ifndef ROUND_BIASED
if (!(word1 (rv) & LSB))
break;
#endif
if (dsign)
#ifndef SMALL_SCANF
rv.d += ulp (rv.d);
#else
rv.d += small_ulp (rv.d);
#endif
#ifndef ROUND_BIASED
else
{
#ifndef SMALL_SCANF
rv.d -= ulp (rv.d);
#else
rv.d -= small_ulp (rv.d);
#endif
#ifndef Sudden_Underflow
if (!rv.d)
goto undfl;
#endif
}
#endif
break;
}
#ifndef SMALL_SCANF
if ((aadj = ratio (delta, bs)) <= 2.)
{
#else
if ((aadj = small_ratio (delta, bs)) <= 2.)
{
#endif
if (dsign)
aadj = aadj1 = 1.;
else if (word1 (rv) || word0 (rv) & Bndry_mask)
{
#ifndef Sudden_Underflow
if (word1 (rv) == Tiny1 && !word0 (rv))
goto undfl;
#endif
aadj = 1.;
aadj1 = -1.;
}
else
{
/* special case -- power of FLT_RADIX to be */
/* rounded down... */
if (aadj < 2. / FLT_RADIX)
aadj = 1. / FLT_RADIX;
else
aadj *= 0.5;
aadj1 = -aadj;
}
}
else
{
aadj *= 0.5;
aadj1 = dsign ? aadj : -aadj;
#ifdef Check_FLT_ROUNDS
switch (FLT_ROUNDS)
{
case 2: /* towards +infinity */
aadj1 -= 0.5;
break;
case 0: /* towards 0 */
case 3: /* towards -infinity */
aadj1 += 0.5;
}
#else
if (FLT_ROUNDS == 0)
aadj1 += 0.5;
#endif
}
y = word0 (rv) & Exp_mask;
/* Check for overflow */
if (y == Exp_msk1 * (DBL_MAX_EXP + Bias - 1))
{
rv0.d = rv.d;
word0 (rv) -= P * Exp_msk1;
#ifndef SMALL_SCANF
adj = aadj1 * ulp (rv.d);
#else
adj = aadj1 * small_ulp (rv.d);
#endif
rv.d += adj;
if ((word0 (rv) & Exp_mask) >=
Exp_msk1 * (DBL_MAX_EXP + Bias - P))
{
if (word0 (rv0) == Big0 && word1 (rv0) == Big1)
goto ovfl;
#ifdef _DOUBLE_IS_32BITS
word0 (rv) = Big1;
#else
word0 (rv) = Big0;
word1 (rv) = Big1;
#endif
goto cont;
}
else
word0 (rv) += P * Exp_msk1;
}
else
{
#ifdef Sudden_Underflow
if ((word0 (rv) & Exp_mask) <= P * Exp_msk1)
{
rv0.d = rv.d;
word0 (rv) += P * Exp_msk1;
#ifndef SMALL_SCANF
adj = aadj1 * ulp (rv.d);
#else
adj = aadj1 * small_ulp (rv.d);
#endif
rv.d += adj;
#ifdef IBM
if ((word0 (rv) & Exp_mask) < P * Exp_msk1)
#else
if ((word0 (rv) & Exp_mask) <= P * Exp_msk1)
#endif
{
if (word0 (rv0) == Tiny0
&& word1 (rv0) == Tiny1)
goto undfl;
word0 (rv) = Tiny0;
word1 (rv) = Tiny1;
goto cont;
}
else
word0 (rv) -= P * Exp_msk1;
}
else
{
#ifndef SMALL_SCANF
adj = aadj1 * ulp (rv.d);
#else
adj = aadj1 * small_ulp (rv.d);
#endif
rv.d += adj;
}
#else
/* Compute adj so that the IEEE rounding rules will
* correctly round rv.d + adj in some half-way cases.
* If rv.d * ulp(rv.d) is denormalized (i.e.,
* y <= (P-1)*Exp_msk1), we must adjust aadj to avoid
* trouble from bits lost to denormalization;
* example: 1.2e-307 .
*/
if (y <= (P - 1) * Exp_msk1 && aadj >= 1.)
{
aadj1 = (double) (int) (aadj + 0.5);
if (!dsign)
aadj1 = -aadj1;
}
#ifndef SMALL_SCANF
adj = aadj1 * ulp (rv.d);
#else
adj = aadj1 * small_ulp (rv.d);
rv.d += adj;
#endif
#endif
}
z = word0 (rv) & Exp_mask;
if (y == z)
{
/* Can we stop now? */
L = aadj;
aadj -= L;
/* The tolerances below are conservative. */
if (dsign || word1 (rv) || word0 (rv) & Bndry_mask)
{
if (aadj < .4999999 || aadj > .5000001)
break;
}
else if (aadj < .4999999 / FLT_RADIX)
break;
}
cont:
#ifndef SMALL_SCANF
Bfree (ptr, bb);
Bfree (ptr, bd);
Bfree (ptr, bs);
Bfree (ptr, delta);
#else
;
#endif
}
retfree:
#ifndef SMALL_SCANF
Bfree (ptr, bb);
Bfree (ptr, bd);
Bfree (ptr, bs);
Bfree (ptr, bd0);
Bfree (ptr, delta);
#endif
ret:
if (se)
*se = (char *) s;
return sign ? -rv.d : rv.d;
}
#ifndef NO_REENT
double
_DEFUN (strtod, (s00, se),
_CONST char *s00 _AND char **se)
{
return _strtod_r (_REENT, s00, se);
}
float
_DEFUN (strtof, (s00, se),
_CONST char *s00 _AND
char **se)
{
return (float)_strtod_r (_REENT, s00, se);
}
#endif

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,59 @@
#include <reent.h>
#include <wchar.h>
#include <stdlib.h>
#include <stdio.h>
#include <errno.h>
#if defined( _SMALL_PRINTF ) || defined(SMALL_SCANF)
#define _ASCII_CAR
#endif
size_t
_DEFUN (_wcrtomb_r, (ptr, s, wc, ps),
struct _reent *ptr _AND
char *s _AND
wchar_t wc _AND
mbstate_t *ps)
{
#ifndef _ASCII_CAR
int retval = 0;
char buf[10];
#ifdef MB_CAPABLE
if (ps == NULL)
{
_REENT_CHECK_MISC(ptr);
ps = &(_REENT_WCRTOMB_STATE(ptr));
}
#endif
if (s == NULL)
retval = _wctomb_r (ptr, buf, L'\0', ps);
else
retval = _wctomb_r (ptr, s, wc, ps);
if (retval == -1)
{
ps->__count = 0;
ptr->_errno = EILSEQ;
return (size_t)(-1);
}
else
return (size_t)retval;
#endif
int retval = 1 ;
return (size_t)retval;
}
#ifndef _REENT_ONLY
size_t
_DEFUN (wcrtomb, (s, wc, ps),
char *s _AND
wchar_t wc _AND
mbstate_t *ps)
{
return _wcrtomb_r (_REENT, s, wc, ps);
}
#endif /* !_REENT_ONLY */

View file

@ -0,0 +1,97 @@
#include <reent.h>
#include <wchar.h>
#include <stdlib.h>
#include <stdio.h>
#include <errno.h>
#if defined( _SMALL_PRINTF ) || defined(SMALL_SCANF)
#define _ASCII_CAR
#endif
size_t
_DEFUN (_wcsrtombs_r, (r, dst, src, len, ps),
struct _reent *r _AND
char *dst _AND
const wchar_t **src _AND
size_t len _AND
mbstate_t *ps)
{
char *ptr = dst;
char buff[10];
wchar_t *pwcs;
size_t n;
int i;
#ifdef MB_CAPABLE
if (ps == NULL)
{
_REENT_CHECK_MISC(r);
ps = &(_REENT_WCSRTOMBS_STATE(r));
}
#endif
/* If no dst pointer, treat len as maximum possible value. */
if (dst == NULL)
len = (size_t)-1;
n = 0;
pwcs = (wchar_t *)(*src);
while (n < len)
{
int count = ps->__count;
wint_t wch = ps->__value.__wch;
#ifndef _ASCII_CAR
int bytes = _wcrtomb_r (r, buff, *pwcs, ps);
if (bytes == -1)
{
r->_errno = EILSEQ;
ps->__count = 0;
return (size_t)-1;
}
#else
int bytes = 1 ;
#endif
if (n <= len - bytes && bytes < len)
{
n += bytes;
if (dst)
{
for (i = 0; i < bytes; ++i)
*ptr++ = buff[i];
++(*src);
}
if (*pwcs++ == 0x00)
{
if (dst)
*src = NULL;
ps->__count = 0;
return n - 1;
}
}
else
{
/* not enough room, we must back up state to before _wctomb_r call */
ps->__count = count;
ps->__value.__wch = wch;
len = 0;
}
}
return n;
}
#ifndef _REENT_ONLY
size_t
_DEFUN (wcsrtombs, (dst, src, len, ps),
char *dst _AND
const wchar_t **src _AND
size_t len _AND
mbstate_t *ps)
{
return _wcsrtombs_r (_REENT, dst, src, len, ps);
}
#endif /* !_REENT_ONLY */

View file

@ -0,0 +1,188 @@
#include <stdlib.h>
#include <string.h>
#include <wchar.h>
#include <locale.h>
#include "mbctype.h"
/* The following function concerns caracter coded in more than 0ne byte. For our small_printf we considered only
caracters coded in ASCII and therefore all our caracters are coded in 8 bits (One byte)
If you need the following treatment because caracter that you use are coded in more than one byte
comment the three following lines */
#if defined( _SMALL_PRINTF ) || defined(SMALL_SCANF)
#define _ASCII_CAR
#endif
/* for some conversions, we use the __count field as a place to store a state value */
#define __state __count
#ifndef _ASCII_CAR
extern char __lc_ctype[12];
#endif
int
_DEFUN (_wctomb_r, (r, s, wchar, state),
struct _reent *r _AND
char *s _AND
wchar_t wchar _AND
mbstate_t *state)
{
#ifndef _ASCII_CAR
if (strlen (__lc_ctype) <= 1)
{ /* fall-through */ }
else if (!strcmp (__lc_ctype, "C-UTF-8"))
{
if (s == NULL)
return 0; /* UTF-8 encoding is not state-dependent */
if (wchar <= 0x7f)
{
*s = wchar;
return 1;
}
else if (wchar >= 0x80 && wchar <= 0x7ff)
{
*s++ = 0xc0 | ((wchar & 0x7c0) >> 6);
*s = 0x80 | (wchar & 0x3f);
return 2;
}
else if (wchar >= 0x800 && wchar <= 0xffff)
{
/* UTF-16 surrogates -- must not occur in normal UCS-4 data */
if (wchar >= 0xd800 && wchar <= 0xdfff)
return -1;
*s++ = 0xe0 | ((wchar & 0xf000) >> 12);
*s++ = 0x80 | ((wchar & 0xfc0) >> 6);
*s = 0x80 | (wchar & 0x3f);
return 3;
}
else if (wchar >= 0x10000 && wchar <= 0x1fffff)
{
*s++ = 0xf0 | ((wchar & 0x1c0000) >> 18);
*s++ = 0x80 | ((wchar & 0x3f000) >> 12);
*s++ = 0x80 | ((wchar & 0xfc0) >> 6);
*s = 0x80 | (wchar & 0x3f);
return 4;
}
else if (wchar >= 0x200000 && wchar <= 0x3ffffff)
{
*s++ = 0xf8 | ((wchar & 0x3000000) >> 24);
*s++ = 0x80 | ((wchar & 0xfc0000) >> 18);
*s++ = 0x80 | ((wchar & 0x3f000) >> 12);
*s++ = 0x80 | ((wchar & 0xfc0) >> 6);
*s = 0x80 | (wchar & 0x3f);
return 5;
}
else if (wchar >= 0x4000000 && wchar <= 0x7fffffff)
{
*s++ = 0xfc | ((wchar & 0x40000000) >> 30);
*s++ = 0x80 | ((wchar & 0x3f000000) >> 24);
*s++ = 0x80 | ((wchar & 0xfc0000) >> 18);
*s++ = 0x80 | ((wchar & 0x3f000) >> 12);
*s++ = 0x80 | ((wchar & 0xfc0) >> 6);
*s = 0x80 | (wchar & 0x3f);
return 6;
}
else
return -1;
}
else if (!strcmp (__lc_ctype, "C-SJIS"))
{
unsigned char char2 = (unsigned char)wchar;
unsigned char char1 = (unsigned char)(wchar >> 8);
if (s == NULL)
return 0; /* not state-dependent */
if (char1 != 0x00)
{
/* first byte is non-zero..validate multi-byte char */
if (_issjis1(char1) && _issjis2(char2))
{
*s++ = (char)char1;
*s = (char)char2;
return 2;
}
else
return -1;
}
}
else if (!strcmp (__lc_ctype, "C-EUCJP"))
{
unsigned char char2 = (unsigned char)wchar;
unsigned char char1 = (unsigned char)(wchar >> 8);
if (s == NULL)
return 0; /* not state-dependent */
if (char1 != 0x00)
{
/* first byte is non-zero..validate multi-byte char */
if (_iseucjp (char1) && _iseucjp (char2))
{
*s++ = (char)char1;
*s = (char)char2;
return 2;
}
else
return -1;
}
}
else if (!strcmp (__lc_ctype, "C-JIS"))
{
int cnt = 0;
unsigned char char2 = (unsigned char)wchar;
unsigned char char1 = (unsigned char)(wchar >> 8);
if (s == NULL)
return 1; /* state-dependent */
if (char1 != 0x00)
{
/* first byte is non-zero..validate multi-byte char */
if (_isjis (char1) && _isjis (char2))
{
if (state->__state == 0)
{
/* must switch from ASCII to JIS state */
state->__state = 1;
*s++ = ESC_CHAR;
*s++ = '$';
*s++ = 'B';
cnt = 3;
}
*s++ = (char)char1;
*s = (char)char2;
return cnt + 2;
}
else
return -1;
}
else
{
if (state->__state != 0)
{
/* must switch from JIS to ASCII state */
state->__state = 0;
*s++ = ESC_CHAR;
*s++ = '(';
*s++ = 'B';
cnt = 3;
}
*s = (char)char2;
return cnt + 1;
}
}
if (s == NULL)
return 0;
#endif
/* otherwise we are dealing with a single byte character */
*s = (char) wchar;
return 1;
}

View file

@ -0,0 +1,453 @@
/*
* Copyright (c) 1990 The Regents of the University of California.
* All rights reserved.
*
* Redistribution and use in source and binary forms are permitted
* provided that the above copyright notice and this paragraph are
* duplicated in all such forms and that any documentation,
* advertising materials, and other materials related to such
* distribution and use acknowledge that the software was developed
* by the University of California, Berkeley. The name of the
* University may not be used to endorse or promote products derived
* from this software without specific prior written permission.
* THIS SOFTWARE IS PROVIDED ``AS IS'' AND WITHOUT ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, WITHOUT LIMITATION, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
*/
/*
FUNCTION
<<scanf>>, <<fscanf>>, <<sscanf>>---scan and format input
INDEX
scanf
INDEX
fscanf
INDEX
sscanf
ANSI_SYNOPSIS
#include <stdio.h>
int scanf(const char *<[format]> [, <[arg]>, ...]);
int fscanf(FILE *<[fd]>, const char *<[format]> [, <[arg]>, ...]);
int sscanf(const char *<[str]>, const char *<[format]>
[, <[arg]>, ...]);
int _scanf_r(struct _reent *<[ptr]>, const char *<[format]> [, <[arg]>, ...]);
int _fscanf_r(struct _reent *<[ptr]>, FILE *<[fd]>, const char *<[format]> [, <[arg]>, ...]);
int _sscanf_r(struct _reent *<[ptr]>, const char *<[str]>, const char *<[format]>
[, <[arg]>, ...]);
TRAD_SYNOPSIS
#include <stdio.h>
int scanf(<[format]> [, <[arg]>, ...])
char *<[format]>;
int fscanf(<[fd]>, <[format]> [, <[arg]>, ...]);
FILE *<[fd]>;
char *<[format]>;
int sscanf(<[str]>, <[format]> [, <[arg]>, ...]);
char *<[str]>;
char *<[format]>;
int _scanf_r(<[ptr]>, <[format]> [, <[arg]>, ...])
struct _reent *<[ptr]>;
char *<[format]>;
int _fscanf_r(<[ptr]>, <[fd]>, <[format]> [, <[arg]>, ...]);
struct _reent *<[ptr]>;
FILE *<[fd]>;
char *<[format]>;
int _sscanf_r(<[ptr]>, <[str]>, <[format]> [, <[arg]>, ...]);
struct _reent *<[ptr]>;
char *<[str]>;
char *<[format]>;
DESCRIPTION
<<scanf>> scans a series of input fields from standard input,
one character at a time. Each field is interpreted according to
a format specifier passed to <<scanf>> in the format string at
<<*<[format]>>>. <<scanf>> stores the interpreted input from
each field at the address passed to it as the corresponding argument
following <[format]>. You must supply the same number of
format specifiers and address arguments as there are input fields.
There must be sufficient address arguments for the given format
specifiers; if not the results are unpredictable and likely
disasterous. Excess address arguments are merely ignored.
<<scanf>> often produces unexpected results if the input diverges from
an expected pattern. Since the combination of <<gets>> or <<fgets>>
followed by <<sscanf>> is safe and easy, that is the preferred way
to be certain that a program is synchronized with input at the end
of a line.
<<fscanf>> and <<sscanf>> are identical to <<scanf>>, other than the
source of input: <<fscanf>> reads from a file, and <<sscanf>>
from a string.
The routines <<_scanf_r>>, <<_fscanf_r>>, and <<_sscanf_r>> are reentrant
versions of <<scanf>>, <<fscanf>>, and <<sscanf>> that take an additional
first argument pointing to a reentrancy structure.
The string at <<*<[format]>>> is a character sequence composed
of zero or more directives. Directives are composed of
one or more whitespace characters, non-whitespace characters,
and format specifications.
Whitespace characters are blank (<< >>), tab (<<\t>>), or
newline (<<\n>>).
When <<scanf>> encounters a whitespace character in the format string
it will read (but not store) all consecutive whitespace characters
up to the next non-whitespace character in the input.
Non-whitespace characters are all other ASCII characters except the
percent sign (<<%>>). When <<scanf>> encounters a non-whitespace
character in the format string it will read, but not store
a matching non-whitespace character.
Format specifications tell <<scanf>> to read and convert characters
from the input field into specific types of values, and store then
in the locations specified by the address arguments.
Trailing whitespace is left unread unless explicitly
matched in the format string.
The format specifiers must begin with a percent sign (<<%>>)
and have the following form:
. %[*][<[width]>][<[size]>]<[type]>
Each format specification begins with the percent character (<<%>>).
The other fields are:
o+
o *
an optional marker; if present, it suppresses interpretation and
assignment of this input field.
o <[width]>
an optional maximum field width: a decimal integer,
which controls the maximum number of characters that
will be read before converting the current input field. If the
input field has fewer than <[width]> characters, <<scanf>>
reads all the characters in the field, and then
proceeds with the next field and its format specification.
If a whitespace or a non-convertable character occurs
before <[width]> character are read, the characters up
to that character are read, converted, and stored.
Then <<scanf>> proceeds to the next format specification.
o size
<<h>>, <<l>>, and <<L>> are optional size characters which
override the default way that <<scanf>> interprets the
data type of the corresponding argument.
.Modifier Type(s)
. hh d, i, o, u, x, n convert input to char,
. store in char object
.
. h d, i, o, u, x, n convert input to short,
. store in short object
.
. h D, I, O, U, X no effect
. e, f, c, s, p
.
. l d, i, o, u, x, n convert input to long,
. store in long object
.
. l e, f, g convert input to double
. store in a double object
.
. l D, I, O, U, X no effect
. c, s, p
.
. ll d, i, o, u, x, n convert to long long,
. store in long long
.
. L d, i, o, u, x, n convert to long long,
. store in long long
.
. L e, f, g, E, G convert to long double,
. store in long double
.
. L all others no effect
o <[type]>
A character to specify what kind of conversion
<<scanf>> performs. Here is a table of the conversion
characters:
o+
o %
No conversion is done; the percent character (<<%>>) is stored.
o c
Scans one character. Corresponding <[arg]>: <<(char *arg)>>.
o s
Reads a character string into the array supplied.
Corresponding <[arg]>: <<(char arg[])>>.
o [<[pattern]>]
Reads a non-empty character string into memory
starting at <[arg]>. This area must be large
enough to accept the sequence and a
terminating null character which will be added
automatically. (<[pattern]> is discussed in the paragraph following
this table). Corresponding <[arg]>: <<(char *arg)>>.
o d
Reads a decimal integer into the corresponding <[arg]>: <<(int *arg)>>.
o D
Reads a decimal integer into the corresponding
<[arg]>: <<(long *arg)>>.
o o
Reads an octal integer into the corresponding <[arg]>: <<(int *arg)>>.
o O
Reads an octal integer into the corresponding <[arg]>: <<(long *arg)>>.
o u
Reads an unsigned decimal integer into the corresponding
<[arg]>: <<(unsigned int *arg)>>.
o U
Reads an unsigned decimal integer into the corresponding <[arg]>:
<<(unsigned long *arg)>>.
o x,X
Read a hexadecimal integer into the corresponding <[arg]>:
<<(int *arg)>>.
o e, f, g
Read a floating-point number into the corresponding <[arg]>:
<<(float *arg)>>.
o E, F, G
Read a floating-point number into the corresponding <[arg]>:
<<(double *arg)>>.
o i
Reads a decimal, octal or hexadecimal integer into the
corresponding <[arg]>: <<(int *arg)>>.
o I
Reads a decimal, octal or hexadecimal integer into the
corresponding <[arg]>: <<(long *arg)>>.
o n
Stores the number of characters read in the corresponding
<[arg]>: <<(int *arg)>>.
o p
Stores a scanned pointer. ANSI C leaves the details
to each implementation; this implementation treats
<<%p>> exactly the same as <<%U>>. Corresponding
<[arg]>: <<(void **arg)>>.
o-
A <[pattern]> of characters surrounded by square brackets can be used
instead of the <<s>> type character. <[pattern]> is a set of
characters which define a search set of possible characters making up
the <<scanf>> input field. If the first character in the brackets is a
caret (<<^>>), the search set is inverted to include all ASCII characters
except those between the brackets. There is also a range facility
which you can use as a shortcut. <<%[0-9] >> matches all decimal digits.
The hyphen must not be the first or last character in the set.
The character prior to the hyphen must be lexically less than the
character after it.
Here are some <[pattern]> examples:
o+
o %[abcd]
matches strings containing only <<a>>, <<b>>, <<c>>, and <<d>>.
o %[^abcd]
matches strings containing any characters except <<a>>, <<b>>,
<<c>>, or <<d>>
o %[A-DW-Z]
matches strings containing <<A>>, <<B>>, <<C>>, <<D>>, <<W>>,
<<X>>, <<Y>>, <<Z>>
o %[z-a]
matches the characters <<z>>, <<->>, and <<a>>
o-
Floating point numbers (for field types <<e>>, <<f>>, <<g>>, <<E>>,
<<F>>, <<G>>) must correspond to the following general form:
. [+/-] ddddd[.]ddd [E|e[+|-]ddd]
where objects inclosed in square brackets are optional, and <<ddd>>
represents decimal, octal, or hexadecimal digits.
o-
RETURNS
<<scanf>> returns the number of input fields successfully
scanned, converted and stored; the return value does
not include scanned fields which were not stored.
If <<scanf>> attempts to read at end-of-file, the return
value is <<EOF>>.
If no fields were stored, the return value is <<0>>.
<<scanf>> might stop scanning a particular field before
reaching the normal field end character, or may
terminate entirely.
<<scanf>> stops scanning and storing the current field
and moves to the next input field (if any)
in any of the following situations:
O+
o The assignment suppressing character (<<*>>) appears
after the <<%>> in the format specification; the current
input field is scanned but not stored.
o <[width]> characters have been read (<[width]> is a
width specification, a positive decimal integer).
o The next character read cannot be converted
under the the current format (for example,
if a <<Z>> is read when the format is decimal).
o The next character in the input field does not appear
in the search set (or does appear in the inverted search set).
O-
When <<scanf>> stops scanning the current input field for one of
these reasons, the next character is considered unread and
used as the first character of the following input field, or the
first character in a subsequent read operation on the input.
<<scanf>> will terminate under the following circumstances:
O+
o The next character in the input field conflicts
with a corresponding non-whitespace character in the
format string.
o The next character in the input field is <<EOF>>.
o The format string has been exhausted.
O-
When the format string contains a character sequence that is
not part of a format specification, the same character
sequence must appear in the input; <<scanf>> will
scan but not store the matched characters. If a
conflict occurs, the first conflicting character remains in the input
as if it had never been read.
PORTABILITY
<<scanf>> is ANSI C.
Supporting OS subroutines required: <<close>>, <<fstat>>, <<isatty>>,
<<lseek>>, <<read>>, <<sbrk>>, <<write>>.
*/
#include <_ansi.h>
#include <reent.h>
#include <stdio.h>
#include <string.h>
#ifdef _HAVE_STDC
#include <stdarg.h>
#else
#include <varargs.h>
#endif
#include "local.h"
/* | ARGSUSED */
/*SUPPRESS 590*/
static
_READ_WRITE_RETURN_TYPE
eofread (cookie, buf, len)
_PTR cookie;
char *buf;
int len;
{
return 0;
}
#ifndef _REENT_ONLY
#ifdef _HAVE_STDC
int
_DEFUN (sscanf, (str, fmt), _CONST char *str _AND _CONST char *fmt _DOTS)
#else
int
sscanf (str, fmt, va_alist)
_CONST char *str;
_CONST char *fmt;
va_dcl
#endif
{
int ret;
va_list ap;
FILE f;
f._flags = __SRD;
f._bf._base = f._p = (unsigned char *) str;
f._bf._size = f._r = strlen (str);
f._read = eofread;
f._ub._base = NULL;
f._lb._base = NULL;
#ifdef _HAVE_STDC
va_start (ap, fmt);
#else
va_start (ap);
#endif
ret = __svfscanf_r (_REENT, &f, fmt, ap);
va_end (ap);
return ret;
}
#endif /* !_REENT_ONLY */
#ifdef _HAVE_STDC
int
_DEFUN (_sscanf_r, (ptr, str, fmt), struct _reent *ptr _AND _CONST char *str _AND _CONST char *fmt _DOTS)
#else
int
_sscanf_r (ptr, str, fmt, va_alist)
struct _reent *ptr;
_CONST char *str;
_CONST char *fmt;
va_dcl
#endif
{
int ret;
va_list ap;
FILE f;
f._flags = __SRD;
f._bf._base = f._p = (unsigned char *) str;
f._bf._size = f._r = strlen (str);
f._read = eofread;
f._ub._base = NULL;
f._lb._base = NULL;
#ifdef _HAVE_STDC
va_start (ap, fmt);
#else
va_start (ap);
#endif
ret = __svfscanf_r (ptr, &f, fmt, ap);
va_end (ap);
return ret;
}

View file

@ -0,0 +1,60 @@
/* SWI numbers for RDP (Demon) monitor. */
#define SWI_WriteC 0x0
#define SWI_Write0 0x2
#define SWI_ReadC 0x4
#define SWI_CLI 0x5
#define SWI_GetEnv 0x10
#define SWI_Exit 0x11
#define SWI_EnterOS 0x16
#define SWI_GetErrno 0x60
#define SWI_Clock 0x61
#define SWI_Time 0x63
#define SWI_Remove 0x64
#define SWI_Rename 0x65
#define SWI_Open 0x66
#define SWI_Close 0x68
#define SWI_Write 0x69
#define SWI_Read 0x6a
#define SWI_Seek 0x6b
#define SWI_Flen 0x6c
#define SWI_IsTTY 0x6e
#define SWI_TmpNam 0x6f
#define SWI_InstallHandler 0x70
#define SWI_GenerateError 0x71
/* Now the SWI numbers and reason codes for RDI (Angel) monitors. */
#define AngelSWI_ARM 0x123456
#ifdef __thumb__
#define AngelSWI 0xAB
#else
#define AngelSWI AngelSWI_ARM
#endif
/* The reason codes: */
#define AngelSWI_Reason_Open 0x01
#define AngelSWI_Reason_Close 0x02
#define AngelSWI_Reason_WriteC 0x03
#define AngelSWI_Reason_Write0 0x04
#define AngelSWI_Reason_Write 0x05
#define AngelSWI_Reason_Read 0x06
#define AngelSWI_Reason_ReadC 0x07
#define AngelSWI_Reason_IsTTY 0x09
#define AngelSWI_Reason_Seek 0x0A
#define AngelSWI_Reason_FLen 0x0C
#define AngelSWI_Reason_TmpNam 0x0D
#define AngelSWI_Reason_Remove 0x0E
#define AngelSWI_Reason_Rename 0x0F
#define AngelSWI_Reason_Clock 0x10
#define AngelSWI_Reason_Time 0x11
#define AngelSWI_Reason_System 0x12
#define AngelSWI_Reason_Errno 0x13
#define AngelSWI_Reason_GetCmdLine 0x15
#define AngelSWI_Reason_HeapInfo 0x16
#define AngelSWI_Reason_EnterSVC 0x17
#define AngelSWI_Reason_ReportException 0x18
#define ADP_Stopped_ApplicationExit ((2 << 16) + 38)
#define ADP_Stopped_RunTimeError ((2 << 16) + 35)

View file

@ -0,0 +1,403 @@
/* Support files for GNU libc. Files in the system namespace go here.
Files in the C namespace (ie those that do not start with an
underscore) go in .c. */
#if 0
/*You can comment this three lines if you want to use _gettimeofday and _times*/
#if defined(_SMALL_PRINTF) || defined(SMALL_SCANF)
#define NO_TIME
#endif
#include <_ansi.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <sys/fcntl.h>
#include <stdio.h>
#ifndef NO_TIME
#include <time.h>
#include <sys/time.h>
#include <sys/times.h>
#endif
#include <errno.h>
#include <reent.h>
#include <unistd.h>
#include "swi.h"
/* Forward prototypes. */
int _system _PARAMS ((const char *));
int _rename _PARAMS ((const char *, const char *));
int isatty _PARAMS ((int));
#ifndef NO_TIME
clock_t _times _PARAMS ((struct tms *));
int _gettimeofday _PARAMS ((struct timeval *, struct timezone *));
#endif
void _raise _PARAMS ((void));
int _unlink _PARAMS ((void));
int _link _PARAMS ((void));
int _stat _PARAMS ((const char *, struct stat *));
int _fstat _PARAMS ((int, struct stat *));
//caddr_t _sbrk _PARAMS ((int));
int _getpid _PARAMS ((int));
int _kill _PARAMS ((int, int));
void _exit _PARAMS ((int));
int _close _PARAMS ((int));
int _swiclose _PARAMS ((int));
int _open _PARAMS ((const char *, int, ...));
int _swiopen _PARAMS ((const char *, int));
int _write _PARAMS ((int, char *, int));
int _swiwrite _PARAMS ((int, char *, int));
int _lseek _PARAMS ((int, int, int));
int _swilseek _PARAMS ((int, int, int));
int _read _PARAMS ((int, char *, int));
int _swiread _PARAMS ((int, char *, int));
void initialise_monitor_handles _PARAMS ((void));
static int wrap _PARAMS ((int));
static int error _PARAMS ((int));
static int get_errno _PARAMS ((void));
static int remap_handle _PARAMS ((int));
static int findslot _PARAMS ((int));
/* Register name faking - works in collusion with the linker. */
register char * stack_ptr asm ("sp");
/* following is copied from libc/stdio/local.h to check std streams */
extern void _EXFUN(__sinit,(struct _reent *));
#ifndef _SMALL_PRINTF
#define CHECK_INIT(fp) \
do \
{ \
if ((fp)->_data == 0) \
(fp)->_data = _REENT; \
if (!(fp)->_data->__sdidinit) \
__sinit ((fp)->_data); \
} \
while (0)
#endif
/* Adjust our internal handles to stay away from std* handles. */
#define FILE_HANDLE_OFFSET (0x20)
static int std_files_checked;
static int monitor_stdin;
static int monitor_stdout;
static int monitor_stderr;
/* Struct used to keep track of the file position, just so we
can implement fseek(fh,x,SEEK_CUR). */
typedef struct
{
int handle;
int pos;
}
poslog;
#define MAX_OPEN_FILES 20
static poslog openfiles [MAX_OPEN_FILES];
/*
static int findslot (int fh)
{
int i;
for (i = 0; i < MAX_OPEN_FILES; i ++)
if (openfiles[i].handle == fh)
break;
return i;
}
*/
/* Function to convert std(in|out|err) handles to internal versions. */
/*
static int remap_handle (int fh)
{
if (!std_files_checked)
{
CHECK_INIT(stdin);
CHECK_INIT(stdout);
CHECK_INIT(stderr);
std_files_checked = 1;
}
if (fh == STDIN_FILENO)
return monitor_stdin;
if (fh == STDOUT_FILENO)
return monitor_stdout;
if (fh == STDERR_FILENO)
return monitor_stderr;
return fh - FILE_HANDLE_OFFSET;
}
*/
/*
void
initialise_monitor_handles (void)
{
int i;
int fh;
const char * name;
name = ":tt";
asm ("mov r0,%2; mov r1, #0; swi %a1; mov %0, r0"
: "=r"(fh)
: "i" (SWI_Open),"r"(name)
: "r0","r1");
monitor_stdin = fh;
name = ":tt";
asm ("mov r0,%2; mov r1, #4; swi %a1; mov %0, r0"
: "=r"(fh)
: "i" (SWI_Open),"r"(name)
: "r0","r1");
monitor_stdout = monitor_stderr = fh;
for (i = 0; i < MAX_OPEN_FILES; i ++)
openfiles[i].handle = -1;
openfiles[0].handle = monitor_stdin;
openfiles[0].pos = 0;
openfiles[1].handle = monitor_stdout;
openfiles[1].pos = 0;
}
*/
static int get_errno (void)
{
asm ("swi %a0" :: "i" (SWI_GetErrno));
}
static int error (int result)
{
errno = get_errno ();
return result;
}
static int wrap (int result)
{
if (result == -1)
return error (-1);
return result;
}
#ifndef NO_FILE
int _read (int file,
char * ptr,
int len)
{
return 0;
}
int _lseek (int file,
int ptr,
int dir)
{
return 0;
}
extern void __io_putchar( char c );
int _write (int file,
char * ptr,
int len)
{
int todo;
for (todo = 0; todo < len; todo++)
{
__io_putchar( *ptr++ );
}
return len;
}
int _open (const char * path,
int flags,
...)
{
return -1;
}
int _close (int file)
{
return -1;
}
void _exit (int n)
{
/* FIXME: return code is thrown away. */
while(1);
}
int _kill (int n, int m)
{
return -1;
}
#if 0 //VC090825: moved to independent lib std_sbrk.lib
caddr_t _sbrk (int incr)
{
extern char end; /* Defined by the linker */
static char *heap_end;
char *prev_heap_end;
if (heap_end == 0) {
heap_end = &end;
}
prev_heap_end = heap_end;
if (heap_end + incr > stack_ptr)
{
_write (1, "Heap and stack collision\n", 25);
abort ();
}
heap_end += incr;
return (caddr_t) prev_heap_end;
}
#endif //if 0 //VC090825: moved to independent lib std_sbrk.lib
#endif
#include <sys/stat.h>
#ifndef NO_FILE
int _fstat(int file, struct stat *st)
{
st->st_mode = S_IFCHR;
return 0;
}
#endif
int _stat (const char *fname, struct stat *st)
{
st->st_mode = S_IFCHR;
return 0;
}
#ifndef NO_FILE
int _link (void)
{
return -1;
}
int _unlink (void)
{
return -1;
}
#endif
void _raise (void)
{
return;
}
#ifndef NO_TIME
int _gettimeofday (struct timeval * tp, struct timezone * tzp)
{
if (tp)
{
/* Ask the host for the seconds since the Unix epoch. */
{
int value;
asm ("swi %a1; mov %0, r0" : "=r" (value): "i" (SWI_Time) : "r0");
tp->tv_sec = value;
}
tp->tv_usec = 0;
}
/* Return fixed data for the timezone. */
if (tzp)
{
tzp->tz_minuteswest = 0;
tzp->tz_dsttime = 0;
}
return 0;
}
/* Return a clock that ticks at 100Hz. */
clock_t _times (struct tms * tp)
{
clock_t timeval;
asm ("swi %a1; mov %0, r0" : "=r" (timeval): "i" (SWI_Clock) : "r0");
if (tp)
{
tp->tms_utime = timeval; /* user time */
tp->tms_stime = 0; /* system time */
tp->tms_cutime = 0; /* user time, children */
tp->tms_cstime = 0; /* system time, children */
}
return timeval;
};
#endif
int isatty (int fd)
{
return 1;
fd = fd;
}
int _system (const char *s)
{
if (s == NULL)
return 0;
errno = ENOSYS;
return -1;
}
#ifndef NO_FILE
int _rename (const char * oldpath, const char * newpath)
{
errno = ENOSYS;
return -1;
}
#endif
#endif

View file

@ -0,0 +1,254 @@
#include "UART0_stdio.h"
int main() {
char ent_char ;
int ent_dec_pos ;
int ent_dec_neg ;
int ent_hex ;
int ent_oct ;
int ent_oct_hex ;
long ent_slong ;
unsigned short ent_ushort ;
unsigned long ent_ulong ;
char tab_char[3] ;
char nom [50] ;
char mois[50] ;
int jour ;
int annee ;
int *ptr ;
char tab[3] ;
long double fld ;
float flottant ;
double f ;
double f4 ;
long double f1 ;
float f2, f3 ;
printf("Entrez un char:");
scanf("%c" , &ent_char);
printf("%c\n", ent_char);
printf("Entrez trois caracteres:\n");
scanf("%3c" , tab_char);
printf("1er char :%c\n", tab_char[0]);
printf("2eme char :%c\n", tab_char[1]);
printf("3eme char :%c\n", tab_char[2]);
printf("Entrez un nombre decimal positif: ");
scanf("%d" , &ent_dec_pos);
printf("%d\n", ent_dec_pos);
printf("Entrez un nombre decimal negatif: ");
scanf("%d" , &ent_dec_neg);
printf("%d\n", ent_dec_neg);
printf("Entrez un nombre decimal long: ");
scanf("%ld" , &ent_slong);
printf("%ld\n", ent_slong);
printf("Entrez un nombre decimal unsigned long: ");
scanf("%lu" , &ent_ulong);
printf("valeur entree: %lu\n", ent_ulong);
printf("Entrez un nombre decimal unsigned short: ");
scanf("%hu" , &ent_ushort);
printf("valeur entree: %lu\n", ent_ushort);
printf("Entrez un nombre en hexa: ");
scanf("%x" , &ent_hex);
printf("%x\n", ent_hex);
printf("Entrez un nombre en octal: ");
scanf("%o" , &ent_oct);
printf("%o \n", ent_oct);
printf("Entrez un nombre en octal ou hexa (preceder de 0 pour octal et de 0x ou 0X pour hexa), ");
scanf("%i" , &ent_oct_hex);
printf("valeur entree en decimal : %i \n", ent_oct_hex);
printf("Entrez une chaine de caracteres: ");
scanf("%s" , nom);
printf("%s \n", nom);
printf("Entrez le jour,le mois et l'annee:\n");
scanf("%d%s%d", &jour, mois, &annee);
printf("\njour:%d \n",jour);
printf("mois:%s \n",mois);
printf("annee:%d \n",annee);
// Dans le cas du format %[...] : le scanf se termine lorsqu'un caractere n'appartenant pas a
// l'ensemble est detecte, inversement si on specifie %[^...] le scanf s'arrete lorsque'un
//caractere de l'ensembles a ete lu
printf("Entrez une chaine de caracteres en majuscules: ");
scanf("%[A-Z]" , nom);
printf("%s \n", nom);
printf("Entrez une chaine de caracteres sans majuscules pour terminer le scanf entrez une majuscule: ");
scanf("%[^A-Z]" , nom);
printf("%s \n", nom);
printf("Entrez une adresse memoire quelconque \n");
scanf("%p",&ptr);
printf("L'adresse %p contient la valeur %d ",ptr,*ptr);
/* printf("Entrez un caractere: ");
scanf("%c" , &ent_char);
__io_ungetc(ent_char);
scanf("%c" , &ent_char);
printf("Apres un scanf suivi d'un ungetc et d'un scanf on a : %c \n", ent_char);
printf("Entrez une chaine de 2 caracteres\n ");
scanf("%s" , nom);
printf("la chaine entree est %s \n",nom);
ent_char = __io_ungetc(nom[0]);
scanf("%c" , nom[0]) ;
printf("Apres un ungetc et d'un scanf on a : %s \n", nom);
*/
printf("Entrer un float:\n");
scanf("%f",&flottant);
printf("Le float entre est %f",flottant);
printf("Entrer un double float:\n");
scanf("%Lf",&f);
printf("Le float entre est %Lf\n",f);
printf("Entrer un nombre avec exposant :\n");
scanf("%le",&f);
printf("Le float entre est %le\n",f);
// Note : le format %g choisit en fonction de la valeur entree le format le plus
// appropriée entre %e et %f
printf("Entrer un nombre avec exposant :\n");
scanf("%lg",&f);
printf("Le float entre est %lg\n",f);
printf("Entrer un nombre avec exposant :\n");
scanf("%Lg",&fld);
printf("Le float entre est %Lg\n",fld);
f1 = 48656568.256479123456789123456789;
f = 48656568.256479123456789123456789;
f2 = 456.45366;
f3 = 456.45362;
printf("Test for Floating points numbers printf\n");
/*Simple test of %f format */
printf("double :%lf\n",f);
/* Test with format specifying first number is equal to minimal number
of caracter to be print the second one is number of digits */
printf("LONG DOUBLE :%Lf - %20.10Lf - %20.15Lf - %20.20Lf - %30.30Lf\n", f1, f1, f1, f1, f1);
printf("float2 :%4.2f %+.0e %E \n", 3.1416, 3.1416, 3.1416);
/*Note: the output should be float2: 3.14 +3e+000 3.141600E+000*/
printf("float3 :%7.3f\n", 1.2345);
printf("float3bis :%7.3lf\n",4865.256479 );
printf("float4 :%10.3f\n", 1.2345e3);
printf("float5 :%10.3f\n", 1.2345e7);
printf("float6 :%12.4e\n", 1.2345);
printf("float7 :%12.4e\n", 123.456789e8);
printf("float8 :%15.5lf\n",48656568.256479 );
printf("float9 :%15.6lf\n",48656568.256479 - 48656568.256478 );
printf("float9bis :%-15.6lf%7.4f\n",48656568.256479 - 48656568.256478,1.2345 );
printf("float9ter :%15.2lf\n",f2*f3 );
/*Note : the outputs shoud be
for 1.2345, ^^1.235
for 1.2345e5, ^^1234.500
for 1.2345e7, 12345000.000
for 1.2345, ^^1.2345e+00
for 123.456789e8, ^^1.2346e+10
for float 9: 48656568.256479 - 48656568.2563,^^^^^^^^0.00001
for float 9bis: 48656568.256479 - 48656568.2563,0.00001^^^^^^^^1.2345
for f2*f3 ,^^^^^^208349,92
^ is equal to a space */
printf("float10 :01234567 \n" );
printf("float11 :%8g|\n", 12.34 );
printf("float12 :%8g|\n", 1234.5678 );
printf("float13 :%8g|\n", 0.0478 );
printf("float14 :%8g|\n", 422121.0 );
printf("float15 :%8g|\n", 422121234.345345 );
/*Note : outputs should be
01234567
12.34|
1234.57|
0.0478|
422121|
4.22121e+08|
*/
printf("float16 :%.0f|\n", 1000.123456789123456789 );
printf("float17 :%.1f|\n", 2000.123456789123456789 );
printf("float18 :%.2f|\n", 3000.123456789123456789 );
printf("float19 :%.10f|\n", 4000.123456789123456789 );
printf("float20 :%.30f|\n", 5000.123456789123456789 );
printf("float21 :%f|\n", 6000.123456789123456789 );
printf("float22 :%.f|\n", 7000.123456789123456789 );
/*Note : outputs should be
1000|
2000.1|
3000.12|
4000.1234567891|
5000.12345678912333823973312939761|
6000.123457|
7000|
*/
int a ;
char c ;
float ft ;
int hex ;
double db ;
char stg[50]="chaine" ;
a=1;
// Test du printf avec une suite de parametres int
printf("Test suite de int: \n a=%d\na+1=%d\na+2=%d\na+3=%d\na+4=%d\na+5=%d\na+6=%d\na+7=%d\na+8=%d\na=%d\n",a,a+1,a+2,a+3,a+4,a+5,a+6,a+7,a+8,a);
//Test du printf avec une suite de floats
ft=1.589634 ;
printf("Test suite de floats: \nft=%f\nft+0.1=%f\nft+0.01=%f\nft+0.001=%f\nft+0.0001=%f\nft+0.00001=%f\n",ft,ft+0.1,ft+0.01,ft+0.001,ft+0.0001,ft+0.00001);
// Test du printf avec un melange de formats
a = 1 ;
c ='c' ;
ft = 1.963214 ;
db = 1.589e+15;
hex = 0x0FA ;
printf("Test avec plusieurs formats:\na=%d\nc=%c\nstg=%s\nft=%6.5f\ndb=%10.2e\nhex=%x\n",a,c,stg,ft,db,hex);
printf("Entrez dans l'ordre un int\n un char\n une chaine\nun float\nun float avec exposant\nun hexa \n");
scanf("%d%c%s%f%le%x",&a,&c,stg,&ft,&db,&hex);
printf("Test avec plusieurs formats apres un scanf:\n a=%d\nc=%c\nstg=%s\nft=%6.5f\ndb=%10.2le\nhex=0x%x\n",a,c,stg,ft,db,hex);
return 0;
}

View file

@ -0,0 +1,44 @@
#define FLOATING
#define PRINT
#define SCANF
int main() {
char ent_char ;
float flottant ;
#ifndef FLOATING
#ifdef PRINT
ent_char='a';
#endif
#ifdef SCANF
scanf("%c" , &ent_char);
#endif
#ifdef PRINT
printf("%c\n", ent_char);
#endif
#else
#ifdef PRINT
flottant = 1.456789;
#endif
#ifdef SCANF
scanf("%f" , &flottant);
#endif
#ifdef PRINT
printf("%f\n", flottant);
#endif
#endif
return 0;
}

View file

@ -0,0 +1,87 @@
int main (){
double f;
/*double f4;
long double f1;
float f2, f3;
float flottant;*/
f = 48656568.256479123456789123456789;
/*
f1= 48656568.256479123456789123456789;
f2 = 456.45366;
f3 = 456.45362; */
//printf("Test du printf");
/*Simple test of %f format */
printf("double :%lf\n",f);
/* Test with format specifying first number is equal to minimal number
of caracter to be print the second one is number of digits */
/*
printf("LONG DOUBLE :%Lf - %20.10Lf - %20.15Lf - %20.20Lf - %30.30Lf\n", f1, f1, f1, f1, f1);
printf("float2 :%4.2f %+.0e %E \n", 3.1416, 3.1416, 3.1416);*/
/*Note: the output should be float2: 3.14 +3e+000 3.141600E+000*/
/*
printf("float3 :%7.3f\n", 1.2345);
printf("float3bis :%7.3lf\n",4865.256479 );
printf("float4 :%10.3f\n", 1.2345e3);
printf("float5 :%10.3f\n", 1.2345e7);
printf("float6 :%12.4e\n", 1.2345);
printf("float7 :%12.4e\n", 123.456789e8);
printf("float8 :%15.5lf\n",48656568.256479 );
printf("float9 :%15.6lf\n",48656568.256479 - 48656568.256478 );
printf("float9bis :%15.2lf\n",f2*f3 );*/
/*Note : the outputs shoud be
for 1.2345, ^^1.235
for 1.2345e5, ^^1234.500
for 1.2345e7, 12345000.000
for 1.2345, ^^1.2345e+00
for 123.456789e8, ^^1.2346e+10
for 48656568.256479 - 48656568.2563,^^^^^^^^0.00001
for f2*f3 ,^^^^^^208349,92
^ is equal to a space */
/*
printf("float10 :01234567 \n" );
printf("float11 :%8g|\n", 12.34 );
printf("float12 :%8g|\n", 1234.5678 );
printf("float13 :%8g|\n", 0.0478 );
printf("float14 :%8g|\n", 422121.0 );
printf("float15 :%8g|\n", 422121234.345345 );*/
/*Note : outputs should be
01234567
12.34|
1234.57|
0.0478|
422121|
4.22121e+08|
*/
/*
printf("float16 :%.0f|\n", 1000.123456789123456789 );
printf("float17 :%.1f|\n", 2000.123456789123456789 );
printf("float18 :%.2f|\n", 3000.123456789123456789 );
printf("float19 :%.10f|\n", 4000.123456789123456789 );
printf("float20 :%.30f|\n", 5000.123456789123456789 );
printf("float21 :%f|\n", 6000.123456789123456789 );
printf("float22 :%.f|\n", 7000.123456789123456789 );
*/
/*Note : outputs should be
1000|
2000.1|
3000.12|
4000.1234567891|
5000.12345678912333823973312939761|
6000.123457|
7000|
*/
//while(1);
}

View file

@ -0,0 +1,14 @@
int main() {
float flottant ;
// char c;
scanf("%f" , &flottant);
// scanf("%c",&c);
//while(1);
return 0;
}

View file

@ -0,0 +1,284 @@
/****************************************************************
*
* The author of this software is David M. Gay.
*
* Copyright (c) 1991 by AT&T.
*
* Permission to use, copy, modify, and distribute this software for any
* purpose without fee is hereby granted, provided that this entire notice
* is included in all copies of any software which is or includes a copy
* or modification of this software and in all copies of the supporting
* documentation for such software.
*
* THIS SOFTWARE IS BEING PROVIDED "AS IS", WITHOUT ANY EXPRESS OR IMPLIED
* WARRANTY. IN PARTICULAR, NEITHER THE AUTHOR NOR AT&T MAKES ANY
* REPRESENTATION OR WARRANTY OF ANY KIND CONCERNING THE MERCHANTABILITY
* OF THIS SOFTWARE OR ITS FITNESS FOR ANY PARTICULAR PURPOSE.
*
***************************************************************/
/* Please send bug reports to
David M. Gay
AT&T Bell Laboratories, Room 2C-463
600 Mountain Avenue
Murray Hill, NJ 07974-2070
U.S.A.
dmg@research.att.com or research!dmg
*/
/* This header file is a modification of mprec.h that only contains floating
point union code. */
#include <ieeefp.h>
#include <math.h>
#include <float.h>
#include <errno.h>
#include <sys/config.h>
#ifdef __IEEE_LITTLE_ENDIAN
#define IEEE_8087
#endif
#ifdef __IEEE_BIG_ENDIAN
#define IEEE_MC68k
#endif
#ifdef __Z8000__
#define Just_16
#endif
#ifdef Unsigned_Shifts
#define Sign_Extend(a,b) if (b < 0) a |= (__uint32_t)0xffff0000;
#else
#define Sign_Extend(a,b) /*no-op*/
#endif
#if defined(IEEE_8087) + defined(IEEE_MC68k) + defined(VAX) + defined(IBM) != 1
Exactly one of IEEE_8087, IEEE_MC68k, VAX, or IBM should be defined.
#endif
#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
a union. This is necessary to avoid undefined behavior according to
the ANSI C spec. */
#ifdef IEEE_8087
#if LDBL_MANT_DIG == 24
struct ldieee
{
unsigned manh:23;
unsigned exp:8;
unsigned sign:1;
};
#elif LDBL_MANT_DIG == 53
struct ldieee
{
unsigned manl:20;
unsigned manh:32;
unsigned exp:11;
unsigned sign:1;
};
#elif LDBL_MANT_DIG == 64
struct ldieee
{
unsigned manl:32;
unsigned manh:32;
unsigned exp:15;
unsigned sign:1;
};
#elif LDBL_MANT_DIG > 64
struct ldieee
{
unsigned manl3:16;
unsigned manl2:32;
unsigned manl:32;
unsigned manh:32;
unsigned exp:15;
unsigned sign:1;
};
#endif /* LDBL_MANT_DIG */
#else /* !IEEE_8087 */
#if LDBL_MANT_DIG == 24
struct ldieee
{
unsigned sign:1;
unsigned exp:8;
unsigned manh:23;
};
#elif LDBL_MANT_DIG == 53
struct ldieee
{
unsigned sign:1;
unsigned exp:11;
unsigned manh:32;
unsigned manl:20;
};
#elif LDBL_MANT_DIG == 64
struct ldieee
{
unsigned sign:1;
unsigned exp:15;
unsigned manh:32;
unsigned manl:32;
};
#elif LDBL_MANT_DIG > 64
struct ldieee
{
unsigned sign:1;
unsigned exp:15;
unsigned manh:32;
unsigned manl:32;
unsigned manl2:32;
unsigned manl3;16;
};
#endif /* LDBL_MANT_DIG */
#endif /* !IEEE_8087 */
#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
a union. This is necessary to avoid undefined behavior according to
the ANSI C spec. */
union double_union
{
double d;
__uint32_t i[2];
};
#ifdef IEEE_8087
#define word0(x) (x.i[1])
#define word1(x) (x.i[0])
#else
#define word0(x) (x.i[0])
#define word1(x) (x.i[1])
#endif
/* #define P DBL_MANT_DIG */
/* Ten_pmax = floor(P*log(2)/log(5)) */
/* Bletch = (highest power of 2 < DBL_MAX_10_EXP) / 16 */
/* Quick_max = floor((P-1)*log(FLT_RADIX)/log(10) - 1) */
/* Int_max = floor(P*log(FLT_RADIX)/log(10) - 1) */
#if defined(IEEE_8087) + defined(IEEE_MC68k)
#if defined (_DOUBLE_IS_32BITS)
#define Exp_shift 23
#define Exp_shift1 23
#define Exp_msk1 ((__uint32_t)0x00800000L)
#define Exp_msk11 ((__uint32_t)0x00800000L)
#define Exp_mask ((__uint32_t)0x7f800000L)
#define P 24
#define Bias 127
#if 0
#define IEEE_Arith /* it is, but the code doesn't handle IEEE singles yet */
#endif
#define Emin (-126)
#define Exp_1 ((__uint32_t)0x3f800000L)
#define Exp_11 ((__uint32_t)0x3f800000L)
#define Ebits 8
#define Frac_mask ((__uint32_t)0x007fffffL)
#define Frac_mask1 ((__uint32_t)0x007fffffL)
#define Ten_pmax 10
#define Sign_bit ((__uint32_t)0x80000000L)
#define Ten_pmax 10
#define Bletch 2
#define Bndry_mask ((__uint32_t)0x007fffffL)
#define Bndry_mask1 ((__uint32_t)0x007fffffL)
#define LSB 1
#define Sign_bit ((__uint32_t)0x80000000L)
#define Log2P 1
#define Tiny0 0
#define Tiny1 1
#define Quick_max 5
#define Int_max 6
#define Infinite(x) (word0(x) == ((__uint32_t)0x7f800000L))
#undef word0
#undef word1
#define word0(x) (x.i[0])
#define word1(x) 0
#else
#define Exp_shift 20
#define Exp_shift1 20
#define Exp_msk1 ((__uint32_t)0x100000L)
#define Exp_msk11 ((__uint32_t)0x100000L)
#define Exp_mask ((__uint32_t)0x7ff00000L)
#define P 53
#define Bias 1023
#define IEEE_Arith
#define Emin (-1022)
#define Exp_1 ((__uint32_t)0x3ff00000L)
#define Exp_11 ((__uint32_t)0x3ff00000L)
#define Ebits 11
#define Frac_mask ((__uint32_t)0xfffffL)
#define Frac_mask1 ((__uint32_t)0xfffffL)
#define Ten_pmax 22
#define Bletch 0x10
#define Bndry_mask ((__uint32_t)0xfffffL)
#define Bndry_mask1 ((__uint32_t)0xfffffL)
#define LSB 1
#define Sign_bit ((__uint32_t)0x80000000L)
#define Log2P 1
#define Tiny0 0
#define Tiny1 1
#define Quick_max 14
#define Int_max 14
#define Infinite(x) (word0(x) == ((__uint32_t)0x7ff00000L)) /* sufficient test for here */
#endif
#else
#undef Sudden_Underflow
#define Sudden_Underflow
#ifdef IBM
#define Exp_shift 24
#define Exp_shift1 24
#define Exp_msk1 ((__uint32_t)0x1000000L)
#define Exp_msk11 ((__uint32_t)0x1000000L)
#define Exp_mask ((__uint32_t)0x7f000000L)
#define P 14
#define Bias 65
#define Exp_1 ((__uint32_t)0x41000000L)
#define Exp_11 ((__uint32_t)0x41000000L)
#define Ebits 8 /* exponent has 7 bits, but 8 is the right value in b2d */
#define Frac_mask ((__uint32_t)0xffffffL)
#define Frac_mask1 ((__uint32_t)0xffffffL)
#define Bletch 4
#define Ten_pmax 22
#define Bndry_mask ((__uint32_t)0xefffffL)
#define Bndry_mask1 ((__uint32_t)0xffffffL)
#define LSB 1
#define Sign_bit ((__uint32_t)0x80000000L)
#define Log2P 4
#define Tiny0 ((__uint32_t)0x100000L)
#define Tiny1 0
#define Quick_max 14
#define Int_max 15
#else /* VAX */
#define Exp_shift 23
#define Exp_shift1 7
#define Exp_msk1 0x80
#define Exp_msk11 ((__uint32_t)0x800000L)
#define Exp_mask ((__uint32_t)0x7f80L)
#define P 56
#define Bias 129
#define Exp_1 ((__uint32_t)0x40800000L)
#define Exp_11 ((__uint32_t)0x4080L)
#define Ebits 8
#define Frac_mask ((__uint32_t)0x7fffffL)
#define Frac_mask1 ((__uint32_t)0xffff007fL)
#define Ten_pmax 24
#define Bletch 2
#define Bndry_mask ((__uint32_t)0xffff007fL)
#define Bndry_mask1 ((__uint32_t)0xffff007fL)
#define LSB ((__uint32_t)0x10000L)
#define Sign_bit ((__uint32_t)0x8000L)
#define Log2P 1
#define Tiny0 0x80
#define Tiny1 0
#define Quick_max 15
#define Int_max 15
#endif
#endif

View file

@ -0,0 +1,362 @@
/** @file hal/micro/cortexm3/flash.c
* @brief Implements the generic flash manipulation routines.
*
* The file 'flash-sw-spec.txt' should provide *all* the information needed
* to understand and work with the FLITF and flash.
*
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
#include PLATFORM_HEADER
#include "error.h"
#include "hal/micro/cortexm3/bootloader/fib-bootloader.h"
#include "hal/micro/cortexm3/mpu.h"
#include "memmap.h"
#include "flash.h"
// A translation table used to convert FibStatus codes to corresponding
// StStatus values
static const StStatus fibToStStatus[] = {
ST_SUCCESS, // FIB_SUCCESS 0
ST_BAD_ARGUMENT, // FIB_ERR_UNALIGNED 1
ST_BAD_ARGUMENT, // FIB_ERR_INVALID_ADDRESS 2
ST_BAD_ARGUMENT, // FIB_ERR_INVALID_TYPE 3
ST_ERR_FLASH_PROG_FAIL, // FIB_ERR_WRITE_PROTECTED 4
ST_ERR_FLASH_PROG_FAIL, // FIB_ERR_WRITE_FAILED 5
ST_ERR_FLASH_WRITE_INHIBITED, // FIB_ERR_ERASE_REQUIRED 6
ST_ERR_FLASH_VERIFY_FAILED // FIB_ERR_VERIFY_FAILED 7
};
//The purpose of flashEraseIsActive and halFlashEraseIsActive() is so that
//interrupts can query the flash library to find out of Flash Erase is
//active when their ISR gets invoked. This is useful because Flash Erase
//causes the chip to go ATOMIC for 21ms and this delay will disrupt interrupt
//latency. By having a sinple API that an ISR can query for this state,
//the ISR can appriopriately adjust for a 21ms latency time.
boolean flashEraseIsActive = FALSE;
boolean halFlashEraseIsActive(void)
{
return flashEraseIsActive;
}
// Emulators do not have FIB bootloaders, so need to include a copy of
// these core flash routines.
#if defined(ST_EMU_TEST)
static void enableFlitf(void)
{
//First, unlock the FLITF by writing the two key values to the Flash
//Protection Unlock register
FPEC_KEY = FPEC_KEY1;
FPEC_KEY = FPEC_KEY2;
//Second, unlock the CIB by writing the two key values to the CIB
//Protection Unlock register
OPT_KEY = FPEC_KEY1;
OPT_KEY = FPEC_KEY2;
//Turn on the FPEC clock for flash manipulation operations
FPEC_CLKREQ = FPEC_CLKREQ_FIELD;
//make sure the FPEC clock is running before we proceed
while( (FPEC_CLKSTAT&FPEC_CLKACK) != FPEC_CLKACK) {}
//just in case, wait until the flash is no longer busy
while( (FLASH_STATUS&FLASH_STATUS_FLA_BSY) == FLASH_STATUS_FLA_BSY ) {}
}
static void disableFlitf(void)
{
//make sure the FPEC is completely idle before turning off the clock
while( (FPEC_CLKSTAT&FPEC_CLKBSY) == FPEC_CLKBSY) {}
//Turn off the FPEC clock now that we're done
FPEC_CLKREQ = FPEC_CLKREQ_RESET;
//Set LOCK and clear OPTWREN to lock both the FLITF and the CIB.
//NOTE: The PROG bit must also be cleared otherwise Flash can still
// be programmed even with the LOCK bit set. BugzID: 6267
FLASH_CTRL = FLASH_CTRL_LOCK; //lock the flash from further accesses
}
static FibStatus fibFlashWrite(int32u address, int8u *data, int32u length, int32u dummy)
{
int32u i;
int16u *ptr;
FibStatus status = FIB_SUCCESS;
// Address and length must be half-word aligned.
if ((address & 1) || (length & 1)) {
return FIB_ERR_UNALIGNED;
}
// Start and end address must be in MFB or CIB.
if (!((address >= MFB_BOTTOM && address + length <= MFB_TOP + 1)
|| (address >= CIB_BOTTOM && address + length <= CIB_TOP + 1))) {
return FIB_ERR_INVALID_ADDRESS;
}
enableFlitf();
ptr = (int16u *)address;
for (i = 0; i < length; i += 2) {
int16u currentData = *ptr;
int16u newData = HIGH_LOW_TO_INT(data[i + 1], data[i]);
// Only program the data if it makes sense to do so.
if (currentData == newData) {
// If the new data matches the flash, don't bother doing anything.
} else if (currentData == 0xFFFF || newData == 0x0000) {
// 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.
// OPTWREN must stay set to keep CIB unlocked.
if ((CIB_OB_BOTTOM <= (int32u)ptr) && ((int32u)ptr <= CIB_OB_TOP)) {
FLASH_CTRL = (FLASH_CTRL_OPTWREN | FLASH_CTRL_OPTPROG);
} else {
FLASH_CTRL = (FLASH_CTRL_OPTWREN | FLASH_CTRL_PROG);
}
// Assigning data to the address performs the actual write.
(*ptr) = newData;
// Wait for the busy bit to clear, indicating operation is done.
while ((FLASH_STATUS & FLASH_STATUS_FLA_BSY) != 0) {}
// Reset the operation complete flag.
FLASH_STATUS = FLASH_STATUS_EOP;
// Check if any error bits have been tripped, and if so, exit.
// The bit PAGE_PROG_ERR is not relevant in this programming mode.
if (FLASH_STATUS & (FLASH_STATUS_WRP_ERR | FLASH_STATUS_PROG_ERR)) {
if (FLASH_STATUS & FLASH_STATUS_WRP_ERR) {
status = FIB_ERR_WRITE_PROTECTED;
} else {
status = FIB_ERR_WRITE_FAILED;
}
FLASH_STATUS = FLASH_STATUS_WRP_ERR;
FLASH_STATUS = FLASH_STATUS_PROG_ERR;
break;
}
} else {
status = FIB_ERR_ERASE_REQUIRED;
break;
}
ptr++;
}
disableFlitf();
return status;
}
static FibStatus fibFlashWriteVerify(int32u address, int8u *data, int32u length)
{
int32u i;
int8u *ptr = (int8u *)address;
for (i = 0; i < length; i++) {
if (*ptr != data[i]) {
return FIB_ERR_VERIFY_FAILED;
}
ptr++;
}
return FIB_SUCCESS;
}
static FibStatus fibFlashErase(FibEraseType eraseType, int32u address)
{
int32u eraseOp;
int32u *ptr;
int32u length;
FibStatus status = FIB_SUCCESS;
if (BYTE_0(eraseType) == MFB_MASS_ERASE) {
eraseOp = FLASH_CTRL_MASSERASE;
ptr = (int32u *)MFB_BOTTOM;
length = MFB_SIZE_W;
} else if (BYTE_0(eraseType) == MFB_PAGE_ERASE) {
if (address < MFB_BOTTOM || address > MFB_TOP) {
return FIB_ERR_INVALID_ADDRESS;
}
eraseOp = FLASH_CTRL_PAGEERASE;
ptr = (int32u *)(address & MFB_PAGE_MASK_B);
length = MFB_PAGE_SIZE_W;
} else if (BYTE_0(eraseType) == CIB_ERASE) {
eraseOp = FLASH_CTRL_OPTWREN | FLASH_CTRL_OPTERASE;
ptr = (int32u *)CIB_BOTTOM;
length = CIB_SIZE_W;
} else {
return FIB_ERR_INVALID_TYPE;
}
if ((eraseType & DO_ERASE) != 0) {
enableFlitf();
FLASH_CTRL = eraseOp;
if (BYTE_0(eraseType) == MFB_PAGE_ERASE) {
FLASH_ADDR = (address & MFB_PAGE_MASK_B);
}
eraseOp |= FLASH_CTRL_FLA_START;
// Perform the actual erase.
FLASH_CTRL = eraseOp;
// Wait for the busy bit to clear, indicating operation is done.
while ((FLASH_STATUS & FLASH_STATUS_FLA_BSY) != 0) {}
// Reset the operation complete flag.
FLASH_STATUS = FLASH_STATUS_EOP;
// Check for errors; the only relevant one for erasing is write protection.
if (FLASH_STATUS & FLASH_STATUS_WRP_ERR) {
FLASH_STATUS = FLASH_STATUS_WRP_ERR;
status = FIB_ERR_WRITE_PROTECTED;
}
disableFlitf();
}
if (status == FIB_SUCCESS
&& (eraseType & DO_VERIFY) != 0) {
int32u i;
for (i = 0; i < length; i++) {
if (*ptr != 0xFFFFFFFF) {
return FIB_ERR_VERIFY_FAILED;
}
ptr++;
}
}
return status;
}
#endif // ST_EMU_TEST
static boolean verifyFib(void)
{
// Ensure that a programmed FIB of a proper version is present
return ( (halFixedAddressTable.baseTable.type == FIXED_ADDRESS_TABLE_TYPE) &&
( ( (halFixedAddressTable.baseTable.version & FAT_MAJOR_VERSION_MASK)
== 0x0000 ) &&
(halFixedAddressTable.baseTable.version >= 0x0002)
)
);
}
//The parameter 'eraseType' chooses which erasure will be performed while
//the 'address' parameter chooses the page to be erased during MFB page erase.
StStatus halInternalFlashErase(int8u eraseType, int32u address)
{
FibStatus status;
ATOMIC(
BYPASS_MPU(
flashEraseIsActive = TRUE;
#if defined(ST_EMU_TEST)
// Always try to use the FIB bootloader if its present
if(verifyFib()) {
status = halFixedAddressTable.fibFlashErase(
(((int32u)eraseType) | DO_ERASE),
address);
} else {
status = fibFlashErase((((int32u)eraseType) | DO_ERASE), address);
}
#else
assert(verifyFib());
status = halFixedAddressTable.fibFlashErase(
(((int32u)eraseType) | DO_ERASE),
address);
#endif
)
)
//If there are any interrupts pending that could have been delayed for 21ms,
//they will be serviced here since we exit the ATOMIC block. These ISRs
//can query the flash library and find out that erasing is active. After
//this point, we're no longer ATOMIC/disrupting latency so our erase
//active flag should be cleared.
flashEraseIsActive = FALSE;
if(status!=FIB_SUCCESS) {
return fibToStStatus[status];
}
#if defined(ST_EMU_TEST)
// Always try to use the FIB bootloader if its present
if(verifyFib()) {
status = halFixedAddressTable.fibFlashErase(
(((int32u)eraseType) | DO_VERIFY),
address);
} else {
status = fibFlashErase((((int32u)eraseType) | DO_VERIFY), address);
}
#else
status = halFixedAddressTable.fibFlashErase(
(((int32u)eraseType) | DO_VERIFY),
address);
#endif
return fibToStStatus[status];
}
//The parameter 'address' defines the starting address of where the
//programming will occur - this parameter MUST be half-word aligned since all
//programming operations are HW. The parameter 'data' is a pointer to a buffer
//containin the 16bit half-words to be written. Length is the number of 16bit
//half-words contained in 'data' to be written to flash.
//NOTE: This function can NOT write the option bytes and will throw an error
//if that is attempted.
StStatus halInternalFlashWrite(int32u address, int16u * data, int32u length)
{
FibStatus status;
length = length * 2; // fib routines specify length in bytes
ATOMIC(
BYPASS_MPU(
#if defined(ST_EMU_TEST)
// Always try to use the FIB bootloader if its present
if(verifyFib()) {
status = halFixedAddressTable.fibFlashWrite(address,
(int8u *)data,
length,
0);
} else {
status = fibFlashWrite(address, (int8u *)data, length, 0);
}
#else
// Ensure that a programmed FIB of a proper version is present
assert(verifyFib());
status = halFixedAddressTable.fibFlashWrite(address,
(int8u *)data,
length,
0);
#endif
)
)
if(status!=FIB_SUCCESS) {
return fibToStStatus[status];
}
#if defined(ST_EMU_TEST)
// Always try to use the FIB bootloader if its present
if(verifyFib()) {
status = halFixedAddressTable.fibFlashWrite(address,
(int8u *)data,
0,
length);
} else {
status = fibFlashWriteVerify(address, (int8u *)data, length);
}
#else
status = halFixedAddressTable.fibFlashWrite(address,
(int8u *)data,
0,
length);
#endif
return fibToStStatus[status];
}
//The parameter 'byte' is the option byte number to be programmed. This
//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
//compliment and program the full 16bit option byte.
StStatus halInternalCibOptionByteWrite(int8u byte, int8u data)
{
int16u dataAndInverse = HIGH_LOW_TO_INT(~data, data);
// There are only 8 option bytes, don't try to program more than that.
if (byte > 7) {
return ST_ERR_FLASH_PROG_FAIL;
}
return halInternalFlashWrite(CIB_OB_BOTTOM + (byte << 1), &dataAndInverse, 1);
}

View file

@ -0,0 +1,126 @@
/** @file hal/micro/cortexm3/flash.h
* @brief Header for flash for APIs
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
/** @addtogroup flash
* @brief Definition and description of public flash manipulation routines.
*
* @note
* During an erase or a write the flash is not available,
* which means code will not be executable from flash. These routines still
* execute from flash, though, since the bus architecture can support doing so.
* <b>Additonally, this also means all interrupts will be disabled.</b>
*
* <b>Hardware documentation indicates 40us for a write and 21ms for an erase.</b>
*
* See flash.h for source code.
*@{
*/
#ifndef __FLASH_H__
#define __FLASH_H__
#include "memmap.h"
/** @brief Tells the calling code if a Flash Erase operation is active.
*
* This state is import to know because Flash Erasing is ATOMIC for 21ms
* and could disrupt interrupt latency. But if an ISR can know that it wasn't
* serviced immediately due to Flash Erasing, then the ISR has the opportunity
* to correct in whatever manner it needs to.
*
* @return A boolean flag: TRUE if Flash Erase is active, FALSE otherwise.
*/
boolean halFlashEraseIsActive(void);
#ifndef DOXYGEN_SHOULD_SKIP_THIS
//[[ The following eraseType definitions must match the FIB erase types! ]]
/**
* @brief Assign numerical value to the type of erasure requested.
*/
#define MFB_MASS_ERASE 0x01
#define MFB_PAGE_ERASE 0x02
#define CIB_ERASE 0x03
/** @brief Erases a section of flash back to all 0xFFFF.
*
* @param eraseType Choose one of the three types of erasures to perform.
* - MFB_MASS_ERASE (0x01) Erase the entire main flash block.
* - MFB_PAGE_ERASE (0x02) Erase one hardware page in the main flash block
* chosen by the \c address parameter.
* - CIB_ERASE (0x03) Erase the entire customer information block.
*
* @param address This parameter is only effectual when a MFB_PAGE_ERASE is
* being performed. The hardware page encapsulating the address given in this
* parameter will be erased. A hardware page size depends on the chip
*
* @return An ::StStatus value indicating the success or failure of the
* command:
* - ST_ERR_FATAL if the \c eraseType is not valid
* - ST_ERR_FLASH_ERASE_FAIL if erasing failed due to write protection
* - ST_ERR_FLASH_VERIFY_FAILED if erase verification failed
* - ST_SUCCESS if erasure completed and verified properly
*/
StStatus halInternalFlashErase(int8u eraseType, int32u address);
/** @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
* address between erasures and this is enforced by the flash interface
* controller. If the value already in the address being written to is 0xFFFF,
* any value can be written. If the value is not 0xFFFF and not 0x0000, only
* 0x0000 can be written. If the value is 0x0000, nothing can be written.
*
* \b NOTE: This function can NOT write the option bytes and will throw an
* error if that is attempted.
*
* @param address The starting address of where the programming will occur.
* This parameter MUST be half-word aligned since all programming operations
* are half-words. Also, the address parameter is NOT a pointer. This
* routines will cast the address to a pointer for the actual hardware access.
*
* @param data A pointer to a buffer containing the 16bit (half-words) to
* be written.
*
* @param length The number of 16bit (half-words) contained in the data buffer
* to be written to flash.
*
* @return An ::StStatus value indicating the success or failure of the
* command:
* - ST_ERR_FLASH_PROG_FAIL if the address is not half-word aligned, the
* address is inside the option bytes, write protection is enabled, or the
* address is being written to more than twice between erasures.
* - ST_ERR_FLASH_VERIFY_FAILED if write verification failed
* - ST_SUCCESS if writing completed and verified properly
*/
StStatus halInternalFlashWrite(int32u address, int16u * data, int32u length);
/** @brief Writes an option byte to the customer information block. Only
* two writes can be performed to the same address between erasures and this
* is enforced by the flash interface controller.
*
* @param byte The option byte number, 0 though 7, to be programmed.
*
* @param data The 8 bit value to be programmed into the option byte. The
* hardware is responsible for calculating the compliment and programming
* the full 16bit option byte space.
*
* @return An ::StStatus value indicating the success or failure of the
* command:
* - ST_ERR_FLASH_PROG_FAIL if the byte chosen is greater than 7, write
* protection is enabled, or the byte is being written to more than twice
* between erasures.
* - ST_ERR_FLASH_VERIFY_FAILED if write verification failed
* - ST_SUCCESS if writing completed and verified properly
*/
StStatus halInternalCibOptionByteWrite(int8u byte, int8u data);
#endif //DOXYGEN_SHOULD_SKIP_THIS
#endif //__FLASH_H__
/** @} END addtogroup */

View file

@ -0,0 +1,52 @@
/** @file hal/micro/cortexm3/led.c
* @brief LED manipulation routines; stack and example APIs
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
#include PLATFORM_HEADER
#include BOARD_HEADER
#include "hal/micro/led.h"
#include "hal/micro/micro-common.h"
#include "hal/micro/cortexm3/micro-common.h"
#define GPIO_PxCLR_BASE (GPIO_PACLR_ADDR)
#define GPIO_PxSET_BASE (GPIO_PASET_ADDR)
#define GPIO_PxOUT_BASE (GPIO_PAOUT_ADDR)
// Each port is offset from the previous port by the same amount
#define GPIO_Px_OFFSET (GPIO_PBCFGL_ADDR-GPIO_PACFGL_ADDR)
void halInitLed(void)
{
/* Set GPIO pins for Led D1 and Led D3 */
halGpioConfig(LED_D1, GPIOCFG_OUT);
halGpioConfig(LED_D3, GPIOCFG_OUT);
/* Switch off Led D1,D3 */
halClearLed(LED_D1);
halClearLed(LED_D3);
}
void halSetLed(HalBoardLed led)
{
if(led/8 < 3) {
*((volatile int32u *)(GPIO_PxCLR_BASE+(GPIO_Px_OFFSET*(led/8)))) = BIT(led&7);
}
}
void halClearLed(HalBoardLed led)
{
if(led/8 < 3) {
*((volatile int32u *)(GPIO_PxSET_BASE+(GPIO_Px_OFFSET*(led/8)))) = BIT(led&7);
}
}
void halToggleLed(HalBoardLed led)
{
//to avoid contention with other code using the other pins for other
//purposes, we disable interrupts since this is a read-modify-write
ATOMIC(
if(led/8 < 3) {
*((volatile int32u *)(GPIO_PxOUT_BASE+(GPIO_Px_OFFSET*(led/8)))) ^= BIT(led&7);
}
)
}

View file

@ -0,0 +1,51 @@
/** @file hal/micro/cortexm3/memmap-fat.h
* @brief STM32W108 series memory map fixed address table definition
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
#ifndef __MEMMAP_FAT_H__
#define __MEMMAP_FAT_H__
#ifndef __MEMMAP_TABLES_H__
// if we weren't included via memmap-tables.h, define a dummy type for the BAT
typedef void HalBootloaderAddressTableType;
#endif
#include "hal/micro/cortexm3/bootloader/fib-bootloader.h"
// ****************************************************************************
// If any of these address table definitions ever need to change, it is highly
// desirable to only add new entries, and only add them on to the end of an
// existing address table... this will provide the best compatibility with
// any existing code which may utilize the tables, and which may not be able to
// be updated to understand a new format (example: bootloader which reads the
// application address table)
// Description of the Fixed Address Table (FAT)
typedef struct {
HalBaseAddressTableType baseTable;
void *CustomerInformationBlock;
HalBootloaderAddressTableType *bootloaderAddressTable;
void *startOfUnusedRam;
// ** pointers to shared functions **
FibStatus (* fibFlashWrite)(int32u address, int8u *data,
int32u writeLength, int32u verifyLength);
FibStatus (* fibFlashErase)(FibEraseType eraseType, int32u address);
} HalFixedAddressTableType;
extern const HalFixedAddressTableType halFixedAddressTable;
#define FIXED_ADDRESS_TABLE_TYPE (0x0FA7)
// The current versions of the address tables.
// Note that the major version should be updated only when a non-backwards
// compatible change is introduced (like removing or rearranging fields)
// adding new fields is usually backwards compatible, and their presence can
// be indicated by incrementing only the minor version
#define FAT_VERSION (0x0003)
#define FAT_MAJOR_VERSION (0x0000)
#define FAT_MAJOR_VERSION_MASK (0xFF00)
#endif //__MEMMAP_FAT_H__

View file

@ -0,0 +1,64 @@
/** @file hal/micro/cortexm3/memmap.h
* @brief STM32W108 series memory map definitions used by the full hal
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
#ifndef __MEMMAP_H__
#define __MEMMAP_H__
// Include the chip specific definitions
#ifndef LOADER
#if defined (CORTEXM3_STM32W108)
#include "hal/micro/cortexm3/stm32w108/memmap.h"
#else
#error no appropriate micro defined
#endif
#endif
//=============================================================================
// A union that describes the entries of the vector table. The union is needed
// since the first entry is the stack pointer and the remainder are function
// pointers.
//
// Normally the vectorTable below would require entries such as:
// { .topOfStack = x },
// { .ptrToHandler = y },
// But since ptrToHandler is defined first in the union, this is the default
// type which means we don't need to use the full, explicit entry. This makes
// the vector table easier to read because it's simply a list of the handler
// functions. topOfStack, though, is the second definition in the union so
// the full entry must be used in the vectorTable.
//=============================================================================
typedef union
{
void (*ptrToHandler)(void);
void *topOfStack;
} HalVectorTableType;
// ****************************************************************************
// If any of these address table definitions ever need to change, it is highly
// desirable to only add new entries, and only add them on to the end of an
// existing address table... this will provide the best compatibility with
// any existing code which may utilize the tables, and which may not be able to
// be updated to understand a new format (example: bootloader which reads the
// application address table)
// Generic Address table definition which describes leading fields which
// are common to all address table types
typedef struct {
void *topOfStack;
void (*resetVector)(void);
void (*nmiHandler)(void);
void (*hardFaultHandler)(void);
int16u type;
int16u version;
const HalVectorTableType *vectorTable;
// Followed by more fields depending on the specific address table type
} HalBaseAddressTableType;
// Hal only references the FAT
#include "memmap-fat.h"
#endif //__MEMMMAP_H__

View file

@ -0,0 +1,241 @@
/** @file mems.c
* @brief MB851 MEMS drivers
*
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
#include PLATFORM_HEADER
#include "hal/hal.h"
#include "hal/error.h"
#include "hal/micro/mems.h"
#define TIMEOUT 20000
#define SUCCESS 1
#define SEND_BYTE(data) do{ SC2_DATA=(data); SC2_TWICTRL1 |= SC_TWISEND; }while(0)
#define WAIT_CMD_FIN() do{}while((SC2_TWISTAT&SC_TWICMDFIN)!=SC_TWICMDFIN)
#define WAIT_TX_FIN() do{}while((SC2_TWISTAT&SC_TWITXFIN)!=SC_TWITXFIN)
#define WAIT_RX_FIN() do{}while((SC2_TWISTAT&SC_TWIRXFIN)!=SC_TWIRXFIN)
static int8u i2c_MEMS_Init (void);
static int8u i2c_MEMS_Read (t_mems_data *mems_data);
//extern void halInternalResetWatchDog(void);
static int8u i2c_Send_Frame (int8u DeviceAddress, int8u *pBuffer, int8u NoOfBytes);
static int8u i2c_Send_Frame (int8u DeviceAddress, int8u *pBuffer, int8u NoOfBytes);
int8u i2c_write_reg (int8u slave_addr, int8u reg_addr, int8u reg_value);
static int8u i2c_MEMS_Init (void);
static int8u i2c_MEMS_Read (t_mems_data *mems_data);
/* Functions -----------------------------------------------------------------*/
int8u mems_Init(void)
{
int8u ret = 0;
// GPIO assignments
// PA1: SC2SDA (Serial Data)
// PA2: SC2SCL (Serial Clock)
//-----SC2 I2C Master GPIO configuration
TIM2_CCER &= 0xFFFFEEEE;
SC2_MODE = SC2_MODE_I2C;
GPIO_PACFGL &= 0xFFFFF00F;
GPIO_PACFGL |= 0x00000DD0;
SC2_RATELIN = 14; // generates standard 100kbps or 400kbps
SC2_RATEEXP = 1; // 3 yields 100kbps; 1 yields 400kbps
SC2_TWICTRL1 = 0; // start from a clean state
SC2_TWICTRL2 = 0; // start from a clean state
ret = i2c_MEMS_Init();
//Add later if really needed
#ifdef ST_DBG
if (!ret)
i2c_DeInit(MEMS_I2C);
#endif
return ret;
}/* end mems_Init */
int8u mems_GetValue(t_mems_data *mems_data)
{
int8u i;
i = i2c_MEMS_Read(mems_data);
return i;
}/* end mems_GetValue() */
/* Private Functions ---------------------------------------------------------*/
/*******************************************************************************
* Function Name : i2c_Send_Frame
* Description : It sends I2C frame
* Input : DeviceAddress is the destination device address
* pBUffer is the buffer data
* NoOfBytes is the number of bytes
* Output : None
* Return : status
*******************************************************************************/
static int8u i2c_Send_Frame (int8u DeviceAddress, int8u *pBuffer, int8u NoOfBytes)
{
int8u i, data;
SC2_TWICTRL1 |= SC_TWISTART; // send start
WAIT_CMD_FIN();
SEND_BYTE(DeviceAddress); // send the address low byte
WAIT_TX_FIN();
// loop sending the data
for (i=0; i<NoOfBytes; i++) {
halInternalResetWatchDog();
data = *(pBuffer+i);
SEND_BYTE(data);
WAIT_TX_FIN();
}
SC2_TWICTRL1 |= SC_TWISTOP;
WAIT_CMD_FIN();
return SUCCESS;
}/* end i2c_Send_Frame() */
/*******************************************************************************
* Function Name : i2c_Receive_Frame
* Description : It receives an I2C frame and stores it in pBUffer parameter
* Input : slave_addr is the slave address
* reg_addr is the register address
* NoOfBytes is the numenr of bytes to read starting from reg_addr
* Output : buffer
* Return : status
*******************************************************************************/
static int8u i2c_Receive_Frame (int8u slave_addr, int8u reg_addr, int8u *pBuffer, int8u NoOfBytes)
{
int8u i, addr = reg_addr;
if (NoOfBytes > 1)
addr += REPETIR;
SC2_TWICTRL1 |= SC_TWISTART; // send start
WAIT_CMD_FIN();
SEND_BYTE(slave_addr | 0x00); // send the address low byte
WAIT_TX_FIN();
SEND_BYTE(addr);
WAIT_TX_FIN();
SC2_TWICTRL1 |= SC_TWISTART; // send start
WAIT_CMD_FIN();
SEND_BYTE(slave_addr | 0x01); // send the address low byte
WAIT_TX_FIN();
// loop receiving the data
for (i=0;i<NoOfBytes;i++){
halInternalResetWatchDog();
if (i < (NoOfBytes - 1))
SC2_TWICTRL2 |= SC_TWIACK; // ack on receipt of data
else
SC2_TWICTRL2 &= ~SC_TWIACK; // don't ack if last one
SC2_TWICTRL1 |= SC_TWIRECV; // set to receive
WAIT_RX_FIN();
*(pBuffer+i) = SC2_DATA; // receive data
}
SC2_TWICTRL1 |= SC_TWISTOP; // send STOP
WAIT_CMD_FIN();
return SUCCESS;
}/* end i2c_Receive_Frame() */
/*******************************************************************************
* Function Name : i2c_write_reg
* Description : It writes a register on the I2C target
* Input : slave addr is the I2C target device
* reg_addr is the address of the register to be written
* reg_value is the value of the register to be written
* NoOfBytes is the numenr of bytes to read starting from reg_addr
* Output : None
* Return : I2C frame
*******************************************************************************/
int8u i2c_write_reg (int8u slave_addr, int8u reg_addr, int8u reg_value)
{
int8u i2c_buffer[2];
i2c_buffer[0] = reg_addr;
i2c_buffer[1] = reg_value;
return i2c_Send_Frame (slave_addr, i2c_buffer, 2);
}/* end i2c_write_reg() */
/*******************************************************************************
* Function Name : i2c_read_reg
* Description : It reads a register on the I2C target
* Input : slave addr is the I2C target device
* reg_addr is the address of the register to be read
* pBuffer is the storage destination for the read data
* NoOfBytes is the amount of data to read
* Output : None
* Return : I2C frame
*******************************************************************************/
int8u i2c_read_reg (int8u slave_addr, int8u reg_addr, int8u *pBuffer, int8u NoOfBytes)
{
return i2c_Receive_Frame (slave_addr, reg_addr, pBuffer, NoOfBytes);
}/* end i2c_read_reg() */
/*******************************************************************************
* Function Name : i2c_MEMS_Init
* Description : It performs basic MEMS register writes for initialization
* purposes
* Input : None
* Output : None
* Return : status
*******************************************************************************/
static int8u i2c_MEMS_Init (void)
{
int8u i = 0;
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, DD_CFG, 0x00); // all off
i += i2c_write_reg (kLIS3L02DQ_SLAVE_ADDR, CTRL_REG2, (1<<4) | (1<<1) | (1 << 0));
i += i2c_write_reg (kLIS3L02DQ_SLAVE_ADDR, CTRL_REG1, 0xC7);
if (i != 5)
return 0;
return 1;
}/* end i2c_MEMS_Init() */
/*******************************************************************************
* Function Name : i2c_MEMS_Read
* Description : It reads 3 axes acceleration data from mems
* Input : None
* Output : mems_data
* Return : I2C frame
*******************************************************************************/
static int8u i2c_MEMS_Read (t_mems_data *mems_data)
{
int8u i, i2c_buffer[8];
i = i2c_read_reg (kLIS3L02DQ_SLAVE_ADDR, OUTX_L, i2c_buffer, 8);
mems_data->outx_h = i2c_buffer[0];
mems_data->outx_l = i2c_buffer[1];
mems_data->outy_h = i2c_buffer[2];
mems_data->outy_l = i2c_buffer[3];
mems_data->outz_h = i2c_buffer[4];
mems_data->outz_l = i2c_buffer[5];
return i;
}/* end i2c_MEMS_Read() */

View file

@ -0,0 +1,104 @@
/** @file hal/micro/cortexm3/mfg-token.c
* @brief Cortex-M3 Manufacturing-Token system
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
#include PLATFORM_HEADER
#include "error.h"
#include "hal/micro/cortexm3/flash.h"
#include "mfg-token.h"
#define DEFINETOKENS
#define TOKEN_MFG(name,creator,iscnt,isidx,type,arraysize,...) \
const int16u TOKEN_##name = TOKEN_##name##_ADDRESS;
#include "hal/micro/cortexm3/token-manufacturing.h"
#undef TOKEN_DEF
#undef TOKEN_MFG
#undef DEFINETOKENS
static const int8u nullEui[] = { 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF };
void halInternalGetMfgTokenData(void *data, int16u ID, int8u index, int8u len)
{
int8u *ram = (int8u*)data;
//0x7F is a non-indexed token. Remap to 0 for the address calculation
index = (index==0x7F) ? 0 : index;
if(ID == MFG_EUI_64_LOCATION) {
//There are two EUI64's stored in the Info Blocks, St and Custom.
//0x0A00 is the address used by the generic EUI64 token, and it is
//token.c's responbility to pick the returned EUI64 from either St
//or Custom. Return the Custom EUI64 if it is not all FF's, otherwise
//return the St EUI64.
tokTypeMfgEui64 eui64;
halCommonGetMfgToken(&eui64, TOKEN_MFG_CUSTOM_EUI_64);
if(MEMCOMPARE(eui64,nullEui, 8 /*EUI64_SIZE*/) == 0) {
halCommonGetMfgToken(&eui64, TOKEN_MFG_ST_EUI_64);
}
MEMCOPY(ram, eui64, 8 /*EUI64_SIZE*/);
} else {
//read from the Information Blocks. The token ID is only the
//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
//to OR the ID with DATA_BIG_INFO_BASE to get the real address.
int32u realAddress = (DATA_BIG_INFO_BASE|ID) + (len*index);
int8u *flash = (int8u *)realAddress;
MEMCOPY(ram, flash, len);
}
}
void halInternalSetMfgTokenData(int16u token, void *data, int8u len)
{
StStatus flashStatus;
int32u realAddress = (DATA_BIG_INFO_BASE|token);
int8u * flash = (int8u *)realAddress;
int32u i;
//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
//the CIB, verify that the token+len falls within the CIB.
assert((token&1) != 1);
assert((len&1) != 1);
assert((realAddress>=CIB_BOTTOM) && ((realAddress+len-1)<=CIB_TOP));
//CIB manufacturing tokens can only be written by on-chip code if the token
//is currently unprogrammed. Verify the entire token is unwritten. The
//flash library performs a similar check, but verifying here ensures that
//the entire token is unprogrammed and will prevent partial writes.
for(i=0;i<len;i++) {
assert(flash[i] == 0xFF);
}
//Remember, the flash library operates in 16bit quantities, but the
//token system operates in 8bit quantities. Hence the divide by 2.
flashStatus = halInternalFlashWrite(realAddress, data, (len/2));
assert(flashStatus == ST_SUCCESS);
}

View file

@ -0,0 +1,163 @@
/** @file hal/micro/cortexm3/mfg-token.h
* @brief Cortex-M3 Manufacturing token system
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
#ifndef __MFG_TOKEN_H__
#define __MFG_TOKEN_H__
// The manufacturing tokens live in the Info Blocks, while all other tokens
// live in the Simulated EEPROM. This requires the token names to be defined
// as different data (mfg tokens are memory address, all others are an enum).
#define DEFINETOKENS
/**
* @description Macro for translating token defs into address variables
* that point to the correct location in the Info Blocks. (This is the
* extern, the actual definition is found in hal/micro/cortexm3/token.c)
*
* @param name: The name of the token.
*
* @param TOKEN_##name##_ADDRESS: The address in EEPROM at which the token
* will be stored. This parameter is generated with a macro above.
*/
#define TOKEN_MFG(name,creator,iscnt,isidx,type,arraysize,...) \
extern const int16u TOKEN_##name;
#include "hal/micro/cortexm3/token-manufacturing.h"
#undef TOKEN_MFG
/**
* @description Macro for translating token definitions into size variables.
* This provides a convenience for abstracting the 'sizeof(type)' anywhere.
*
* @param name: The name of the token.
*
* @param type: The token type. The types are found in token-stack.h.
*/
#define TOKEN_MFG(name,creator,iscnt,isidx,type,arraysize,...) \
TOKEN_##name##_SIZE = sizeof(type),
enum {
#include "hal/micro/cortexm3/token-manufacturing.h"
};
#undef TOKEN_MFG
#undef TOKEN_DEF
/**
* @description Macro for typedef'ing the CamelCase token type found in
* token-stack.h to a capitalized TOKEN style name that ends in _TYPE.
* This macro allows other macros below to use 'token##_TYPE' to declare
* a local copy of that token.
*
* @param name: The name of the token.
*
* @param type: The token type. The types are found in token-stack.h.
*/
#define TOKEN_MFG(name,creator,iscnt,isidx,type,arraysize,...) \
typedef type TOKEN_##name##_TYPE;
#include "hal/micro/cortexm3/token-manufacturing.h"
#undef TOKEN_MFG
#undef TOKEN_NEXT_ADDRESS
#define DEFINEADDRESSES
/**
* @description Macro for creating a 'region' element in the enum below. This
* creates an element in the enum that provides a starting point (address) for
* subsequent tokens to align against. ( See hal/micro/cortexm3/token.c for
* the instances of TOKEN_NEXT_ADDRESS() );
*
* @param region: The name to give to the element in the address enum..
*
* @param address: The address in EEPROM where the region begins.
*/
#define TOKEN_NEXT_ADDRESS(region, address) \
TOKEN_##region##_NEXT_ADDRESS = ((address) - 1),
/**
* @description Macro for creating ADDRESS and END elements for each token in
* the enum below. The ADDRESS element is linked to from the the normal
* TOKEN_##name macro and provides the value passed into the internal token
* system calls. The END element is a placeholder providing the starting
* point for the ADDRESS of the next dynamically positioned token.
*
* @param name: The name of the token.
*
* @param arraysize: The number of elements in an indexed token (arraysize=1
* for scalar tokens).
*/
#define TOKEN_MFG(name,creator,iscnt,isidx,type,arraysize,...) \
TOKEN_##name##_ADDRESS, \
TOKEN_##name##_END = TOKEN_##name##_ADDRESS + \
(TOKEN_##name##_SIZE * arraysize) - 1,
/**
* @description The enum that operates on the two macros above. Also provides
* an indentifier so the address of the top of the token system can be known.
*/
enum {
#include "hal/micro/cortexm3/token-manufacturing.h"
};
#undef TOKEN_MFG
#undef DEFINEADDRESSES
#undef DEFINETOKENS
#ifndef DOXYGEN_SHOULD_SKIP_THIS
/**
* @description Copies the token value from non-volatile storage into a RAM
* location. This is the internal function that the exposed API
* (halCommonGetMfgToken) expands out to. The
* API simplifies the access into this function by hiding the size parameter.
*
* @param data: A pointer to where the data being read should be placed.
*
* @param token: The name of the token to get data from. On this platform
* that name is defined as an address.
*
* @param index: The index to access. If the token being accessed is not an
* indexed token, this parameter is set by the API to be 0x7F.
*
* @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.
*/
void halInternalGetMfgTokenData(void *data, int16u token, int8u index, int8u len);
/**
* @description Sets the value of a token in non-volatile storage. This is
* the internal function that the exposed API (halCommonSetMfgToken)
* expands out to. The API simplifies the access into this function
* by hiding the size parameter.
*
* <b>NOTE:</b> CIB manufacturing tokens can only be written by on-chip
* code if the token is currently unprogrammed.
*
* <b>REMEMBER:</b> The flash hardware requires writing to 16bit aligned
* addresses with a length that is multiples of 16bits.
*
* @param token: The name of the token to get data from. On this platform
* that name is defined as an address.
*
* @param data: A pointer to the data being written.
*
* @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.
*/
void halInternalSetMfgTokenData(int16u token, void *data, int8u len);
#define halCommonGetMfgToken( data, token ) \
halInternalGetMfgTokenData(data, token, 0x7F, token##_SIZE)
#define halCommonGetIndexedMfgToken( data, token, index ) \
halInternalGetMfgTokenData(data, token, index, token##_SIZE)
#define halCommonSetMfgToken( token, data ) \
halInternalSetMfgTokenData(token, data, token##_SIZE)
#endif //DOXYGEN_SHOULD_SKIP_THIS
#endif //__MFG_TOKEN_H__

View file

@ -0,0 +1,294 @@
/*
* File: micro-common-internal.c
* Description: STM32W108 internal, micro specific HAL functions.
* This file is provided for completeness and it should not be modified
* by customers as it comtains code very tightly linked to undocumented
* device features
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
#include PLATFORM_HEADER
#include "error.h"
#include "hal/micro/micro-common.h"
#include "hal/micro/cortexm3/micro-common.h"
#include "hal/micro/cortexm3/mfg-token.h"
#define HAL_STANDALONE
#ifdef HAL_STANDALONE
#define AUXADC_REG (0xC0u)
#define DUMMY 0
#define ADC_6MHZ_CLOCK 0
#define ADC_1MHZ_CLOCK 1
#define ADC_SAMPLE_CLOCKS_32 0
#define ADC_SAMPLE_CLOCKS_64 1
#define ADC_SAMPLE_CLOCKS_128 2
#define ADC_SAMPLE_CLOCKS_256 3
#define ADC_SAMPLE_CLOCKS_512 4
#define ADC_SAMPLE_CLOCKS_1024 5
#define ADC_SAMPLE_CLOCKS_2048 6
#define ADC_SAMPLE_CLOCKS_4096 7
#define CAL_ADC_CHANNEL_VDD_4 0x00 //VDD_PADS/4
#define CAL_ADC_CHANNEL_VREG_2 0x01 //VREG_OUT/2
#define CAL_ADC_CHANNEL_TEMP 0x02
#define CAL_ADC_CHANNEL_GND 0x03
#define CAL_ADC_CHANNEL_VREF 0x04
#define CAL_ADC_CHANNEL_I 0x06
#define CAL_ADC_CHANNEL_Q 0x07
#define CAL_ADC_CHANNEL_ATEST_A 0x09
void stCalibrateVref(void)
{
// Calibrate Vref by measuring a known voltage, Vdd/2.
//
// FIXME: add support for calibration if done in boost mode.
extern int16u stmRadioTxPowerMode;
tokTypeMfgAnalogueTrimBoth biasTrim;
halCommonGetMfgToken(&biasTrim, TOKEN_MFG_ANALOG_TRIM_BOTH);
if(biasTrim.auxadc == 0xFFFF) {
assert(FALSE);
} else {
//The bias trim token is set, so use the trim directly
int16u temp_value;
int16u mask = 0xFFFF;
// halClearLed(BOARDLED3);
while (SCR_BUSY_REG) ;
SCR_ADDR_REG = AUXADC_REG ; // prepare the address to write to
// initiate read (starts on falling edge of SCR_CTRL_SCR_READ)
SCR_CTRL_REG = SCR_CTRL_SCR_READ_MASK;
SCR_CTRL_REG = 0;
// wait for read to complete
while (SCR_BUSY_REG) ;
temp_value = SCR_READ_REG & ~mask;
temp_value |= biasTrim.auxadc & mask;
SCR_WRITE_REG = temp_value;
// initiate write (starts on falling edge of SCR_CTRL_SCR_WRITE_MASK)
SCR_CTRL_REG = SCR_CTRL_SCR_WRITE_MASK;
SCR_CTRL_REG = 0;
while (SCR_BUSY_REG) ;
}
}
void calDisableAdc(void) {
// Disable the Calibration ADC to save current.
CAL_ADC_CONFIG &= ~CAL_ADC_CONFIG_CAL_ADC_EN;
}
// These routines maintain the same signature as their hal- counterparts to
// facilitate simple support between phys.
// It is assumed (hoped?) that the compiler will optimize out unused arguments.
StStatus calStartAdcConversion(int8u dummy1, // Not used.
int8u dummy2, // Not used.
int8u channel,
int8u rate,
int8u clock) {
// Disable the Calibration ADC interrupt so that we can poll it.
INT_MGMTCFG &= ~INT_MGMTCALADC;
ATOMIC(
// Enable the Calibration ADC, choose source, set rate, and choose clock.
CAL_ADC_CONFIG =((CAL_ADC_CONFIG_CAL_ADC_EN) |
(channel << CAL_ADC_CONFIG_CAL_ADC_MUX_BIT) |
(rate << CAL_ADC_CONFIG_CAL_ADC_RATE_BIT) |
(clock << CAL_ADC_CONFIG_CAL_ADC_CLKSEL_BIT) );
// Clear any pending Calibration ADC interrupt. Since we're atomic, the
// one we're interested in hasn't happened yet (will take ~10us at minimum).
// We're only clearing stale info.
INT_MGMTFLAG = INT_MGMTCALADC;
)
return ST_SUCCESS;
}
StStatus calReadAdcBlocking(int8u dummy,
int16u *value) {
// Wait for conversion to complete.
while ( ! (INT_MGMTFLAG & INT_MGMTCALADC) );
// Clear the interrupt for this conversion.
INT_MGMTFLAG = INT_MGMTCALADC;
// Get the result.
*value = (int16u)CAL_ADC_DATA;
return ST_SUCCESS;
}
//Using 6MHz clock reduces resolution but greatly increases conversion speed.
//The sample clocks were chosen based upon empirical evidence and provided
//the fastest conversions with the greatest reasonable accuracy. Variation
//across successive conversions appears to be +/-20mv of the average
//conversion. Overall function time is <150us.
int16u stMeasureVddFast(void)
{
int16u value;
int32u Ngnd;
int32u Nreg;
int32u Nvdd;
tokTypeMfgRegVoltage1V8 vregOutTok;
halCommonGetMfgToken(&vregOutTok, TOKEN_MFG_1V8_REG_VOLTAGE);
//Measure GND
calStartAdcConversion(DUMMY,
DUMMY,
CAL_ADC_CHANNEL_GND,
ADC_SAMPLE_CLOCKS_128,
ADC_6MHZ_CLOCK);
calReadAdcBlocking(DUMMY, &value);
Ngnd = (int32u)value;
//Measure VREG_OUT/2
calStartAdcConversion(DUMMY,
DUMMY,
CAL_ADC_CHANNEL_VREG_2,
ADC_SAMPLE_CLOCKS_128,
ADC_6MHZ_CLOCK);
calReadAdcBlocking(DUMMY, &value);
Nreg = (int32u)value;
//Measure VDD_PADS/4
calStartAdcConversion(DUMMY,
DUMMY,
CAL_ADC_CHANNEL_VDD_4,
ADC_SAMPLE_CLOCKS_128,
ADC_6MHZ_CLOCK);
calReadAdcBlocking(DUMMY, &value);
Nvdd = (int32u)value;
calDisableAdc();
//Convert the value into mV. VREG_OUT is ideally 1.8V, but it wont be
//exactly 1.8V. The actual value is stored in the manufacturing token
//TOKEN_MFG_1V8_REG_VOLTAGE. The token stores the value in 10^-4, but we
//need 10^-3 so divide by 10. If this token is not set (0xFFFF), then
//assume 1800mV.
if(vregOutTok == 0xFFFF) {
vregOutTok = 1800;
} else {
vregOutTok /= 10;
}
return ((((((Nvdd-Ngnd)<<16)/(Nreg-Ngnd))*vregOutTok)*2)>>16);
}
#endif
void halCommonCalibratePads(void)
{
if(stMeasureVddFast() < 2700) {
GPIO_DBGCFG |= GPIO_DBGCFGRSVD;
} else {
GPIO_DBGCFG &= ~GPIO_DBGCFGRSVD;
}
}
void halInternalSetRegTrim(boolean boostMode)
{
tokTypeMfgRegTrim regTrim;
int8u trim1V2;
int8u trim1V8;
halCommonGetMfgToken(&regTrim, TOKEN_MFG_REG_TRIM);
// The compiler can optimize this function a bit more and keep the
// values in processor registers if we use separate local vars instead
// of just accessing via the structure fields
trim1V8 = regTrim.regTrim1V8;
trim1V2 = regTrim.regTrim1V2;
//If tokens are erased, default to reasonable values, otherwise use the
//token values.
if((trim1V2 == 0xFF) && (trim1V8 == 0xFF)) {
trim1V8 = 4;
trim1V2 = 0;
}
//When the radio is in boost mode, we have to increase the 1.8V trim.
if(boostMode) {
trim1V8 += 2;
}
//Clamp at 7 to ensure we don't exceed max values, accidentally set
//other bits, or wrap values.
if(trim1V8>7) {
trim1V8 = 7;
}
if(trim1V2>7) {
trim1V2 = 7;
}
VREG_REG = ( (trim1V8<<VREG_VREG_1V8_TRIM_BIT) |
(trim1V2<<VREG_VREG_1V2_TRIM_BIT) );
}
// halCommonDelayMicroseconds
// -enables MAC Timer and leaves it enabled.
// -does not touch MAC Timer Compare registers.
// -max delay is 65535 usec.
// NOTE: This function primarily designed for when the chip is running off of
// the XTAL, which is the most common situation. When running from
// 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
// the accuracy of OSCHF (much lower than XTAL).
void halCommonDelayMicroseconds(int16u us)
{
int32u beginTime = MAC_TIMER;
//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
//time.
if((OSC24M_CTRL&OSC24M_CTRL_OSC24M_SEL)!=OSC24M_CTRL_OSC24M_SEL) {
us >>= 1;
}
//we have about 2us of overhead in the calculations
if(us<=2) {
return;
}
// MAC Timer is enabled in stmRadioInit, which may not have been called yet.
// This algorithm needs the MAC Timer so we enable it here.
MAC_TIMER_CTRL |= MAC_TIMER_CTRL_MAC_TIMER_EN;
// since our max delay (65535<<1) is less than half the size of the
// 20 bit mac timer, we can easily just handle the potential for
// mac timer wrapping by subtracting the time delta and masking out
// the extra bits
while( ((MAC_TIMER-beginTime)&MAC_TIMER_MAC_TIMER_MASK) < us ) {
; // spin
}
}
//Burning cycles for milliseconds is generally a bad idea, but it is
//necessary in some situations. If you have to burn more than 65ms of time,
//the halCommonDelayMicroseconds function becomes cumbersome, so this
//function gives you millisecond granularity.
void halCommonDelayMilliseconds(int16u ms)
{
if(ms==0) {
return;
}
while(ms-->0) {
halCommonDelayMicroseconds(1000);
}
}

View file

@ -0,0 +1,115 @@
/** @file micro-common.c
* @brief STM32W108 micro specific HAL functions common to
* full and minimal hal
*
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
#include PLATFORM_HEADER
#include "error.h"
#include "hal/micro/micro-common.h"
#include "hal/micro/cortexm3/micro-common.h"
void halInternalEnableWatchDog(void)
{
//Just to be on the safe side, restart the watchdog before enabling it
WDOG_RESET = 1;
WDOG_KEY = 0xEABE;
WDOG_CFG = WDOG_ENABLE;
}
void halInternalResetWatchDog(void)
{
//Writing any value will restart the watchdog
WDOG_RESET = 1;
}
void halInternalDisableWatchDog(int8u magicKey)
{
if (magicKey == MICRO_DISABLE_WATCH_DOG_KEY) {
WDOG_KEY = 0xDEAD;
WDOG_CFG = WDOG_DISABLE;
}
}
boolean halInternalWatchDogEnabled(void)
{
if(WDOG_CFG&WDOG_ENABLE) {
return TRUE;
} else {
return FALSE;
}
}
void halGpioConfig(int32u io, int32u config)
{
static volatile int32u *const configRegs[] =
{ (volatile int32u *)GPIO_PACFGL_ADDR,
(volatile int32u *)GPIO_PACFGH_ADDR,
(volatile int32u *)GPIO_PBCFGL_ADDR,
(volatile int32u *)GPIO_PBCFGH_ADDR,
(volatile int32u *)GPIO_PCCFGL_ADDR,
(volatile int32u *)GPIO_PCCFGH_ADDR };
int32u portcfg;
portcfg = *configRegs[io/4]; // get current config
portcfg = portcfg & ~((0xF)<<((io&3)*4)); // mask out config of this pin
*configRegs[io/4] = portcfg | (config <<((io&3)*4));
}
int16u halInternalStartSystemTimer(void)
{
//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
//configured for a tick value time of 1024 ticks/second (0.9765625 ms/tick)
//using either the 10 kHz internal SlowRC clock divided and calibrated to
//1024 Hz or the external 32.768 kHz crystal divided to 1024 Hz.
//With a tick time of ~1ms, this 32bit timer will wrap after ~48.5 days.
//disable top-level interrupt while configuring
INT_CFGCLR = INT_SLEEPTMR;
#ifdef ENABLE_OSC32K
#ifdef DIGITAL_OSC32_EXT
//Disable both OSC32K and SLOWRC if using external digital clock input
SLEEPTMR_CLKEN = 0;
#else//!DIGITAL_OSC32_EXT
//Enable the 32kHz XTAL (and disable SlowRC since it is not needed)
SLEEPTMR_CLKEN = SLEEPTMR_CLK32KEN;
#endif
//Sleep timer configuration is the same for crystal and external clock
SLEEPTMR_CFG = (SLEEPTMR_ENABLE | //enable TMR
(0 << SLEEPTMR_DBGPAUSE_BIT)| //TMR paused when halted
(5 << SLEEPTMR_CLKDIV_BIT) | //divide down to 1024Hz
(1 << SLEEPTMR_CLKSEL_BIT)) ; //select XTAL
#else //!ENABLE_OSC32K
//Enable the SlowRC (and disable 32kHz XTAL since it is not needed)
SLEEPTMR_CLKEN = SLEEPTMR_CLK10KEN;
SLEEPTMR_CFG = (SLEEPTMR_ENABLE | //enable TMR
(0 << SLEEPTMR_DBGPAUSE_BIT)| //TMR paused when halted
(0 << SLEEPTMR_CLKDIV_BIT) | //already 1024Hz
(0 << SLEEPTMR_CLKSEL_BIT)) ; //select SlowRC
#ifndef DISABLE_RC_CALIBRATION
halInternalCalibrateSlowRc(); //calibrate SlowRC to 1024Hz
#endif//DISABLE_RC_CALIBRATION
#endif//ENABLE_OSC32K
//clear out any stale interrupts
INT_SLEEPTMRFLAG = (INT_SLEEPTMRWRAP | INT_SLEEPTMRCMPA | INT_SLEEPTMRCMPB);
//turn off second level interrupts. they will be enabled elsewhere as needed
INT_SLEEPTMRCFG = INT_SLEEPTMRCFG_RESET;
//enable top-level interrupt
INT_CFGSET = INT_SLEEPTMR;
return 0;
}

View file

@ -0,0 +1,271 @@
/** @file hal/micro/cortexm3/micro-common.h
* @brief Utility and convenience functions for STM32W108 microcontroller,
* common to both the full and minimal hal.
* See @ref micro for documentation.
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
/** @addtogroup micro
* See also hal/micro/cortexm3/micro.h for source code.
*@{
*/
#ifndef __STM32W108XX_MICRO_COMMON_H__
#define __STM32W108XX_MICRO_COMMON_H__
#ifndef DOXYGEN_SHOULD_SKIP_THIS
#ifndef __STSTATUS_TYPE__
#define __STSTATUS_TYPE__
//This is necessary here because halSleepForQsWithOptions returns an
//StStatus and not adding this typedef to this file breaks a
//whole lot of builds.
typedef int8u StStatus;
#endif //__STSTATUS_TYPE__
#endif // DOXYGEN_SHOULD_SKIP_THIS
/**
* @brief Some registers and variables require indentifying GPIO by
* a single number instead of the port and pin. This macro converts
* Port A pins into a single number.
*/
#define PORTA_PIN(y) ((0<<3)|y)
/**
* @brief Some registers and variables require indentifying GPIO by
* a single number instead of the port and pin. This macro converts
* Port B pins into a single number.
*/
#define PORTB_PIN(y) ((1<<3)|y)
/**
* @brief Some registers and variables require indentifying GPIO by
* a single number instead of the port and pin. This macro converts
* Port C pins into a single number.
*/
#define PORTC_PIN(y) ((2<<3)|y)
/**
* @brief Resets the watchdog timer. This function is pointed
* to by the macro ::halResetWatchdog().
* @warning Be very careful when using this as you can easily get into an
* infinite loop.
*/
void halInternalResetWatchDog( void );
/**
* @brief Configure an IO pin's operating mode
*
* @param io The io pin to use, can be specified with the convenience macros
* PORTA_PIN(), PORTB_PIN(), PORTC_PIN()
* @param config The configuration mode to use.
*
*/
void halGpioConfig(int32u io, int32u config);
/**
* @brief Calibrates the internal SlowRC to generate a 1024 Hz (1kHz) clock.
*/
void halInternalCalibrateSlowRc( void );
/**
* @brief Calibrates the internal FastRC to generate a 12Mhz clock.
*/
void halInternalCalibrateFastRc(void);
/**
* @brief Sets the trim values for the 1.8V and 1.2V regulators based upon
* manufacturing configuration.
*
* @param boostMode Alter the regulator trim based upon the state
* of boost mode. TRUE if boost mode is active, FALSE otherwise.
*/
void halInternalSetRegTrim(boolean boostMode);
/** @brief Takes a slow ADC measurement of VDD_PADS in millivolts. Due to
* the conversions performed, this function takes slightly under 3.2ms with a
* variation across successive conversions approximately +/-2mv of the average
* conversion.
*
* @return A slow measurement of VDD_PADS in millivolts.
*/
int16u stMeasureVddSlow(void);
/** @brief Takes a fast ADC measurement of VDD_PADS in millivolts.
* Due to the conversions performed, this function takes slightly under 150us
* with a variation across successive conversions approximately +/-20mv of
* the average conversion.
*
* @return A fast measurement of VDD_PADS in millivolts.
*/
int16u stMeasureVddFast(void);
/**
* @brief Calibrates the GPIO pads. This function is called from within
* the stack and HAL at appropriate times.
*/
void halCommonCalibratePads(void);
/**
* @brief This function is intended to be called periodically, from the
* stack and application, to check the XTAL bias trim is within
* appropriate levels and adjust if not. This function is *not* designed
* to be used before halInternalSwitchToXtal() has been called.
*/
void halCommonCheckXtalBiasTrim(void);
/**
* @brief Switches to running off of the 24MHz crystal, including changing
* the CPU to be 24MHz (FCLK sourced from SYSCLK). The switch function
* will respect the BIASTRIM HI and LO flags and adjust bias trim until
* appropriate crystal biasing is used. This function is called from
* within the stack and HAL at appropriate times.
*/
void halInternalSwitchToXtal(void);
/**
* @brief Search for optimal 24MHz crystal bias trim, assuming no valid
* prior value. This function is typically called during initialization
* of the microcontroller.
*/
void halInternalSearchForBiasTrim(void);
/** @brief Blocks the current thread of execution for the specified
* amount of time, in milliseconds.
*
* The function is implemented with cycle-counted busy loops
* and is intended to create the short delays required when interfacing with
* hardware peripherals. This function works by simply adding another
* layer on top of halCommonDelayMicroseconds().
*
* @param ms The specified time, in milliseconds.
*/
void halCommonDelayMilliseconds(int16u ms);
/** @brief Puts the microcontroller to sleep in a specified mode, allows
* the GPIO wake sources to be determined at runtime. This function
* requires the GPIO wake sources to be defined at compile time in the board
* file.
*
* @note This routine always enables interrupts.
*
* @param sleepMode A microcontroller sleep mode.
*
* @param gpioWakeBitMask A bit mask of the GPIO that are allowed to wake
* the chip from deep sleep. A high bit in the mask will enable waking
* the chip if the corresponding GPIO changes state. bit0 is PA0, bit1 is
* PA1, bit8 is PB0, bit16 is PCO, bit23 is PC7, bits[31:24] are ignored.
*
* @sa ::SleepModes
*/
void halSleepWithOptions(SleepModes sleepMode, int32u gpioWakeBitMask);
/**
* @brief Uses the system timer to enter ::SLEEPMODE_WAKETIMER for
* approximately the specified amount of time (provided in quarter seconds),
* the GPIO wake sources can be provided at runtime.
*
* This function returns ::ST_SUCCESS and the duration parameter is
* decremented to 0 after sleeping for the specified amount of time. If an
* interrupt occurs that brings the chip out of sleep, the function returns
* ::ST_SLEEP_INTERRUPTED and the duration parameter reports the amount of
* time remaining out of the original request.
*
* @note This routine always enables interrupts.
*
* @note The maximum sleep time of the hardware is limited on STM32W108 platforms
* to 48.5 days. Any sleep duration greater than this limit will wake up
* briefly (e.g. 16 microseconds) to reenable another sleep cycle.
*
* @nostackusage
*
* @param duration The amount of time, expressed in quarter seconds, that the
* micro should be placed into ::SLEEPMODE_WAKETIMER. When the function returns,
* this parameter provides the amount of time remaining out of the original
* sleep time request (normally the return value will be 0).
*
* @param gpioWakeBitMask A bit mask of the GPIO that are allowed to wake
* the chip from deep sleep. A high bit in the mask will enable waking
* the chip if the corresponding GPIO changes state. bit0 is PA0, bit1 is
* PA1, bit8 is PB0, bit16 is PCO, bit23 is PC7, bits[31:24] are ignored.
*
* @return An StStatus value indicating the success or
* failure of the command.
*/
StStatus halSleepForQsWithOptions(int32u *duration, int32u gpioWakeBitMask);
/**
* @brief Provides access to assembly code which triggers idle sleep.
*/
void halInternalIdleSleep(void);
/** @brief Puts the microcontroller to sleep in a specified mode. This
* internal function performs the actual sleep operation. This function
* assumes all of the wake source registers are configured properly.
*
* @note This routine always enables interrupts.
*
* @param sleepMode A microcontroller sleep mode
*/
void halInternalSleep(SleepModes sleepMode);
/**
* @brief Obtains the events that caused the last wake from sleep. The
* meaning of each bit is as follows:
* - [31] = WakeInfoValid
* - [30] = SleepSkipped
* - [29] = CSYSPWRUPREQ
* - [28] = CDBGPWRUPREQ
* - [27] = PWRUP_WAKECORE
* - [26] = PWRUP_SLEEPTMRWRAP
* - [25] = PWRUP_SLEEPTMRCOMPB
* - [24] = PWRUP_SLEEPTMRCOMPA
* - [23:0] = corresponding GPIO activity
*
* WakeInfoValid means that ::halSleepWithOptions (::halInternalSleep) has been called
* at least once. Since the power on state clears the wake event info,
* this bit says the sleep code has been called since power on.
*
* SleepSkipped means that the chip never left the running state. Sleep can
* be skipped if any wake event occurs between going ::ATOMIC and transferring
* control from the CPU to the power management state machine. Sleep can
* also be skipped if the debugger is connected (JTAG/SerialWire CSYSPWRUPREQ
* signal is set). The net affect of skipping sleep is the Low Voltage
* domain never goes through a power/reset cycle.
*
* @return The events that caused the last wake from sleep.
*/
int32u halGetWakeInfo(void);
/** @brief Seeds the ::halCommonGetRandom() pseudorandom number
* generator.
*
* It should be called by the application during initialization with a seed
* from the radio randon number generator.
*
* @param seed A seed for the pseudorandom number generator.
*/
void halCommonSeedRandom(int32u seed);
/** @brief Runs a standard LFSR to generate pseudorandom numbers.
*
* Called by the MAC in the stack to choose random backoff slots.
*
* Complicated implementations may improve the MAC's
* ability to avoid collisions in large networks, but it is \b critical to
* implement this function to return quickly.
*/
int16u halCommonGetRandom(void);
#endif //__STM32W108XX_MICRO_COMMON_H__
/**@} // END micro group
*/

View file

@ -0,0 +1,108 @@
/** @file micro.c
* @brief STM32W108 micro specific minimal HAL functions
*
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
#include PLATFORM_HEADER
#include "error.h"
#include "hal/micro/micro-common.h"
#include "hal/micro/cortexm3/micro-common.h"
#include "micro/system-timer.h"
#include "micro/adc.h"
#include <stdlib.h>
#include <string.h>
void halInit(void)
{
//Disable the REG_EN external regulator enable signal. Out of reset this
//signal overrides PA7. By disabling it early, PA7 is reclaimed as a GPIO.
//If an external regulator is required, the following line of code should
//be deleted.
GPIO_DBGCFG &= ~GPIO_EXTREGEN;
halInternalSetRegTrim(FALSE);
halPowerUp();
halInternalCalibrateFastRc();
#ifndef DISABLE_WATCHDOG
halInternalEnableWatchDog();
#endif
halInternalStartSystemTimer();
}
void halReboot(void)
{
INTERRUPTS_OFF();
//FCLK must be 6MHz to allow the SYSRESETREQ signal to cleanly
//propagate and reset the chip. Switch SYSCLK first since we need
//the cycles used by switching FCLK to guarantee the SYSCLK is
//stable and ready for SYSRESETREQ.
OSC24M_CTRL = OSC24M_CTRL_RESET; //Guarantee SYSCLK is sourced from OSCHF
CPU_CLKSEL = CPU_CLKSEL_RESET; //Guarantee FCLK is sourced from PCLK
SCS_AIRCR = (0x05FA0000 | SCS_AIRCR_SYSRESETREQ); // trigger the reset
//NOTE: SYSRESETREQ is not the same as nRESET. It will not do the debug
//pieces: DWT, ITM, FPB, vector catch, etc
}
void halPowerDown(void)
{
}
void halPowerUp(void)
{
halInternalInitAdc();
halCommonCalibratePads();
halInternalSwitchToXtal();
}
static int16u seed0 = 0xbeef;
static int16u seed1 = 0xface;
void halCommonSeedRandom(int32u seed)
{
seed0 = (int16u) seed;
if (seed0 == 0)
seed0 = 0xbeef;
seed1 = (int16u) (seed >> 16);
if (seed1 == 0)
seed1 = 0xface;
}
static int16u shift(int16u *val, int16u taps)
{
int16u newVal = *val;
if (newVal & 0x8000)
newVal ^= taps;
*val = newVal << 1;
return newVal;
}
int16u halCommonGetRandom(void)
{
return (shift(&seed0, 0x0062)
^ shift(&seed1, 0x100B));
}
void halCommonMemCopy(void *dest, const void *source, int8u bytes)
{
memcpy(dest, source, bytes);
}
int8s halCommonMemCompare(const void *source0, const void *source1, int8u bytes)
{
return memcmp(source0, source1, bytes);
}
void halCommonMemSet(void *dest, int8u val, int16u bytes)
{
memset(dest, val, bytes);
}

View file

@ -0,0 +1,12 @@
/** @file hal/micro/cortexm3/mpu.h
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
#ifndef __MPU_H__
#define __MPU_H__
#define BYPASS_MPU(blah) blah
#endif//__MPU_H__

View file

@ -0,0 +1,53 @@
/** @file hal/micro/cortexm3/nvm-def.h
* @brief Data definitions for the Cortex-M3 Non-Volatile Memory data storage
* system.
* See @ref nvm for documentation.
*
* See hal/micro/cortexm3/nvm-def.h for source code.
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
/** @addtogroup nvm
* @brief Data definitions for the Cortex-M3 Non-Volatile Memory data storage
* system.
*
* This header defines all of the data sets in the NVM data storage. Each
* piece of data in NVM storage uses an offset to indicate where the data
* lives and a size to indicate the size of that data. Both the offset
* and size are defined in bytes and must be a mupltiple of 16bits. The
* offset is from the start of an NVM page, defined by NVM_LEFT_PAGE and
* NVM_RIGHT_PAGE. The offset and size must be below the maximum size
* of NVM storage as defined by NVM_DATA_SIZE_B. All NVM data must start
* above NVM_MGMT_SIZE_B, since this is where the management bytes live.
*
* @note This file is not directly used by the nvm.c or nvm.h files. This
* file is intended to be a convenient place to define all data that
* lives in NVM so it can be seen together in one group. nvm.h includes
* this file which means any code that includes nvm.h to call the read
* and write functions also has access to these defines.
*@{
*/
#ifndef __NVM_DEF_H__
#define __NVM_DEF_H__
//The bottom 64 bytes of NVM storage is allocated to radio calibration
//values. These 64 bytes *must* exist for the radio to function.
#define NVM_RADIO_CAL_OFFSET (NVM_MGMT_SIZE_B+0x0000)
#define NVM_RADIO_CAL_SIZE_B 64
//IMPORTANT: Data storage starts at offset 0x0040.
//Three example pieces of data:
#define NVM_FOO_OFFSET (NVM_MGMT_SIZE_B+0x0040)
#define NVM_FOO_SIZE_B 2
#define NVM_HAM_OFFSET (NVM_MGMT_SIZE_B+0x0042)
#define NVM_HAM_SIZE_B 10
#define NVM_SPAM_OFFSET (NVM_MGMT_SIZE_B+0x004C)
#define NVM_SPAM_SIZE_B 20
/** @} END addtogroup */
#endif // __NVM_DEF_H__

View file

@ -0,0 +1,377 @@
/** @file hal/micro/cortexm3/nvm.c
* @brief Cortex-M3 Non-Volatile Memory data storage system.
*
* This file implements the NVM data storage system. Refer to nvm.h for
* full documentation of how the NVM data storage system works, is configured,
* and is accessed.
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
#include PLATFORM_HEADER
#include "error.h"
//flash.h gives access to halInternalFlashErase and halInternalFlashWrite.
#include "hal/micro/cortexm3/flash.h"
//nvm.h includes memmap.h. These two headers define the key parameters:
// MFB_PAGE_SIZE_B
// MFB_TOP
// NVM_LEFT_PAGE
// NVM_RIGHT_PAGE
// NVM_DATA_SIZE_B
// NVM_FLASH_PAGE_COUNT
// NVM_MGMT_SIZE_B
#include "hal/micro/cortexm3/nvm.h"
//Define two variables that hold the actual NVM data storage. LEFT and RIGHT
//are not required to be continuous memory blocks so they can be define
//separately. The linker is responsible for placing these storage containers
//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 int8u nvmStorageRight[NVM_DATA_SIZE_B], __NVM__);
static int8u determineState(void)
{
int32u leftMgmt = *(int32u *)NVM_LEFT_PAGE;
int32u rightMgmt = *(int32u *)NVM_RIGHT_PAGE;
int8u state=0;
if((leftMgmt==0xFFFF0000) && (rightMgmt==0xFFFFFFFF)) {
//State 1 and state 4 use identical mgmt words. The function
//determineState() is only called at the start of a NVM read
//or write. During a read, state 1 and 4 both read from the
//LEFT so there is no reason to make a distinction. During
//a write, the system will see the current page as LEFT and
//therefore be transitioning from LEFT to RIGHT so state 4 is
//correct. State 1 is only required to transition from 0 to 2.
state = 4;
} else if((leftMgmt==0xFFFF0000) && (rightMgmt==0xFF00FFFF)) {
state = 2;
} else if((leftMgmt==0xFFFF0000) && (rightMgmt==0xFF000000)) {
state = 3;
} else if((leftMgmt==0xFFFF0000) && (rightMgmt==0xFFFFFFFF)) {
state = 4;
} else if((leftMgmt==0xFFFF0000) && (rightMgmt==0xFFFFFF00)) {
state = 5;
} else if((leftMgmt==0xFF000000) && (rightMgmt==0xFFFFFF00)) {
state = 6;
} else if((leftMgmt==0xFF000000) && (rightMgmt==0xFFFF0000)) {
state = 7;
} else if((leftMgmt==0xFFFFFFFF) && (rightMgmt==0xFFFF0000)) {
state = 8;
} else if((leftMgmt==0xFFFFFF00) && (rightMgmt==0xFFFF0000)) {
state = 9;
} else if((leftMgmt==0xFFFFFF00) && (rightMgmt==0xFF000000)) {
state = 10;
} else {
//State 0 is used to indicate erased or invalid.
state = 0;
}
return state;
}
int8u halCommonReadFromNvm(void *data, int32u offset, int16u length)
{
int16u i;
int16u *flash;
//Remember: all flash writes are 16bits.
int16u *ram = (int16u*)data;
//The NVM data storage system cannot function if the LEFT and RIGHT
//storage are not aligned to physical flash pages.
assert((NVM_LEFT_PAGE%MFB_PAGE_SIZE_B)==0);
assert((NVM_RIGHT_PAGE%MFB_PAGE_SIZE_B)==0);
//The offset of the NVM data must be 16bit aligned.
assert((offset&0x1)==0);
//The length of the NVM data must be 16bit aligned.
assert((length&0x1)==0);
assert(offset+length<NVM_DATA_SIZE_B);
//Obtain the data from NVM storage.
switch(determineState()) {
case 1:
case 2:
case 3:
case 4:
case 9:
case 10:
flash = (int16u *)(NVM_LEFT_PAGE+offset);
for(i=0;i<(length/2);i++) {
ram[i] = flash[i];
}
break;
case 5:
case 6:
case 7:
case 8:
flash = (int16u *)(NVM_RIGHT_PAGE+offset);
for(i=0;i<(length/2);i++) {
ram[i] = flash[i];
}
break;
case 0:
default:
//Reading from NVM while the mgmt bytes are in an invalid state
//should not return any bytes actually found in flash. Instead,
//return nothing but 0xFF. This is legitimate because the next
//call to the write function will also find invalid mgmt bytes
//and trigger an erasure of NVM, after which the NVM really will
//contain just 0xFF for data (plus the new data supplied during
//the write call).
for(i=0;i<(length/2);i++) {
ram[i] = 0xFFFF;
}
//Inform the calling code. using ST_ERR_FATAL, that there were
//invalid mgmt bytes and 0xFF was forcefully returned.
return ST_ERR_FATAL;
}
return ST_SUCCESS;
}
int16u *halCommonGetAddressFromNvm(int32u offset)
{
int16u *flash;
//The NVM data storage system cannot function if the LEFT and RIGHT
//storage are not aligned to physical flash pages.
assert((NVM_LEFT_PAGE%MFB_PAGE_SIZE_B)==0);
assert((NVM_RIGHT_PAGE%MFB_PAGE_SIZE_B)==0);
//The offset of the NVM data must be 16bit aligned.
assert((offset&0x1)==0);
//Obtain the data from NVM storage.
switch(determineState()) {
case 1:
case 2:
case 3:
case 4:
case 9:
case 10:
flash = (int16u *)(NVM_LEFT_PAGE+offset);
break;
case 5:
case 6:
case 7:
case 8:
flash = (int16u *)(NVM_RIGHT_PAGE+offset);
break;
case 0:
default:
// Flash is in an invalid state
// Fix it with a dummy write and then return the flash page left
{
int16u dummy = 0xFFFF;
halCommonWriteToNvm(&dummy, 0, 2);
flash = (int16u *)(NVM_LEFT_PAGE+offset);
}
}
return flash;
}
static int8u erasePage(int32u page)
{
StStatus status;
int32u i, k;
int32u address;
int8u *flash;
//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
//are erased from the top down ensuring that that mgmt words are the last
//data to be erased. This way, if a reset occurs while erasing, the mgmt
//words are still valid the next time determineState() is called.
for(i=NVM_FLASH_PAGE_COUNT;i>0;i--) {
address = (page+((i-1)*MFB_PAGE_SIZE_B));
flash = (int8u *)address;
//Scan the page to determine if it is fully erased already.
//If the flash is not erased, erase it. The purpose of scanning
//first is to save a little time if erasing is not required.
for(k=0;k<MFB_PAGE_SIZE_B;k++,flash++) {
if(*flash != 0xFF) {
status = halInternalFlashErase(MFB_PAGE_ERASE, address);
if(status != ST_SUCCESS) {
return status;
}
//Don't bother looking at the rest of this flash page and just
//move to the next.
k=MFB_PAGE_SIZE_B;
}
}
}
return ST_SUCCESS;
}
//This macro is responsible for erasing an NVM page (LEFT or RIGHT).
#define ERASE_PAGE(page) \
do { \
status = erasePage(page); \
if(status != ST_SUCCESS) { \
return status; \
} \
} while(0)
//This macro is responsible for writing the new data into the destination
//page and copying existing data from the source page to the
//destination page.
#define WRITE_DATA(destPage, srcPage, offset, length) \
do { \
/*Copy all data below the new data from the srcPage to the destPage*/ \
status = halInternalFlashWrite(destPage+NVM_MGMT_SIZE_B, \
(int16u *)(srcPage+NVM_MGMT_SIZE_B), \
(offset-NVM_MGMT_SIZE_B)/2); \
if(status != ST_SUCCESS) { return status; } \
/*Write the new data*/ \
status = halInternalFlashWrite(destPage+offset, \
ram, \
(length)/2); \
if(status != ST_SUCCESS) { return status; } \
/*Copy all data above the new data from the srcPage to the destPage*/ \
status = halInternalFlashWrite(destPage+offset+length, \
(int16u *)(srcPage+offset+length), \
(NVM_DATA_SIZE_B- \
length-offset- \
NVM_MGMT_SIZE_B)/2); \
if(status != ST_SUCCESS) { return status; } \
} while(0)
//This macro is responsible for writing 16bits of management data to
//the proper management address.
#define WRITE_MGMT_16BITS(address, data) \
do{ \
int16u value = data; \
status = halInternalFlashWrite((address), &value, 1); \
if(status != ST_SUCCESS) { \
return status; \
} \
} while(0)
int8u halCommonWriteToNvm(const void *data, int32u offset, int16u length)
{
StStatus status;
int8u state, exitState;
int32u srcPage;
int32u destPage;
//Remember: NVM data storage works on 16bit quantities.
int16u *ram = (int16u*)data;
//The NVM data storage system cannot function if the LEFT and RIGHT
//storage are not aligned to physical flash pages.
assert((NVM_LEFT_PAGE%MFB_PAGE_SIZE_B)==0);
assert((NVM_RIGHT_PAGE%MFB_PAGE_SIZE_B)==0);
//The offset of the NVM data must be 16bit aligned.
assert((offset&0x1)==0);
//The length of the NVM data must be 16bit aligned.
assert((length&0x1)==0);
//It is illegal to write to an offset outside of NVM storage.
assert(offset+length<NVM_DATA_SIZE_B);
state = determineState();
switch(state) {
case 1:
case 2:
case 3:
case 4:
case 9:
case 10:
srcPage = NVM_LEFT_PAGE;
destPage = NVM_RIGHT_PAGE;
exitState = 7;
break;
case 5:
case 6:
case 7:
case 8:
srcPage = NVM_RIGHT_PAGE;
destPage = NVM_LEFT_PAGE;
exitState = 3;
break;
case 0:
default:
//Invalid state. Default to writing to the LEFT page. Defaulting to
//using RIGHT as the source page is valid since the RIGHT page
//will also be erased and therefore produce 0xFF for data values.
state = 0;
srcPage = NVM_RIGHT_PAGE;
destPage = NVM_LEFT_PAGE;
exitState = 3;
break;
}
//Advance the state machine. Starting on state 3 requires state 7 to
//exit and starting on state 7 requires state 3 to exit. Starting on
//any other state requires either 3 or 7 to exit.
//NOTE: Refer to nvm.h for a description of the states and how the
// state transitions correspond to erasing, writing data, and
// writing mgmt values.
while(TRUE) {
switch(state) {
case 0:
//State 0 is the only state where the source page needs to be erased.
ERASE_PAGE(srcPage);
ERASE_PAGE(destPage);
WRITE_DATA(destPage, srcPage, offset, length);
WRITE_MGMT_16BITS(NVM_LEFT_PAGE+0, 0x0000);
state=1;
break;
case 1:
WRITE_MGMT_16BITS(NVM_RIGHT_PAGE+2, 0xFF00);
state=2;
break;
case 2:
WRITE_MGMT_16BITS(NVM_RIGHT_PAGE+0, 0x0000);
state=3;
break;
case 3:
if(exitState==3) {
return ST_SUCCESS;
}
ERASE_PAGE(destPage);
state=4;
break;
case 4:
WRITE_DATA(destPage, srcPage, offset, length);
WRITE_MGMT_16BITS(NVM_RIGHT_PAGE+0, 0xFF00);
state=5;
break;
case 5:
WRITE_MGMT_16BITS(NVM_LEFT_PAGE+2, 0xFF00);
state=6;
break;
case 6:
WRITE_MGMT_16BITS(NVM_RIGHT_PAGE+0, 0x0000);
state=7;
break;
case 7:
if(exitState==7) {
return ST_SUCCESS;
}
ERASE_PAGE(destPage);
state=8;
break;
case 8:
WRITE_DATA(destPage, srcPage, offset, length);
WRITE_MGMT_16BITS(NVM_LEFT_PAGE+0, 0xFF00);
state=9;
break;
case 9:
WRITE_MGMT_16BITS(NVM_RIGHT_PAGE+2, 0xFF00);
state=10;
break;
case 10:
WRITE_MGMT_16BITS(NVM_LEFT_PAGE+0, 0x0000);
state=3;
break;
}
}
}

View file

@ -0,0 +1,279 @@
/** @file hal/micro/cortexm3/nvm.h
* @brief Cortex-M3 Non-Volatile Memory data storage system.
* See @ref nvm for documentation.
*
* The functions in this file return an ::StStatus value.
* See error-def.h for definitions of all ::StStatus return values.
*
* See hal/micro/cortexm3/nvm.h for source code.
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
/** @addtogroup nvm
* @brief Cortex-M3 Non-Volatile Memory data storage system.
*
* This header defines the API for NVM data storage. This header also
* describes the algorithm behind the NVM data storage system with notes
* on algorithm behavior.
*
* See hal/micro/cortexm3/nvm.h for source code.
*
* @note The algorithm description uses "page" to indicate an area of memory
* that is a multiple of physical flash pages. There are two pages: LEFT
* and RIGHT. The term "flash page" is used to refer to a page of
* physical flash.
*
* NVM data storage works by alternating between two pages: LEFT and RIGHT.
* The basic algorithm is driven by a call to halCommonSaveToNvm(). It will:
* - erase the inactive page
* - write the new data to the inactive page
* - copy existing data from the active page to the inactive page
* - mark the inactive page as the new active page
* - mark the old active page as the new inactive page
* To accomplish alternating between two pages and knowing which page has the
* valid set of data, the algorithm uses 4 bytes of mgmt data that exists
* at the top of both LEFT and RIGHT (the term "mgmt" is shorthand referring to
* the management data). The management data is comprised of a Valid marker,
* an Active marker, a Dead marker, and a Spare byte. Viewing the
* management data as a single 32 bit quantity yields:
* - Valid is mgmt[0]
* - Active is mgmt[1]
* - Dead is mgmt[2]
* - Spare is mgmt[3]
* The algorithm is based on a simple, circular state machine. The following
* discussion details all of the possible mgmt bytes and the states they
* correspond to. The "Reads from" line indicates which page a call to
* halCommonReadFromNvm() will read from (an 'x' page will stuff the read
* data with 0xFF). The vertical "erase" and "write" words indicate the
* flash altering actions taken between those states. Invalid mgmt bytes
* is equivalent to erased mgmt bytes (state 0) and will trigger an
* erase of both LEFT and RIGHT. State 3 and state 7 are the only exit
* states. When the algorithm is run, regardless of starting state, it
* will advance to the next exit state. This means if the "Read from"
* is LEFT then the state machine will advance until state 7 and then exit.
* If "Read from" is RIGHT, then the state machine will advance until
* state 3 and then exit.
*
* @code
* Starting from erased or invalid mgmt, write to LEFT
* State # 0 0 1 2 3
* Reads from: x x e w L L L
* Valid xx|xx FF|FF r r 00|FF 00|FF 00|00
* Active xx|xx FF|FF a i 00|FF 00|FF 00|00
* Dead xx|xx FF|FF s t FF|FF FF|00 FF|00
* Spare xx|xx FF|FF e e FF|FF FF|FF FF|FF
*
*
* Starting from LEFT page, transition to RIGHT page:
* State # 3 4 5 6 7
* Reads from: L e L w R R R
* Valid 00|00 r 00|FF r 00|00 00|00 00|00
* Active 00|00 a 00|FF i 00|FF 00|FF 00|00
* Dead FF|00 s FF|FF t FF|FF 00|FF 00|FF
* Spare FF|FF e FF|FF e FF|FF FF|FF FF|FF
*
*
* Starting from RIGHT page, transition to LEFT page:
* State # 7 8 9 10 3
* Reads from: R e R w L L L
* Valid 00|00 r FF|00 r 00|00 00|00 00|00
* Active 00|00 a FF|00 i FF|00 FF|00 00|00
* Dead 00|FF s FF|FF t FF|FF FF|00 FF|00
* Spare FF|FF e FF|FF e FF|FF FF|FF FF|FF
* @endcode
*
* Based on the 10 possible states, there are 5 valid 32bit mgmt words:
* - 0xFFFFFFFF
* - 0xFFFFFF00
* - 0xFFFF0000
* - 0xFF000000
* - 0xFF00FFFF
* The algorithm determines the current state by using these 5 mgmt words
* with the 10 possible combinations of LEFT mgmt and RIGHT mgmt.
*
* Detailed State Description:
* - State 0:
* In this state the mgmt bytes do not conform to any of the other states
* and therefore the entire NVM system, both the LEFT and RIGHT, is
* invalid. Invalid could be as simple as both LEFT and RIGHT are erased
* or as complex as serious memory corruption or a bug caused bad data to
* be written to the NVM. By using a small set of very strict, precise,
* valid states (versus other management systems such as a simple counter),
* the algorithm/data gains some protection against not only corruption, but
* also executing the NVM algorithm on a chip that previously did not
* have the NVM system running on it.
* - State 1, 4, 8
* In these states, mgmt is saying that one page is valid and active, while
* the other page is erased. This tells the algorithm which page to read
* from and indicates that the other page has already been erased.
* - State 2
* This state is only necessary for transitioning from state 0. From state
* 0, the goal is to arrive at state 3. Ideally, the RIGHT mgmt would
* be written with 0xFF000000, but the flash library only permits 16 bit
* writes. If a reset were to occur in the middle of this section of the
* algorithm, we want to ensure that the mgmt is left in a known state,
* state 2, so that the algorithm could continue from where it got
* interrupted.
* - State 5, 9
* These states indicate that the other page has just become valid because
* the new data has just been written. Once at these states, reading
* from the NVM will now pull data from the other page.
* - State 6, 10
* These states indicate that the old page is now dead and not in use.
* While the algorithm already knows to read from the new page, the Dead
* mgmt byte is primarily used to indicate that the other page needs to
* be erased. Conceptually, the Dead byte can also be considered a type
* of "garbage collection" flag indicating the old page needs to be
* destroyed and has not yet been erased.
* - State 3, 7
* These states are the final exit points of the circular state machine.
* Once at these states, the current page is marked Valid and Active and
* the old page is marked as Dead. The algorithm knows which page to
* read from and which page needs to be erased on the next write to the NVM.
*
*
* Notes on algorithm behavior:
* - Refer to nvm-def.h for a list of offset/length that define the data
* stored in NVM storage space.
* - All writes to flash are 16bit granularity and therefore the internal
* flash writes cast the data to int16u. Length is also required to be
* a multiple of 16bits.
* - 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
* the define MFB_PAGE_SIZE_B.
* - Erasing will only occur when halCommonSaveToNvm() is called.
* - Erasing will always occur when halCommonSaveToNvm() is called unless the
* page intended to be erased is already entirely 0xFFFF.
* - When reading and management is invalid, the read will return 0xFF for data.
* - Calling halCommonSaveToNvm() while in any state is always valid and the
* new data will be written to flash.
* - halCommonSaveToNvm() will always advance the state machine to 3 or 7.
* - When writing and management is invalid, both LEFT and RIGHT will be erased
* and the new data will be written to LEFT.
* - Writing causes the new data being passed into halCommonSaveToNvm() to be
* written to flash. The data already existing in the currently valid page
* will be copied over to the new page.
* - Reading or writing to an offset equal to or greater than NVM_DATA_SIZE_B is
* illegal and will cause an assert.
* - Offset and length must always be multiples of 16bits. If not, both a read
* and a write will trigger an assert.
* - Offset and length must be supplied in bytes.
* - All data in NVM storage must exist above the mgmt bytes, denoted by
* NVM_MGMT_SIZE_B.
* - The bottom 64 bytes of NVM storage are allocated to radio calibration
* values. These 64 bytes *must* exist for the radio to function.
* - There is no error checking beyond checking for 16bit alignment. This
* means it is possible to use data offset and size combinations that
* exceed NVM storage space or overlap with other data. Be careful!
*@{
*/
#ifndef __NVM_H__
#define __NVM_H__
//Pull in the MFB_ definitions.
#include "hal/micro/cortexm3/memmap.h"
//Pull in nvm-def.h so any code including nvm.h has access to the
//offsets and sizes defining the NVM data.
#include "hal/micro/cortexm3/nvm-def.h"
//Necessary to define StStatus and codes.
#include "error.h"
/**
* @brief Copy the NVM data from flash into the provided RAM location.
* It is illegal for the offset to be greater than NVM_DATA_SIZE_B.
*
* @param data A (RAM) pointer to where the data should be copied.
*
* @param offset The location from which the data should be copied. Must be
* 16bit aligned.
*
* @param length The length of the data in bytes. Must be 16bit aligned.
*
* @return An StStatus value indicating the success of the function.
* - ST_SUCCESS if the read completed cleanly.
* - ST_ERR_FATAL if the NVM storage management indicated an invalid
* state. The function will return entirely 0xFF in the data parameter.
*/
StStatus halCommonReadFromNvm(void *data, int32u offset, int16u length);
/**
* @brief Return the address of the token in NVM
*
* @param offset The location offset from which the address should be returned
*
*
* @return The address requested
*/
int16u *halCommonGetAddressFromNvm(int32u offset);
/**
* @brief Write the NVM data from the provided location RAM into flash.
* It is illegal for the offset to be greater than NVM_DATA_SIZE_B.
*
* @param data A (RAM) pointer from where the data should be taken.
*
* @param offset The location to which the data should be written. Must be
* 16bit aligned.
*
* @param length The length of the data in bytes. Must be 16bit aligned.
*
* @return An StStatus value indicating the success of the function.
* - ST_SUCCESS if the write completed cleanly.
* - Any other status value is an error code generated by the low level
* flash erase and write API. Refer to flash.h for details.
*/
StStatus halCommonWriteToNvm(const void *data, int32u offset, int16u length);
/**
* @brief Define the number of physical flash pages that comprise a NVM page.
* Since NVM_DATA_SIZE_B must be a multiple of MFB_PAGE_SIZE_B, increasing the
* size of NVM storage should be done by modifying this define.
*
* @note The total flash area consumed by NVM storage is double this value.
* This is due to the fact that there are two NVM pages, LEFT and RIGHT,
* which the algorithm alternates between.
*/
#define NVM_FLASH_PAGE_COUNT (1)
/**
* @brief Define the total size of a NVM page, in bytes. This must be a
* multiple of the memory map define MFB_PAGE_SIZE_B. Note that 4 bytes of
* the total size of an NVM page are dedicated to page management.
*
* @note <b>DO NOT EDIT THIS DEFINE. Instead, edit NVM_FLASH_PAGE_COUNT.</b>
*/
#define NVM_DATA_SIZE_B (MFB_PAGE_SIZE_B*NVM_FLASH_PAGE_COUNT)
#if ((NVM_DATA_SIZE_B%MFB_PAGE_SIZE_B) != 0)
#error Illegal NVM data storage size. NVM_DATA_SIZE_B must be a multiple of MFB_PAGE_SIZE_B.
#endif
/**
* @brief Define the absolute address of the LEFT page. LEFT page storage
* is defined by nvmStorageLeft[NVM_DATA_SIZE_B] and placed by the linker
* using the segment "NVM".
*/
#define NVM_LEFT_PAGE ((int32u)nvmStorageLeft)
/**
* @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
* using the segment "NVM".
*/
#define NVM_RIGHT_PAGE ((int32u)nvmStorageRight)
/**
* @brief Define the number of bytes that comprise the NVM management bytes.
* All data must begin at an offset above the management bytes.
*
* @note This value <b>must not change</b>.
*/
#define NVM_MGMT_SIZE_B (4)
/** @} END addtogroup */
#endif // __NVM_H__

View file

@ -0,0 +1,873 @@
/** @file hal/micro/cortexm3/sleep.c
*
* @brief STM32W108 micro specific sleep functions.
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
#include PLATFORM_HEADER
#include "hal/micro/micro-common.h"
#include "hal/micro/cortexm3/micro-common.h"
//We don't have a real register to hold this composite information.
//Pretend we do so halGetWakeInfo can operate like halGetResetInfo.
//This "register" is only ever set by halInternalSleep.
// [31] = WakeInfoValid
// [30] = SleepSkipped
// [29] = CSYSPWRUPREQ
// [28] = CDBGPWRUPREQ
// [27] = WAKE_CORE
// [26] = TIMER_WAKE_WRAP
// [25] = TIMER_WAKE_COMPB
// [24] = TIMER_WAKE_COMPA
// [23:0] = corresponding GPIO activity
#define WAKEINFOVALID_INTERNAL_WAKE_EVENT_BIT 31
#define SLEEPSKIPPED_INTERNAL_WAKE_EVENT_BIT 30
#define CSYSPWRUPREQ_INTERNAL_WAKE_EVENT_BIT 29
#define CDBGPWRUPREQ_INTERNAL_WAKE_EVENT_BIT 28
#define WAKE_CORE_INTERNAL_WAKE_EVENT_BIT 27
#define WRAP_INTERNAL_WAKE_EVENT_BIT 26
#define CMPB_INTERNAL_WAKE_EVENT_BIT 25
#define CMPA_INTERNAL_WAKE_EVENT_BIT 24
//This define shifts events from the PWRUP_EVENT register into the proper
//place in the halInternalWakeEvent variable
#define INTERNAL_WAKE_EVENT_BIT_SHIFT 20
static int32u halInternalWakeEvent=0;
int32u halGetWakeInfo(void)
{
return halInternalWakeEvent;
}
void halInternalSleep(SleepModes sleepMode)
{
//Timer restoring always takes place during the wakeup sequence. We save
//the state here in case SLEEPMODE_NOTIMER is invoked, which would disable
//the clocks.
int32u SLEEPTMR_CLKEN_SAVED = SLEEPTMR_CLKEN;
//This code assumes all wake source registers are properly configured.
//As such, it should be called from halSleepWithOptions() or from
// halSleepForQsWithOptions() which configues the wake sources.
//The parameter gpioWakeSel is a bitfield composite of the GPIO wake
//sources derived from the 3 ports, indicating which of the 24 GPIO
//are configured as a wake source.
int32u gpioWakeSel = (GPIO_PAWAKE<<0);
gpioWakeSel |= (GPIO_PBWAKE<<8);
gpioWakeSel |= (GPIO_PCWAKE<<16);
//PB2 is also WAKE_SC1. Set this wake source if PB2's GPIO wake is set.
if(GPIO_PBWAKE & PB2) {
WAKE_SEL |= WAKE_SC1;
}
//PA2 is also WAKE_SC2. Set this wake source if PA2's GPIO wake is set.
if(GPIO_PAWAKE & PA2) {
WAKE_SEL |= WAKE_SC2;
}
//The WAKE_IRQD source can come from any pin based on IRQD's sel register.
if(gpioWakeSel & BIT(GPIO_IRQDSEL)) {
WAKE_SEL |= WAKE_IRQD;
}
halInternalWakeEvent = 0; //clear old wake events
switch(sleepMode)
{
case SLEEPMODE_NOTIMER:
//The sleep timer clock sources (both RC and XTAL) are turned off.
//Wakeup is possible from only GPIO. System time is lost.
//NOTE: Timer restoring always takes place during the wakeup sequence.
SLEEPTMR_CLKEN = 0;
goto deepSleepCore;
case SLEEPMODE_WAKETIMER:
//The sleep timer clock sources remain running. The RC is always
//running and the 32kHz XTAL depends on the board header. Wakeup
//is possible from both GPIO and the sleep timer. System time
//is maintained. The sleep timer is assumed to be configured
//properly for wake events.
//NOTE: This mode assumes the caller has configured the *entire*
// sleep timer properly.
if(INT_SLEEPTMRCFG&INT_SLEEPTMRWRAP) {
WAKE_SEL |= WAKE_SLEEPTMRWRAP;
}
if(INT_SLEEPTMRCFG&INT_SLEEPTMRCMPB) {
WAKE_SEL |= WAKE_SLEEPTMRCMPB;
}
if(INT_SLEEPTMRCFG&INT_SLEEPTMRCMPA) {
WAKE_SEL |= WAKE_SLEEPTMRCMPA;
}
//fall into SLEEPMODE_MAINTAINTIMER's sleep code:
case SLEEPMODE_MAINTAINTIMER:
//The sleep timer clock sources remain running. The RC is always
//running and the 32kHz XTAL depends on the board header. Wakeup
//is possible from only GPIO. System time is maintained.
//NOTE: System time is maintained without any sleep timer interrupts
// because the hardware sleep timer counter is large enough
// to hold the entire count value and not need a RAM counter.
////////////////////////////////////////////////////////////////////////////
// Core deep sleep code
////////////////////////////////////////////////////////////////////////////
deepSleepCore:
// Interrupts *must* be/stay disabled for DEEP SLEEP operation
// INTERRUPTS_OFF will use BASEPRI to disable all interrupts except
// fault handlers and PendSV.
INTERRUPTS_OFF();
// This is the point of no return. From here on out, only the interrupt
// sources available in WAKE_SEL will be captured and propagated across
// deep sleep.
//stick all our saved info onto stack since it's only temporary
{
boolean restoreWatchdog = halInternalWatchDogEnabled();
boolean skipSleep = FALSE;
// Only three register blocks keep power across deep sleep:
// CM_HV, GPIO, SLOW_TIMERS
//
// All other register blocks lose their state across deep sleep:
// BASEBAND, MAC, SECURITY, SERIAL, TMR1, TMR2, EVENT, CM_LV, RAM_CTRL,
// AUX_ADC, CAL_ADC, FLASH_CONTROL, ITM, DWT, FPB, NVIC, TPIU
//
// The sleep code will only save and restore registers where it is
// meaningful and necessary to do so. In most cases, there must still
// be a powerup function to restore proper state.
//
// NOTE: halPowerUp() and halPowerDown() will always be called before
// and after this function. halPowerDown and halPowerUp should leave
// the modules in a safe state and then restart the modules.
// (For example, shutting down and restarting Timer1)
//
//----BASEBAND
// reinitialized by stStackPowerUp()
//----MAC
// reinitialized by stStackPowerUp()
//----SECURITY
// reinitialized by stStackPowerUp()
//----SERIAL
// reinitialized by halPowerUp() or similar
//----TMR1
// reinitialized by halPowerUp() or similar
//----TMR2
// reinitialized by halPowerUp() or similar
//----EVENT
//SRC or FLAG interrupts are not saved or restored
//MISS interrupts are not saved or restored
//MAC_RX_INT_MASK - reinitialized by stStackPowerUp()
//MAC_TX_INT_MASK - reinitialized by stStackPowerUp()
//MAC_TIMER_INT_MASK - reinitialized by stStackPowerUp()
//BB_INT_MASK - reinitialized by stStackPowerUp()
//SEC_INT_MASK - reinitialized by stStackPowerUp()
int32u INT_SLEEPTMRCFG_SAVED = INT_SLEEPTMRCFG_REG;
int32u INT_MGMTCFG_SAVED = INT_MGMTCFG_REG;
//INT_TIM1CFG - reinitialized by halPowerUp() or similar
//INT_TIM2CFG - reinitialized by halPowerUp() or similar
//INT_SC1CFG - reinitialized by halPowerUp() or similar
//INT_SC2CFG - reinitialized by halPowerUp() or similar
//INT_ADCCFG - reinitialized by halPowerUp() or similar
int32u GPIO_INTCFGA_SAVED = GPIO_INTCFGA_REG;
int32u GPIO_INTCFGB_SAVED = GPIO_INTCFGB_REG;
int32u GPIO_INTCFGC_SAVED = GPIO_INTCFGC_REG;
int32u GPIO_INTCFGD_SAVED = GPIO_INTCFGD_REG;
//SC1_INTMODE - reinitialized by halPowerUp() or similar
//SC2_INTMODE - reinitialized by halPowerUp() or similar
//----CM_LV
int32u OSC24M_BIASTRIM_SAVED = OSC24M_BIASTRIM_REG;
int32u OSCHF_TUNE_SAVED = OSCHF_TUNE_REG;
int32u DITHER_DIS_SAVED = DITHER_DIS_REG;
//OSC24M_CTRL - reinitialized by halPowerUp() or similar
//CPU_CLKSEL - reinitialized by halPowerUp() or similar
//TMR1_CLK_SEL - reinitialized by halPowerUp() or similar
//TMR2_CLK_SEL - reinitialized by halPowerUp() or similar
int32u PCTRACE_SEL_SAVED = PCTRACE_SEL_REG;
//----RAM_CTRL
int32u MEM_PROT_0_SAVED = MEM_PROT_0_REG;
int32u MEM_PROT_1_SAVED = MEM_PROT_1_REG;
int32u MEM_PROT_2_SAVED = MEM_PROT_2_REG;
int32u MEM_PROT_3_SAVED = MEM_PROT_3_REG;
int32u MEM_PROT_4_SAVED = MEM_PROT_4_REG;
int32u MEM_PROT_5_SAVED = MEM_PROT_5_REG;
int32u MEM_PROT_6_SAVED = MEM_PROT_6_REG;
int32u MEM_PROT_7_SAVED = MEM_PROT_7_REG;
int32u MEM_PROT_EN_SAVED = MEM_PROT_EN_REG;
//----AUX_ADC
// reinitialized by halPowerUp() or similar
//----CAL_ADC
// reinitialized by stStackPowerUp()
//----FLASH_CONTROL
// configured on the fly by the flash library
//----ITM
// reinitialized by halPowerUp() or similar
//----DWT
// not used by software on chip
//----FPB
// not used by software on chip
//----NVIC
//ST_CSR - 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
//INT_PENDSET - used below when overlapping interrupts and wake sources
//NVIC_IPR_3to0 - 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_15to12 - 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;
//SCS_CCR - 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_15to12 - fixed, restored by cstartup when exiting deep sleep
//SCS_SHCSR - fixed, restored by cstartup when exiting deep sleep
//----TPIU
// reinitialized by halPowerUp() or similar
//stmDebugPowerDown() should have shutdown the DWT/ITM/TPIU already.
//freeze input to the GPIO from LV (alternate output functions freeze)
EVENT_CTRL = LV_FREEZE;
//record GPIO state for wake monitoring purposes
//By having a snapshot of GPIO state, we can figure out after waking
//up exactly which GPIO could have woken us up.
//Reading the three IN registers is done separately to avoid warnings
//about undefined order of volatile access.
int32u GPIO_IN_SAVED = GPIO_PAIN;
GPIO_IN_SAVED |= (GPIO_PBIN<<8);
GPIO_IN_SAVED |= (GPIO_PCIN<<16);
//reset the power up events by writing 1 to all bits.
PWRUP_EVENT = 0xFFFFFFFF;
//By clearing the events, the wake up event capturing is activated.
//At this point we can safely check our interrupt flags since event
//capturing is now overlapped. Up to now, interrupts indicate
//activity, after this point, powerup events indicate activity.
//If any of the interrupt flags are set, that means we saw a wake event
//sometime while entering sleep, so we need to skip over sleeping
//
//--possible interrupt sources for waking:
// IRQA, IRQB, IRQC, IRQD
// SleepTMR CMPA, CMPB, Wrap
// WAKE_CORE (DebugIsr)
//
//check for IRQA interrupt and if IRQA (PB0) is wake source
if((INT_PENDSET&INT_IRQA) &&
(GPIO_PBWAKE&PB0) &&
(WAKE_SEL&GPIO_WAKE)) {
skipSleep = TRUE;
//log IRQA as a wake event
halInternalWakeEvent |= BIT(PORTB_PIN(0));
}
//check for IRQB interrupt and if IRQB (PB6) is wake source
if((INT_PENDSET&INT_IRQB) &&
(GPIO_PBWAKE&PB6) &&
(WAKE_SEL&GPIO_WAKE)) {
skipSleep = TRUE;
//log IRQB as a wake event
halInternalWakeEvent |= BIT(PORTB_PIN(6));
}
//check for IRQC interrupt and if IRQC (GPIO_IRQCSEL) is wake source
if((INT_PENDSET&INT_IRQC) &&
(gpioWakeSel&BIT(GPIO_IRQCSEL)) &&
(WAKE_SEL&GPIO_WAKE)) {
skipSleep = TRUE;
//log IRQC as a wake event
halInternalWakeEvent |= BIT(GPIO_IRQCSEL);
}
//check for IRQD interrupt and if IRQD (GPIO_IRQDSEL) is wake source
if((INT_PENDSET&INT_IRQD) &&
(gpioWakeSel&BIT(GPIO_IRQDSEL)) &&
((WAKE_SEL&GPIO_WAKE) ||
(WAKE_SEL&WAKE_IRQD))) {
skipSleep = TRUE;
//log IRQD as a wake event
halInternalWakeEvent |= BIT(GPIO_IRQDSEL);
}
//check for SleepTMR CMPA interrupt and if SleepTMR CMPA is wake source
if((INT_SLEEPTMR&INT_SLEEPTMRCMPA) && (WAKE_SEL&WAKE_SLEEPTMRCMPA)) {
skipSleep = TRUE;
//log SleepTMR CMPA as a wake event
halInternalWakeEvent |= BIT32(CMPA_INTERNAL_WAKE_EVENT_BIT);
}
//check for SleepTMR CMPB interrupt and if SleepTMR CMPB is wake source
if((INT_SLEEPTMR&INT_SLEEPTMRCMPB) && (WAKE_SEL&WAKE_SLEEPTMRCMPB)) {
skipSleep = TRUE;
//log SleepTMR CMPB as a wake event
halInternalWakeEvent |= BIT32(CMPB_INTERNAL_WAKE_EVENT_BIT);
}
//check for SleepTMR WRAP interrupt and if SleepTMR WRAP is wake source
if((INT_SLEEPTMR&INT_SLEEPTMRWRAP) && (WAKE_SEL&WAKE_SLEEPTMRWRAP)) {
skipSleep = TRUE;
//log SleepTMR WRAP as a wake event
halInternalWakeEvent |= BIT32(WRAP_INTERNAL_WAKE_EVENT_BIT);
}
//check for Debug interrupt and if WAKE_CORE is wake source
if((INT_PENDSET&INT_DEBUG) && (WAKE_SEL&WAKE_WAKE_CORE)) {
skipSleep = TRUE;
//log WAKE_CORE as a wake event
halInternalWakeEvent |= BIT32(WAKE_CORE_INTERNAL_WAKE_EVENT_BIT);
}
//only propagate across deep sleep the interrupts that are both
//enabled and possible wake sources
{
int32u wakeSourceInterruptMask = 0;
if(GPIO_PBWAKE&PB0) {
wakeSourceInterruptMask |= INT_IRQA;
}
if(GPIO_PBWAKE&PB6) {
wakeSourceInterruptMask |= INT_IRQB;
}
if(gpioWakeSel&BIT(GPIO_IRQCSEL)) {
wakeSourceInterruptMask |= INT_IRQC;
}
if(gpioWakeSel&BIT(GPIO_IRQDSEL)) {
wakeSourceInterruptMask |= INT_IRQD;
}
if( (WAKE_SEL&WAKE_SLEEPTMRCMPA) ||
(WAKE_SEL&WAKE_SLEEPTMRCMPB) ||
(WAKE_SEL&WAKE_SLEEPTMRWRAP) ) {
wakeSourceInterruptMask |= INT_SLEEPTMR;
}
if(WAKE_SEL&WAKE_WAKE_CORE) {
wakeSourceInterruptMask |= INT_DEBUG;
}
INT_CFGSET_SAVED &= wakeSourceInterruptMask;
}
//disable watchdog while sleeping (since we can't reset it asleep)
halInternalDisableWatchDog(MICRO_DISABLE_WATCH_DOG_KEY);
//The chip is not allowed to enter a deep sleep mode (which could
//cause a core reset cycle) while CSYSPWRUPREQ is set. CSYSPWRUPREQ
//indicates that the debugger is trying to access sections of the
//chip that would get reset during deep sleep. Therefore, a reset
//cycle could very easily cause the debugger to error and we don't
//want that. While the power management state machine will stall
//if CSYSPWRUPREQ is set (to avoid the situation just described),
//in this stalled state the chip will not be responsive to wake
//events. To be sensitive to wake events, we must handle them in
//software instead. To accomplish this, we request that the
//CSYSPWRUPACK be inhibited (which will indicate the debugger is not
//connected). But, we cannot induce deep sleep until CSYSPWRUPREQ/ACK
//go low and these are under the debuggers control, so we must stall
//and wait here. If there is a wake event during this time, break
//out and wake like normal. If the ACK eventually clears,
//we can proceed into deep sleep. The CSYSPWRUPACK_INHIBIT
//functionality will hold off the debugger (by holding off the ACK)
//until we are safely past and out of deep sleep. The power management
//state machine then becomes responsible for clearing
//CSYSPWRUPACK_INHIBIT and responding to a CSYSPWRUPREQ with a
//CSYSPWRUPACK at the right/safe time.
CSYSPWRUPACK_INHIBIT = CSYSPWRUPACK_INHIBIT_CSYSPWRUPACK_INHIBIT;
{
//Use a local copy of WAKE_SEL to avoid warnings from the compiler
//about order of volatile accesses
int32u wakeSel = WAKE_SEL;
//stall until a wake event or CSYSPWRUPREQ/ACK clears
while( (CSYSPWRUPACK_STATUS) && (!(PWRUP_EVENT&wakeSel)) ) {}
//if there was a wake event, allow CSYSPWRUPACK and skip sleep
if(PWRUP_EVENT&wakeSel) {
CSYSPWRUPACK_INHIBIT = CSYSPWRUPACK_INHIBIT_RESET;
skipSleep = TRUE;
}
}
if(!skipSleep) {
//FogBugz 7283 states that we must switch to the OSCHF when entering
//deep sleep since using the 24MHz XTAL could result in RAM
//corruption. This switch must occur at least 2*24MHz cycles before
//sleeping.
//FogBugz 8858 states that we cannot go into deep-sleep when the
//chip is clocked with the 24MHz XTAL with a duty cycle as low as
//70/30 since this causes power_down generation timing to fail.
OSC24M_CTRL &= ~OSC24M_CTRL_OSC24M_SEL;
//If DS12 needs to be forced regardless of state, clear
//REGEN_DSLEEP here. This is hugely dangerous and
//should only be done in very controlled chip tests.
SCS_SCR |= SCS_SCR_SLEEPDEEP; //enable deep sleep
extern volatile boolean halPendSvSaveContext;
halPendSvSaveContext = 1; //1 means save context
//The INTERRUPTS_OFF used at the beginning of this function set
//BASEPRI such that the only interrupts that will fire are faults
//and PendSV. Trigger PendSV now to induce a context save.
SCS_ICSR |= SCS_ICSR_PENDSVSET; //pend the context save and Dsleep
//Since the interrupt will not fire immediately it is possible to
//execute a few lines of code. To stay halted in this spot until the
//WFI instruction, spin on the context flag (which will get cleared
//during the startup sequence when restoring context).
while(halPendSvSaveContext) {}
//I AM ASLEEP. WHEN EXECUTION RESUMES, CSTARTUP WILL RESTORE TO HERE
} else {
//Record the fact that we skipped sleep
halInternalWakeEvent |= BIT32(SLEEPSKIPPED_INTERNAL_WAKE_EVENT_BIT);
//If this was a true deep sleep, we would have executed cstartup and
//PRIMASK would be set right now. If we skipped sleep, PRIMASK is not
//set so we explicitely set it to guarantee the powerup sequence
//works cleanly and consistently with respect to interrupt
//dispatching and enabling.
_setPriMask();
}
//Clear the interrupt flags for all wake sources. This
//is necessary because if we don't execute an actual deep sleep cycle
//the interrupt flags will never be cleared. By clearing the flags,
//we always mimick a real deep sleep as closely as possible and
//guard against any accidental interrupt triggering coming out
//of deep sleep. (The interrupt dispatch code coming out of sleep
//is responsible for translating wake events into interrupt events,
//and if we don't clear interrupt flags here it's possible for an
//interrupt to trigger even if it wasn't the true wake event.)
INT_SLEEPTMRFLAG = (INT_SLEEPTMRCMPA |
INT_SLEEPTMRCMPB |
INT_SLEEPTMRWRAP);
INT_GPIOFLAG = (INT_IRQAFLAG |
INT_IRQBFLAG |
INT_IRQCFLAG |
INT_IRQDFLAG);
//immediately restore the registers we saved before sleeping
//so IRQ and SleepTMR capture can be reenabled as quickly as possible
//this is safe because our global interrupts are still disabled
//other registers will be restored later
SLEEPTMR_CLKEN_REG = SLEEPTMR_CLKEN_SAVED;
INT_SLEEPTMRCFG_REG = INT_SLEEPTMRCFG_SAVED;
INT_MGMTCFG_REG = INT_MGMTCFG_SAVED;
GPIO_INTCFGA_REG = GPIO_INTCFGA_SAVED;
GPIO_INTCFGB_REG = GPIO_INTCFGB_SAVED;
GPIO_INTCFGC_REG = GPIO_INTCFGC_SAVED;
GPIO_INTCFGD_REG = GPIO_INTCFGD_SAVED;
OSC24M_BIASTRIM_REG = OSC24M_BIASTRIM_SAVED;
OSCHF_TUNE_REG = OSCHF_TUNE_SAVED;
DITHER_DIS_REG = DITHER_DIS_SAVED;
PCTRACE_SEL_REG = PCTRACE_SEL_SAVED;
MEM_PROT_0_REG = MEM_PROT_0_SAVED;
MEM_PROT_1_REG = MEM_PROT_1_SAVED;
MEM_PROT_2_REG = MEM_PROT_2_SAVED;
MEM_PROT_3_REG = MEM_PROT_3_SAVED;
MEM_PROT_4_REG = MEM_PROT_4_SAVED;
MEM_PROT_5_REG = MEM_PROT_5_SAVED;
MEM_PROT_6_REG = MEM_PROT_6_SAVED;
MEM_PROT_7_REG = MEM_PROT_7_SAVED;
MEM_PROT_EN_REG = MEM_PROT_EN_SAVED;
INT_CFGSET_REG = INT_CFGSET_SAVED;
SCS_VTOR_REG = SCS_VTOR_SAVED;
//WAKE_CORE/INT_DEBUG and INT_IRQx is cleared by INT_PENDCLR below
INT_PENDCLR = 0xFFFFFFFF;
//Now that we're awake, normal interrupts are operational again
//Take a snapshot of the new GPIO state and the EVENT register to
//record our wake event
int32u GPIO_IN_NEW = GPIO_PAIN;
GPIO_IN_NEW |= (GPIO_PBIN<<8);
GPIO_IN_NEW |= (GPIO_PCIN<<16);
//Only operate on power up events that are also wake events. Power
//up events will always trigger like an interrupt flag, so we have
//to check them against events that are enabled for waking. (This is
//a two step process because we're accessing two volatile values.)
int32u powerUpEvents = PWRUP_EVENT;
powerUpEvents &= WAKE_SEL;
halInternalWakeEvent |= ((GPIO_IN_SAVED^GPIO_IN_NEW)&gpioWakeSel);
//PWRUP_SC1 is PB2 which is bit 10
halInternalWakeEvent |= (!!(powerUpEvents&PWRUP_SC1))<<((1*8)+2);
//PWRUP_SC2 is PA2 which is bit 2
halInternalWakeEvent |= (!!(powerUpEvents&PWRUP_SC2))<<((0*8)+2);
//PWRUP_IRQD is chosen by GPIO_IRQDSEL
halInternalWakeEvent |= (!!(powerUpEvents&PWRUP_IRQD))<<(GPIO_IRQDSEL);
halInternalWakeEvent |= ((powerUpEvents &
(PWRUP_CSYSPWRUPREQ_MASK |
PWRUP_CDBGPWRUPREQ_MASK |
PWRUP_WAKECORE_MASK |
PWRUP_SLEEPTMRWRAP_MASK |
PWRUP_SLEEPTMRCOMPB_MASK |
PWRUP_SLEEPTMRCOMPA_MASK ))
<<INTERNAL_WAKE_EVENT_BIT_SHIFT);
//at this point wake events are fully captured and interrupts have
//taken over handling all new events
//Bring limited interrupts back online. INTERRUPTS_OFF will use
//BASEPRI to disable all interrupts except fault handlers and PendSV.
//PRIMASK is still set though (global interrupt disable) so we need
//to clear that next.
INTERRUPTS_OFF();
//Now that BASEPRI has taken control of interrupt enable/disable,
//we can clear PRIMASK to reenable global interrupt operation.
_clearPriMask();
//wake events are saved and interrupts are back on track,
//disable gpio freeze
EVENT_CTRL = EVENT_CTRL_RESET;
//restart watchdog if it was running when we entered sleep
//do this before dispatching interrupts while we still have tight
//control of code execution
if(restoreWatchdog) {
halInternalEnableWatchDog();
}
//Pend any interrupts associated with deep sleep wake sources. The
//restoration of INT_CFGSET above and the changing of BASEPRI below
//is responsible for proper dispatching of interrupts at the end of
//halSleepWithOptions.
//
//
//The WAKE_CORE wake source triggers a Debug Interrupt. If INT_DEBUG
//interrupt is enabled and WAKE_CORE is a wake event, then pend the
//Debug interrupt (using the wake_core bit).
if( (INT_CFGSET&INT_DEBUG) &&
(halInternalWakeEvent&BIT(WAKE_CORE_INTERNAL_WAKE_EVENT_BIT)) ) {
WAKE_CORE = WAKE_CORE_FIELD;
}
//
//
//The SleepTMR CMPA is linked to a real ISR. If the SleepTMR CMPA
//interrupt is enabled and CMPA is a wake event, then pend the CMPA
//interrupt (force the second level interrupt).
if( (INT_SLEEPTMRCFG&INT_SLEEPTMRCMPA) &&
(halInternalWakeEvent&BIT(CMPA_INTERNAL_WAKE_EVENT_BIT)) ) {
INT_SLEEPTMRFORCE = INT_SLEEPTMRCMPA;
}
//
//The SleepTMR CMPB is linked to a real ISR. If the SleepTMR CMPB
//interrupt is enabled and CMPB is a wake event, then pend the CMPB
//interrupt (force the second level interrupt).
if( (INT_SLEEPTMRCFG&INT_SLEEPTMRCMPB) &&
(halInternalWakeEvent&BIT(CMPB_INTERNAL_WAKE_EVENT_BIT)) ) {
INT_SLEEPTMRFORCE = INT_SLEEPTMRCMPB;
}
//
//The SleepTMR WRAP is linked to a real ISR. If the SleepTMR WRAP
//interrupt is enabled and WRAP is a wake event, then pend the WRAP
//interrupt (force the second level interrupt).
if( (INT_SLEEPTMRCFG&INT_SLEEPTMRWRAP) &&
(halInternalWakeEvent&BIT(WRAP_INTERNAL_WAKE_EVENT_BIT)) ) {
INT_SLEEPTMRFORCE = INT_SLEEPTMRWRAP;
}
//
//
//The four IRQs are linked to a real ISR. If any of the four IRQs
//triggered, then pend their ISR
//
//If the IRQA interrupt mode is enabled and IRQA (PB0) is wake
//event, then pend the interrupt.
if( ((GPIO_INTCFGA&GPIO_INTMOD)!=0) &&
(halInternalWakeEvent&BIT(PORTB_PIN(0))) ) {
INT_PENDSET = INT_IRQA;
}
//If the IRQB interrupt mode is enabled and IRQB (PB6) is wake
//event, then pend the interrupt.
if( ((GPIO_INTCFGB&GPIO_INTMOD)!=0) &&
(halInternalWakeEvent&BIT(PORTB_PIN(6))) ) {
INT_PENDSET = INT_IRQB;
}
//If the IRQC interrupt mode is enabled and IRQC (GPIO_IRQCSEL) is wake
//event, then pend the interrupt.
if( ((GPIO_INTCFGC&GPIO_INTMOD)!=0) &&
(halInternalWakeEvent&BIT(GPIO_IRQCSEL)) ) {
INT_PENDSET = INT_IRQC;
}
//If the IRQD interrupt mode is enabled and IRQD (GPIO_IRQDSEL) is wake
//event, then pend the interrupt.
if( ((GPIO_INTCFGD&GPIO_INTMOD)!=0) &&
(halInternalWakeEvent&BIT(GPIO_IRQDSEL)) ) {
INT_PENDSET = INT_IRQD;
}
}
//Mark the wake events valid just before exiting
halInternalWakeEvent |= BIT32(WAKEINFOVALID_INTERNAL_WAKE_EVENT_BIT);
//We are now reconfigured, appropriate ISRs are pended, and ready to go,
//so enable interrupts!
INTERRUPTS_ON();
break; //and deep sleeping is done!
case SLEEPMODE_IDLE:
//Only the CPU is idled. The rest of the chip continues runing
//normally. The chip will wake from any interrupt.
{
boolean restoreWatchdog = halInternalWatchDogEnabled();
//disable watchdog while sleeping (since we can't reset it asleep)
halInternalDisableWatchDog(MICRO_DISABLE_WATCH_DOG_KEY);
//Normal ATOMIC/INTERRUPTS_OFF/INTERRUPTS_ON uses the BASEPRI mask
//to juggle priority levels so that the fault handlers can always
//be serviced. But, the WFI instruction is only capable of
//working with the PRIMASK bit. Therefore, we have to switch from
//using BASEPRI to PRIMASK to keep interrupts disabled so that the
//WFI can return on an interrupt
//Globally disable interrupts with PRIMASK
_setPriMask();
//Bring the BASEPRI up to 0 to allow interrupts (but still disabled
//with PRIMASK)
INTERRUPTS_ON();
//an internal function call is made here instead of injecting the
//"WFI" assembly instruction because injecting assembly code will
//cause the compiler's optimizer to reduce efficiency.
halInternalIdleSleep();
//The WFI instruction does not actually clear the PRIMASK bit, it
//only allows the PRIMASK bit to be bypassed. Therefore, we must
//manually clear PRIMASK to reenable all interrupts.
_clearPriMask();
//restart watchdog if it was running when we entered sleep
if(restoreWatchdog)
halInternalEnableWatchDog();
}
break;
default:
//Oops! Invalid sleepMode parameter.
assert(0);
}
}
void halSleepWithOptions(SleepModes sleepMode, int32u gpioWakeBitMask)
{
//configure all GPIO wake sources
GPIO_PAWAKE = (gpioWakeBitMask>>0)&0xFF;
GPIO_PBWAKE = (gpioWakeBitMask>>8)&0xFF;
GPIO_PCWAKE = (gpioWakeBitMask>>16)&0xFF;
//use the defines found in the board file to choose our wakeup source(s)
WAKE_SEL = 0; //start with no wake sources
//if any of the GPIO wakeup monitor bits are set, enable the top level
//GPIO wakeup monitor
if((GPIO_PAWAKE)||(GPIO_PBWAKE)||(GPIO_PCWAKE)) {
WAKE_SEL |= GPIO_WAKE;
}
//always wakeup when the debugger is connected
WAKE_SEL |= WAKE_CDBGPWRUPREQ;
//always wakeup when the debugger attempts to access the chip
WAKE_SEL |= WAKE_CSYSPWRUPREQ;
//always wakeup when the debug channel attempts to access the chip
WAKE_SEL |= WAKE_WAKE_CORE;
//the timer wakeup sources are enabled below in POWERSAVE, if needed
//wake sources are configured so do the actual sleeping
halInternalSleep(sleepMode);
}

View file

@ -0,0 +1,35 @@
CC = arm-none-eabi-gcc
AR = arm-none-eabi-ar
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
AROPTS = cq
SOURCE_FILES = _SP_printf.c _SP_puts.c _SP_sprintf.c _SP_snprintf.c _SP_vfprintf.c
SOURCE_OBJS = ${patsubst %.c,%.o,$(SOURCE_FILES)}
LIB = smallprintf_thumb2.a
all: clean $(LIB)
clean:
rm -f $(LIB)
%.a: $(SOURCE_OBJS)
$(AR) $(AROPTS) $@ $^
%.o: %.c
$(CC) $(CFLAGS) -c $< -o $@

View file

@ -0,0 +1,78 @@
#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

@ -0,0 +1,34 @@
#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

@ -0,0 +1,124 @@
/*
* Copyright (c) 1990 The Regents of the University of California.
* All rights reserved.
*
* Redistribution and use in source and binary forms are permitted
* provided that the above copyright notice and this paragraph are
* duplicated in all such forms and that any documentation,
* advertising materials, and other materials related to such
* distribution and use acknowledge that the software was developed
* by the University of California, Berkeley. The name of the
* University may not be used to endorse or promote products derived
* from this software without specific prior written permission.
* THIS SOFTWARE IS PROVIDED ``AS IS'' AND WITHOUT ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, WITHOUT LIMITATION, THE IMPLIED
* 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. */
#include <stdio.h>
#ifdef _HAVE_STDC
#include <stdarg.h>
#else
#include <varargs.h>
#endif
#include <limits.h>
#include <errno.h>
#include <_ansi.h>
#ifndef _SMALL_PRINTF
#include "local.h"
#else
#ifdef INTEGER_ONLY
#define _vfprintf_r _vfiprintf_r
#endif
#endif
#ifndef _SMALL_PRINTF
int
#ifdef _HAVE_STDC
_DEFUN (_snprintf_r, (ptr, str, size, fmt), struct _reent *ptr _AND char *str _AND size_t size _AND _CONST char *fmt _DOTS)
#else
_snprintf_r (ptr, str, size, fmt, va_alist)
struct _reent *ptr;
char *str;
size_t size;
_CONST char *fmt;
va_dcl
#endif
{
int ret;
va_list ap;
FILE f;
if (size > INT_MAX)
{
ptr->_errno = EOVERFLOW;
return EOF;
}
f._flags = __SWR | __SSTR;
f._bf._base = f._p = (unsigned char *) str;
f._bf._size = f._w = (size > 0 ? size - 1 : 0);
f._file = -1; /* No file. */
#ifdef _HAVE_STDC
va_start (ap, fmt);
#else
va_start (ap);
#endif
ret = _vfprintf_r (ptr, &f, fmt, ap);
va_end (ap);
if (ret < EOF)
ptr->_errno = EOVERFLOW;
if (size > 0)
*f._p = 0;
return (ret);
}
#endif
#ifndef _REENT_ONLY
int
#ifdef _HAVE_STDC
_DEFUN (snprintf, (str, size, fmt), char *str _AND size_t size _AND _CONST char *fmt _DOTS)
#else
snprintf (str, size, fmt, va_alist)
char *str;
size_t size;
_CONST char *fmt;
va_dcl
#endif
{
int ret;
va_list ap;
FILE f;
struct _reent *ptr = _REENT;
if (size > INT_MAX)
{
ptr->_errno = EOVERFLOW;
return EOF;
}
f._flags = __SWR | __SSTR;
f._bf._base = f._p = (unsigned char *) str;
f._bf._size = f._w = (size > 0 ? size - 1 : 0);
f._file = -1; /* No file. */
#ifdef _HAVE_STDC
va_start (ap, fmt);
#else
va_start (ap);
#endif
ret = _vfprintf_r (ptr, &f, fmt, ap);
va_end (ap);
if (ret < EOF)
ptr->_errno = EOVERFLOW;
if (size > 0)
*f._p = 0;
return (ret);
}
#endif

View file

@ -0,0 +1,389 @@
/*
* Copyright (c) 1990 The Regents of the University of California.
* All rights reserved.
*
* Redistribution and use in source and binary forms are permitted
* provided that the above copyright notice and this paragraph are
* duplicated in all such forms and that any documentation,
* advertising materials, and other materials related to such
* distribution and use acknowledge that the software was developed
* by the University of California, Berkeley. The name of the
* University may not be used to endorse or promote products derived
* from this software without specific prior written permission.
* THIS SOFTWARE IS PROVIDED ``AS IS'' AND WITHOUT ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, WITHOUT LIMITATION, THE IMPLIED
* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
*/
/*
FUNCTION
<<printf>>, <<fprintf>>, <<asprintf>>, <<sprintf>>, <<snprintf>>---format output
INDEX
fprintf
INDEX
printf
INDEX
asprintf
INDEX
sprintf
INDEX
snprintf
ANSI_SYNOPSIS
#include <stdio.h>
int printf(const char *<[format]> [, <[arg]>, ...]);
int fprintf(FILE *<[fd]>, const char *<[format]> [, <[arg]>, ...]);
int sprintf(char *<[str]>, const char *<[format]> [, <[arg]>, ...]);
int asprintf(char **<[strp]>, const char *<[format]> [, <[arg]>, ...]);
int snprintf(char *<[str]>, size_t <[size]>, const char *<[format]> [, <[arg]>, ...]);
TRAD_SYNOPSIS
#include <stdio.h>
int printf(<[format]> [, <[arg]>, ...])
char *<[format]>;
int fprintf(<[fd]>, <[format]> [, <[arg]>, ...]);
FILE *<[fd]>;
char *<[format]>;
int asprintf(<[strp]>, <[format]> [, <[arg]>, ...]);
char **<[strp]>;
char *<[format]>;
int sprintf(<[str]>, <[format]> [, <[arg]>, ...]);
char *<[str]>;
char *<[format]>;
int snprintf(<[str]>, size_t <[size]>, <[format]> [, <[arg]>, ...]);
char *<[str]>;
size_t <[size]>;
char *<[format]>;
DESCRIPTION
<<printf>> accepts a series of arguments, applies to each a
format specifier from <<*<[format]>>>, and writes the
formatted data to <<stdout>>, terminated with a null character.
The behavior of <<printf>> is undefined if there are not enough
arguments for the format.
<<printf>> returns when it reaches the end of the format string.
If there are more arguments than the format requires, excess
arguments are ignored.
<<fprintf>>, <<asprintf>>, <<sprintf>> and <<snprintf>> are identical
to <<printf>>, other than the destination of the formatted output:
<<fprintf>> sends the output to a specified file <[fd]>, while
<<asprintf>> stores the output in a dynamically allocated buffer,
while <<sprintf>> stores the output in the specified char array
<[str]> and <<snprintf>> limits number of characters written to
<[str]> to at most <[size]> (including terminating <<0>>). For
<<sprintf>> and <<snprintf>>, the behavior is undefined if the
output <<*<[str]>>> overlaps with one of the arguments. For
<<asprintf>>, <[strp]> points to a pointer to char which is filled
in with the dynamically allocated buffer. <[format]> is a pointer
to a charater string containing two types of objects: ordinary
characters (other than <<%>>), which are copied unchanged to the
output, and conversion specifications, each of which is introduced
by <<%>>. (To include <<%>> in the output, use <<%%>> in the format
string.) A conversion specification has the following form:
. %[<[flags]>][<[width]>][.<[prec]>][<[size]>][<[type]>]
The fields of the conversion specification have the following meanings:
O+
o <[flags]>
an optional sequence of characters which control
output justification, numeric signs, decimal points,
trailing zeroes, and octal and hex prefixes.
The flag characters are minus (<<->>), plus (<<+>>),
space ( ), zero (<<0>>), and sharp (<<#>>). They can
appear in any combination.
o+
o -
The result of the conversion is left justified, and the right is
padded with blanks. If you do not use this flag, the result is right
justified, and padded on the left.
o +
The result of a signed conversion (as determined by <[type]>)
will always begin with a plus or minus sign. (If you do not use
this flag, positive values do not begin with a plus sign.)
o " " (space)
If the first character of a signed conversion specification
is not a sign, or if a signed conversion results in no
characters, the result will begin with a space. If the
space ( ) flag and the plus (<<+>>) flag both appear,
the space flag is ignored.
o 0
If the <[type]> character is <<d>>, <<i>>, <<o>>, <<u>>,
<<x>>, <<X>>, <<e>>, <<E>>, <<f>>, <<g>>, or <<G>>: leading zeroes,
are used to pad the field width (following any indication of sign or
base); no spaces are used for padding. If the zero (<<0>>) and
minus (<<->>) flags both appear, the zero (<<0>>) flag will
be ignored. For <<d>>, <<i>>, <<o>>, <<u>>, <<x>>, and <<X>>
conversions, if a precision <[prec]> is specified, the zero (<<0>>)
flag is ignored.
Note that <<0>> is interpreted as a flag, not as the beginning
of a field width.
o #
The result is to be converted to an alternative form, according
to the next character:
o+
o 0
increases precision to force the first digit
of the result to be a zero.
o x
a non-zero result will have a <<0x>> prefix.
o X
a non-zero result will have a <<0X>> prefix.
o e, E or f
The result will always contain a decimal point
even if no digits follow the point.
(Normally, a decimal point appears only if a
digit follows it.) Trailing zeroes are removed.
o g or G
same as <<e>> or <<E>>, but trailing zeroes
are not removed.
o all others
undefined.
o-
o-
o <[width]>
<[width]> is an optional minimum field width. You can either
specify it directly as a decimal integer, or indirectly by
using instead an asterisk (<<*>>), in which case an <<int>>
argument is used as the field width. Negative field widths
are not supported; if you attempt to specify a negative field
width, it is interpreted as a minus (<<->>) flag followed by a
positive field width.
o <[prec]>
an optional field; if present, it is introduced with `<<.>>'
(a period). This field gives the maximum number of
characters to print in a conversion; the minimum number of
digits of an integer to print, for conversions with <[type]>
<<d>>, <<i>>, <<o>>, <<u>>, <<x>>, and <<X>>; the maximum number of
significant digits, for the <<g>> and <<G>> conversions;
or the number of digits to print after the decimal
point, for <<e>>, <<E>>, and <<f>> conversions. You can specify
the precision either directly as a decimal integer or
indirectly by using an asterisk (<<*>>), in which case
an <<int>> argument is used as the precision. Supplying a negative
precision is equivalent to omitting the precision.
If only a period is specified the precision is zero.
If a precision appears with any other conversion <[type]>
than those listed here, the behavior is undefined.
o <[size]>
<<h>>, <<l>>, and <<L>> are optional size characters which
override the default way that <<printf>> interprets the
data type of the corresponding argument. <<h>> forces
the following <<d>>, <<i>>, <<o>>, <<u>>, <<x>> or <<X>> conversion
<[type]> to apply to a <<short>> or <<unsigned short>>. <<h>> also
forces a following <<n>> <[type]> to apply to
a pointer to a <<short>>. Similarily, an
<<l>> forces the following <<d>>, <<i>>, <<o>>, <<u>>,
<<x>> or <<X>> conversion <[type]> to apply to a <<long>> or
<<unsigned long>>. <<l>> also forces a following <<n>> <[type]> to
apply to a pointer to a <<long>>. <<l>> with <<c>>, <<s>> is
equivalent to <<C>>, <<S>> respectively. If an <<h>>
or an <<l>> appears with another conversion
specifier, the behavior is undefined. <<L>> forces a
following <<e>>, <<E>>, <<f>>, <<g>> or <<G>> conversion <[type]> to
apply to a <<long double>> argument. If <<L>> appears with
any other conversion <[type]>, the behavior is undefined.
o <[type]>
<[type]> specifies what kind of conversion <<printf>> performs.
Here is a table of these:
o+
o %
prints the percent character (<<%>>)
o c
prints <[arg]> as single character
o C
prints wchar_t <[arg]> as single multibyte character
o s
prints characters until precision is reached or a null terminator
is encountered; takes a string pointer
o S
converts wchar_t characters to multibyte output characters until
precision is reached or a null wchar_t terminator
is encountered; takes a wchar_t pointer
o d
prints a signed decimal integer; takes an <<int>> (same as <<i>>)
o i
prints a signed decimal integer; takes an <<int>> (same as <<d>>)
o o
prints a signed octal integer; takes an <<int>>
o u
prints an unsigned decimal integer; takes an <<int>>
o x
prints an unsigned hexadecimal integer (using <<abcdef>> as
digits beyond <<9>>); takes an <<int>>
o X
prints an unsigned hexadecimal integer (using <<ABCDEF>> as
digits beyond <<9>>); takes an <<int>>
o f
prints a signed value of the form <<[-]9999.9999>>; takes
a floating-point number
o e
prints a signed value of the form <<[-]9.9999e[+|-]999>>; takes a
floating-point number
o E
prints the same way as <<e>>, but using <<E>> to introduce the
exponent; takes a floating-point number
o g
prints a signed value in either <<f>> or <<e>> form, based on given
value and precision---trailing zeros and the decimal point are
printed only if necessary; takes a floating-point number
o G
prints the same way as <<g>>, but using <<E>> for the exponent if an
exponent is needed; takes a floating-point number
o n
stores (in the same object) a count of the characters written;
takes a pointer to <<int>>
o p
prints a pointer in an implementation-defined format.
This implementation treats the pointer as an
<<unsigned long>> (same as <<Lu>>).
o-
O-
RETURNS
<<sprintf>> and <<asprintf>> return the number of bytes in the output string,
save that the concluding <<NULL>> is not counted.
<<printf>> and <<fprintf>> return the number of characters transmitted.
If an error occurs, <<printf>> and <<fprintf>> return <<EOF>> and
<<asprintf>> returns -1. No error returns occur for <<sprintf>>.
PORTABILITY
The ANSI C standard specifies that implementations must
support at least formatted output of up to 509 characters.
Supporting OS subroutines required: <<close>>, <<fstat>>, <<isatty>>,
<<lseek>>, <<read>>, <<sbrk>>, <<write>>.
*/
#include <stdio.h>
#ifdef _HAVE_STDC
#include <stdarg.h>
#else
#include <varargs.h>
#endif
#include <limits.h>
#include <_ansi.h>
#ifndef _SMALL_PRINTF
#include "local.h"
#else
#ifdef INTEGER_ONLY
#define _vfprintf_r _vfiprintf_r
#endif
#endif
#ifndef _SMALL_PRINTF
int
#ifdef _HAVE_STDC
_DEFUN (_sprintf_r, (ptr, str, fmt), struct _reent *ptr _AND char *str _AND _CONST char *fmt _DOTS)
#else
_sprintf_r (ptr, str, fmt, va_alist)
struct _reent *ptr;
char *str;
_CONST char *fmt;
va_dcl
#endif
{
int ret;
va_list ap;
FILE f;
f._flags = __SWR | __SSTR;
f._bf._base = f._p = (unsigned char *) str;
f._bf._size = f._w = INT_MAX;
f._file = -1; /* No file. */
#ifdef _HAVE_STDC
va_start (ap, fmt);
#else
va_start (ap);
#endif
ret = _vfprintf_r (ptr, &f, fmt, ap);
va_end (ap);
*f._p = 0;
return (ret);
}
#endif
#ifndef _REENT_ONLY
int
#ifdef _HAVE_STDC
_DEFUN (sprintf, (str, fmt), char *str _AND _CONST char *fmt _DOTS)
#else
sprintf (str, fmt, va_alist)
char *str;
_CONST char *fmt;
va_dcl
#endif
{
int ret;
va_list ap;
FILE f;
f._flags = __SWR | __SSTR;
f._bf._base = f._p = (unsigned char *) str;
f._bf._size = f._w = INT_MAX;
f._file = -1; /* No file. */
#ifdef _HAVE_STDC
va_start (ap, fmt);
#else
va_start (ap);
#endif
ret = _vfprintf_r (_REENT, &f, fmt, ap);
va_end (ap);
*f._p = 0;
return (ret);
}
#endif

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,284 @@
/****************************************************************
*
* The author of this software is David M. Gay.
*
* Copyright (c) 1991 by AT&T.
*
* Permission to use, copy, modify, and distribute this software for any
* purpose without fee is hereby granted, provided that this entire notice
* is included in all copies of any software which is or includes a copy
* or modification of this software and in all copies of the supporting
* documentation for such software.
*
* THIS SOFTWARE IS BEING PROVIDED "AS IS", WITHOUT ANY EXPRESS OR IMPLIED
* WARRANTY. IN PARTICULAR, NEITHER THE AUTHOR NOR AT&T MAKES ANY
* REPRESENTATION OR WARRANTY OF ANY KIND CONCERNING THE MERCHANTABILITY
* OF THIS SOFTWARE OR ITS FITNESS FOR ANY PARTICULAR PURPOSE.
*
***************************************************************/
/* Please send bug reports to
David M. Gay
AT&T Bell Laboratories, Room 2C-463
600 Mountain Avenue
Murray Hill, NJ 07974-2070
U.S.A.
dmg@research.att.com or research!dmg
*/
/* This header file is a modification of mprec.h that only contains floating
point union code. */
#include <ieeefp.h>
#include <math.h>
#include <float.h>
#include <errno.h>
#include <sys/config.h>
#ifdef __IEEE_LITTLE_ENDIAN
#define IEEE_8087
#endif
#ifdef __IEEE_BIG_ENDIAN
#define IEEE_MC68k
#endif
#ifdef __Z8000__
#define Just_16
#endif
#ifdef Unsigned_Shifts
#define Sign_Extend(a,b) if (b < 0) a |= (__uint32_t)0xffff0000;
#else
#define Sign_Extend(a,b) /*no-op*/
#endif
#if defined(IEEE_8087) + defined(IEEE_MC68k) + defined(VAX) + defined(IBM) != 1
Exactly one of IEEE_8087, IEEE_MC68k, VAX, or IBM should be defined.
#endif
#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
a union. This is necessary to avoid undefined behavior according to
the ANSI C spec. */
#ifdef IEEE_8087
#if LDBL_MANT_DIG == 24
struct ldieee
{
unsigned manh:23;
unsigned exp:8;
unsigned sign:1;
};
#elif LDBL_MANT_DIG == 53
struct ldieee
{
unsigned manl:20;
unsigned manh:32;
unsigned exp:11;
unsigned sign:1;
};
#elif LDBL_MANT_DIG == 64
struct ldieee
{
unsigned manl:32;
unsigned manh:32;
unsigned exp:15;
unsigned sign:1;
};
#elif LDBL_MANT_DIG > 64
struct ldieee
{
unsigned manl3:16;
unsigned manl2:32;
unsigned manl:32;
unsigned manh:32;
unsigned exp:15;
unsigned sign:1;
};
#endif /* LDBL_MANT_DIG */
#else /* !IEEE_8087 */
#if LDBL_MANT_DIG == 24
struct ldieee
{
unsigned sign:1;
unsigned exp:8;
unsigned manh:23;
};
#elif LDBL_MANT_DIG == 53
struct ldieee
{
unsigned sign:1;
unsigned exp:11;
unsigned manh:32;
unsigned manl:20;
};
#elif LDBL_MANT_DIG == 64
struct ldieee
{
unsigned sign:1;
unsigned exp:15;
unsigned manh:32;
unsigned manl:32;
};
#elif LDBL_MANT_DIG > 64
struct ldieee
{
unsigned sign:1;
unsigned exp:15;
unsigned manh:32;
unsigned manl:32;
unsigned manl2:32;
unsigned manl3;16;
};
#endif /* LDBL_MANT_DIG */
#endif /* !IEEE_8087 */
#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
a union. This is necessary to avoid undefined behavior according to
the ANSI C spec. */
union double_union
{
double d;
__uint32_t i[2];
};
#ifdef IEEE_8087
#define word0(x) (x.i[1])
#define word1(x) (x.i[0])
#else
#define word0(x) (x.i[0])
#define word1(x) (x.i[1])
#endif
/* #define P DBL_MANT_DIG */
/* Ten_pmax = floor(P*log(2)/log(5)) */
/* Bletch = (highest power of 2 < DBL_MAX_10_EXP) / 16 */
/* Quick_max = floor((P-1)*log(FLT_RADIX)/log(10) - 1) */
/* Int_max = floor(P*log(FLT_RADIX)/log(10) - 1) */
#if defined(IEEE_8087) + defined(IEEE_MC68k)
#if defined (_DOUBLE_IS_32BITS)
#define Exp_shift 23
#define Exp_shift1 23
#define Exp_msk1 ((__uint32_t)0x00800000L)
#define Exp_msk11 ((__uint32_t)0x00800000L)
#define Exp_mask ((__uint32_t)0x7f800000L)
#define P 24
#define Bias 127
#if 0
#define IEEE_Arith /* it is, but the code doesn't handle IEEE singles yet */
#endif
#define Emin (-126)
#define Exp_1 ((__uint32_t)0x3f800000L)
#define Exp_11 ((__uint32_t)0x3f800000L)
#define Ebits 8
#define Frac_mask ((__uint32_t)0x007fffffL)
#define Frac_mask1 ((__uint32_t)0x007fffffL)
#define Ten_pmax 10
#define Sign_bit ((__uint32_t)0x80000000L)
#define Ten_pmax 10
#define Bletch 2
#define Bndry_mask ((__uint32_t)0x007fffffL)
#define Bndry_mask1 ((__uint32_t)0x007fffffL)
#define LSB 1
#define Sign_bit ((__uint32_t)0x80000000L)
#define Log2P 1
#define Tiny0 0
#define Tiny1 1
#define Quick_max 5
#define Int_max 6
#define Infinite(x) (word0(x) == ((__uint32_t)0x7f800000L))
#undef word0
#undef word1
#define word0(x) (x.i[0])
#define word1(x) 0
#else
#define Exp_shift 20
#define Exp_shift1 20
#define Exp_msk1 ((__uint32_t)0x100000L)
#define Exp_msk11 ((__uint32_t)0x100000L)
#define Exp_mask ((__uint32_t)0x7ff00000L)
#define P 53
#define Bias 1023
#define IEEE_Arith
#define Emin (-1022)
#define Exp_1 ((__uint32_t)0x3ff00000L)
#define Exp_11 ((__uint32_t)0x3ff00000L)
#define Ebits 11
#define Frac_mask ((__uint32_t)0xfffffL)
#define Frac_mask1 ((__uint32_t)0xfffffL)
#define Ten_pmax 22
#define Bletch 0x10
#define Bndry_mask ((__uint32_t)0xfffffL)
#define Bndry_mask1 ((__uint32_t)0xfffffL)
#define LSB 1
#define Sign_bit ((__uint32_t)0x80000000L)
#define Log2P 1
#define Tiny0 0
#define Tiny1 1
#define Quick_max 14
#define Int_max 14
#define Infinite(x) (word0(x) == ((__uint32_t)0x7ff00000L)) /* sufficient test for here */
#endif
#else
#undef Sudden_Underflow
#define Sudden_Underflow
#ifdef IBM
#define Exp_shift 24
#define Exp_shift1 24
#define Exp_msk1 ((__uint32_t)0x1000000L)
#define Exp_msk11 ((__uint32_t)0x1000000L)
#define Exp_mask ((__uint32_t)0x7f000000L)
#define P 14
#define Bias 65
#define Exp_1 ((__uint32_t)0x41000000L)
#define Exp_11 ((__uint32_t)0x41000000L)
#define Ebits 8 /* exponent has 7 bits, but 8 is the right value in b2d */
#define Frac_mask ((__uint32_t)0xffffffL)
#define Frac_mask1 ((__uint32_t)0xffffffL)
#define Bletch 4
#define Ten_pmax 22
#define Bndry_mask ((__uint32_t)0xefffffL)
#define Bndry_mask1 ((__uint32_t)0xffffffL)
#define LSB 1
#define Sign_bit ((__uint32_t)0x80000000L)
#define Log2P 4
#define Tiny0 ((__uint32_t)0x100000L)
#define Tiny1 0
#define Quick_max 14
#define Int_max 15
#else /* VAX */
#define Exp_shift 23
#define Exp_shift1 7
#define Exp_msk1 0x80
#define Exp_msk11 ((__uint32_t)0x800000L)
#define Exp_mask ((__uint32_t)0x7f80L)
#define P 56
#define Bias 129
#define Exp_1 ((__uint32_t)0x40800000L)
#define Exp_11 ((__uint32_t)0x4080L)
#define Ebits 8
#define Frac_mask ((__uint32_t)0x7fffffL)
#define Frac_mask1 ((__uint32_t)0xffff007fL)
#define Ten_pmax 24
#define Bletch 2
#define Bndry_mask ((__uint32_t)0xffff007fL)
#define Bndry_mask1 ((__uint32_t)0xffff007fL)
#define LSB ((__uint32_t)0x10000L)
#define Sign_bit ((__uint32_t)0x8000L)
#define Log2P 1
#define Tiny0 0x80
#define Tiny1 0
#define Quick_max 15
#define Int_max 15
#endif
#endif

View file

@ -0,0 +1,181 @@
//------------------------------------------------------------------------------
// @file hal/micro/cortexm3/spmr.s79
// @brief SPMR (Special Purpose Mask Registers) manipulation routines.
//
// Since the compiler does not provide low level intrinsic functions for some
// required operations, this file maintains the small set of assembly code
// needed to manipulate the Special Purpose Mask Registers.
//
// While it is possible to add this functionality as inline assembly in C files,
// IAR highly recommends against this due to not only code being fragile in its
// surroundings, but it also negates the possibility of size optimization.
//
// NOTE: This file looks more complicated than it really is. It was originally
// generated by writing a C file and having the compiler generate the
// corresponding assembly file. This is where all the CFI (Call Frame
// Information) expressions came from. The CFI information enables proper debug
// backtrace ability. The pieces to pay attention to are the actual funtions
// near the end.
//
// * <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
//------------------------------------------------------------------------------
#include "compiler/asm.h"
// NOTE!! IF THIS VALUE IS CHANGED, NVIC-CONFIG.H MUST ALSO BE UPDATED
#define INTERRUPTS_DISABLED_PRIORITY (12 << 3)
__EXPORT__ _readBasePri
__EXPORT__ _writeBasePri
__EXPORT__ _disableBasePri
__EXPORT__ _basePriIsDisabled
__EXPORT__ _enableBasePri
__EXPORT__ _setPriMask
__EXPORT__ _clearPriMask
__EXPORT__ _executeBarrierInstructions
//------------------------------------------------------------------------------
// int8u _readBasePri(void)
//
// Read and return the BASEPRI value.
//
//------------------------------------------------------------------------------
__CODE__
__THUMB__
__CFI__(Block cfiBlock0 Using cfiCommon0)
__CFI__(Function _readBasePri)
_readBasePri:
MRS R0, BASEPRI // read current BASEPRI
BX LR
__CFI__(EndBlock cfiBlock0)
//------------------------------------------------------------------------------
// void _writeBasePri(int8u 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
// to be properly aligned in the BASEPRI register.
// (Refer to nvic-config.h for the PRIGROUP table.)
//
//------------------------------------------------------------------------------
__CODE__
__THUMB__
__CFI__(Block cfiBlock1 Using cfiCommon0)
__CFI__(Function _writeBasePri)
_writeBasePri:
MSR BASEPRI, R0 // load BASEPRI from variable (R0)
BX LR
__CFI__(EndBlock cfiBlock1)
//------------------------------------------------------------------------------
// int8u _disableBasePri(void)
//
// Set BASEPRI to mask out interrupts but allow faults. It returns the value
// BASEPRI had when it was called.
//
//------------------------------------------------------------------------------
__CODE__
__THUMB__
__CFI__(Block cfiBlock2 Using cfiCommon0)
__CFI__(Function _disableBasePri)
_disableBasePri:
MRS R0, BASEPRI // read current BASEPRI
LDR R1, =INTERRUPTS_DISABLED_PRIORITY // disable ints, allow faults
MSR BASEPRI, R1
BX LR
__CFI__(EndBlock cfiBlock2)
//------------------------------------------------------------------------------
// boolean _basePriIsDisabled(void)
//
// Compare BASEPRI to the priority used to disable interrupts (but not faults).
// Return TRUE if the priority is higher or equal to that.
//
//------------------------------------------------------------------------------
__CODE__
__THUMB__
__CFI__(Block cfiBlock3 Using cfiCommon0)
__CFI__(Function _basePriIsDisabled)
_basePriIsDisabled:
MRS R0, BASEPRI // read current BASEPRI
CMP R0, #INTERRUPTS_DISABLED_PRIORITY
ITE le
LDRLE R0, =1
LDRGT R0, =0
BX LR
__CFI__(EndBlock cfiBlock3)
//------------------------------------------------------------------------------
// void _enableBasePri(void)
//
// Set BASEPRI to 0, which disables it from masking any interrupts.
//
//------------------------------------------------------------------------------
__CODE__
__THUMB__
__CFI__(Block cfiBlock4 Using cfiCommon0)
__CFI__(Function _enableBasePri)
_enableBasePri:
LDR R1, = 0 // zero disables BASEPRI masking
MSR BASEPRI, R1
BX LR
__CFI__(EndBlock cfiBlock4)
//------------------------------------------------------------------------------
// void _setPriMask(void)
//
// Set the 1-bit PRIMASK register, which sets the base priority to 0. This
// locks out all interrupts and configurable faults (usage, memory management
// and bus faults).
//
// Note: generally speaking PRIMASK should not be set because faults should
// be enabled even when interrupts are disabled. If they are not enabled,
// a fault will immediately escalate to a hard fault.
//
//------------------------------------------------------------------------------
__CODE__
__THUMB__
__CFI__(Block cfiBlock5 Using cfiCommon0)
__CFI__(Function _setPriMask)
_setPriMask:
CPSID i
BX LR
__CFI__(EndBlock cfiBlock5)
//------------------------------------------------------------------------------
// void _clearPriMask(void)
//
// Clears the 1-bit PRIMASK register, which allows the BASEPRI value to
// mask interrupts (if non-zero).
//
//------------------------------------------------------------------------------
__CODE__
__THUMB__
__CFI__(Block cfiBlock6 Using cfiCommon0)
__CFI__(Function _clearPriMask)
_clearPriMask:
CPSIE i
BX LR
__CFI__(EndBlock cfiBlock6)
//------------------------------------------------------------------------------
// void _executeBarrierInstructions(void)
//
//A utility function for inserting barrier instructions. These
//instructions should be used whenever the MPU is enabled or disabled so
//that all memory/instruction accesses can complete before the MPU changes
//state.
//
//------------------------------------------------------------------------------
__CODE__
__THUMB__
__CFI__(Block cfiBlock7 Using cfiCommon0)
__CFI__(Function _executeBarrierInstructions)
_executeBarrierInstructions:
DMB
DSB
ISB
BX LR
__CFI__(EndBlock cfiBlock7)
__END__

View file

@ -0,0 +1,33 @@
/** @file board.h
* @brief Header file x STM32W108 Kits boards
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
#ifndef _BOARD_H_
#define _BOARD_H_
#ifdef BOARD_MB851
/* leds definitions */
#define LED_D1 PORTB_PIN(6)
#define LED_D3 PORTB_PIN(5)
/** Description buttons definition */
#define BUTTON_S1 PORTA_PIN(7)
#define BUTTON_S1_INPUT_GPIO GPIO_PAIN
#define BUTTON_S1_OUTPUT_GPIO GPIO_PAOUT
#define BUTTON_S1_GPIO_PIN PA7_BIT
#define BUTTON_S1_WAKE_SOURCE 0x00000080
/** Description uart definition */
#define UART_TX PORTB_PIN(1)
#define UART_RX PORTB_PIN(2)
#define UART_RX_WAKE_SOURCE 0x00000400
/** Description temperature sensor GPIO */
#define TEMPERATURE_SENSOR_GPIO PORTB_PIN(7)
#endif /* BOARD_MB851 */
#endif /* _BOARD_H_ */

View file

@ -0,0 +1,362 @@
/******************** (C) COPYRIGHT 2007 STMicroelectronics ********************
* File Name : stm32f10x_vector.c
* Author : MCD Tools Team
* Date First Issued : 05/14/2007
* Description : This file contains the vector table for STM32F10x.
* After Reset the Cortex-M3 processor is in Thread mode,
* priority is Privileged, and the Stack is set to Main.
********************************************************************************
* History:
* 05/14/2007: V0.2
*
********************************************************************************
* THE PRESENT SOFTWARE 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 SOFTWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
#include <stdio.h>
#include <sys/stat.h>
#define RESERVED 0
//#define DUMMY_MALLOC
/* Includes ----------------------------------------------------------------------*/
#include PLATFORM_HEADER
void NMI_Handler(void);
void HardFault_Handler(void);
void MemManage_Handler(void);
void BusFault_Handler(void);
void UsageFault_Handler(void);
void SVC_Handler(void);
void DebugMonitor_Handler(void);
void PendSV_Handler(void);
void SysTick_Handler(void);
void halTimer1Isr(void);
void halTimer2Isr(void);
void halManagementIsr(void);
void halBaseBandIsr(void);
void halSleepTimerIsr(void);
void halSc1Isr(void);
void halSc2Isr(void);
void halSecurityIsr(void);
void halStackMacTimerIsr(void);
void stmRadioTransmitIsr(void);
void stmRadioReceiveIsr(void);
void halAdcIsr(void);
void halIrqAIsr(void);
void halIrqBIsr(void);
void halIrqCIsr(void);
void halIrqDIsr(void);
void halDebugIsr(void);
/* Exported types --------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
extern unsigned long _etext;
extern unsigned long _sidata; /* start address for the initialization values of the .data section. defined in linker script */
extern unsigned long _sdata; /* start address for the .data section. defined in linker script */
extern unsigned long _edata; /* end address for the .data section. defined in linker script */
extern unsigned long _sbss; /* start address for the .bss section. defined in linker script */
extern unsigned long _ebss; /* end address for the .bss section. defined in linker script */
extern void _estack; /* init value for the stack pointer. defined in linker script */
#include "hal/micro/cortexm3/memmap.h"
VAR_AT_SEGMENT(const HalFixedAddressTableType halFixedAddressTable, __FAT__);
/* Private typedef -----------------------------------------------------------*/
/* function prototypes ------------------------------------------------------*/
void Reset_Handler(void) __attribute__((__interrupt__));
extern int main(void);
/******************************************************************************
*
* The minimal vector table for a Cortex M3. Note that the proper constructs
* must be placed on this to ensure that it ends up at physical address
* 0x0000.0000.
*
******************************************************************************/
__attribute__ ((section(".isr_vector")))
void (* const g_pfnVectors[])(void) =
{
&_estack, // The initial stack pointer
Reset_Handler, // 1 The reset handler
NMI_Handler, // 2
HardFault_Handler, // 3
MemManage_Handler, // 4
BusFault_Handler, // 5
UsageFault_Handler, // 6
RESERVED, // 7
RESERVED, // 8
RESERVED, // 9
RESERVED, // 10
SVC_Handler, // 11
DebugMonitor_Handler, // 12
RESERVED, // 13
PendSV_Handler, // 14
SysTick_Handler, // 15
halTimer1Isr, // 16
halTimer2Isr, // 17
halManagementIsr, // 18
halBaseBandIsr, // 19
halSleepTimerIsr, // 20
halSc1Isr, // 21
halSc2Isr, // 22
halSecurityIsr, // 23
halStackMacTimerIsr, // 24
stmRadioTransmitIsr, // 25
stmRadioReceiveIsr, // 26
halAdcIsr, // 27
halIrqAIsr, // 28
halIrqBIsr, // 29
halIrqCIsr, // 30
halIrqDIsr, // 31
halDebugIsr, // 32
};
/*******************************************************************************
* Function Name : Reset_Handler
* Description : This is the code that gets called when the processor first starts execution
* following a reset event. Only the absolutely necessary set is performed,
* after which the application supplied main() routine is called.
* Input :
* Output :
* Return :
*******************************************************************************/
void Reset_Handler(void)
{
//Ensure there is enough margin on VREG_1V8 for stable RAM reads by
//setting it to a code of 6. VREG_1V2 can be left at its reset value.
VREG = 0x00000307;
// This code should be careful about the use of local variables in case the
// reset type happens to be a deep sleep reset. If the reset is not from
// deep sleep, then locals can be freely used
//When the Cortex-M3 exits reset, interrupts are enable. Explicitely
//disable them immediately using the standard set PRIMASK instruction.
//Injecting an assembly instruction this early does not effect optimization.
asm("CPSID i");
//It is quite possible that when the Cortex-M3 begins executing code the
//Core Reset Vector Catch is still left enabled. Because this VC would
//cause us to halt at reset if another reset event tripped, we should
//clear it as soon as possible. If a debugger wants to halt at reset,
//it will set this bit again.
DEBUG_EMCR &= ~DEBUG_EMCR_VC_CORERESET;
//Configure flash access for optimal current consumption early
//during boot to save as much current as we can.
FLASH_ACCESS = (FLASH_ACCESS_PREFETCH_EN |
(1<<FLASH_ACCESS_CODE_LATENCY_BIT));
////---- Always Configure Interrupt Priorities ----////
//The STM32W support 5 bits of priority configuration.
// The cortex allows this to be further divided into preemption and a
// "tie-breaker" sub-priority.
//We configure a scheme that allows for 3 bits (8 values) of preemption and
// 2 bits (4 values) of tie-breaker by using the value 4 in PRIGROUP.
//The value 0x05FA0000 is a special key required to write to this register.
SCS_AIRCR = (0x05FA0000 | (4 <<SCS_AIRCR_PRIGROUP_BIT));
//A few macros to help with interrupt priority configuration. Really only
// uses 6 of the possible levels, and ignores the tie-breaker sub-priority
// for now.
//Don't forget that the priority level values need to be shifted into the
// top 5 bits of the 8 bit priority fields. (hence the <<3)
//
// NOTE: The ATOMIC and DISABLE_INTERRUPTS macros work by setting the
// current priority to a value of 12, which still allows CRITICAL and
// HIGH priority interrupts to fire, while blocking MED and LOW.
// If a different value is desired, spmr.s79 will need to be edited.
#define CRITICAL (0 <<3)
#define HIGH (8 <<3)
#define MED (16 <<3)
#define LOW (28 <<3)
#define NONE (31 <<3)
//With optimization turned on, the compiler will indentify all the values
//and variables used here as constants at compile time and will truncate
//this entire block of code to 98 bytes, comprised of 7 load-load-store
//operations.
//vect00 is fixed //Stack pointer
//vect01 is fixed //Reset Vector
//vect02 is fixed //NMI Handler
//vect03 is fixed //Hard Fault Handler
SCS_SHPR_7to4 = ((CRITICAL <<SCS_SHPR_7to4_PRI_4_BIT) | //Memory Fault Handler
(CRITICAL <<SCS_SHPR_7to4_PRI_5_BIT) | //Bus Fault Handler
(CRITICAL <<SCS_SHPR_7to4_PRI_6_BIT) | //Usage Fault Handler
(NONE <<SCS_SHPR_7to4_PRI_7_BIT)); //Reserved
SCS_SHPR_11to8 = ((NONE <<SCS_SHPR_11to8_PRI_8_BIT) | //Reserved
(NONE <<SCS_SHPR_11to8_PRI_9_BIT) | //Reserved
(NONE <<SCS_SHPR_11to8_PRI_10_BIT) | //Reserved
(HIGH <<SCS_SHPR_11to8_PRI_11_BIT)); //SVCall Handler
SCS_SHPR_15to12 = ((MED <<SCS_SHPR_15to12_PRI_12_BIT) | //Debug Monitor Handler
(NONE <<SCS_SHPR_15to12_PRI_13_BIT) | //Reserved
(HIGH <<SCS_SHPR_15to12_PRI_14_BIT) | //PendSV Handler
(MED <<SCS_SHPR_15to12_PRI_15_BIT)); //SysTick Handler
NVIC_IPR_3to0 = ((MED <<NVIC_IPR_3to0_PRI_0_BIT) | //Timer 1 Handler
(MED <<NVIC_IPR_3to0_PRI_1_BIT) | //Timer 2 Handler
(HIGH <<NVIC_IPR_3to0_PRI_2_BIT) | //Management Handler
(MED <<NVIC_IPR_3to0_PRI_3_BIT)); //BaseBand Handler
NVIC_IPR_7to4 = ((MED <<NVIC_IPR_7to4_PRI_4_BIT) | //Sleep Timer Handler
(MED <<NVIC_IPR_7to4_PRI_5_BIT) | //SC1 Handler
(MED <<NVIC_IPR_7to4_PRI_6_BIT) | //SC2 Handler
(MED <<NVIC_IPR_7to4_PRI_7_BIT)); //Security Handler
NVIC_IPR_11to8 = ((MED <<NVIC_IPR_11to8_PRI_8_BIT) | //MAC Timer Handler
(MED <<NVIC_IPR_11to8_PRI_9_BIT) | //MAC TX Handler
(MED <<NVIC_IPR_11to8_PRI_10_BIT) | //MAC RX Handler
(MED <<NVIC_IPR_11to8_PRI_11_BIT)); //ADC Handler
NVIC_IPR_15to12 = ((MED <<NVIC_IPR_15to12_PRI_12_BIT) | //GPIO IRQA Handler
(MED <<NVIC_IPR_15to12_PRI_13_BIT) | //GPIO IRQB Handler
(MED <<NVIC_IPR_15to12_PRI_14_BIT) | //GPIO IRQC Handler
(MED <<NVIC_IPR_15to12_PRI_15_BIT)); //GPIO IRQD Handler
NVIC_IPR_19to16 = ((LOW <<NVIC_IPR_19to16_PRI_16_BIT)); //Debug Handler
//vect33 not implemented
//vect34 not implemented
//vect35 not implemented
////---- Always Configure System Handlers Control and Configuration ----////
SCS_CCR = SCS_CCR_DIV_0_TRP_MASK;
SCS_SHCSR = ( SCS_SHCSR_USGFAULTENA_MASK
| SCS_SHCSR_BUSFAULTENA_MASK
| SCS_SHCSR_MEMFAULTENA_MASK );
if((RESET_EVENT&RESET_DSLEEP) == RESET_DSLEEP) {
//Since the 13 NVIC registers above are fixed values, they are restored
//above (where they get set anyways during normal boot sequences) instead
//of inside of the halInternalSleep code:
void halTriggerContextRestore(void);
extern volatile boolean halPendSvSaveContext;
halPendSvSaveContext = 0; //0 means restore context
SCS_ICSR |= SCS_ICSR_PENDSVSET; //pend halPendSvIsr to enable later
halTriggerContextRestore(); //sets MSP, enables interrupts
//if the context restore worked properly, we should never return here
while(1) { ; }
}
INTERRUPTS_OFF();
asm("CPSIE i");
/*==================================*/
/* Choose if segment initialization */
/* should be done or not. */
/* Return: 0 to omit seg_init */
/* 1 to run seg_init */
/*==================================*/
//return 1;
unsigned long *pulSrc, *pulDest;
//
// Copy the data segment initializers from flash to SRAM.
//
pulSrc = &_sidata;
for(pulDest = &_sdata; pulDest < &_edata; )
{
*(pulDest++) = *(pulSrc++);
}
//
// Zero fill the bss segment.
//
for(pulDest = &_sbss; pulDest < &_ebss; )
{
*(pulDest++) = 0;
}
//
// Call the application's entry point.
//
main();
}
#ifdef USE_HEAP
static unsigned char __HEAP_START[1024*3-560+0x200];
caddr_t _sbrk ( int incr )
{
static unsigned char *heap = NULL;
unsigned char *prev_heap;
//printf ("_sbrk (%d)\n\r", incr);
if (heap == NULL) {
heap = (unsigned char *)__HEAP_START;
}
prev_heap = heap;
/* check removed to show basic approach */
if ((heap + incr) > (__HEAP_START + sizeof(__HEAP_START))) {
prev_heap = NULL;
} else {
heap += incr;
}
if (prev_heap == NULL) {
printf ("_sbrk %d return %p\n\r", incr, prev_heap);
}
return (caddr_t) prev_heap;
}
#else
# ifdef DUMMY_MALLOC
caddr_t _sbrk ( int incr )
{
return NULL;
}
# endif
#endif
int _lseek (int file,
int ptr,
int dir)
{
return 0;
}
int _close (int file)
{
return -1;
}
void _exit (int n)
{
/* FIXME: return code is thrown away. */
while(1);
}
int _kill (int n, int m)
{
return -1;
}
int _fstat(int file, struct stat *st)
{
st->st_mode = S_IFCHR;
return 0;
}
int _isatty (int fd)
{
return 1;
fd = fd;
}
int _getpid (int n)
{
return -1;
}
int _open (const char * path,
int flags,
...)
{
return -1;
}
int _fflush_r(struct _reent *r, FILE *f)
{
return 0;
}
/********************* (C) COPYRIGHT 2007 STMicroelectronics *****END OF FILE****/

View file

@ -0,0 +1,245 @@
/*SEARCH_DIR("C:\Program Files\Raisonance\Ride\Lib\ARM")
EXTERN( __io_putchar )
EXTERN( _write )
GROUP(
"std_sbrk_thumb.lib"
"smallprintf_thumb.a"
"libc.a"
"libm.a"
)
*/
/* default stack sizes.
These are used by the startup in order to allocate stacks for the different modes.
*/
__Stack_Size = 0x400 ;
PROVIDE ( _Stack_Size = __Stack_Size ) ;
__Stack_Init = _estack - __Stack_Size ;
/*"PROVIDE" allows to easily override these values from an object file or the commmand line.*/
PROVIDE ( _Stack_Init = __Stack_Init ) ;
/*
There will be a link error if there is not this amount of RAM free at the end.
*/
_Minimum_Stack_Size = 0x400 ;
/*
this sends all unreferenced IRQHandlers to reset
*/
PROVIDE(Default_Handler = 0 );
PROVIDE(NMI_Handler = Default_Handler );
PROVIDE(HardFault_Handler = Default_Handler );
PROVIDE(MemManage_Handler = Default_Handler );
PROVIDE(BusFault_Handler = Default_Handler );
PROVIDE(UsageFault_Handler = Default_Handler );
PROVIDE(SVC_Handler = Default_Handler );
PROVIDE(DebugMonitor_Handler = Default_Handler );
PROVIDE(PendSV_Handler = Default_Handler );
PROVIDE(SysTick_Handler = Default_Handler );
PROVIDE(halTimer1Isr = Default_Handler );
PROVIDE(halTimer2Isr = Default_Handler );
PROVIDE(halManagementIsr = Default_Handler );
PROVIDE(halBaseBandIsr = Default_Handler );
PROVIDE(halSleepTimerIsr = Default_Handler );
PROVIDE(halSc1Isr = Default_Handler );
PROVIDE(halSc2Isr = Default_Handler );
PROVIDE(halSecurityIsr = Default_Handler );
PROVIDE(halStackMacTimerIsr = Default_Handler );
PROVIDE(stmRadioTransmitIsr = Default_Handler );
PROVIDE(stmRadioReceiveIsr = Default_Handler );
PROVIDE(halAdcIsr = Default_Handler );
PROVIDE(halIrqAIsr = Default_Handler );
PROVIDE(halIrqBIsr = Default_Handler );
PROVIDE(halIrqCIsr = Default_Handler );
PROVIDE(halIrqDIsr = Default_Handler );
PROVIDE(halDebugIsr = Default_Handler );
/*PROVIDE(stSerialPrintf = printf );*/
/******************************************************************************/
/* Peripheral memory map */
/******************************************************************************/
/*this allows to compile the ST lib in "non-debug" mode*/
/* include the memory spaces definitions sub-script */
MEMORY
{
RAM_region (xrw) : ORIGIN = 0x20000000, LENGTH = 8K
ROM_region (rx) : ORIGIN = 0x08000000, LENGTH = 128K-3K
NVM_region (rx) : ORIGIN = 0x0801F400, LENGTH = 3K
FIB_region (ra) : ORIGIN = 0x08040000, LENGTH = 2K
}
/* higher address of the user mode stack */
_estack = 0x20002000;
/* Sections management for FLASH mode */
/* Sections Definitions */
SECTIONS
{
/* for Cortex devices, the beginning of the startup code is stored in the .isr_vector section, which goes to FLASH */
.isr_vector :
{
. = ALIGN(4);
KEEP(*(.isr_vector)) /* Startup code */
. = ALIGN(4);
} >ROM_region
/* for some STRx devices, the beginning of the startup code is stored in the .flashtext section, which goes to FLASH */
.flashtext :
{
. = ALIGN(4);
*(.flashtext) /* Startup code */
. = ALIGN(4);
} >ROM_region
/* the program code is stored in the .text section, which goes to Flash */
.text :
{
. = ALIGN(4);
*(.text) /* remaining code */
*(.text.*) /* remaining code */
*(.rodata) /* read-only data (constants) */
*(.rodata*)
*(.glue_7)
*(.glue_7t)
. = ALIGN(4);
_etext = .;
/* This is used by the startup in order to initialize the .data secion */
_sidata = _etext;
} >ROM_region
NVM (NOLOAD):
{
. = ALIGN(1024);
KEEP(*(NVM))
. = ALIGN(4);
} > NVM_region
FAT (NOLOAD) :
{
. = ALIGN(4);
KEEP(*(FAT))
. = ALIGN(4);
} > FIB_region
/*
.FAT (NOLOAD):
{
KEEP(*(.FAT))
} > FIB_region
*/
/* after that it's only debugging information. */
/* This is the initialized data section
The program executes knowing that the data is in the RAM
but the loader puts the initial values in the FLASH (inidata).
It is one task of the startup to copy the initial values from FLASH to RAM. */
.data : AT ( _sidata )
{
. = ALIGN(4);
/* This is used by the startup in order to initialize the .data secion */
_sdata = . ;
*(.data)
*(.data.*)
. = ALIGN(4);
/* This is used by the startup in order to initialize the .data secion */
_edata = . ;
} >RAM_region
/* This is the uninitialized data section */
.bss :
{
. = ALIGN(4);
/* This is used by the startup in order to initialize the .bss secion */
_sbss = .;
*(.bss)
*(COMMON)
. = ALIGN(4);
/* This is used by the startup in order to initialize the .bss secion */
_ebss = . ;
} >RAM_region
PROVIDE ( end = _ebss );
PROVIDE ( _end = _ebss );
/* This is the user stack section
This is just to check that there is enough RAM left for the User mode stack
It should generate an error if it's full.
*/
._usrstack :
{
. = ALIGN(4);
_susrstack = . ;
. = . + _Minimum_Stack_Size ;
. = ALIGN(4);
_eusrstack = . ;
} >RAM_region
__exidx_start = .;
__exidx_end = .;
/* remove the debugging information from the standard libraries */
/DISCARD/ :
{
libc.a ( * )
libm.a ( * )
libgcc.a ( * )
}
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
/* DWARF debug sections.
Symbols in the DWARF debugging sections are relative to the beginning
of the section so we begin them at 0. */
/* DWARF 1 */
.debug 0 : { *(.debug) }
.line 0 : { *(.line) }
/* GNU DWARF 1 extensions */
.debug_srcinfo 0 : { *(.debug_srcinfo) }
.debug_sfnames 0 : { *(.debug_sfnames) }
/* DWARF 1.1 and DWARF 2 */
.debug_aranges 0 : { *(.debug_aranges) }
.debug_pubnames 0 : { *(.debug_pubnames) }
/* DWARF 2 */
.debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_line 0 : { *(.debug_line) }
.debug_frame 0 : { *(.debug_frame) }
.debug_str 0 : { *(.debug_str) }
.debug_loc 0 : { *(.debug_loc) }
.debug_macinfo 0 : { *(.debug_macinfo) }
/* SGI/MIPS DWARF 2 extensions */
.debug_weaknames 0 : { *(.debug_weaknames) }
.debug_funcnames 0 : { *(.debug_funcnames) }
.debug_typenames 0 : { *(.debug_typenames) }
.debug_varnames 0 : { *(.debug_varnames) }
}

View file

@ -0,0 +1,30 @@
define symbol __ICFEDIT_intvec_start__ = 0x08000000;
/*-Memory Regions-*/
define symbol __ICFEDIT_region_ROM_start__ = 0x08000000;
define symbol __ICFEDIT_region_ROM_end__ = 0x0801FFFF;
define symbol __ICFEDIT_region_FIB_start__ = 0x08040000;
define symbol __ICFEDIT_region_FIB_end__ = 0x080407FF;
define symbol __ICFEDIT_region_RAM_start__ = 0x20000000;
define symbol __ICFEDIT_region_RAM_end__ = 0x20001FFF;
/*-Sizes-*/
define symbol __ICFEDIT_size_cstack__ = 0x500;
define memory mem with size = 4G;
define region ROM_region = mem:[from __ICFEDIT_region_ROM_start__ to __ICFEDIT_region_ROM_end__];
define region RAM_region = mem:[from __ICFEDIT_region_RAM_start__ to __ICFEDIT_region_RAM_end__];
define block CSTACK with alignment = 8, size = __ICFEDIT_size_cstack__ { };
initialize by copy { readwrite };
do not initialize { section .noinit,
section FAT,
section NVM };
place at address mem:__ICFEDIT_intvec_start__ { readonly section .intvec };
place at address mem:__ICFEDIT_region_FIB_start__ { section FAT };
place in ROM_region { readonly };
place at end of ROM_region { section NVM };
place in RAM_region { readwrite,
block CSTACK };

View file

@ -0,0 +1,173 @@
/**************************************************
*
* This module contains the function `__low_level_init', a function
* that is called before the `main' function of the program. Normally
* low-level initializations - such as setting the prefered interrupt
* level or setting the watchdog - can be performed here.
*
* Note that this function is called before the data segments are
* initialized, this means that this function cannot rely on the
* values of global or static variables.
*
* When this function returns zero, the startup code will inhibit the
* initialization of the data segments. The result is faster startup,
* the drawback is that neither global nor static data will be
* initialized.
*
* Copyright 1999-2004 IAR Systems. All rights reserved.
* Customized by STMicroelectronics for STM32W
*
**************************************************/
#include PLATFORM_HEADER
#ifdef __cplusplus
extern "C" {
#endif
#pragma language=extended
#include "hal/micro/cortexm3/memmap.h"
__root __no_init const HalFixedAddressTableType halFixedAddressTable @ __FAT__;
extern const HalVectorTableType __vector_table[];
__interwork int __low_level_init(void);
__interwork int __low_level_init(void)
{
//Ensure there is enough margin on VREG_1V8 for stable RAM reads by
//setting it to a code of 6. VREG_1V2 can be left at its reset value.
VREG = 0x00000307;
// This code should be careful about the use of local variables in case the
// reset type happens to be a deep sleep reset. If the reset is not from
// deep sleep, then locals can be freely used
//When the Cortex-M3 exits reset, interrupts are enable. Explicitely
//disable them immediately using the standard set PRIMASK instruction.
//Injecting an assembly instruction this early does not effect optimization.
asm("CPSID i");
//It is quite possible that when the Cortex-M3 begins executing code the
//Core Reset Vector Catch is still left enabled. Because this VC would
//cause us to halt at reset if another reset event tripped, we should
//clear it as soon as possible. If a debugger wants to halt at reset,
//it will set this bit again.
DEBUG_EMCR &= ~DEBUG_EMCR_VC_CORERESET;
//Configure flash access for optimal current consumption early
//during boot to save as much current as we can.
FLASH_ACCESS = (FLASH_ACCESS_PREFETCH_EN |
(1<<FLASH_ACCESS_CODE_LATENCY_BIT));
////---- Always remap the vector table ----////
// 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
SCS_VTOR = (int32u)__vector_table;
////---- Always Configure Interrupt Priorities ----////
//The STM32W support 5 bits of priority configuration.
// The cortex allows this to be further divided into preemption and a
// "tie-breaker" sub-priority.
//We configure a scheme that allows for 3 bits (8 values) of preemption and
// 2 bits (4 values) of tie-breaker by using the value 4 in PRIGROUP.
//The value 0x05FA0000 is a special key required to write to this register.
SCS_AIRCR = (0x05FA0000 | (4 <<SCS_AIRCR_PRIGROUP_BIT));
//A few macros to help with interrupt priority configuration. Really only
// uses 6 of the possible levels, and ignores the tie-breaker sub-priority
// for now.
//Don't forget that the priority level values need to be shifted into the
// top 5 bits of the 8 bit priority fields. (hence the <<3)
//
// NOTE: The ATOMIC and DISABLE_INTERRUPTS macros work by setting the
// current priority to a value of 12, which still allows CRITICAL and
// HIGH priority interrupts to fire, while blocking MED and LOW.
// If a different value is desired, spmr.s79 will need to be edited.
#define CRITICAL (0 <<3)
#define HIGH (8 <<3)
#define MED (16 <<3)
#define LOW (28 <<3)
#define NONE (31 <<3)
//With optimization turned on, the compiler will indentify all the values
//and variables used here as constants at compile time and will truncate
//this entire block of code to 98 bytes, comprised of 7 load-load-store
//operations.
//vect00 is fixed //Stack pointer
//vect01 is fixed //Reset Vector
//vect02 is fixed //NMI Handler
//vect03 is fixed //Hard Fault Handler
SCS_SHPR_7to4 = ((CRITICAL <<SCS_SHPR_7to4_PRI_4_BIT) | //Memory Fault Handler
(CRITICAL <<SCS_SHPR_7to4_PRI_5_BIT) | //Bus Fault Handler
(CRITICAL <<SCS_SHPR_7to4_PRI_6_BIT) | //Usage Fault Handler
(NONE <<SCS_SHPR_7to4_PRI_7_BIT)); //Reserved
SCS_SHPR_11to8 = ((NONE <<SCS_SHPR_11to8_PRI_8_BIT) | //Reserved
(NONE <<SCS_SHPR_11to8_PRI_9_BIT) | //Reserved
(NONE <<SCS_SHPR_11to8_PRI_10_BIT) | //Reserved
(HIGH <<SCS_SHPR_11to8_PRI_11_BIT)); //SVCall Handler
SCS_SHPR_15to12 = ((MED <<SCS_SHPR_15to12_PRI_12_BIT) | //Debug Monitor Handler
(NONE <<SCS_SHPR_15to12_PRI_13_BIT) | //Reserved
(HIGH <<SCS_SHPR_15to12_PRI_14_BIT) | //PendSV Handler
(MED <<SCS_SHPR_15to12_PRI_15_BIT)); //SysTick Handler
NVIC_IPR_3to0 = ((MED <<NVIC_IPR_3to0_PRI_0_BIT) | //Timer 1 Handler
(MED <<NVIC_IPR_3to0_PRI_1_BIT) | //Timer 2 Handler
(HIGH <<NVIC_IPR_3to0_PRI_2_BIT) | //Management Handler
(MED <<NVIC_IPR_3to0_PRI_3_BIT)); //BaseBand Handler
NVIC_IPR_7to4 = ((MED <<NVIC_IPR_7to4_PRI_4_BIT) | //Sleep Timer Handler
(MED <<NVIC_IPR_7to4_PRI_5_BIT) | //SC1 Handler
(MED <<NVIC_IPR_7to4_PRI_6_BIT) | //SC2 Handler
(MED <<NVIC_IPR_7to4_PRI_7_BIT)); //Security Handler
NVIC_IPR_11to8 = ((MED <<NVIC_IPR_11to8_PRI_8_BIT) | //MAC Timer Handler
(MED <<NVIC_IPR_11to8_PRI_9_BIT) | //MAC TX Handler
(MED <<NVIC_IPR_11to8_PRI_10_BIT) | //MAC RX Handler
(MED <<NVIC_IPR_11to8_PRI_11_BIT)); //ADC Handler
NVIC_IPR_15to12 = ((MED <<NVIC_IPR_15to12_PRI_12_BIT) | //GPIO IRQA Handler
(MED <<NVIC_IPR_15to12_PRI_13_BIT) | //GPIO IRQB Handler
(MED <<NVIC_IPR_15to12_PRI_14_BIT) | //GPIO IRQC Handler
(MED <<NVIC_IPR_15to12_PRI_15_BIT)); //GPIO IRQD Handler
NVIC_IPR_19to16 = ((LOW <<NVIC_IPR_19to16_PRI_16_BIT)); //Debug Handler
//vect33 not implemented
//vect34 not implemented
//vect35 not implemented
////---- Always Configure System Handlers Control and Configuration ----////
SCS_CCR = SCS_CCR_DIV_0_TRP_MASK;
SCS_SHCSR = ( SCS_SHCSR_USGFAULTENA_MASK
| SCS_SHCSR_BUSFAULTENA_MASK
| SCS_SHCSR_MEMFAULTENA_MASK );
if((RESET_EVENT&RESET_DSLEEP) == RESET_DSLEEP) {
//Since the 13 NVIC registers above are fixed values, they are restored
//above (where they get set anyways during normal boot sequences) instead
//of inside of the halInternalSleep code:
void halTriggerContextRestore(void);
extern volatile boolean halPendSvSaveContext;
halPendSvSaveContext = 0; //0 means restore context
SCS_ICSR |= SCS_ICSR_PENDSVSET; //pend halPendSvIsr to enable later
halTriggerContextRestore(); //sets MSP, enables interrupts
//if the context restore worked properly, we should never return here
while(1) { ; }
}
INTERRUPTS_OFF();
asm("CPSIE i");
/*==================================*/
/* Choose if segment initialization */
/* should be done or not. */
/* Return: 0 to omit seg_init */
/* 1 to run seg_init */
/*==================================*/
return 1;
}
#pragma language=default
#ifdef __cplusplus
}
#endif

View file

@ -0,0 +1,57 @@
/** @file hal/micro/cortexm3/stm32w108/memmap.h
* @brief Definition of STM32W108 chip specific memory map information
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
#ifndef __MEMMAP_H__
#error This header should not be included directly, use hal/micro/cortexm3/memmap.h
#endif
#ifndef __STM32W108_MEMMAP_H__
#define __STM32W108_MEMMAP_H__
#define RAM_BOTTOM (0x20000000u)
#define RAM_SIZE_B (0x2000)
#define RAM_SIZE_W (RAM_SIZE_B/4)
#define RAM_TOP (RAM_BOTTOM+RAM_SIZE_B-1)
#define MFB_BOTTOM (0x08000000u)
#define MFB_SIZE_B (0x20000)
#define MFB_SIZE_W (MFB_SIZE_B/4)
#define MFB_TOP (MFB_BOTTOM+MFB_SIZE_B-1)
#define MFB_PAGE_SIZE_B (1024)
#define MFB_PAGE_SIZE_W (MFB_PAGE_SIZE_B/4)
#define MFB_PAGE_MASK_B (0xFFFFFC00)
#define MFB_REGION_SIZE (4) // One write protection region is 4 pages.
#define MFB_ADDR_MASK (0x0003FFFFu)
#define CIB_BOTTOM (0x08040800u)
#define CIB_SIZE_B (0x200)
#define CIB_SIZE_W (CIB_SIZE_B/4)
#define CIB_TOP (CIB_BOTTOM+CIB_SIZE_B-1)
#define CIB_PAGE_SIZE_B (512)
#define CIB_PAGE_SIZE_W (CIB_PAGE_SIZE_B/4)
#define CIB_OB_BOTTOM (CIB_BOTTOM+0x00) //bottom address of CIB option bytes
#define CIB_OB_TOP (CIB_BOTTOM+0x0F) //top address of CIB option bytes
#define FIB_BOTTOM (0x08040000u)
#define FIB_SIZE_B (0x800)
#define FIB_SIZE_W (FIB_SIZE_B/4)
#define FIB_TOP (FIB_BOTTOM+FIB_SIZE_B-1)
#define FIB_PAGE_SIZE_B (1024)
#define FIB_PAGE_SIZE_W (FIB_PAGE_SIZE_B/4)
#define FPEC_KEY1 0x45670123 //magic key defined in hardware
#define FPEC_KEY2 0xCDEF89AB //magic key defined in hardware
//Translation between page number and simee (word based) address
#define SIMEE_ADDR_TO_PAGE(x) ((int8u)(((int16u)(x)) >> 9))
#define PAGE_TO_SIMEE_ADDR(x) (((int16u)(x)) << 9)
//Translation between page number and code addresses, used by bootloaders
#define PROG_ADDR_TO_PAGE(x) ((int8u)((((int32u)(x))&MFB_ADDR_MASK) >> 10))
#define PAGE_TO_PROG_ADDR(x) ((((int32u)(x)) << 10)|MFB_BOTTOM)
#endif //__STM32W108_MEMMAP_H__

View file

@ -0,0 +1,924 @@
;------------------------------------------------------------------------------
; @file regs.ddf
; @brief Device Description File for use with IAR's C-SPY
;
; To see all registers defined in Embedded Workbench's C-SPY Register window,
; this file must be pointed to under
; Project > Options > Debugger > Device description file
;
; Please Note: This file is automatically generated, and should not
; be directly edited
;
; COPYRIGHT 2010 STMicroelectronics. All rights reserved.
;------------------------------------------------------------------------------
; Start of SFR definition.
[Sfr]
; Name Zone Address Bytesize Displaybase Bitrange
; ---- ---- ------- -------- ----------- --------
sfr = "INT_TIM1FLAG", "Memory", 0x4000A800, 4, base=16
sfr = "INT_TIM1FLAG.INT_TIMRSVD", "Memory", 0x4000A800, 4, base=16, bitMask=0x00001E00
sfr = "INT_TIM1FLAG.INT_TIMTIF", "Memory", 0x4000A800, 4, base=16, bitMask=0x00000040
sfr = "INT_TIM1FLAG.INT_TIMCC4IF", "Memory", 0x4000A800, 4, base=16, bitMask=0x00000010
sfr = "INT_TIM1FLAG.INT_TIMCC3IF", "Memory", 0x4000A800, 4, base=16, bitMask=0x00000008
sfr = "INT_TIM1FLAG.INT_TIMCC2IF", "Memory", 0x4000A800, 4, base=16, bitMask=0x00000004
sfr = "INT_TIM1FLAG.INT_TIMCC1IF", "Memory", 0x4000A800, 4, base=16, bitMask=0x00000002
sfr = "INT_TIM1FLAG.INT_TIMUIF", "Memory", 0x4000A800, 4, base=16, bitMask=0x00000001
sfr = "INT_TIM2FLAG", "Memory", 0x4000A804, 4, base=16
sfr = "INT_TIM2FLAG.INT_TIMRSVD", "Memory", 0x4000A804, 4, base=16, bitMask=0x00001E00
sfr = "INT_TIM2FLAG.INT_TIMTIF", "Memory", 0x4000A804, 4, base=16, bitMask=0x00000040
sfr = "INT_TIM2FLAG.INT_TIMCC4IF", "Memory", 0x4000A804, 4, base=16, bitMask=0x00000010
sfr = "INT_TIM2FLAG.INT_TIMCC3IF", "Memory", 0x4000A804, 4, base=16, bitMask=0x00000008
sfr = "INT_TIM2FLAG.INT_TIMCC2IF", "Memory", 0x4000A804, 4, base=16, bitMask=0x00000004
sfr = "INT_TIM2FLAG.INT_TIMCC1IF", "Memory", 0x4000A804, 4, base=16, bitMask=0x00000002
sfr = "INT_TIM2FLAG.INT_TIMUIF", "Memory", 0x4000A804, 4, base=16, bitMask=0x00000001
sfr = "INT_SC1FLAG", "Memory", 0x4000A808, 4, base=16
sfr = "INT_SC1FLAG.INT_SC1PARERR", "Memory", 0x4000A808, 4, base=16, bitMask=0x00004000
sfr = "INT_SC1FLAG.INT_SC1FRMERR", "Memory", 0x4000A808, 4, base=16, bitMask=0x00002000
sfr = "INT_SC1FLAG.INT_SCTXULDB", "Memory", 0x4000A808, 4, base=16, bitMask=0x00001000
sfr = "INT_SC1FLAG.INT_SCTXULDA", "Memory", 0x4000A808, 4, base=16, bitMask=0x00000800
sfr = "INT_SC1FLAG.INT_SCRXULDB", "Memory", 0x4000A808, 4, base=16, bitMask=0x00000400
sfr = "INT_SC1FLAG.INT_SCRXULDA", "Memory", 0x4000A808, 4, base=16, bitMask=0x00000200
sfr = "INT_SC1FLAG.INT_SCNAK", "Memory", 0x4000A808, 4, base=16, bitMask=0x00000100
sfr = "INT_SC1FLAG.INT_SCCMDFIN", "Memory", 0x4000A808, 4, base=16, bitMask=0x00000080
sfr = "INT_SC1FLAG.INT_SCTXFIN", "Memory", 0x4000A808, 4, base=16, bitMask=0x00000040
sfr = "INT_SC1FLAG.INT_SCRXFIN", "Memory", 0x4000A808, 4, base=16, bitMask=0x00000020
sfr = "INT_SC1FLAG.INT_SCTXUND", "Memory", 0x4000A808, 4, base=16, bitMask=0x00000010
sfr = "INT_SC1FLAG.INT_SCRXOVF", "Memory", 0x4000A808, 4, base=16, bitMask=0x00000008
sfr = "INT_SC1FLAG.INT_SCTXIDLE", "Memory", 0x4000A808, 4, base=16, bitMask=0x00000004
sfr = "INT_SC1FLAG.INT_SCTXFREE", "Memory", 0x4000A808, 4, base=16, bitMask=0x00000002
sfr = "INT_SC1FLAG.INT_SCRXVAL", "Memory", 0x4000A808, 4, base=16, bitMask=0x00000001
sfr = "INT_SC2FLAG", "Memory", 0x4000A80C, 4, base=16
sfr = "INT_SC2FLAG.INT_SCTXULDB", "Memory", 0x4000A80C, 4, base=16, bitMask=0x00001000
sfr = "INT_SC2FLAG.INT_SCTXULDA", "Memory", 0x4000A80C, 4, base=16, bitMask=0x00000800
sfr = "INT_SC2FLAG.INT_SCRXULDB", "Memory", 0x4000A80C, 4, base=16, bitMask=0x00000400
sfr = "INT_SC2FLAG.INT_SCRXULDA", "Memory", 0x4000A80C, 4, base=16, bitMask=0x00000200
sfr = "INT_SC2FLAG.INT_SCNAK", "Memory", 0x4000A80C, 4, base=16, bitMask=0x00000100
sfr = "INT_SC2FLAG.INT_SCCMDFIN", "Memory", 0x4000A80C, 4, base=16, bitMask=0x00000080
sfr = "INT_SC2FLAG.INT_SCTXFIN", "Memory", 0x4000A80C, 4, base=16, bitMask=0x00000040
sfr = "INT_SC2FLAG.INT_SCRXFIN", "Memory", 0x4000A80C, 4, base=16, bitMask=0x00000020
sfr = "INT_SC2FLAG.INT_SCTXUND", "Memory", 0x4000A80C, 4, base=16, bitMask=0x00000010
sfr = "INT_SC2FLAG.INT_SCRXOVF", "Memory", 0x4000A80C, 4, base=16, bitMask=0x00000008
sfr = "INT_SC2FLAG.INT_SCTXIDLE", "Memory", 0x4000A80C, 4, base=16, bitMask=0x00000004
sfr = "INT_SC2FLAG.INT_SCTXFREE", "Memory", 0x4000A80C, 4, base=16, bitMask=0x00000002
sfr = "INT_SC2FLAG.INT_SCRXVAL", "Memory", 0x4000A80C, 4, base=16, bitMask=0x00000001
sfr = "INT_ADCFLAG", "Memory", 0x4000A810, 4, base=16
sfr = "INT_ADCFLAG.INT_ADCOVF", "Memory", 0x4000A810, 4, base=16, bitMask=0x00000010
sfr = "INT_ADCFLAG.INT_ADCSAT", "Memory", 0x4000A810, 4, base=16, bitMask=0x00000008
sfr = "INT_ADCFLAG.INT_ADCULDFULL", "Memory", 0x4000A810, 4, base=16, bitMask=0x00000004
sfr = "INT_ADCFLAG.INT_ADCULDHALF", "Memory", 0x4000A810, 4, base=16, bitMask=0x00000002
sfr = "INT_ADCFLAG.INT_ADCFLAGRSVD", "Memory", 0x4000A810, 4, base=16, bitMask=0x00000001
sfr = "INT_GPIOFLAG", "Memory", 0x4000A814, 4, base=16
sfr = "INT_GPIOFLAG.INT_IRQDFLAG", "Memory", 0x4000A814, 4, base=16, bitMask=0x00000008
sfr = "INT_GPIOFLAG.INT_IRQCFLAG", "Memory", 0x4000A814, 4, base=16, bitMask=0x00000004
sfr = "INT_GPIOFLAG.INT_IRQBFLAG", "Memory", 0x4000A814, 4, base=16, bitMask=0x00000002
sfr = "INT_GPIOFLAG.INT_IRQAFLAG", "Memory", 0x4000A814, 4, base=16, bitMask=0x00000001
sfr = "INT_TIM1MISS", "Memory", 0x4000A818, 4, base=16
sfr = "INT_TIM1MISS.INT_TIMMISSCC4IF", "Memory", 0x4000A818, 4, base=16, bitMask=0x00001000
sfr = "INT_TIM1MISS.INT_TIMMISSCC3IF", "Memory", 0x4000A818, 4, base=16, bitMask=0x00000800
sfr = "INT_TIM1MISS.INT_TIMMISSCC2IF", "Memory", 0x4000A818, 4, base=16, bitMask=0x00000400
sfr = "INT_TIM1MISS.INT_TIMMISSCC1IF", "Memory", 0x4000A818, 4, base=16, bitMask=0x00000200
sfr = "INT_TIM1MISS.INT_TIMMISSRSVD", "Memory", 0x4000A818, 4, base=16, bitMask=0x0000007F
sfr = "INT_TIM2MISS", "Memory", 0x4000A81C, 4, base=16
sfr = "INT_TIM2MISS.INT_TIMMISSCC4IF", "Memory", 0x4000A81C, 4, base=16, bitMask=0x00001000
sfr = "INT_TIM2MISS.INT_TIMMISSCC3IF", "Memory", 0x4000A81C, 4, base=16, bitMask=0x00000800
sfr = "INT_TIM2MISS.INT_TIMMISSCC2IF", "Memory", 0x4000A81C, 4, base=16, bitMask=0x00000400
sfr = "INT_TIM2MISS.INT_TIMMISSCC1IF", "Memory", 0x4000A81C, 4, base=16, bitMask=0x00000200
sfr = "INT_TIM2MISS.INT_TIMMISSRSVD", "Memory", 0x4000A81C, 4, base=16, bitMask=0x0000007F
sfr = "INT_MISS", "Memory", 0x4000A820, 4, base=16
sfr = "INT_MISS.INT_MISSIRQD", "Memory", 0x4000A820, 4, base=16, bitMask=0x00008000
sfr = "INT_MISS.INT_MISSIRQC", "Memory", 0x4000A820, 4, base=16, bitMask=0x00004000
sfr = "INT_MISS.INT_MISSIRQB", "Memory", 0x4000A820, 4, base=16, bitMask=0x00002000
sfr = "INT_MISS.INT_MISSIRQA", "Memory", 0x4000A820, 4, base=16, bitMask=0x00001000
sfr = "INT_MISS.INT_MISSADC", "Memory", 0x4000A820, 4, base=16, bitMask=0x00000800
sfr = "INT_MISS.INT_MISSMACRX", "Memory", 0x4000A820, 4, base=16, bitMask=0x00000400
sfr = "INT_MISS.INT_MISSMACTX", "Memory", 0x4000A820, 4, base=16, bitMask=0x00000200
sfr = "INT_MISS.INT_MISSMACTMR", "Memory", 0x4000A820, 4, base=16, bitMask=0x00000100
sfr = "INT_MISS.INT_MISSSEC", "Memory", 0x4000A820, 4, base=16, bitMask=0x00000080
sfr = "INT_MISS.INT_MISSSC2", "Memory", 0x4000A820, 4, base=16, bitMask=0x00000040
sfr = "INT_MISS.INT_MISSSC1", "Memory", 0x4000A820, 4, base=16, bitMask=0x00000020
sfr = "INT_MISS.INT_MISSSLEEP", "Memory", 0x4000A820, 4, base=16, bitMask=0x00000010
sfr = "INT_MISS.INT_MISSBB", "Memory", 0x4000A820, 4, base=16, bitMask=0x00000008
sfr = "INT_MISS.INT_MISSMGMT", "Memory", 0x4000A820, 4, base=16, bitMask=0x00000004
sfr = "INT_TIM1CFG", "Memory", 0x4000A840, 4, base=16
sfr = "INT_TIM1CFG.INT_TIMTIF", "Memory", 0x4000A840, 4, base=16, bitMask=0x00000040
sfr = "INT_TIM1CFG.INT_TIMCC4IF", "Memory", 0x4000A840, 4, base=16, bitMask=0x00000010
sfr = "INT_TIM1CFG.INT_TIMCC3IF", "Memory", 0x4000A840, 4, base=16, bitMask=0x00000008
sfr = "INT_TIM1CFG.INT_TIMCC2IF", "Memory", 0x4000A840, 4, base=16, bitMask=0x00000004
sfr = "INT_TIM1CFG.INT_TIMCC1IF", "Memory", 0x4000A840, 4, base=16, bitMask=0x00000002
sfr = "INT_TIM1CFG.INT_TIMUIF", "Memory", 0x4000A840, 4, base=16, bitMask=0x00000001
sfr = "INT_TIM2CFG", "Memory", 0x4000A844, 4, base=16
sfr = "INT_TIM2CFG.INT_TIMTIF", "Memory", 0x4000A844, 4, base=16, bitMask=0x00000040
sfr = "INT_TIM2CFG.INT_TIMCC4IF", "Memory", 0x4000A844, 4, base=16, bitMask=0x00000010
sfr = "INT_TIM2CFG.INT_TIMCC3IF", "Memory", 0x4000A844, 4, base=16, bitMask=0x00000008
sfr = "INT_TIM2CFG.INT_TIMCC2IF", "Memory", 0x4000A844, 4, base=16, bitMask=0x00000004
sfr = "INT_TIM2CFG.INT_TIMCC1IF", "Memory", 0x4000A844, 4, base=16, bitMask=0x00000002
sfr = "INT_TIM2CFG.INT_TIMUIF", "Memory", 0x4000A844, 4, base=16, bitMask=0x00000001
sfr = "INT_SC1CFG", "Memory", 0x4000A848, 4, base=16
sfr = "INT_SC1CFG.INT_SC1PARERR", "Memory", 0x4000A848, 4, base=16, bitMask=0x00004000
sfr = "INT_SC1CFG.INT_SC1FRMERR", "Memory", 0x4000A848, 4, base=16, bitMask=0x00002000
sfr = "INT_SC1CFG.INT_SCTXULDB", "Memory", 0x4000A848, 4, base=16, bitMask=0x00001000
sfr = "INT_SC1CFG.INT_SCTXULDA", "Memory", 0x4000A848, 4, base=16, bitMask=0x00000800
sfr = "INT_SC1CFG.INT_SCRXULDB", "Memory", 0x4000A848, 4, base=16, bitMask=0x00000400
sfr = "INT_SC1CFG.INT_SCRXULDA", "Memory", 0x4000A848, 4, base=16, bitMask=0x00000200
sfr = "INT_SC1CFG.INT_SCNAK", "Memory", 0x4000A848, 4, base=16, bitMask=0x00000100
sfr = "INT_SC1CFG.INT_SCCMDFIN", "Memory", 0x4000A848, 4, base=16, bitMask=0x00000080
sfr = "INT_SC1CFG.INT_SCTXFIN", "Memory", 0x4000A848, 4, base=16, bitMask=0x00000040
sfr = "INT_SC1CFG.INT_SCRXFIN", "Memory", 0x4000A848, 4, base=16, bitMask=0x00000020
sfr = "INT_SC1CFG.INT_SCTXUND", "Memory", 0x4000A848, 4, base=16, bitMask=0x00000010
sfr = "INT_SC1CFG.INT_SCRXOVF", "Memory", 0x4000A848, 4, base=16, bitMask=0x00000008
sfr = "INT_SC1CFG.INT_SCTXIDLE", "Memory", 0x4000A848, 4, base=16, bitMask=0x00000004
sfr = "INT_SC1CFG.INT_SCTXFREE", "Memory", 0x4000A848, 4, base=16, bitMask=0x00000002
sfr = "INT_SC1CFG.INT_SCRXVAL", "Memory", 0x4000A848, 4, base=16, bitMask=0x00000001
sfr = "INT_SC2CFG", "Memory", 0x4000A84C, 4, base=16
sfr = "INT_SC2CFG.INT_SCTXULDB", "Memory", 0x4000A84C, 4, base=16, bitMask=0x00001000
sfr = "INT_SC2CFG.INT_SCTXULDA", "Memory", 0x4000A84C, 4, base=16, bitMask=0x00000800
sfr = "INT_SC2CFG.INT_SCRXULDB", "Memory", 0x4000A84C, 4, base=16, bitMask=0x00000400
sfr = "INT_SC2CFG.INT_SCRXULDA", "Memory", 0x4000A84C, 4, base=16, bitMask=0x00000200
sfr = "INT_SC2CFG.INT_SCNAK", "Memory", 0x4000A84C, 4, base=16, bitMask=0x00000100
sfr = "INT_SC2CFG.INT_SCCMDFIN", "Memory", 0x4000A84C, 4, base=16, bitMask=0x00000080
sfr = "INT_SC2CFG.INT_SCTXFIN", "Memory", 0x4000A84C, 4, base=16, bitMask=0x00000040
sfr = "INT_SC2CFG.INT_SCRXFIN", "Memory", 0x4000A84C, 4, base=16, bitMask=0x00000020
sfr = "INT_SC2CFG.INT_SCTXUND", "Memory", 0x4000A84C, 4, base=16, bitMask=0x00000010
sfr = "INT_SC2CFG.INT_SCRXOVF", "Memory", 0x4000A84C, 4, base=16, bitMask=0x00000008
sfr = "INT_SC2CFG.INT_SCTXIDLE", "Memory", 0x4000A84C, 4, base=16, bitMask=0x00000004
sfr = "INT_SC2CFG.INT_SCTXFREE", "Memory", 0x4000A84C, 4, base=16, bitMask=0x00000002
sfr = "INT_SC2CFG.INT_SCRXVAL", "Memory", 0x4000A84C, 4, base=16, bitMask=0x00000001
sfr = "INT_ADCCFG", "Memory", 0x4000A850, 4, base=16
sfr = "INT_ADCCFG.INT_ADCOVF", "Memory", 0x4000A850, 4, base=16, bitMask=0x00000010
sfr = "INT_ADCCFG.INT_ADCSAT", "Memory", 0x4000A850, 4, base=16, bitMask=0x00000008
sfr = "INT_ADCCFG.INT_ADCULDFULL", "Memory", 0x4000A850, 4, base=16, bitMask=0x00000004
sfr = "INT_ADCCFG.INT_ADCULDHALF", "Memory", 0x4000A850, 4, base=16, bitMask=0x00000002
sfr = "INT_ADCCFG.INT_ADCCFGRSVD", "Memory", 0x4000A850, 4, base=16, bitMask=0x00000001
sfr = "SC1_INTMODE", "Memory", 0x4000A854, 4, base=16
sfr = "SC1_INTMODE.SC_TXIDLELEVEL", "Memory", 0x4000A854, 4, base=16, bitMask=0x00000004
sfr = "SC1_INTMODE.SC_TXFREELEVEL", "Memory", 0x4000A854, 4, base=16, bitMask=0x00000002
sfr = "SC1_INTMODE.SC_RXVALLEVEL", "Memory", 0x4000A854, 4, base=16, bitMask=0x00000001
sfr = "SC2_INTMODE", "Memory", 0x4000A858, 4, base=16
sfr = "SC2_INTMODE.SC_TXIDLELEVEL", "Memory", 0x4000A858, 4, base=16, bitMask=0x00000004
sfr = "SC2_INTMODE.SC_TXFREELEVEL", "Memory", 0x4000A858, 4, base=16, bitMask=0x00000002
sfr = "SC2_INTMODE.SC_RXVALLEVEL", "Memory", 0x4000A858, 4, base=16, bitMask=0x00000001
sfr = "GPIO_INTCFGA", "Memory", 0x4000A860, 4, base=16
sfr = "GPIO_INTCFGA.GPIO_INTFILT", "Memory", 0x4000A860, 4, base=16, bitMask=0x00000100
sfr = "GPIO_INTCFGA.GPIO_INTMOD", "Memory", 0x4000A860, 4, base=16, bitMask=0x000000E0
sfr = "GPIO_INTCFGB", "Memory", 0x4000A864, 4, base=16
sfr = "GPIO_INTCFGB.GPIO_INTFILT", "Memory", 0x4000A864, 4, base=16, bitMask=0x00000100
sfr = "GPIO_INTCFGB.GPIO_INTMOD", "Memory", 0x4000A864, 4, base=16, bitMask=0x000000E0
sfr = "GPIO_INTCFGC", "Memory", 0x4000A868, 4, base=16
sfr = "GPIO_INTCFGC.GPIO_INTFILT", "Memory", 0x4000A868, 4, base=16, bitMask=0x00000100
sfr = "GPIO_INTCFGC.GPIO_INTMOD", "Memory", 0x4000A868, 4, base=16, bitMask=0x000000E0
sfr = "GPIO_INTCFGD", "Memory", 0x4000A86C, 4, base=16
sfr = "GPIO_INTCFGD.GPIO_INTFILT", "Memory", 0x4000A86C, 4, base=16, bitMask=0x00000100
sfr = "GPIO_INTCFGD.GPIO_INTMOD", "Memory", 0x4000A86C, 4, base=16, bitMask=0x000000E0
sfr = "GPIO_PACFGL", "Memory", 0x4000B000, 4, base=16
sfr = "GPIO_PACFGL.PA3_CFG", "Memory", 0x4000B000, 4, base=16, bitMask=0x0000F000
sfr = "GPIO_PACFGL.PA2_CFG", "Memory", 0x4000B000, 4, base=16, bitMask=0x00000F00
sfr = "GPIO_PACFGL.PA1_CFG", "Memory", 0x4000B000, 4, base=16, bitMask=0x000000F0
sfr = "GPIO_PACFGL.PA0_CFG", "Memory", 0x4000B000, 4, base=16, bitMask=0x0000000F
sfr = "GPIO_PACFGH", "Memory", 0x4000B004, 4, base=16
sfr = "GPIO_PACFGH.PA7_CFG", "Memory", 0x4000B004, 4, base=16, bitMask=0x0000F000
sfr = "GPIO_PACFGH.PA6_CFG", "Memory", 0x4000B004, 4, base=16, bitMask=0x00000F00
sfr = "GPIO_PACFGH.PA5_CFG", "Memory", 0x4000B004, 4, base=16, bitMask=0x000000F0
sfr = "GPIO_PACFGH.PA4_CFG", "Memory", 0x4000B004, 4, base=16, bitMask=0x0000000F
sfr = "GPIO_PAIN", "Memory", 0x4000B008, 4, base=16
sfr = "GPIO_PAIN.PA7", "Memory", 0x4000B008, 4, base=16, bitMask=0x00000080
sfr = "GPIO_PAIN.PA6", "Memory", 0x4000B008, 4, base=16, bitMask=0x00000040
sfr = "GPIO_PAIN.PA5", "Memory", 0x4000B008, 4, base=16, bitMask=0x00000020
sfr = "GPIO_PAIN.PA4", "Memory", 0x4000B008, 4, base=16, bitMask=0x00000010
sfr = "GPIO_PAIN.PA3", "Memory", 0x4000B008, 4, base=16, bitMask=0x00000008
sfr = "GPIO_PAIN.PA2", "Memory", 0x4000B008, 4, base=16, bitMask=0x00000004
sfr = "GPIO_PAIN.PA1", "Memory", 0x4000B008, 4, base=16, bitMask=0x00000002
sfr = "GPIO_PAIN.PA0", "Memory", 0x4000B008, 4, base=16, bitMask=0x00000001
sfr = "GPIO_PAOUT", "Memory", 0x4000B00C, 4, base=16
sfr = "GPIO_PAOUT.PA7", "Memory", 0x4000B00C, 4, base=16, bitMask=0x00000080
sfr = "GPIO_PAOUT.PA6", "Memory", 0x4000B00C, 4, base=16, bitMask=0x00000040
sfr = "GPIO_PAOUT.PA5", "Memory", 0x4000B00C, 4, base=16, bitMask=0x00000020
sfr = "GPIO_PAOUT.PA4", "Memory", 0x4000B00C, 4, base=16, bitMask=0x00000010
sfr = "GPIO_PAOUT.PA3", "Memory", 0x4000B00C, 4, base=16, bitMask=0x00000008
sfr = "GPIO_PAOUT.PA2", "Memory", 0x4000B00C, 4, base=16, bitMask=0x00000004
sfr = "GPIO_PAOUT.PA1", "Memory", 0x4000B00C, 4, base=16, bitMask=0x00000002
sfr = "GPIO_PAOUT.PA0", "Memory", 0x4000B00C, 4, base=16, bitMask=0x00000001
sfr = "GPIO_PASET", "Memory", 0x4000B010, 4, base=16
sfr = "GPIO_PASET.GPIO_PXSETRSVD", "Memory", 0x4000B010, 4, base=16, bitMask=0x0000FF00
sfr = "GPIO_PASET.PA7", "Memory", 0x4000B010, 4, base=16, bitMask=0x00000080
sfr = "GPIO_PASET.PA6", "Memory", 0x4000B010, 4, base=16, bitMask=0x00000040
sfr = "GPIO_PASET.PA5", "Memory", 0x4000B010, 4, base=16, bitMask=0x00000020
sfr = "GPIO_PASET.PA4", "Memory", 0x4000B010, 4, base=16, bitMask=0x00000010
sfr = "GPIO_PASET.PA3", "Memory", 0x4000B010, 4, base=16, bitMask=0x00000008
sfr = "GPIO_PASET.PA2", "Memory", 0x4000B010, 4, base=16, bitMask=0x00000004
sfr = "GPIO_PASET.PA1", "Memory", 0x4000B010, 4, base=16, bitMask=0x00000002
sfr = "GPIO_PASET.PA0", "Memory", 0x4000B010, 4, base=16, bitMask=0x00000001
sfr = "GPIO_PACLR", "Memory", 0x4000B014, 4, base=16
sfr = "GPIO_PACLR.PA7", "Memory", 0x4000B014, 4, base=16, bitMask=0x00000080
sfr = "GPIO_PACLR.PA6", "Memory", 0x4000B014, 4, base=16, bitMask=0x00000040
sfr = "GPIO_PACLR.PA5", "Memory", 0x4000B014, 4, base=16, bitMask=0x00000020
sfr = "GPIO_PACLR.PA4", "Memory", 0x4000B014, 4, base=16, bitMask=0x00000010
sfr = "GPIO_PACLR.PA3", "Memory", 0x4000B014, 4, base=16, bitMask=0x00000008
sfr = "GPIO_PACLR.PA2", "Memory", 0x4000B014, 4, base=16, bitMask=0x00000004
sfr = "GPIO_PACLR.PA1", "Memory", 0x4000B014, 4, base=16, bitMask=0x00000002
sfr = "GPIO_PACLR.PA0", "Memory", 0x4000B014, 4, base=16, bitMask=0x00000001
sfr = "GPIO_PBCFGL", "Memory", 0x4000B400, 4, base=16
sfr = "GPIO_PBCFGL.PB3_CFG", "Memory", 0x4000B400, 4, base=16, bitMask=0x0000F000
sfr = "GPIO_PBCFGL.PB2_CFG", "Memory", 0x4000B400, 4, base=16, bitMask=0x00000F00
sfr = "GPIO_PBCFGL.PB1_CFG", "Memory", 0x4000B400, 4, base=16, bitMask=0x000000F0
sfr = "GPIO_PBCFGL.PB0_CFG", "Memory", 0x4000B400, 4, base=16, bitMask=0x0000000F
sfr = "GPIO_PBCFGH", "Memory", 0x4000B404, 4, base=16
sfr = "GPIO_PBCFGH.PB7_CFG", "Memory", 0x4000B404, 4, base=16, bitMask=0x0000F000
sfr = "GPIO_PBCFGH.PB6_CFG", "Memory", 0x4000B404, 4, base=16, bitMask=0x00000F00
sfr = "GPIO_PBCFGH.PB5_CFG", "Memory", 0x4000B404, 4, base=16, bitMask=0x000000F0
sfr = "GPIO_PBCFGH.PB4_CFG", "Memory", 0x4000B404, 4, base=16, bitMask=0x0000000F
sfr = "GPIO_PBIN", "Memory", 0x4000B408, 4, base=16
sfr = "GPIO_PBIN.PB7", "Memory", 0x4000B408, 4, base=16, bitMask=0x00000080
sfr = "GPIO_PBIN.PB6", "Memory", 0x4000B408, 4, base=16, bitMask=0x00000040
sfr = "GPIO_PBIN.PB5", "Memory", 0x4000B408, 4, base=16, bitMask=0x00000020
sfr = "GPIO_PBIN.PB4", "Memory", 0x4000B408, 4, base=16, bitMask=0x00000010
sfr = "GPIO_PBIN.PB3", "Memory", 0x4000B408, 4, base=16, bitMask=0x00000008
sfr = "GPIO_PBIN.PB2", "Memory", 0x4000B408, 4, base=16, bitMask=0x00000004
sfr = "GPIO_PBIN.PB1", "Memory", 0x4000B408, 4, base=16, bitMask=0x00000002
sfr = "GPIO_PBIN.PB0", "Memory", 0x4000B408, 4, base=16, bitMask=0x00000001
sfr = "GPIO_PBOUT", "Memory", 0x4000B40C, 4, base=16
sfr = "GPIO_PBOUT.PB7", "Memory", 0x4000B40C, 4, base=16, bitMask=0x00000080
sfr = "GPIO_PBOUT.PB6", "Memory", 0x4000B40C, 4, base=16, bitMask=0x00000040
sfr = "GPIO_PBOUT.PB5", "Memory", 0x4000B40C, 4, base=16, bitMask=0x00000020
sfr = "GPIO_PBOUT.PB4", "Memory", 0x4000B40C, 4, base=16, bitMask=0x00000010
sfr = "GPIO_PBOUT.PB3", "Memory", 0x4000B40C, 4, base=16, bitMask=0x00000008
sfr = "GPIO_PBOUT.PB2", "Memory", 0x4000B40C, 4, base=16, bitMask=0x00000004
sfr = "GPIO_PBOUT.PB1", "Memory", 0x4000B40C, 4, base=16, bitMask=0x00000002
sfr = "GPIO_PBOUT.PB0", "Memory", 0x4000B40C, 4, base=16, bitMask=0x00000001
sfr = "GPIO_PBSET", "Memory", 0x4000B410, 4, base=16
sfr = "GPIO_PBSET.GPIO_PXSETRSVD", "Memory", 0x4000B410, 4, base=16, bitMask=0x0000FF00
sfr = "GPIO_PBSET.PB7", "Memory", 0x4000B410, 4, base=16, bitMask=0x00000080
sfr = "GPIO_PBSET.PB6", "Memory", 0x4000B410, 4, base=16, bitMask=0x00000040
sfr = "GPIO_PBSET.PB5", "Memory", 0x4000B410, 4, base=16, bitMask=0x00000020
sfr = "GPIO_PBSET.PB4", "Memory", 0x4000B410, 4, base=16, bitMask=0x00000010
sfr = "GPIO_PBSET.PB3", "Memory", 0x4000B410, 4, base=16, bitMask=0x00000008
sfr = "GPIO_PBSET.PB2", "Memory", 0x4000B410, 4, base=16, bitMask=0x00000004
sfr = "GPIO_PBSET.PB1", "Memory", 0x4000B410, 4, base=16, bitMask=0x00000002
sfr = "GPIO_PBSET.PB0", "Memory", 0x4000B410, 4, base=16, bitMask=0x00000001
sfr = "GPIO_PBCLR", "Memory", 0x4000B414, 4, base=16
sfr = "GPIO_PBCLR.PB7", "Memory", 0x4000B414, 4, base=16, bitMask=0x00000080
sfr = "GPIO_PBCLR.PB6", "Memory", 0x4000B414, 4, base=16, bitMask=0x00000040
sfr = "GPIO_PBCLR.PB5", "Memory", 0x4000B414, 4, base=16, bitMask=0x00000020
sfr = "GPIO_PBCLR.PB4", "Memory", 0x4000B414, 4, base=16, bitMask=0x00000010
sfr = "GPIO_PBCLR.PB3", "Memory", 0x4000B414, 4, base=16, bitMask=0x00000008
sfr = "GPIO_PBCLR.PB2", "Memory", 0x4000B414, 4, base=16, bitMask=0x00000004
sfr = "GPIO_PBCLR.PB1", "Memory", 0x4000B414, 4, base=16, bitMask=0x00000002
sfr = "GPIO_PBCLR.PB0", "Memory", 0x4000B414, 4, base=16, bitMask=0x00000001
sfr = "GPIO_PCCFGL", "Memory", 0x4000B800, 4, base=16
sfr = "GPIO_PCCFGL.PC3_CFG", "Memory", 0x4000B800, 4, base=16, bitMask=0x0000F000
sfr = "GPIO_PCCFGL.PC2_CFG", "Memory", 0x4000B800, 4, base=16, bitMask=0x00000F00
sfr = "GPIO_PCCFGL.PC1_CFG", "Memory", 0x4000B800, 4, base=16, bitMask=0x000000F0
sfr = "GPIO_PCCFGL.PC0_CFG", "Memory", 0x4000B800, 4, base=16, bitMask=0x0000000F
sfr = "GPIO_PCCFGH", "Memory", 0x4000B804, 4, base=16
sfr = "GPIO_PCCFGH.PC7_CFG", "Memory", 0x4000B804, 4, base=16, bitMask=0x0000F000
sfr = "GPIO_PCCFGH.PC6_CFG", "Memory", 0x4000B804, 4, base=16, bitMask=0x00000F00
sfr = "GPIO_PCCFGH.PC5_CFG", "Memory", 0x4000B804, 4, base=16, bitMask=0x000000F0
sfr = "GPIO_PCCFGH.PC4_CFG", "Memory", 0x4000B804, 4, base=16, bitMask=0x0000000F
sfr = "GPIO_PCIN", "Memory", 0x4000B808, 4, base=16
sfr = "GPIO_PCIN.PC7", "Memory", 0x4000B808, 4, base=16, bitMask=0x00000080
sfr = "GPIO_PCIN.PC6", "Memory", 0x4000B808, 4, base=16, bitMask=0x00000040
sfr = "GPIO_PCIN.PC5", "Memory", 0x4000B808, 4, base=16, bitMask=0x00000020
sfr = "GPIO_PCIN.PC4", "Memory", 0x4000B808, 4, base=16, bitMask=0x00000010
sfr = "GPIO_PCIN.PC3", "Memory", 0x4000B808, 4, base=16, bitMask=0x00000008
sfr = "GPIO_PCIN.PC2", "Memory", 0x4000B808, 4, base=16, bitMask=0x00000004
sfr = "GPIO_PCIN.PC1", "Memory", 0x4000B808, 4, base=16, bitMask=0x00000002
sfr = "GPIO_PCIN.PC0", "Memory", 0x4000B808, 4, base=16, bitMask=0x00000001
sfr = "GPIO_PCOUT", "Memory", 0x4000B80C, 4, base=16
sfr = "GPIO_PCOUT.PC7", "Memory", 0x4000B80C, 4, base=16, bitMask=0x00000080
sfr = "GPIO_PCOUT.PC6", "Memory", 0x4000B80C, 4, base=16, bitMask=0x00000040
sfr = "GPIO_PCOUT.PC5", "Memory", 0x4000B80C, 4, base=16, bitMask=0x00000020
sfr = "GPIO_PCOUT.PC4", "Memory", 0x4000B80C, 4, base=16, bitMask=0x00000010
sfr = "GPIO_PCOUT.PC3", "Memory", 0x4000B80C, 4, base=16, bitMask=0x00000008
sfr = "GPIO_PCOUT.PC2", "Memory", 0x4000B80C, 4, base=16, bitMask=0x00000004
sfr = "GPIO_PCOUT.PC1", "Memory", 0x4000B80C, 4, base=16, bitMask=0x00000002
sfr = "GPIO_PCOUT.PC0", "Memory", 0x4000B80C, 4, base=16, bitMask=0x00000001
sfr = "GPIO_PCSET", "Memory", 0x4000B810, 4, base=16
sfr = "GPIO_PCSET.GPIO_PXSETRSVD", "Memory", 0x4000B810, 4, base=16, bitMask=0x0000FF00
sfr = "GPIO_PCSET.PC7", "Memory", 0x4000B810, 4, base=16, bitMask=0x00000080
sfr = "GPIO_PCSET.PC6", "Memory", 0x4000B810, 4, base=16, bitMask=0x00000040
sfr = "GPIO_PCSET.PC5", "Memory", 0x4000B810, 4, base=16, bitMask=0x00000020
sfr = "GPIO_PCSET.PC4", "Memory", 0x4000B810, 4, base=16, bitMask=0x00000010
sfr = "GPIO_PCSET.PC3", "Memory", 0x4000B810, 4, base=16, bitMask=0x00000008
sfr = "GPIO_PCSET.PC2", "Memory", 0x4000B810, 4, base=16, bitMask=0x00000004
sfr = "GPIO_PCSET.PC1", "Memory", 0x4000B810, 4, base=16, bitMask=0x00000002
sfr = "GPIO_PCSET.PC0", "Memory", 0x4000B810, 4, base=16, bitMask=0x00000001
sfr = "GPIO_PCCLR", "Memory", 0x4000B814, 4, base=16
sfr = "GPIO_PCCLR.PC7", "Memory", 0x4000B814, 4, base=16, bitMask=0x00000080
sfr = "GPIO_PCCLR.PC6", "Memory", 0x4000B814, 4, base=16, bitMask=0x00000040
sfr = "GPIO_PCCLR.PC5", "Memory", 0x4000B814, 4, base=16, bitMask=0x00000020
sfr = "GPIO_PCCLR.PC4", "Memory", 0x4000B814, 4, base=16, bitMask=0x00000010
sfr = "GPIO_PCCLR.PC3", "Memory", 0x4000B814, 4, base=16, bitMask=0x00000008
sfr = "GPIO_PCCLR.PC2", "Memory", 0x4000B814, 4, base=16, bitMask=0x00000004
sfr = "GPIO_PCCLR.PC1", "Memory", 0x4000B814, 4, base=16, bitMask=0x00000002
sfr = "GPIO_PCCLR.PC0", "Memory", 0x4000B814, 4, base=16, bitMask=0x00000001
sfr = "GPIO_DBGCFG", "Memory", 0x4000BC00, 4, base=16
sfr = "GPIO_DBGCFG.GPIO_DEBUGDIS", "Memory", 0x4000BC00, 4, base=16, bitMask=0x00000020
sfr = "GPIO_DBGCFG.GPIO_EXTREGEN", "Memory", 0x4000BC00, 4, base=16, bitMask=0x00000010
sfr = "GPIO_DBGCFG.GPIO_DBGCFGRSVD", "Memory", 0x4000BC00, 4, base=16, bitMask=0x00000008
sfr = "GPIO_DBGSTAT", "Memory", 0x4000BC04, 4, base=16
sfr = "GPIO_DBGSTAT.GPIO_BOOTMODE", "Memory", 0x4000BC04, 4, base=16, bitMask=0x00000008
sfr = "GPIO_DBGSTAT.GPIO_FORCEDBG", "Memory", 0x4000BC04, 4, base=16, bitMask=0x00000002
sfr = "GPIO_DBGSTAT.GPIO_SWEN", "Memory", 0x4000BC04, 4, base=16, bitMask=0x00000001
sfr = "GPIO_PAWAKE", "Memory", 0x4000BC08, 4, base=16
sfr = "GPIO_PAWAKE.PA7", "Memory", 0x4000BC08, 4, base=16, bitMask=0x00000080
sfr = "GPIO_PAWAKE.PA6", "Memory", 0x4000BC08, 4, base=16, bitMask=0x00000040
sfr = "GPIO_PAWAKE.PA5", "Memory", 0x4000BC08, 4, base=16, bitMask=0x00000020
sfr = "GPIO_PAWAKE.PA4", "Memory", 0x4000BC08, 4, base=16, bitMask=0x00000010
sfr = "GPIO_PAWAKE.PA3", "Memory", 0x4000BC08, 4, base=16, bitMask=0x00000008
sfr = "GPIO_PAWAKE.PA2", "Memory", 0x4000BC08, 4, base=16, bitMask=0x00000004
sfr = "GPIO_PAWAKE.PA1", "Memory", 0x4000BC08, 4, base=16, bitMask=0x00000002
sfr = "GPIO_PAWAKE.PA0", "Memory", 0x4000BC08, 4, base=16, bitMask=0x00000001
sfr = "GPIO_PBWAKE", "Memory", 0x4000BC0C, 4, base=16
sfr = "GPIO_PBWAKE.PB7", "Memory", 0x4000BC0C, 4, base=16, bitMask=0x00000080
sfr = "GPIO_PBWAKE.PB6", "Memory", 0x4000BC0C, 4, base=16, bitMask=0x00000040
sfr = "GPIO_PBWAKE.PB5", "Memory", 0x4000BC0C, 4, base=16, bitMask=0x00000020
sfr = "GPIO_PBWAKE.PB4", "Memory", 0x4000BC0C, 4, base=16, bitMask=0x00000010
sfr = "GPIO_PBWAKE.PB3", "Memory", 0x4000BC0C, 4, base=16, bitMask=0x00000008
sfr = "GPIO_PBWAKE.PB2", "Memory", 0x4000BC0C, 4, base=16, bitMask=0x00000004
sfr = "GPIO_PBWAKE.PB1", "Memory", 0x4000BC0C, 4, base=16, bitMask=0x00000002
sfr = "GPIO_PBWAKE.PB0", "Memory", 0x4000BC0C, 4, base=16, bitMask=0x00000001
sfr = "GPIO_PCWAKE", "Memory", 0x4000BC10, 4, base=16
sfr = "GPIO_PCWAKE.PC7", "Memory", 0x4000BC10, 4, base=16, bitMask=0x00000080
sfr = "GPIO_PCWAKE.PC6", "Memory", 0x4000BC10, 4, base=16, bitMask=0x00000040
sfr = "GPIO_PCWAKE.PC5", "Memory", 0x4000BC10, 4, base=16, bitMask=0x00000020
sfr = "GPIO_PCWAKE.PC4", "Memory", 0x4000BC10, 4, base=16, bitMask=0x00000010
sfr = "GPIO_PCWAKE.PC3", "Memory", 0x4000BC10, 4, base=16, bitMask=0x00000008
sfr = "GPIO_PCWAKE.PC2", "Memory", 0x4000BC10, 4, base=16, bitMask=0x00000004
sfr = "GPIO_PCWAKE.PC1", "Memory", 0x4000BC10, 4, base=16, bitMask=0x00000002
sfr = "GPIO_PCWAKE.PC0", "Memory", 0x4000BC10, 4, base=16, bitMask=0x00000001
sfr = "GPIO_IRQCSEL", "Memory", 0x4000BC14, 4, base=16
sfr = "GPIO_IRQDSEL", "Memory", 0x4000BC18, 4, base=16
sfr = "GPIO_WAKEFILT", "Memory", 0x4000BC1C, 4, base=16
sfr = "GPIO_WAKEFILT.IRQD_WAKE_FILTER", "Memory", 0x4000BC1C, 4, base=16, bitMask=0x00000008
sfr = "GPIO_WAKEFILT.SC2_WAKE_FILTER", "Memory", 0x4000BC1C, 4, base=16, bitMask=0x00000004
sfr = "GPIO_WAKEFILT.SC1_WAKE_FILTER", "Memory", 0x4000BC1C, 4, base=16, bitMask=0x00000002
sfr = "GPIO_WAKEFILT.GPIO_WAKE_FILTER", "Memory", 0x4000BC1C, 4, base=16, bitMask=0x00000001
sfr = "SC2_RXBEGA", "Memory", 0x4000C000, 4, base=16
sfr = "SC2_RXENDA", "Memory", 0x4000C004, 4, base=16
sfr = "SC2_RXBEGB", "Memory", 0x4000C008, 4, base=16
sfr = "SC2_RXENDB", "Memory", 0x4000C00C, 4, base=16
sfr = "SC2_TXBEGA", "Memory", 0x4000C010, 4, base=16
sfr = "SC2_TXENDA", "Memory", 0x4000C014, 4, base=16
sfr = "SC2_TXBEGB", "Memory", 0x4000C018, 4, base=16
sfr = "SC2_TXENDB", "Memory", 0x4000C01C, 4, base=16
sfr = "SC2_RXCNTA", "Memory", 0x4000C020, 4, base=16
sfr = "SC2_RXCNTB", "Memory", 0x4000C024, 4, base=16
sfr = "SC2_TXCNT", "Memory", 0x4000C028, 4, base=16
sfr = "SC2_DMASTAT", "Memory", 0x4000C02C, 4, base=16
sfr = "SC2_DMASTAT.SC_RXSSEL", "Memory", 0x4000C02C, 4, base=16, bitMask=0x00001C00
sfr = "SC2_DMASTAT.SC_RXOVFB", "Memory", 0x4000C02C, 4, base=16, bitMask=0x00000020
sfr = "SC2_DMASTAT.SC_RXOVFA", "Memory", 0x4000C02C, 4, base=16, bitMask=0x00000010
sfr = "SC2_DMASTAT.SC_TXACTB", "Memory", 0x4000C02C, 4, base=16, bitMask=0x00000008
sfr = "SC2_DMASTAT.SC_TXACTA", "Memory", 0x4000C02C, 4, base=16, bitMask=0x00000004
sfr = "SC2_DMASTAT.SC_RXACTB", "Memory", 0x4000C02C, 4, base=16, bitMask=0x00000002
sfr = "SC2_DMASTAT.SC_RXACTA", "Memory", 0x4000C02C, 4, base=16, bitMask=0x00000001
sfr = "SC2_DMACTRL", "Memory", 0x4000C030, 4, base=16
sfr = "SC2_DMACTRL.SC_TXDMARST", "Memory", 0x4000C030, 4, base=16, bitMask=0x00000020
sfr = "SC2_DMACTRL.SC_RXDMARST", "Memory", 0x4000C030, 4, base=16, bitMask=0x00000010
sfr = "SC2_DMACTRL.SC_TXLODB", "Memory", 0x4000C030, 4, base=16, bitMask=0x00000008
sfr = "SC2_DMACTRL.SC_TXLODA", "Memory", 0x4000C030, 4, base=16, bitMask=0x00000004
sfr = "SC2_DMACTRL.SC_RXLODB", "Memory", 0x4000C030, 4, base=16, bitMask=0x00000002
sfr = "SC2_DMACTRL.SC_RXLODA", "Memory", 0x4000C030, 4, base=16, bitMask=0x00000001
sfr = "SC2_RXERRA", "Memory", 0x4000C034, 4, base=16
sfr = "SC2_RXERRB", "Memory", 0x4000C038, 4, base=16
sfr = "SC2_DATA", "Memory", 0x4000C03C, 4, base=16
sfr = "SC2_SPISTAT", "Memory", 0x4000C040, 4, base=16
sfr = "SC2_SPISTAT.SC_SPITXIDLE", "Memory", 0x4000C040, 4, base=16, bitMask=0x00000008
sfr = "SC2_SPISTAT.SC_SPITXFREE", "Memory", 0x4000C040, 4, base=16, bitMask=0x00000004
sfr = "SC2_SPISTAT.SC_SPIRXVAL", "Memory", 0x4000C040, 4, base=16, bitMask=0x00000002
sfr = "SC2_SPISTAT.SC_SPIRXOVF", "Memory", 0x4000C040, 4, base=16, bitMask=0x00000001
sfr = "SC2_TWISTAT", "Memory", 0x4000C044, 4, base=16
sfr = "SC2_TWISTAT.SC_TWICMDFIN", "Memory", 0x4000C044, 4, base=16, bitMask=0x00000008
sfr = "SC2_TWISTAT.SC_TWIRXFIN", "Memory", 0x4000C044, 4, base=16, bitMask=0x00000004
sfr = "SC2_TWISTAT.SC_TWITXFIN", "Memory", 0x4000C044, 4, base=16, bitMask=0x00000002
sfr = "SC2_TWISTAT.SC_TWIRXNAK", "Memory", 0x4000C044, 4, base=16, bitMask=0x00000001
sfr = "SC2_TWICTRL1", "Memory", 0x4000C04C, 4, base=16
sfr = "SC2_TWICTRL1.SC_TWISTOP", "Memory", 0x4000C04C, 4, base=16, bitMask=0x00000008
sfr = "SC2_TWICTRL1.SC_TWISTART", "Memory", 0x4000C04C, 4, base=16, bitMask=0x00000004
sfr = "SC2_TWICTRL1.SC_TWISEND", "Memory", 0x4000C04C, 4, base=16, bitMask=0x00000002
sfr = "SC2_TWICTRL1.SC_TWIRECV", "Memory", 0x4000C04C, 4, base=16, bitMask=0x00000001
sfr = "SC2_TWICTRL2", "Memory", 0x4000C050, 4, base=16
sfr = "SC2_MODE", "Memory", 0x4000C054, 4, base=16
sfr = "SC2_SPICFG", "Memory", 0x4000C058, 4, base=16
sfr = "SC2_SPICFG.SC_SPIRXDRV", "Memory", 0x4000C058, 4, base=16, bitMask=0x00000020
sfr = "SC2_SPICFG.SC_SPIMST", "Memory", 0x4000C058, 4, base=16, bitMask=0x00000010
sfr = "SC2_SPICFG.SC_SPIRPT", "Memory", 0x4000C058, 4, base=16, bitMask=0x00000008
sfr = "SC2_SPICFG.SC_SPIORD", "Memory", 0x4000C058, 4, base=16, bitMask=0x00000004
sfr = "SC2_SPICFG.SC_SPIPHA", "Memory", 0x4000C058, 4, base=16, bitMask=0x00000002
sfr = "SC2_SPICFG.SC_SPIPOL", "Memory", 0x4000C058, 4, base=16, bitMask=0x00000001
sfr = "SC2_RATELIN", "Memory", 0x4000C060, 4, base=16
sfr = "SC2_RATELIN.SC_RATELIN", "Memory", 0x4000C060, 4, base=16, bitMask=0x0000000F
sfr = "SC2_RATEEXP", "Memory", 0x4000C064, 4, base=16
sfr = "SC2_RATEEXP.SC_RATEEXP", "Memory", 0x4000C064, 4, base=16, bitMask=0x0000000F
sfr = "SC2_RXCNTSAVED", "Memory", 0x4000C070, 4, base=16
sfr = "SC1_RXBEGA", "Memory", 0x4000C800, 4, base=16
sfr = "SC1_RXENDA", "Memory", 0x4000C804, 4, base=16
sfr = "SC1_RXBEGB", "Memory", 0x4000C808, 4, base=16
sfr = "SC1_RXENDB", "Memory", 0x4000C80C, 4, base=16
sfr = "SC1_TXBEGA", "Memory", 0x4000C810, 4, base=16
sfr = "SC1_TXENDA", "Memory", 0x4000C814, 4, base=16
sfr = "SC1_TXBEGB", "Memory", 0x4000C818, 4, base=16
sfr = "SC1_TXENDB", "Memory", 0x4000C81C, 4, base=16
sfr = "SC1_RXCNTA", "Memory", 0x4000C820, 4, base=16
sfr = "SC1_RXCNTB", "Memory", 0x4000C824, 4, base=16
sfr = "SC1_TXCNT", "Memory", 0x4000C828, 4, base=16
sfr = "SC1_DMASTAT", "Memory", 0x4000C82C, 4, base=16
sfr = "SC1_DMASTAT.SC_RXSSEL", "Memory", 0x4000C82C, 4, base=16, bitMask=0x00001C00
sfr = "SC1_DMASTAT.SC_RXFRMB", "Memory", 0x4000C82C, 4, base=16, bitMask=0x00000200
sfr = "SC1_DMASTAT.SC_RXFRMA", "Memory", 0x4000C82C, 4, base=16, bitMask=0x00000100
sfr = "SC1_DMASTAT.SC_RXPARB", "Memory", 0x4000C82C, 4, base=16, bitMask=0x00000080
sfr = "SC1_DMASTAT.SC_RXPARA", "Memory", 0x4000C82C, 4, base=16, bitMask=0x00000040
sfr = "SC1_DMASTAT.SC_RXOVFB", "Memory", 0x4000C82C, 4, base=16, bitMask=0x00000020
sfr = "SC1_DMASTAT.SC_RXOVFA", "Memory", 0x4000C82C, 4, base=16, bitMask=0x00000010
sfr = "SC1_DMASTAT.SC_TXACTB", "Memory", 0x4000C82C, 4, base=16, bitMask=0x00000008
sfr = "SC1_DMASTAT.SC_TXACTA", "Memory", 0x4000C82C, 4, base=16, bitMask=0x00000004
sfr = "SC1_DMASTAT.SC_RXACTB", "Memory", 0x4000C82C, 4, base=16, bitMask=0x00000002
sfr = "SC1_DMASTAT.SC_RXACTA", "Memory", 0x4000C82C, 4, base=16, bitMask=0x00000001
sfr = "SC1_DMACTRL", "Memory", 0x4000C830, 4, base=16
sfr = "SC1_DMACTRL.SC_TXDMARST", "Memory", 0x4000C830, 4, base=16, bitMask=0x00000020
sfr = "SC1_DMACTRL.SC_RXDMARST", "Memory", 0x4000C830, 4, base=16, bitMask=0x00000010
sfr = "SC1_DMACTRL.SC_TXLODB", "Memory", 0x4000C830, 4, base=16, bitMask=0x00000008
sfr = "SC1_DMACTRL.SC_TXLODA", "Memory", 0x4000C830, 4, base=16, bitMask=0x00000004
sfr = "SC1_DMACTRL.SC_RXLODB", "Memory", 0x4000C830, 4, base=16, bitMask=0x00000002
sfr = "SC1_DMACTRL.SC_RXLODA", "Memory", 0x4000C830, 4, base=16, bitMask=0x00000001
sfr = "SC1_RXERRA", "Memory", 0x4000C834, 4, base=16
sfr = "SC1_RXERRB", "Memory", 0x4000C838, 4, base=16
sfr = "SC1_DATA", "Memory", 0x4000C83C, 4, base=16
sfr = "SC1_SPISTAT", "Memory", 0x4000C840, 4, base=16
sfr = "SC1_SPISTAT.SC_SPITXIDLE", "Memory", 0x4000C840, 4, base=16, bitMask=0x00000008
sfr = "SC1_SPISTAT.SC_SPITXFREE", "Memory", 0x4000C840, 4, base=16, bitMask=0x00000004
sfr = "SC1_SPISTAT.SC_SPIRXVAL", "Memory", 0x4000C840, 4, base=16, bitMask=0x00000002
sfr = "SC1_SPISTAT.SC_SPIRXOVF", "Memory", 0x4000C840, 4, base=16, bitMask=0x00000001
sfr = "SC1_TWISTAT", "Memory", 0x4000C844, 4, base=16
sfr = "SC1_TWISTAT.SC_TWICMDFIN", "Memory", 0x4000C844, 4, base=16, bitMask=0x00000008
sfr = "SC1_TWISTAT.SC_TWIRXFIN", "Memory", 0x4000C844, 4, base=16, bitMask=0x00000004
sfr = "SC1_TWISTAT.SC_TWITXFIN", "Memory", 0x4000C844, 4, base=16, bitMask=0x00000002
sfr = "SC1_TWISTAT.SC_TWIRXNAK", "Memory", 0x4000C844, 4, base=16, bitMask=0x00000001
sfr = "SC1_UARTSTAT", "Memory", 0x4000C848, 4, base=16
sfr = "SC1_UARTSTAT.SC_UARTTXIDLE", "Memory", 0x4000C848, 4, base=16, bitMask=0x00000040
sfr = "SC1_UARTSTAT.SC_UARTPARERR", "Memory", 0x4000C848, 4, base=16, bitMask=0x00000020
sfr = "SC1_UARTSTAT.SC_UARTFRMERR", "Memory", 0x4000C848, 4, base=16, bitMask=0x00000010
sfr = "SC1_UARTSTAT.SC_UARTRXOVF", "Memory", 0x4000C848, 4, base=16, bitMask=0x00000008
sfr = "SC1_UARTSTAT.SC_UARTTXFREE", "Memory", 0x4000C848, 4, base=16, bitMask=0x00000004
sfr = "SC1_UARTSTAT.SC_UARTRXVAL", "Memory", 0x4000C848, 4, base=16, bitMask=0x00000002
sfr = "SC1_UARTSTAT.SC_UARTCTS", "Memory", 0x4000C848, 4, base=16, bitMask=0x00000001
sfr = "SC1_TWICTRL1", "Memory", 0x4000C84C, 4, base=16
sfr = "SC1_TWICTRL1.SC_TWISTOP", "Memory", 0x4000C84C, 4, base=16, bitMask=0x00000008
sfr = "SC1_TWICTRL1.SC_TWISTART", "Memory", 0x4000C84C, 4, base=16, bitMask=0x00000004
sfr = "SC1_TWICTRL1.SC_TWISEND", "Memory", 0x4000C84C, 4, base=16, bitMask=0x00000002
sfr = "SC1_TWICTRL1.SC_TWIRECV", "Memory", 0x4000C84C, 4, base=16, bitMask=0x00000001
sfr = "SC1_TWICTRL2", "Memory", 0x4000C850, 4, base=16
sfr = "SC1_MODE", "Memory", 0x4000C854, 4, base=16
sfr = "SC1_SPICFG", "Memory", 0x4000C858, 4, base=16
sfr = "SC1_SPICFG.SC_SPIRXDRV", "Memory", 0x4000C858, 4, base=16, bitMask=0x00000020
sfr = "SC1_SPICFG.SC_SPIMST", "Memory", 0x4000C858, 4, base=16, bitMask=0x00000010
sfr = "SC1_SPICFG.SC_SPIRPT", "Memory", 0x4000C858, 4, base=16, bitMask=0x00000008
sfr = "SC1_SPICFG.SC_SPIORD", "Memory", 0x4000C858, 4, base=16, bitMask=0x00000004
sfr = "SC1_SPICFG.SC_SPIPHA", "Memory", 0x4000C858, 4, base=16, bitMask=0x00000002
sfr = "SC1_SPICFG.SC_SPIPOL", "Memory", 0x4000C858, 4, base=16, bitMask=0x00000001
sfr = "SC1_UARTCFG", "Memory", 0x4000C85C, 4, base=16
sfr = "SC1_UARTCFG.SC_UARTAUTO", "Memory", 0x4000C85C, 4, base=16, bitMask=0x00000040
sfr = "SC1_UARTCFG.SC_UARTFLOW", "Memory", 0x4000C85C, 4, base=16, bitMask=0x00000020
sfr = "SC1_UARTCFG.SC_UARTODD", "Memory", 0x4000C85C, 4, base=16, bitMask=0x00000010
sfr = "SC1_UARTCFG.SC_UARTPAR", "Memory", 0x4000C85C, 4, base=16, bitMask=0x00000008
sfr = "SC1_UARTCFG.SC_UART2STP", "Memory", 0x4000C85C, 4, base=16, bitMask=0x00000004
sfr = "SC1_UARTCFG.SC_UART8BIT", "Memory", 0x4000C85C, 4, base=16, bitMask=0x00000002
sfr = "SC1_UARTCFG.SC_UARTRTS", "Memory", 0x4000C85C, 4, base=16, bitMask=0x00000001
sfr = "SC1_RATELIN", "Memory", 0x4000C860, 4, base=16
sfr = "SC1_RATEEXP", "Memory", 0x4000C864, 4, base=16
sfr = "SC1_UARTPER", "Memory", 0x4000C868, 4, base=16
sfr = "SC1_UARTFRAC", "Memory", 0x4000C86C, 4, base=16
sfr = "SC1_RXCNTSAVED", "Memory", 0x4000C870, 4, base=16
sfr = "ADC_CFG", "Memory", 0x4000D004, 4, base=16
sfr = "ADC_CFG.ADC_PERIOD", "Memory", 0x4000D004, 4, base=16, bitMask=0x0000E000
sfr = "ADC_CFG.ADC_HVSELP", "Memory", 0x4000D004, 4, base=16, bitMask=0x00001000
sfr = "ADC_CFG.ADC_HVSELN", "Memory", 0x4000D004, 4, base=16, bitMask=0x00000800
sfr = "ADC_CFG.ADC_MUXP", "Memory", 0x4000D004, 4, base=16, bitMask=0x00000780
sfr = "ADC_CFG.ADC_MUXN", "Memory", 0x4000D004, 4, base=16, bitMask=0x00000078
sfr = "ADC_CFG.ADC_1MHZCLK", "Memory", 0x4000D004, 4, base=16, bitMask=0x00000004
sfr = "ADC_CFG.ADC_CFGRSVD", "Memory", 0x4000D004, 4, base=16, bitMask=0x00000002
sfr = "ADC_CFG.ADC_ENABLE", "Memory", 0x4000D004, 4, base=16, bitMask=0x00000001
sfr = "ADC_OFFSET", "Memory", 0x4000D008, 4, base=16
sfr = "ADC_GAIN", "Memory", 0x4000D00C, 4, base=16
sfr = "ADC_DMACFG", "Memory", 0x4000D010, 4, base=16
sfr = "ADC_DMACFG.ADC_DMARST", "Memory", 0x4000D010, 4, base=16, bitMask=0x00000010
sfr = "ADC_DMACFG.ADC_DMAAUTOWRAP", "Memory", 0x4000D010, 4, base=16, bitMask=0x00000002
sfr = "ADC_DMACFG.ADC_DMALOAD", "Memory", 0x4000D010, 4, base=16, bitMask=0x00000001
sfr = "ADC_DMASTAT", "Memory", 0x4000D014, 4, base=16
sfr = "ADC_DMASTAT.ADC_DMAOVF", "Memory", 0x4000D014, 4, base=16, bitMask=0x00000002
sfr = "ADC_DMASTAT.ADC_DMAACT", "Memory", 0x4000D014, 4, base=16, bitMask=0x00000001
sfr = "ADC_DMABEG", "Memory", 0x4000D018, 4, base=16
sfr = "ADC_DMASIZE", "Memory", 0x4000D01C, 4, base=16
sfr = "ADC_DMACUR", "Memory", 0x4000D020, 4, base=16
sfr = "ADC_DMACNT", "Memory", 0x4000D024, 4, base=16
sfr = "TIM1_CR1", "Memory", 0x4000E000, 4, base=16
sfr = "TIM1_CR1.TIM_ARBE", "Memory", 0x4000E000, 4, base=16, bitMask=0x00000080
sfr = "TIM1_CR1.TIM_CMS", "Memory", 0x4000E000, 4, base=16, bitMask=0x00000060
sfr = "TIM1_CR1.TIM_DIR", "Memory", 0x4000E000, 4, base=16, bitMask=0x00000010
sfr = "TIM1_CR1.TIM_OPM", "Memory", 0x4000E000, 4, base=16, bitMask=0x00000008
sfr = "TIM1_CR1.TIM_URS", "Memory", 0x4000E000, 4, base=16, bitMask=0x00000004
sfr = "TIM1_CR1.TIM_UDIS", "Memory", 0x4000E000, 4, base=16, bitMask=0x00000002
sfr = "TIM1_CR1.TIM_CEN", "Memory", 0x4000E000, 4, base=16, bitMask=0x00000001
sfr = "TIM1_CR2", "Memory", 0x4000E004, 4, base=16
sfr = "TIM1_CR2.TIM_TI1S", "Memory", 0x4000E004, 4, base=16, bitMask=0x00000080
sfr = "TIM1_CR2.TIM_MMS", "Memory", 0x4000E004, 4, base=16, bitMask=0x00000070
sfr = "TIM1_SMCR", "Memory", 0x4000E008, 4, base=16
sfr = "TIM1_SMCR.TIM_ETP", "Memory", 0x4000E008, 4, base=16, bitMask=0x00008000
sfr = "TIM1_SMCR.TIM_ECE", "Memory", 0x4000E008, 4, base=16, bitMask=0x00004000
sfr = "TIM1_SMCR.TIM_ETPS", "Memory", 0x4000E008, 4, base=16, bitMask=0x00003000
sfr = "TIM1_SMCR.TIM_ETF", "Memory", 0x4000E008, 4, base=16, bitMask=0x00000F00
sfr = "TIM1_SMCR.TIM_MSM", "Memory", 0x4000E008, 4, base=16, bitMask=0x00000080
sfr = "TIM1_SMCR.TIM_TS", "Memory", 0x4000E008, 4, base=16, bitMask=0x00000070
sfr = "TIM1_SMCR.TIM_SMS", "Memory", 0x4000E008, 4, base=16, bitMask=0x00000007
sfr = "TIM1_EGR", "Memory", 0x4000E014, 4, base=16
sfr = "TIM1_EGR.TIM_TG", "Memory", 0x4000E014, 4, base=16, bitMask=0x00000040
sfr = "TIM1_EGR.TIM_CC4G", "Memory", 0x4000E014, 4, base=16, bitMask=0x00000010
sfr = "TIM1_EGR.TIM_CC3G", "Memory", 0x4000E014, 4, base=16, bitMask=0x00000008
sfr = "TIM1_EGR.TIM_CC2G", "Memory", 0x4000E014, 4, base=16, bitMask=0x00000004
sfr = "TIM1_EGR.TIM_CC1G", "Memory", 0x4000E014, 4, base=16, bitMask=0x00000002
sfr = "TIM1_EGR.TIM_UG", "Memory", 0x4000E014, 4, base=16, bitMask=0x00000001
sfr = "TIM1_CCMR1", "Memory", 0x4000E018, 4, base=16
sfr = "TIM1_CCMR1.TIM_IC2F", "Memory", 0x4000E018, 4, base=16, bitMask=0x0000F000
sfr = "TIM1_CCMR1.TIM_IC2PSC", "Memory", 0x4000E018, 4, base=16, bitMask=0x00000C00
sfr = "TIM1_CCMR1.TIM_IC1F", "Memory", 0x4000E018, 4, base=16, bitMask=0x000000F0
sfr = "TIM1_CCMR1.TIM_IC1PSC", "Memory", 0x4000E018, 4, base=16, bitMask=0x0000000C
sfr = "TIM1_CCMR1.TIM_OC2CE", "Memory", 0x4000E018, 4, base=16, bitMask=0x00008000
sfr = "TIM1_CCMR1.TIM_OC2M", "Memory", 0x4000E018, 4, base=16, bitMask=0x00007000
sfr = "TIM1_CCMR1.TIM_OC2BE", "Memory", 0x4000E018, 4, base=16, bitMask=0x00000800
sfr = "TIM1_CCMR1.TIM_OC2FE", "Memory", 0x4000E018, 4, base=16, bitMask=0x00000400
sfr = "TIM1_CCMR1.TIM_CC2S", "Memory", 0x4000E018, 4, base=16, bitMask=0x00000300
sfr = "TIM1_CCMR1.TIM_OC1CE", "Memory", 0x4000E018, 4, base=16, bitMask=0x00000080
sfr = "TIM1_CCMR1.TIM_OC1M", "Memory", 0x4000E018, 4, base=16, bitMask=0x00000070
sfr = "TIM1_CCMR1.TIM_OC1PE", "Memory", 0x4000E018, 4, base=16, bitMask=0x00000008
sfr = "TIM1_CCMR1.TIM_OC1FE", "Memory", 0x4000E018, 4, base=16, bitMask=0x00000004
sfr = "TIM1_CCMR1.TIM_CC1S", "Memory", 0x4000E018, 4, base=16, bitMask=0x00000003
sfr = "TIM1_CCMR2", "Memory", 0x4000E01C, 4, base=16
sfr = "TIM1_CCMR2.TIM_IC4F", "Memory", 0x4000E01C, 4, base=16, bitMask=0x0000F000
sfr = "TIM1_CCMR2.TIM_IC4PSC", "Memory", 0x4000E01C, 4, base=16, bitMask=0x00000C00
sfr = "TIM1_CCMR2.TIM_IC3F", "Memory", 0x4000E01C, 4, base=16, bitMask=0x000000F0
sfr = "TIM1_CCMR2.TIM_IC3PSC", "Memory", 0x4000E01C, 4, base=16, bitMask=0x0000000C
sfr = "TIM1_CCMR2.TIM_OC4CE", "Memory", 0x4000E01C, 4, base=16, bitMask=0x00008000
sfr = "TIM1_CCMR2.TIM_OC4M", "Memory", 0x4000E01C, 4, base=16, bitMask=0x00007000
sfr = "TIM1_CCMR2.TIM_OC4BE", "Memory", 0x4000E01C, 4, base=16, bitMask=0x00000800
sfr = "TIM1_CCMR2.TIM_OC4FE", "Memory", 0x4000E01C, 4, base=16, bitMask=0x00000400
sfr = "TIM1_CCMR2.TIM_CC4S", "Memory", 0x4000E01C, 4, base=16, bitMask=0x00000300
sfr = "TIM1_CCMR2.TIM_OC3CE", "Memory", 0x4000E01C, 4, base=16, bitMask=0x00000080
sfr = "TIM1_CCMR2.TIM_OC3M", "Memory", 0x4000E01C, 4, base=16, bitMask=0x00000070
sfr = "TIM1_CCMR2.TIM_OC3BE", "Memory", 0x4000E01C, 4, base=16, bitMask=0x00000008
sfr = "TIM1_CCMR2.TIM_OC3FE", "Memory", 0x4000E01C, 4, base=16, bitMask=0x00000004
sfr = "TIM1_CCMR2.TIM_CC3S", "Memory", 0x4000E01C, 4, base=16, bitMask=0x00000003
sfr = "TIM1_CCER", "Memory", 0x4000E020, 4, base=16
sfr = "TIM1_CCER.TIM_CC4P", "Memory", 0x4000E020, 4, base=16, bitMask=0x00002000
sfr = "TIM1_CCER.TIM_CC4E", "Memory", 0x4000E020, 4, base=16, bitMask=0x00001000
sfr = "TIM1_CCER.TIM_CC3P", "Memory", 0x4000E020, 4, base=16, bitMask=0x00000200
sfr = "TIM1_CCER.TIM_CC3E", "Memory", 0x4000E020, 4, base=16, bitMask=0x00000100
sfr = "TIM1_CCER.TIM_CC2P", "Memory", 0x4000E020, 4, base=16, bitMask=0x00000020
sfr = "TIM1_CCER.TIM_CC2E", "Memory", 0x4000E020, 4, base=16, bitMask=0x00000010
sfr = "TIM1_CCER.TIM_CC1P", "Memory", 0x4000E020, 4, base=16, bitMask=0x00000002
sfr = "TIM1_CCER.TIM_CC1E", "Memory", 0x4000E020, 4, base=16, bitMask=0x00000001
sfr = "TIM1_CNT", "Memory", 0x4000E024, 4, base=16
sfr = "TIM1_PSC", "Memory", 0x4000E028, 4, base=16
sfr = "TIM1_ARR", "Memory", 0x4000E02C, 4, base=16
sfr = "TIM1_CCR1", "Memory", 0x4000E034, 4, base=16
sfr = "TIM1_CCR2", "Memory", 0x4000E038, 4, base=16
sfr = "TIM1_CCR3", "Memory", 0x4000E03C, 4, base=16
sfr = "TIM1_CCR4", "Memory", 0x4000E040, 4, base=16
sfr = "TIM1_OR", "Memory", 0x4000E050, 4, base=16
sfr = "TIM1_OR.TIM_ORRSVD", "Memory", 0x4000E050, 4, base=16, bitMask=0x00000008
sfr = "TIM1_OR.TIM_CLKMSKEN", "Memory", 0x4000E050, 4, base=16, bitMask=0x00000004
sfr = "TIM1_OR.TIM1_EXTRIGSEL", "Memory", 0x4000E050, 4, base=16, bitMask=0x00000003
sfr = "TIM2_CR1", "Memory", 0x4000F000, 4, base=16
sfr = "TIM2_CR1.TIM_ARBE", "Memory", 0x4000F000, 4, base=16, bitMask=0x00000080
sfr = "TIM2_CR1.TIM_CMS", "Memory", 0x4000F000, 4, base=16, bitMask=0x00000060
sfr = "TIM2_CR1.TIM_DIR", "Memory", 0x4000F000, 4, base=16, bitMask=0x00000010
sfr = "TIM2_CR1.TIM_OPM", "Memory", 0x4000F000, 4, base=16, bitMask=0x00000008
sfr = "TIM2_CR1.TIM_URS", "Memory", 0x4000F000, 4, base=16, bitMask=0x00000004
sfr = "TIM2_CR1.TIM_UDIS", "Memory", 0x4000F000, 4, base=16, bitMask=0x00000002
sfr = "TIM2_CR1.TIM_CEN", "Memory", 0x4000F000, 4, base=16, bitMask=0x00000001
sfr = "TIM2_CR2", "Memory", 0x4000F004, 4, base=16
sfr = "TIM2_CR2.TIM_TI1S", "Memory", 0x4000F004, 4, base=16, bitMask=0x00000080
sfr = "TIM2_CR2.TIM_MMS", "Memory", 0x4000F004, 4, base=16, bitMask=0x00000070
sfr = "TIM2_SMCR", "Memory", 0x4000F008, 4, base=16
sfr = "TIM2_SMCR.TIM_ETP", "Memory", 0x4000F008, 4, base=16, bitMask=0x00008000
sfr = "TIM2_SMCR.TIM_ECE", "Memory", 0x4000F008, 4, base=16, bitMask=0x00004000
sfr = "TIM2_SMCR.TIM_ETPS", "Memory", 0x4000F008, 4, base=16, bitMask=0x00003000
sfr = "TIM2_SMCR.TIM_ETF", "Memory", 0x4000F008, 4, base=16, bitMask=0x00000F00
sfr = "TIM2_SMCR.TIM_MSM", "Memory", 0x4000F008, 4, base=16, bitMask=0x00000080
sfr = "TIM2_SMCR.TIM_TS", "Memory", 0x4000F008, 4, base=16, bitMask=0x00000070
sfr = "TIM2_SMCR.TIM_SMS", "Memory", 0x4000F008, 4, base=16, bitMask=0x00000007
sfr = "TIM2_EGR", "Memory", 0x4000F014, 4, base=16
sfr = "TIM2_EGR.TIM_TG", "Memory", 0x4000F014, 4, base=16, bitMask=0x00000040
sfr = "TIM2_EGR.TIM_CC4G", "Memory", 0x4000F014, 4, base=16, bitMask=0x00000010
sfr = "TIM2_EGR.TIM_CC3G", "Memory", 0x4000F014, 4, base=16, bitMask=0x00000008
sfr = "TIM2_EGR.TIM_CC2G", "Memory", 0x4000F014, 4, base=16, bitMask=0x00000004
sfr = "TIM2_EGR.TIM_CC1G", "Memory", 0x4000F014, 4, base=16, bitMask=0x00000002
sfr = "TIM2_EGR.TIM_UG", "Memory", 0x4000F014, 4, base=16, bitMask=0x00000001
sfr = "TIM2_CCMR1", "Memory", 0x4000F018, 4, base=16
sfr = "TIM2_CCMR1.TIM_IC2F", "Memory", 0x4000F018, 4, base=16, bitMask=0x0000F000
sfr = "TIM2_CCMR1.TIM_IC2PSC", "Memory", 0x4000F018, 4, base=16, bitMask=0x00000C00
sfr = "TIM2_CCMR1.TIM_IC1F", "Memory", 0x4000F018, 4, base=16, bitMask=0x000000F0
sfr = "TIM2_CCMR1.TIM_IC1PSC", "Memory", 0x4000F018, 4, base=16, bitMask=0x0000000C
sfr = "TIM2_CCMR1.TIM_OC2CE", "Memory", 0x4000F018, 4, base=16, bitMask=0x00008000
sfr = "TIM2_CCMR1.TIM_OC2M", "Memory", 0x4000F018, 4, base=16, bitMask=0x00007000
sfr = "TIM2_CCMR1.TIM_OC2BE", "Memory", 0x4000F018, 4, base=16, bitMask=0x00000800
sfr = "TIM2_CCMR1.TIM_OC2FE", "Memory", 0x4000F018, 4, base=16, bitMask=0x00000400
sfr = "TIM2_CCMR1.TIM_CC2S", "Memory", 0x4000F018, 4, base=16, bitMask=0x00000300
sfr = "TIM2_CCMR1.TIM_OC1CE", "Memory", 0x4000F018, 4, base=16, bitMask=0x00000080
sfr = "TIM2_CCMR1.TIM_OC1M", "Memory", 0x4000F018, 4, base=16, bitMask=0x00000070
sfr = "TIM2_CCMR1.TIM_OC1PE", "Memory", 0x4000F018, 4, base=16, bitMask=0x00000008
sfr = "TIM2_CCMR1.TIM_OC1FE", "Memory", 0x4000F018, 4, base=16, bitMask=0x00000004
sfr = "TIM2_CCMR1.TIM_CC1S", "Memory", 0x4000F018, 4, base=16, bitMask=0x00000003
sfr = "TIM2_CCMR2", "Memory", 0x4000F01C, 4, base=16
sfr = "TIM2_CCMR2.TIM_IC4F", "Memory", 0x4000F01C, 4, base=16, bitMask=0x0000F000
sfr = "TIM2_CCMR2.TIM_IC4PSC", "Memory", 0x4000F01C, 4, base=16, bitMask=0x00000C00
sfr = "TIM2_CCMR2.TIM_IC3F", "Memory", 0x4000F01C, 4, base=16, bitMask=0x000000F0
sfr = "TIM2_CCMR2.TIM_IC3PSC", "Memory", 0x4000F01C, 4, base=16, bitMask=0x0000000C
sfr = "TIM2_CCMR2.TIM_OC4CE", "Memory", 0x4000F01C, 4, base=16, bitMask=0x00008000
sfr = "TIM2_CCMR2.TIM_OC4M", "Memory", 0x4000F01C, 4, base=16, bitMask=0x00007000
sfr = "TIM2_CCMR2.TIM_OC4BE", "Memory", 0x4000F01C, 4, base=16, bitMask=0x00000800
sfr = "TIM2_CCMR2.TIM_OC4FE", "Memory", 0x4000F01C, 4, base=16, bitMask=0x00000400
sfr = "TIM2_CCMR2.TIM_CC4S", "Memory", 0x4000F01C, 4, base=16, bitMask=0x00000300
sfr = "TIM2_CCMR2.TIM_OC3CE", "Memory", 0x4000F01C, 4, base=16, bitMask=0x00000080
sfr = "TIM2_CCMR2.TIM_OC3M", "Memory", 0x4000F01C, 4, base=16, bitMask=0x00000070
sfr = "TIM2_CCMR2.TIM_OC3BE", "Memory", 0x4000F01C, 4, base=16, bitMask=0x00000008
sfr = "TIM2_CCMR2.TIM_OC3FE", "Memory", 0x4000F01C, 4, base=16, bitMask=0x00000004
sfr = "TIM2_CCMR2.TIM_CC3S", "Memory", 0x4000F01C, 4, base=16, bitMask=0x00000003
sfr = "TIM2_CCER", "Memory", 0x4000F020, 4, base=16
sfr = "TIM2_CCER.TIM_CC4P", "Memory", 0x4000F020, 4, base=16, bitMask=0x00002000
sfr = "TIM2_CCER.TIM_CC4E", "Memory", 0x4000F020, 4, base=16, bitMask=0x00001000
sfr = "TIM2_CCER.TIM_CC3P", "Memory", 0x4000F020, 4, base=16, bitMask=0x00000200
sfr = "TIM2_CCER.TIM_CC3E", "Memory", 0x4000F020, 4, base=16, bitMask=0x00000100
sfr = "TIM2_CCER.TIM_CC2P", "Memory", 0x4000F020, 4, base=16, bitMask=0x00000020
sfr = "TIM2_CCER.TIM_CC2E", "Memory", 0x4000F020, 4, base=16, bitMask=0x00000010
sfr = "TIM2_CCER.TIM_CC1P", "Memory", 0x4000F020, 4, base=16, bitMask=0x00000002
sfr = "TIM2_CCER.TIM_CC1E", "Memory", 0x4000F020, 4, base=16, bitMask=0x00000001
sfr = "TIM2_CNT", "Memory", 0x4000F024, 4, base=16
sfr = "TIM2_PSC", "Memory", 0x4000F028, 4, base=16
sfr = "TIM2_ARR", "Memory", 0x4000F02C, 4, base=16
sfr = "TIM2_CCR1", "Memory", 0x4000F034, 4, base=16
sfr = "TIM2_CCR2", "Memory", 0x4000F038, 4, base=16
sfr = "TIM2_CCR3", "Memory", 0x4000F03C, 4, base=16
sfr = "TIM2_CCR4", "Memory", 0x4000F040, 4, base=16
sfr = "TIM2_OR", "Memory", 0x4000F050, 4, base=16
sfr = "TIM2_OR.TIM_REMAPC4", "Memory", 0x4000F050, 4, base=16, bitMask=0x00000080
sfr = "TIM2_OR.TIM_REMAPC3", "Memory", 0x4000F050, 4, base=16, bitMask=0x00000040
sfr = "TIM2_OR.TIM_REMAPC2", "Memory", 0x4000F050, 4, base=16, bitMask=0x00000020
sfr = "TIM2_OR.TIM_REMAPC1", "Memory", 0x4000F050, 4, base=16, bitMask=0x00000010
sfr = "TIM2_OR.TIM_ORRSVD", "Memory", 0x4000F050, 4, base=16, bitMask=0x00000008
sfr = "TIM2_OR.TIM_CLKMSKEN", "Memory", 0x4000F050, 4, base=16, bitMask=0x00000004
sfr = "TIM2_OR.TIM1_EXTRIGSEL", "Memory", 0x4000F050, 4, base=16, bitMask=0x00000003
sfr = "INT_CFGSET", "Memory", 0xE000E100, 4, base=16
sfr = "INT_CFGSET.INT_DEBUG", "Memory", 0xE000E100, 4, base=16, bitMask=0x00010000
sfr = "INT_CFGSET.INT_IRQD", "Memory", 0xE000E100, 4, base=16, bitMask=0x00008000
sfr = "INT_CFGSET.INT_IRQC", "Memory", 0xE000E100, 4, base=16, bitMask=0x00004000
sfr = "INT_CFGSET.INT_IRQB", "Memory", 0xE000E100, 4, base=16, bitMask=0x00002000
sfr = "INT_CFGSET.INT_IRQA", "Memory", 0xE000E100, 4, base=16, bitMask=0x00001000
sfr = "INT_CFGSET.INT_ADC", "Memory", 0xE000E100, 4, base=16, bitMask=0x00000800
sfr = "INT_CFGSET.INT_MACRX", "Memory", 0xE000E100, 4, base=16, bitMask=0x00000400
sfr = "INT_CFGSET.INT_MACTX", "Memory", 0xE000E100, 4, base=16, bitMask=0x00000200
sfr = "INT_CFGSET.INT_MACTMR", "Memory", 0xE000E100, 4, base=16, bitMask=0x00000100
sfr = "INT_CFGSET.INT_SEC", "Memory", 0xE000E100, 4, base=16, bitMask=0x00000080
sfr = "INT_CFGSET.INT_SC2", "Memory", 0xE000E100, 4, base=16, bitMask=0x00000040
sfr = "INT_CFGSET.INT_SC1", "Memory", 0xE000E100, 4, base=16, bitMask=0x00000020
sfr = "INT_CFGSET.INT_SLEEPTMR", "Memory", 0xE000E100, 4, base=16, bitMask=0x00000010
sfr = "INT_CFGSET.INT_BB", "Memory", 0xE000E100, 4, base=16, bitMask=0x00000008
sfr = "INT_CFGSET.INT_MGMT", "Memory", 0xE000E100, 4, base=16, bitMask=0x00000004
sfr = "INT_CFGSET.INT_TIM2", "Memory", 0xE000E100, 4, base=16, bitMask=0x00000002
sfr = "INT_CFGSET.INT_TIM1", "Memory", 0xE000E100, 4, base=16, bitMask=0x00000001
sfr = "INT_CFGCLR", "Memory", 0xE000E180, 4, base=16
sfr = "INT_CFGCLR.INT_DEBUG", "Memory", 0xE000E180, 4, base=16, bitMask=0x00010000
sfr = "INT_CFGCLR.INT_IRQD", "Memory", 0xE000E180, 4, base=16, bitMask=0x00008000
sfr = "INT_CFGCLR.INT_IRQC", "Memory", 0xE000E180, 4, base=16, bitMask=0x00004000
sfr = "INT_CFGCLR.INT_IRQB", "Memory", 0xE000E180, 4, base=16, bitMask=0x00002000
sfr = "INT_CFGCLR.INT_IRQA", "Memory", 0xE000E180, 4, base=16, bitMask=0x00001000
sfr = "INT_CFGCLR.INT_ADC", "Memory", 0xE000E180, 4, base=16, bitMask=0x00000800
sfr = "INT_CFGCLR.INT_MACRX", "Memory", 0xE000E180, 4, base=16, bitMask=0x00000400
sfr = "INT_CFGCLR.INT_MACTX", "Memory", 0xE000E180, 4, base=16, bitMask=0x00000200
sfr = "INT_CFGCLR.INT_MACTMR", "Memory", 0xE000E180, 4, base=16, bitMask=0x00000100
sfr = "INT_CFGCLR.INT_SEC", "Memory", 0xE000E180, 4, base=16, bitMask=0x00000080
sfr = "INT_CFGCLR.INT_SC2", "Memory", 0xE000E180, 4, base=16, bitMask=0x00000040
sfr = "INT_CFGCLR.INT_SC1", "Memory", 0xE000E180, 4, base=16, bitMask=0x00000020
sfr = "INT_CFGCLR.INT_SLEEPTMR", "Memory", 0xE000E180, 4, base=16, bitMask=0x00000010
sfr = "INT_CFGCLR.INT_BB", "Memory", 0xE000E180, 4, base=16, bitMask=0x00000008
sfr = "INT_CFGCLR.INT_MGMT", "Memory", 0xE000E180, 4, base=16, bitMask=0x00000004
sfr = "INT_CFGCLR.INT_TIM2", "Memory", 0xE000E180, 4, base=16, bitMask=0x00000002
sfr = "INT_CFGCLR.INT_TIM1", "Memory", 0xE000E180, 4, base=16, bitMask=0x00000001
sfr = "INT_PENDSET", "Memory", 0xE000E200, 4, base=16
sfr = "INT_PENDSET.INT_DEBUG", "Memory", 0xE000E200, 4, base=16, bitMask=0x00010000
sfr = "INT_PENDSET.INT_IRQD", "Memory", 0xE000E200, 4, base=16, bitMask=0x00008000
sfr = "INT_PENDSET.INT_IRQC", "Memory", 0xE000E200, 4, base=16, bitMask=0x00004000
sfr = "INT_PENDSET.INT_IRQB", "Memory", 0xE000E200, 4, base=16, bitMask=0x00002000
sfr = "INT_PENDSET.INT_IRQA", "Memory", 0xE000E200, 4, base=16, bitMask=0x00001000
sfr = "INT_PENDSET.INT_ADC", "Memory", 0xE000E200, 4, base=16, bitMask=0x00000800
sfr = "INT_PENDSET.INT_MACRX", "Memory", 0xE000E200, 4, base=16, bitMask=0x00000400
sfr = "INT_PENDSET.INT_MACTX", "Memory", 0xE000E200, 4, base=16, bitMask=0x00000200
sfr = "INT_PENDSET.INT_MACTMR", "Memory", 0xE000E200, 4, base=16, bitMask=0x00000100
sfr = "INT_PENDSET.INT_SEC", "Memory", 0xE000E200, 4, base=16, bitMask=0x00000080
sfr = "INT_PENDSET.INT_SC2", "Memory", 0xE000E200, 4, base=16, bitMask=0x00000040
sfr = "INT_PENDSET.INT_SC1", "Memory", 0xE000E200, 4, base=16, bitMask=0x00000020
sfr = "INT_PENDSET.INT_SLEEPTMR", "Memory", 0xE000E200, 4, base=16, bitMask=0x00000010
sfr = "INT_PENDSET.INT_BB", "Memory", 0xE000E200, 4, base=16, bitMask=0x00000008
sfr = "INT_PENDSET.INT_MGMT", "Memory", 0xE000E200, 4, base=16, bitMask=0x00000004
sfr = "INT_PENDSET.INT_TIM2", "Memory", 0xE000E200, 4, base=16, bitMask=0x00000002
sfr = "INT_PENDSET.INT_TIM1", "Memory", 0xE000E200, 4, base=16, bitMask=0x00000001
sfr = "INT_PENDCLR", "Memory", 0xE000E280, 4, base=16
sfr = "INT_PENDCLR.INT_DEBUG", "Memory", 0xE000E280, 4, base=16, bitMask=0x00010000
sfr = "INT_PENDCLR.INT_IRQD", "Memory", 0xE000E280, 4, base=16, bitMask=0x00008000
sfr = "INT_PENDCLR.INT_IRQC", "Memory", 0xE000E280, 4, base=16, bitMask=0x00004000
sfr = "INT_PENDCLR.INT_IRQB", "Memory", 0xE000E280, 4, base=16, bitMask=0x00002000
sfr = "INT_PENDCLR.INT_IRQA", "Memory", 0xE000E280, 4, base=16, bitMask=0x00001000
sfr = "INT_PENDCLR.INT_ADC", "Memory", 0xE000E280, 4, base=16, bitMask=0x00000800
sfr = "INT_PENDCLR.INT_MACRX", "Memory", 0xE000E280, 4, base=16, bitMask=0x00000400
sfr = "INT_PENDCLR.INT_MACTX", "Memory", 0xE000E280, 4, base=16, bitMask=0x00000200
sfr = "INT_PENDCLR.INT_MACTMR", "Memory", 0xE000E280, 4, base=16, bitMask=0x00000100
sfr = "INT_PENDCLR.INT_SEC", "Memory", 0xE000E280, 4, base=16, bitMask=0x00000080
sfr = "INT_PENDCLR.INT_SC2", "Memory", 0xE000E280, 4, base=16, bitMask=0x00000040
sfr = "INT_PENDCLR.INT_SC1", "Memory", 0xE000E280, 4, base=16, bitMask=0x00000020
sfr = "INT_PENDCLR.INT_SLEEPTMR", "Memory", 0xE000E280, 4, base=16, bitMask=0x00000010
sfr = "INT_PENDCLR.INT_BB", "Memory", 0xE000E280, 4, base=16, bitMask=0x00000008
sfr = "INT_PENDCLR.INT_MGMT", "Memory", 0xE000E280, 4, base=16, bitMask=0x00000004
sfr = "INT_PENDCLR.INT_TIM2", "Memory", 0xE000E280, 4, base=16, bitMask=0x00000002
sfr = "INT_PENDCLR.INT_TIM1", "Memory", 0xE000E280, 4, base=16, bitMask=0x00000001
sfr = "INT_ACTIVE", "Memory", 0xE000E300, 4, base=16
sfr = "INT_ACTIVE.INT_DEBUG", "Memory", 0xE000E300, 4, base=16, bitMask=0x00010000
sfr = "INT_ACTIVE.INT_IRQD", "Memory", 0xE000E300, 4, base=16, bitMask=0x00008000
sfr = "INT_ACTIVE.INT_IRQC", "Memory", 0xE000E300, 4, base=16, bitMask=0x00004000
sfr = "INT_ACTIVE.INT_IRQB", "Memory", 0xE000E300, 4, base=16, bitMask=0x00002000
sfr = "INT_ACTIVE.INT_IRQA", "Memory", 0xE000E300, 4, base=16, bitMask=0x00001000
sfr = "INT_ACTIVE.INT_ADC", "Memory", 0xE000E300, 4, base=16, bitMask=0x00000800
sfr = "INT_ACTIVE.INT_MACRX", "Memory", 0xE000E300, 4, base=16, bitMask=0x00000400
sfr = "INT_ACTIVE.INT_MACTX", "Memory", 0xE000E300, 4, base=16, bitMask=0x00000200
sfr = "INT_ACTIVE.INT_MACTMR", "Memory", 0xE000E300, 4, base=16, bitMask=0x00000100
sfr = "INT_ACTIVE.INT_SEC", "Memory", 0xE000E300, 4, base=16, bitMask=0x00000080
sfr = "INT_ACTIVE.INT_SC2", "Memory", 0xE000E300, 4, base=16, bitMask=0x00000040
sfr = "INT_ACTIVE.INT_SC1", "Memory", 0xE000E300, 4, base=16, bitMask=0x00000020
sfr = "INT_ACTIVE.INT_SLEEPTMR", "Memory", 0xE000E300, 4, base=16, bitMask=0x00000010
sfr = "INT_ACTIVE.INT_BB", "Memory", 0xE000E300, 4, base=16, bitMask=0x00000008
sfr = "INT_ACTIVE.INT_MGMT", "Memory", 0xE000E300, 4, base=16, bitMask=0x00000004
sfr = "INT_ACTIVE.INT_TIM2", "Memory", 0xE000E300, 4, base=16, bitMask=0x00000002
sfr = "INT_ACTIVE.INT_TIM1", "Memory", 0xE000E300, 4, base=16, bitMask=0x00000001
sfr = "SCS_AFSR", "Memory", 0xE000ED3C, 4, base=16
sfr = "SCS_AFSR.WRONGSIZE", "Memory", 0xE000ED3C, 4, base=16, bitMask=0x00000008
sfr = "SCS_AFSR.PROTECTED", "Memory", 0xE000ED3C, 4, base=16, bitMask=0x00000004
sfr = "SCS_AFSR.RESERVED", "Memory", 0xE000ED3C, 4, base=16, bitMask=0x00000002
sfr = "SCS_AFSR.MISSED", "Memory", 0xE000ED3C, 4, base=16, bitMask=0x00000001
; Group info for SFR Window.
[SfrGroupInfo]
group = "GPIO" , "GPIO_PACFGL" , "GPIO_PACFGH" , "GPIO_PAIN" , "GPIO_PAOUT" , "GPIO_PASET" , "GPIO_PACLR" , "GPIO_PBCFGL" , "GPIO_PBCFGH" , "GPIO_PBIN" , "GPIO_PBOUT" , "GPIO_PBSET" , "GPIO_PBCLR" , "GPIO_PCCFGL" , "GPIO_PCCFGH" , "GPIO_PCIN" , "GPIO_PCOUT" , "GPIO_PCSET" , "GPIO_PCCLR" , "GPIO_DBGCFG" , "GPIO_DBGSTAT"
group = "Top-level Interrupts" , "INT_CFGSET" , "INT_CFGCLR" , "INT_PENDSET" , "INT_PENDCLR" , "INT_MISS" , "INT_ACTIVE" , "SCS_AFSR"
group = "External Interrupts" , "GPIO_IRQCSEL" , "GPIO_IRQDSEL" , "GPIO_INTCFGA" , "GPIO_INTCFGB" , "GPIO_INTCFGC" , "GPIO_INTCFGD" , "INT_GPIOFLAG"
group = "Serial Controller 1" , "INT_SC1CFG" , "SC1_INTMODE" , "INT_SC1FLAG" , "SC1_RXBEGA" , "SC1_RXENDA" , "SC1_RXBEGB" , "SC1_RXENDB" , "SC1_TXBEGA" , "SC1_TXENDA" , "SC1_TXBEGB" , "SC1_TXENDB" , "SC1_RXCNTA" , "SC1_RXCNTB" , "SC1_TXCNT" , "SC1_DMASTAT" , "SC1_DMACTRL" , "SC1_RXERRA" , "SC1_RXERRB" , "SC1_DATA" , "SC1_SPISTAT" , "SC1_TWISTAT" , "SC1_UARTSTAT" , "SC1_TWICTRL1" , "SC1_TWICTRL2" , "SC1_MODE" , "SC1_SPICFG" , "SC1_UARTCFG" , "SC1_RATELIN" , "SC1_RATEEXP" , "SC1_UARTPER" , "SC1_UARTFRAC" , "SC1_RXCNTSAVED"
group = "Serial Controller 2" , "INT_SC2CFG" , "SC2_INTMODE" , "INT_SC2FLAG" , "SC2_RXBEGA" , "SC2_RXENDA" , "SC2_RXBEGB" , "SC2_RXENDB" , "SC2_TXBEGA" , "SC2_TXENDA" , "SC2_TXBEGB" , "SC2_TXENDB" , "SC2_RXCNTA" , "SC2_RXCNTB" , "SC2_TXCNT" , "SC2_DMASTAT" , "SC2_DMACTRL" , "SC2_RXERRA" , "SC2_RXERRB" , "SC2_DATA" , "SC2_SPISTAT" , "SC2_TWISTAT" , "SC2_TWICTRL1" , "SC2_TWICTRL2" , "SC2_MODE" , "SC2_SPICFG" , "SC2_RATELIN" , "SC2_RATEEXP" , "SC2_RXCNTSAVED"
group = "ADC" , "INT_ADCCFG" , "INT_ADCFLAG" , "ADC_CFG" , "ADC_OFFSET" , "ADC_GAIN" , "ADC_DMACFG" , "ADC_DMASTAT" , "ADC_DMABEG" , "ADC_DMASIZE" , "ADC_DMACUR" , "ADC_DMACNT"
group = "Timer 1" , "INT_TIM1CFG" , "INT_TIM1FLAG" , "INT_TIM1MISS" , "TIM1_CR1" , "TIM1_CR2" , "TIM1_SMCR" , "TIM1_EGR" , "TIM1_CCMR1" , "TIM1_CCMR2" , "TIM1_CCER" , "TIM1_CNT" , "TIM1_PSC" , "TIM1_ARR" , "TIM1_CCR1" , "TIM1_CCR2" , "TIM1_CCR3" , "TIM1_CCR4" , "TIM1_OR"
group = "Timer 2" , "INT_TIM2CFG" , "INT_TIM2FLAG" , "INT_TIM2MISS" ,"TIM2_CR1" , "TIM2_CR2" , "TIM2_SMCR" , "TIM2_EGR" , "TIM2_CCMR1" , "TIM2_CCMR2" , "TIM2_CCER" , "TIM2_CNT" , "TIM2_PSC" , "TIM2_ARR" , "TIM2_CCR1" , "TIM2_CCR2" , "TIM2_CCR3" , "TIM2_CCR4" , "TIM2_OR"
group = "Wake-Up Controls" , "GPIO_PAWAKE" , "GPIO_PBWAKE" , "GPIO_PCWAKE" , "GPIO_WAKEFILT"

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,80 @@
/******************** (C) COPYRIGHT 2007 STMicroelectronics ********************
* File Name : stm32w108_type.h
* Author : MCD Application Team
* Version : V1.0
* Date : 10/08/2009
* Description : This file contains all the common data types used for the
* STM32W108 firmware library.
********************************************************************************
* THE PRESENT SOFTWARE 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 SOFTWARE AND/OR THE USE MADE BY CUSTOMERS OF THE CODING
* INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS.
*******************************************************************************/
/* Define to prevent recursive inclusion -------------------------------------*/
#ifndef __STM32W108_TYPE_H
#define __STM32W108_TYPE_H
/* Includes ------------------------------------------------------------------*/
/* Exported types ------------------------------------------------------------*/
typedef signed long s32;
typedef signed short s16;
typedef signed char s8;
typedef signed long const sc32; /* Read Only */
typedef signed short const sc16; /* Read Only */
typedef signed char const sc8; /* Read Only */
typedef volatile signed long vs32;
typedef volatile signed short vs16;
typedef volatile signed char vs8;
typedef volatile signed long const vsc32; /* Read Only */
typedef volatile signed short const vsc16; /* Read Only */
typedef volatile signed char const vsc8; /* Read Only */
typedef unsigned long u32;
typedef unsigned short u16;
typedef unsigned char u8;
typedef unsigned long const uc32; /* Read Only */
typedef unsigned short const uc16; /* Read Only */
typedef unsigned char const uc8; /* Read Only */
typedef volatile unsigned long vu32;
typedef volatile unsigned short vu16;
typedef volatile unsigned char vu8;
typedef volatile unsigned long const vuc32; /* Read Only */
typedef volatile unsigned short const vuc16; /* Read Only */
typedef volatile unsigned char const vuc8; /* Read Only */
//typedef enum {FALSE = 0, TRUE = !FALSE} bool;
typedef enum {RESET = 0, SET = !RESET} FlagStatus, ITStatus;
typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;
#define IS_FUNCTIONAL_STATE(STATE) ((STATE == DISABLE) || (STATE == ENABLE))
typedef enum {ERROR = 0, SUCCESS = !ERROR} ErrorStatus;
#define U8_MAX ((u8)255)
#define S8_MAX ((s8)127)
#define S8_MIN ((s8)-128)
#define U16_MAX ((u16)65535u)
#define S16_MAX ((s16)32767)
#define S16_MIN ((s16)-32768)
#define U32_MAX ((u32)4294967295uL)
#define S32_MAX ((s32)2147483647)
#define S32_MIN ((s32)2147483648uL)
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
/* Exported functions ------------------------------------------------------- */
#endif /* __STM32W108_TYPE_H */
/******************* (C) COPYRIGHT 2009 STMicroelectronics *****END OF FILE****/

View file

@ -0,0 +1,172 @@
/** @file hal/micro/cortexm3/system-timer.c
* @brief STM32W108 System Timer HAL functions.
*
* \b NOTE: The Sleep Timer count and compare registers are only 16 bits, but
* the counter and comparators themselves are actually 32bits. To deal with
* this, there are High ("H") and Low ("L") registers. The High register is
* the "action" register. When working with SLEEPTMR_CNT, reading the "H"
* register will return the upper 16 bits and simultaneously trigger the
* capture of the lower 16bits in the "L" register. The "L" register may then
* be read. When working with the SLEEPTMR_CMP registers, writing "L" will
* set a shadow register. Writing "H" will cause the value from the "H" write
* and the "L" shadow register to be combined and simultaneously loaded into
* the true 32bit comparator.
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
#include PLATFORM_HEADER
#include "error.h"
#include "hal/micro/micro-common.h"
#include "hal/micro/cortexm3/micro-common.h"
#include "micro/system-timer.h"
//A simple flag used by internalSleepForQs to check that it has exited
//from sleep mode at the request of the expected timer interrupt.
static boolean sleepTimerInterruptOccurred = FALSE;
// halInternalStartSystemTimer() was moved to micro.c
/**
* Return a 16 bit real time clock value. With 1024 clock ticks per second,
* a single clock tick occurs every 0.9769625 milliseconds, and a rollover
* of the 16-bit timer occurs every 64 seconds.
*/
int16u halCommonGetInt16uMillisecondTick(void)
{
return (int16u)halCommonGetInt32uMillisecondTick();
}
int16u halCommonGetInt16uQuarterSecondTick(void)
{
return (int16u)(halCommonGetInt32uMillisecondTick() >> 8);
}
/**
* Return a 32 bit real time clock value. With 1024 clock ticks per second,
* a single clock tick occurs every 0.9769625 milliseconds, and a rollover
* of the 32-bit timer occurs approximately every 48.5 days.
*/
int32u halCommonGetInt32uMillisecondTick(void)
{
int32u time;
time = SLEEPTMR_CNTH<<16;
time |= SLEEPTMR_CNTL;
return time;
}
void halSleepTimerIsr(void)
{
//clear the second level interrupts
INT_SLEEPTMRFLAG = INT_SLEEPTMRWRAP | INT_SLEEPTMRCMPA | INT_SLEEPTMRCMPB;
//mark a sleep timer interrupt as having occurred
sleepTimerInterruptOccurred = TRUE;
}
#define CONVERT_QS_TO_TICKS(x) (x << 8)
#define CONVERT_TICKS_TO_QS(x) (x >> 8)
#define TIMER_MAX_QS 0x1000000 // = 4194304 seconds * 4 = 16777216
static StStatus internalSleepForQs(boolean useGpioWakeMask,
int32u *duration,
int32u gpioWakeBitMask)
{
StStatus status = ST_SUCCESS;
int32u sleepOverflowCount;
int32u remainder;
int32u startCount;
//There is really no reason to bother with a duration of 0qs
if(*duration==0) {
INTERRUPTS_ON();
return status;
}
ATOMIC(
//disable top-level interrupt while configuring
INT_CFGCLR = INT_SLEEPTMR;
//Our tick is calibrated to 1024Hz, giving a tick of 976.6us and an
//overflow of 4194304.0 seconds. Calculate the number of sleep overflows
//in the duration
sleepOverflowCount = (*duration)/TIMER_MAX_QS;
//calculate the remaining ticks
remainder = CONVERT_QS_TO_TICKS((*duration)%TIMER_MAX_QS);
//grab the starting sleep count
startCount = halCommonGetInt32uMillisecondTick();
sleepTimerInterruptOccurred = FALSE;
if(remainder) {
//set CMPA value
SLEEPTMR_CMPAL = (startCount+remainder)&0xFFFF;
SLEEPTMR_CMPAH = ((startCount+remainder)>>16)&0xFFFF;
//clear any stale interrupt flag and set the CMPA interrupt
INT_SLEEPTMRFLAG = INT_SLEEPTMRCMPA;
INT_SLEEPTMRCFG = INT_SLEEPTMRCMPA;
}
if(sleepOverflowCount) {
//set CMPB value
SLEEPTMR_CMPBL = startCount&0xFFFF;
SLEEPTMR_CMPBH = (startCount>>16)&0xFFFF;
//clear any stale interrupt flag and set the CMPB interrupt
//this will also disable the CMPA interrupt, since we only want to wake
//on overflows, not the remainder yet
INT_SLEEPTMRFLAG = INT_SLEEPTMRCMPB;
INT_SLEEPTMRCFG = INT_SLEEPTMRCMPB;
}
//enable top-level interrupt
INT_CFGSET = INT_SLEEPTMR;
)
while(*duration > 0) {
{
halSleepWithOptions(SLEEPMODE_WAKETIMER, gpioWakeBitMask);
}
INT_SLEEPTMRCFG = INT_SLEEPTMRCFG_RESET; //disable all SleepTMR interrupts
//If we didn't come out of sleep via a compare or overflow interrupt,
//it was an abnormal sleep interruption; report the event.
if(!sleepTimerInterruptOccurred) {
status = ST_SLEEP_INTERRUPTED;
//Update duration to account for how long last sleep was. Using the
//startCount variable is always valid because full timer wraps always
//return to this value and the remainder is an offset from this value.
//And since the duration is always reduced after each full timer wrap,
//we only need to calculate the final duration here.
*duration -= CONVERT_TICKS_TO_QS(halCommonGetInt32uMillisecondTick() -
startCount);
break;
} else {
if(sleepOverflowCount) {
sleepOverflowCount--;
*duration -= TIMER_MAX_QS;
} else {
*duration -= CONVERT_TICKS_TO_QS(remainder);
}
sleepTimerInterruptOccurred = FALSE;
if(sleepOverflowCount) {
//enable sleeping for a full timer wrap
INT_SLEEPTMRFLAG = INT_SLEEPTMRCMPB;
INT_SLEEPTMRCFG = INT_SLEEPTMRCMPB;
} else if(!sleepOverflowCount && (*duration>0)){
//enable sleeping for the remainder
INT_SLEEPTMRFLAG = INT_SLEEPTMRCMPA;
INT_SLEEPTMRCFG = INT_SLEEPTMRCMPA;
}
}
}
return status;
}
StStatus halSleepForQsWithOptions(int32u *duration, int32u gpioWakeBitMask)
{
return internalSleepForQs(TRUE, duration, gpioWakeBitMask);
}

View file

@ -0,0 +1,54 @@
/**@file temperature_sensor.c
* @brief MB851 temperature sensor APIS
*
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
#include PLATFORM_HEADER
#include BOARD_HEADER
#include "hal/hal.h"
#include "hal/error.h"
#include "hal/micro/temperature_sensor.h"
#include "hal/micro/adc.h"
void temperatureSensor_Init(void)
{
/* Configure temperature sensor GPIO */
halGpioConfig(TEMPERATURE_SENSOR_GPIO,GPIOCFG_ANALOG);
/* Init ADC driver */
halInternalInitAdc();
/*
NOTE:
The ADC extended range is inaccurate due to the high voltage mode bug of the general purpose ADC
(see STM32W108 errata). As consequence, it is not reccomended to use this ADC driver for getting
the temperature values.
*/
#ifdef ENABLE_ADC_EXTENDED_RANGE_BROKEN
halAdcSetRange(TRUE);
#endif /* ENABLE_ADC_EXTENDED_RANGE_BROKEN */
}/* end temperatureSensor_Init() */
int32u temperatureSensor_GetValue(int8u type)
{
static int16u ADCvalue;
static int16s volts;
/*
NOTE:
The ADC extended range is inaccurate due to the high voltage mode bug of the general purpose ADC
(see STM32W108 errata). As consequence, it is not reccomended to use this ADC driver for getting
the temperature values.
*/
#ifdef ENABLE_ADC_EXTENDED_RANGE_BROKEN
halStartAdcConversion(ADC_USER_APP, ADC_REF_INT, ADC_SOURCE_ADC2_VREF2, ADC_CONVERSION_TIME_US_4096);
halReadAdcBlocking(ADC_USER_APP, &ADCvalue); // This blocks for a while, about 4ms.
// 100 uVolts
volts = halConvertValueToVolts(ADCvalue);
return ((18641 - (int32s)volts)*100)/1171;
#endif /* ENABLE_ADC_EXTENDED_RANGE_BROKEN */
}/* end temperatureSensor_GetValue() */

View file

@ -0,0 +1,369 @@
/** @file hal/micro/cortexm3/token-manufacturing.h
* @brief Definitions for manufacturing tokens.
*
* This file should not be included directly. It is accessed by the other
* token files.
*
* Please see hal/micro/token.h for a full explanation of the tokens.
*
* The tokens listed below are the manufacturing tokens.
*
* Since this file contains both the typedefs and the token defs, there are
* two \#defines used to select which one is needed when this file is included.
* \#define DEFINETYPES is used to select the type definitions and
* \#define DEFINETOKENS is used to select the token definitions.
* Refer to token.h and token.c to see how these are used.
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
/**
* @name Convenience Macros
* @brief The following convenience macros are used to simplify the definition
* process for commonly specified parameters to the basic TOKEN_DEF macro.
* Please see hal/micro/token.h for a more complete explanation.
*@{
*/
#define DEFINE_MFG_TOKEN(name, type, address, ...) \
TOKEN_NEXT_ADDRESS(name,(address)) \
TOKEN_MFG(name, CREATOR_##name, 0, 0, type, 1, __VA_ARGS__)
/** @} END Convenience Macros */
//////////////////////////////////////////////////////////////////////////////
// MANUFACTURING DATA
// *the addresses of these tokens must not change*
// MANUFACTURING CREATORS
// The creator codes are here in one list instead of next to their token
// definitions so comparision of the codes is easier. The only requirement
// on these creator definitions is that they all must be unique. A favorite
// method for picking creator codes is to use two ASCII characters in order
// to make the codes more memorable. Also, the msb of Stack and Manufacturing
// token creator codes is always 1, while the msb of Application token creator
// codes is always 0. This distinction allows Application tokens
// to freely use the lower 15 bits for creator codes without the risk of
// duplicating a Stack or Manufacturing token creator code.
//--- Fixed Information Block ---
#define CREATOR_MFG_CHIP_DATA 0xC344 // msb+'C'+'D'
#define CREATOR_MFG_PART_DATA 0xF064 // msb+'p'+'d'
#define CREATOR_MFG_TESTER_DATA 0xF464 // msb+'t'+'d'
#define CREATOR_MFG_ST_EUI_64 0xE545 // msb+'e'+'E'
#define CREATOR_MFG_ANALOG_TRIM_NORMAL 0xF46E // msb+'t'+'n'
#define CREATOR_MFG_ANALOG_TRIM_BOOST 0xF442 // msb+'t'+'B'
#define CREATOR_MFG_ANALOG_TRIM_BOTH 0xF462 // msb+'t'+'b'
#define CREATOR_MFG_REG_TRIM 0xF274 // msb+'r'+'t'
#define CREATOR_MFG_1V8_REG_VOLTAGE 0xF276 // msb+'r'+'v'
#define CREATOR_MFG_VREF_VOLTAGE 0xF676 // msb+'v'+'v'
#define CREATOR_MFG_TEMP_CAL 0xF463 // msb+'t'+'c'
#define CREATOR_MFG_FIB_VERSION 0xFF09
#define CREATOR_MFG_FIB_CHECKSUM 0xE663 // msb+'f'+'c'
#define CREATOR_MFG_FIB_OBS 0xE66F // msb+'f'+'o'
//--- Customer Information Block ---
#define CREATOR_MFG_CIB_OBS 0xE36F // msb+'c'+'o'
#define CREATOR_MFG_CUSTOM_VERSION 0xC356
#define CREATOR_MFG_CUSTOM_EUI_64 0xE345
#define CREATOR_MFG_STRING 0xED73
#define CREATOR_MFG_BOARD_NAME 0xC24E // msb+'B'+'N' (Board Name)
#define CREATOR_MFG_EUI_64 0xB634
#define CREATOR_MFG_MANUF_ID 0xC944 // msb+'I'+'D' (Id)
#define CREATOR_MFG_PHY_CONFIG 0xD043 // msb+'P'+'C' (Phy Config)
#define CREATOR_MFG_BOOTLOAD_AES_KEY 0xC24B // msb+'B'+'K' (Bootloader Key)
#define CREATOR_MFG_EZSP_STORAGE 0xCD53
#define CREATOR_MFG_ASH_CONFIG 0xC143 // msb+'A'+'C' (ASH Config)
#define CREATOR_MFG_CBKE_DATA 0xC342 // msb+'C'+'B' (CBke)
#define CREATOR_MFG_INSTALLATION_CODE 0xC943 // msb+'I'+'C' (Installation Code)
#define CREATOR_MFG_OSC24M_BIAS_TRIM 0xB254 // msb+'2'+'T' (2[4mHz] Trim)
// The master defines indicating the verions number these definitions work with.
#define CURRENT_MFG_TOKEN_VERSION 0x01FE //MSB is version, LSB is complement
#define CURRENT_MFG_CUSTOM_VERSION 0x01FE //MSB is version, LSB is complement
#ifndef __MFG_TYPES_DEFINED__
#define __MFG_TYPES_DEFINED__
//--- Fixed Information Block ---
typedef int8u tokTypeMfgChipData[24];
typedef int8u tokTypeMfgPartData[6];
typedef int8u tokTypeMfgTesterData[6];
typedef int8u tokTypeMfgStEui64[8];
typedef struct {
int16u iffilterL;
int16u lna;
int16u ifamp;
int16u rxadcH;
int16u prescalar;
int16u phdet;
int16u vco;
int16u loopfilter;
int16u pa;
int16u iqmixer;
} tokTypeMfgAnalogueTrim;
typedef struct {
int16u iffilterH;
int16u biasmaster;
int16u moddac;
int16u auxadc;
int16u caladc;
} tokTypeMfgAnalogueTrimBoth;
typedef struct {
int8u regTrim1V2;
int8u regTrim1V8;
} tokTypeMfgRegTrim;
typedef int16u tokTypeMfgRegVoltage1V8;
typedef int16u tokTypeMfgAdcVrefVoltage;
typedef int16u tokTypeMfgTempCal;
typedef int16u tokTypeMfgFibVersion;
typedef int16u tokTypeMfgFibChecksum;
typedef struct {
int16u ob2;
int16u ob3;
int16u ob0;
int16u ob1;
} tokTypeMfgFibObs;
//--- Customer Information Block ---
typedef struct {
int16u ob0;
int16u ob1;
int16u ob2;
int16u ob3;
int16u ob4;
int16u ob5;
int16u ob6;
int16u ob7;
} tokTypeMfgCibObs;
typedef int16u tokTypeMfgCustomVersion;
typedef int8u tokTypeMfgCustomEui64[8];
typedef int8u tokTypeMfgString[16];
typedef int8u tokTypeMfgBoardName[16];
typedef int16u tokTypeMfgManufId;
typedef int16u tokTypeMfgPhyConfig;
typedef int8u tokTypeMfgBootloadAesKey[16];
typedef int8u tokTypeMfgEui64[8];
typedef int8u tokTypeMfgEzspStorage[8];
typedef int16u tokTypeMfgAshConfig;
typedef struct {
int8u certificate[48];
int8u caPublicKey[22];
int8u privateKey[21];
// The bottom flag bit is 1 for uninitialized, 0 for initialized.
// The other flag bits should be set to 0 at initialization.
int8u flags;
} tokTypeMfgCbkeData;
typedef struct {
// The bottom flag bit is 1 for uninitialized, 0 for initialized.
// Bits 1 and 2 give the size of the value string:
// 0 = 6 bytes, 1 = 8 bytes, 2 = 12 bytes, 3 = 16 bytes.
// The other flag bits should be set to 0 at initialization.
// Special flags support. Due to a bug in the way some customers
// had programmed the flags field, we will also examine the upper
// bits 9 and 10 for the size field. Those bits are also reserved.
int16u flags;
int8u value[16];
int16u crc;
} tokTypeMfgInstallationCode;
typedef int16u tokTypeMfgOsc24mBiasTrim;
#endif //__MFG_TYPES_DEFINED__
#ifdef DEFINETOKENS
//The Manufacturing tokens need to be stored at well-defined locations.
//None of these addresses should ever change without extremely great care.
//All locations are OR'ed with DATA_BIG_INFO_BASE to make a full 32bit address.
//--- Fixed Information Block ---
// FIB Bootloader 0x0000 //1918 bytes
#define MFG_CHIP_DATA_LOCATION 0x077E // 24 bytes
#define MFG_PART_DATA_LOCATION 0x0796 // 6 bytes
#define MFG_TESTER_DATA_LOCATION 0x079C // 6 bytes
#define MFG_ST_EUI_64_LOCATION 0x07A2 // 8 bytes
#define MFG_ANALOG_TRIM_NORMAL_LOCATION 0x07AA // 20 bytes
#define MFG_ANALOG_TRIM_BOOST_LOCATION 0x07BE // 20 bytes
#define MFG_ANALOG_TRIM_BOTH_LOCATION 0x07D2 // 10 bytes
#define MFG_REG_TRIM_LOCATION 0x07DC // 2 bytes
#define MFG_1V8_REG_VOLTAGE_LOCATION 0x07DE // 2 bytes
#define MFG_VREF_VOLTAGE_LOCATION 0x07E0 // 2 bytes
#define MFG_TEMP_CAL_LOCATION 0x07E2 // 2 bytes
//reserved 0x07E4 // 16 bytes
#define MFG_FIB_VERSION_LOCATION 0x07F4 // 2 bytes
#define MFG_FIB_CHECKSUM_LOCATION 0x07F6 // 2 bytes
#define MFG_FIB_OBS_LOCATION 0x07F8 // 8 bytes
//--- Customer Information Block ---
#define MFG_CIB_OBS_LOCATION 0x0800 // 16 bytes
#define MFG_CUSTOM_VERSION_LOCATION 0x0810 // 2 bytes
#define MFG_CUSTOM_EUI_64_LOCATION 0x0812 // 8 bytes
#define MFG_STRING_LOCATION 0x081A // 16 bytes
#define MFG_BOARD_NAME_LOCATION 0x082A // 16 bytes
#define MFG_MANUF_ID_LOCATION 0x083A // 2 bytes
#define MFG_PHY_CONFIG_LOCATION 0x083C // 2 bytes
#define MFG_BOOTLOAD_AES_KEY_LOCATION 0x083E // 16 bytes
#define MFG_EZSP_STORAGE_LOCATION 0x084E // 8 bytes
#define MFG_ASH_CONFIG_LOCATION 0x0856 // 40 bytes
#define MFG_CBKE_DATA_LOCATION 0x087E // 92 bytes
#define MFG_INSTALLATION_CODE_LOCATION 0x08DA // 20 bytes
#define MFG_OSC24M_BIAS_TRIM_LOCATION 0x08EE // 2 bytes
// unused 0x08F0 //1808 bytes
//--- Virtual MFG Tokens ---
#define MFG_EUI_64_LOCATION 0x8000 // Special Trigger - see token.c
// Define the size of indexed token array
#define MFG_ASH_CONFIG_ARRAY_SIZE 20
#ifndef TOKEN_NEXT_ADDRESS
#define TOKEN_NEXT_ADDRESS(region, address)
#endif
// NOTE: because of their special handling, the manufacturing tokens
// cannot use the convenience macros in their definitions, so the full
// definitions are present here.
//--- Fixed Information Block ---
TOKEN_NEXT_ADDRESS(MFG_CHIP_DATA_ADDR,MFG_CHIP_DATA_LOCATION)
TOKEN_MFG(MFG_CHIP_DATA, CREATOR_MFG_CHIP_DATA,
0, 0, tokTypeMfgChipData, 1,
{0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,
0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,
0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF})
TOKEN_NEXT_ADDRESS(MFG_PART_DATA_ADDR,MFG_PART_DATA_LOCATION)
TOKEN_MFG(MFG_PART_DATA, CREATOR_MFG_PART_DATA,
0, 0, tokTypeMfgPartData, 1,
{0xFF,0xFF,0xFF,0xFF,0xFF,0xFF})
TOKEN_NEXT_ADDRESS(MFG_TESTER_DATA_ADDR,MFG_TESTER_DATA_LOCATION)
TOKEN_MFG(MFG_TESTER_DATA, CREATOR_MFG_TESTER_DATA,
0, 0, tokTypeMfgTesterData, 1,
{0xFF,0xFF,0xFF,0xFF,0xFF,0xFF})
TOKEN_NEXT_ADDRESS(MFG_ST_EUI_64_ADDR,MFG_ST_EUI_64_LOCATION)
TOKEN_MFG(MFG_ST_EUI_64, CREATOR_MFG_ST_EUI_64,
0, 0, tokTypeMfgStEui64, 1,
{3,0,0,0,0,0,0,3})
TOKEN_NEXT_ADDRESS(MFG_ANALOG_TRIM_NORMAL_ADDR,MFG_ANALOG_TRIM_NORMAL_LOCATION)
TOKEN_MFG(MFG_ANALOG_TRIM_NORMAL, CREATOR_MFG_ANALOG_TRIM_NORMAL,
0, 0, tokTypeMfgAnalogueTrim, 1,
{0xFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF,
0xFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF})
TOKEN_NEXT_ADDRESS(MFG_ANALOG_TRIM_BOOST_ADDR,MFG_ANALOG_TRIM_BOOST_LOCATION)
TOKEN_MFG(MFG_ANALOG_TRIM_BOOST, CREATOR_MFG_ANALOG_TRIM_BOOST,
0, 0, tokTypeMfgAnalogueTrim, 1,
{0xFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF,
0xFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF})
TOKEN_NEXT_ADDRESS(MFG_ANALOG_TRIM_BOTH_ADDR,MFG_ANALOG_TRIM_BOTH_LOCATION)
TOKEN_MFG(MFG_ANALOG_TRIM_BOTH, CREATOR_MFG_ANALOG_TRIM_BOTH,
0, 0, tokTypeMfgAnalogueTrimBoth, 1,
{0xFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF})
TOKEN_NEXT_ADDRESS(MFG_REG_TRIM_ADDR,MFG_REG_TRIM_LOCATION)
TOKEN_MFG(MFG_REG_TRIM, CREATOR_MFG_REG_TRIM,
0, 0, tokTypeMfgRegTrim, 1,
{0xFF, 0xFF})
TOKEN_NEXT_ADDRESS(MFG_1V8_REG_VOLTAGE_ADDR,MFG_1V8_REG_VOLTAGE_LOCATION)
TOKEN_MFG(MFG_1V8_REG_VOLTAGE, CREATOR_MFG_1V8_REG_VOLTAGE,
0, 0, tokTypeMfgRegVoltage1V8, 1,
0xFFFF)
TOKEN_NEXT_ADDRESS(MFG_VREF_VOLTAGE_ADDR,MFG_VREF_VOLTAGE_LOCATION)
TOKEN_MFG(MFG_VREF_VOLTAGE, CREATOR_MFG_VREF_VOLTAGE,
0, 0, tokTypeMfgAdcVrefVoltage, 1,
0xFFFF)
TOKEN_NEXT_ADDRESS(MFG_TEMP_CAL_ADDR,MFG_TEMP_CAL_LOCATION)
TOKEN_MFG(MFG_TEMP_CAL, CREATOR_MFG_TEMP_CAL,
0, 0, tokTypeMfgTempCal, 1,
0xFFFF)
TOKEN_NEXT_ADDRESS(MFG_FIB_VERSION_ADDR,MFG_FIB_VERSION_LOCATION)
TOKEN_MFG(MFG_FIB_VERSION, CREATOR_MFG_FIB_VERSION,
0, 0, tokTypeMfgFibVersion, 1,
CURRENT_MFG_TOKEN_VERSION)
TOKEN_NEXT_ADDRESS(MFG_FIB_CHECKSUM_ADDR,MFG_FIB_CHECKSUM_LOCATION)
TOKEN_MFG(MFG_FIB_CHECKSUM, CREATOR_MFG_FIB_CHECKSUM,
0, 0, tokTypeMfgFibChecksum, 1,
0xFFFF)
TOKEN_NEXT_ADDRESS(MFG_FIB_OBS_ADDR,MFG_FIB_OBS_LOCATION)
TOKEN_MFG(MFG_FIB_OBS, CREATOR_MFG_FIB_OBS,
0, 0, tokTypeMfgFibObs, 1,
{0xFFFF,0x03FC,0xAA55,0xFFFF})
//--- Customer Information Block ---
TOKEN_NEXT_ADDRESS(MFG_CIB_OBS_ADDR,MFG_CIB_OBS_LOCATION)
TOKEN_MFG(MFG_CIB_OBS, CREATOR_MFG_CIB_OBS,
0, 0, tokTypeMfgCibObs, 1,
{0x5AA5,0xFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF})
TOKEN_NEXT_ADDRESS(MFG_CUSTOM_VERSION_ADDR,MFG_CUSTOM_VERSION_LOCATION)
TOKEN_MFG(MFG_CUSTOM_VERSION, CREATOR_MFG_CUSTOM_VERSION,
0, 0, tokTypeMfgCustomVersion, 1,
CURRENT_MFG_CUSTOM_VERSION)
TOKEN_NEXT_ADDRESS(MFG_CUSTOM_EUI_64_ADDR,MFG_CUSTOM_EUI_64_LOCATION)
TOKEN_MFG(MFG_CUSTOM_EUI_64, CREATOR_MFG_CUSTOM_EUI_64,
0, 0, tokTypeMfgCustomEui64, 1,
{0,3,3,3,3,3,3,0})
TOKEN_NEXT_ADDRESS(MFG_STRING_ADDR,MFG_STRING_LOCATION)
TOKEN_MFG(MFG_STRING, CREATOR_MFG_STRING,
0, 0, tokTypeMfgString, 1,
{0,})
TOKEN_NEXT_ADDRESS(MFG_BOARD_NAME_ADDR,MFG_BOARD_NAME_LOCATION)
TOKEN_MFG(MFG_BOARD_NAME, CREATOR_MFG_BOARD_NAME,
0, 0, tokTypeMfgBoardName, 1,
{0,})
TOKEN_NEXT_ADDRESS(MFG_MANUF_ID_ADDR,MFG_MANUF_ID_LOCATION)
TOKEN_MFG(MFG_MANUF_ID, CREATOR_MFG_MANUF_ID,
0, 0, tokTypeMfgManufId, 1,
{0x00,0x00,}) // default to 0 for st
TOKEN_NEXT_ADDRESS(MFG_PHY_CONFIG_ADDR,MFG_PHY_CONFIG_LOCATION)
TOKEN_MFG(MFG_PHY_CONFIG, CREATOR_MFG_PHY_CONFIG,
0, 0, tokTypeMfgPhyConfig, 1,
{0x00,0x00,}) // default to non-boost mode, internal pa.
TOKEN_NEXT_ADDRESS(MFG_BOOTLOAD_AES_KEY_ADDR,MFG_BOOTLOAD_AES_KEY_LOCATION)
TOKEN_MFG(MFG_BOOTLOAD_AES_KEY, CREATOR_MFG_BOOTLOAD_AES_KEY,
0, 0, tokTypeMfgBootloadAesKey, 1,
{0xFF,}) // default key is all f's
TOKEN_NEXT_ADDRESS(MFG_EZSP_STORAGE_ADDR,MFG_EZSP_STORAGE_LOCATION)
TOKEN_MFG(MFG_EZSP_STORAGE, CREATOR_MFG_EZSP_STORAGE,
0, 0, tokTypeMfgEzspStorage, 1,
{ 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF })
TOKEN_NEXT_ADDRESS(MFG_ASH_CONFIG_ADDR,MFG_ASH_CONFIG_LOCATION)
TOKEN_MFG(MFG_ASH_CONFIG, CREATOR_MFG_ASH_CONFIG,
0, 1, tokTypeMfgAshConfig, MFG_ASH_CONFIG_ARRAY_SIZE,
{ 0xFFFF, })
TOKEN_NEXT_ADDRESS(MFG_CBKE_DATA_ADDR,MFG_CBKE_DATA_LOCATION)
TOKEN_MFG(MFG_CBKE_DATA, CREATOR_MFG_CBKE_DATA,
0, 0, tokTypeMfgCbkeData, 1,
{0xFF,})
TOKEN_NEXT_ADDRESS(MFG_INSTALLATION_CODE_ADDR,MFG_INSTALLATION_CODE_LOCATION)
TOKEN_MFG(MFG_INSTALLATION_CODE, CREATOR_MFG_INSTALLATION_CODE,
0, 0, tokTypeMfgInstallationCode, 1,
{0xFF,})
TOKEN_NEXT_ADDRESS(MFG_OSC24M_BIAS_TRIM_ADDR,MFG_OSC24M_BIAS_TRIM_LOCATION)
TOKEN_MFG(MFG_OSC24M_BIAS_TRIM, CREATOR_MFG_OSC24M_BIAS_TRIM,
0, 0, tokTypeMfgOsc24mBiasTrim, 1,
{0xFF,})
TOKEN_NEXT_ADDRESS(MFG_EUI_64_ADDR,MFG_EUI_64_LOCATION)
TOKEN_MFG(MFG_EUI_64, CREATOR_MFG_EUI_64,
0, 0, tokTypeMfgEui64, 1,
{3,3,3,3,0,0,0,0})
#undef TOKEN_NEXT_ADDRESS
#endif //DEFINETOKENS

View file

@ -0,0 +1,259 @@
/** @file hal/micro/cortexm3/uart.c
* @brief STM32W uart drivers, supporting IAR's standard library
* IO routines.
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
#include PLATFORM_HEADER
#include "hal/micro/micro-common.h"
#include "hal/micro/cortexm3/micro-common.h"
#include "uart.h"
#ifdef __GNUC__
#include <sys/stat.h>
#include <stdio.h>
#define _LLIO_STDIN ((int) stdin)
#define _LLIO_STDOUT ((int) stdout)
#define _LLIO_STDERR ((int) stderr)
#define _LLIO_ERROR (-1)
#define __write _write
#define __read _read
#undef putchar
void __io_putchar( char c );
int putchar (int c)
{
__io_putchar((char) c);
return c;
}
#endif
#define RECEIVE_QUEUE_SIZE (128)
int8u rxQ[RECEIVE_QUEUE_SIZE];
int16u rxHead;
int16u rxTail;
int16u rxUsed;
//////////////////////////////////////////////////////////////////////////////
// Initialization
void uartInit(int32u baudrate, int8u databits, SerialParity parity, int8u stopbits)
{
int32u tempcfg;
int32u tmp;
assert( (baudrate >= 300) && (baudrate <=921600) );
tmp = (2*12000000L + baudrate/2) / baudrate;
SC1_UARTFRAC = tmp & 1;
SC1_UARTPER = tmp / 2;
if(databits == 7) {
tempcfg = 0;
} else {
tempcfg = SC_UART8BIT;
}
if (parity == PARITY_ODD) {
tempcfg |= SC_UARTPAR | SC_UARTODD;
} else if( parity == PARITY_EVEN ) {
tempcfg |= SC_UARTPAR;
}
if ((stopbits & 0x0F) >= 2) {
tempcfg |= SC_UART2STP;
}
SC1_UARTCFG = tempcfg;
SC1_MODE = SC1_MODE_UART;
rxHead=0;
rxTail=0;
rxUsed=0;
halGpioConfig(PORTB_PIN(1),GPIOCFG_OUT_ALT);
halGpioConfig(PORTB_PIN(2),GPIOCFG_IN);
// Make the RX Valid interrupt level sensitive (instead of edge)
SC1_INTMODE = SC_RXVALLEVEL;
// Enable just RX interrupts; TX interrupts are controlled separately
INT_SC1CFG |= (INT_SCRXVAL |
INT_SCRXOVF |
INT_SC1FRMERR |
INT_SC1PARERR);
INT_SC1FLAG = 0xFFFF; // Clear any stale interrupts
INT_CFGSET = INT_SC1;
}
//////////////////////////////////////////////////////////////////////////////
// Transmit
// IAR Standard library hook for serial output
size_t __write(int handle, const unsigned char * buffer, size_t size)
{
size_t nChars = 0;
/* This template only writes to "standard out" and "standard err",
* for all other file handles it returns failure. */
if (handle != _LLIO_STDOUT && handle != _LLIO_STDERR) {
return _LLIO_ERROR;
}
if (buffer == 0) {
// This means that we should flush internal buffers.
//spin until TX complete (TX is idle)
while ((SC1_UARTSTAT&SC_UARTTXIDLE)!=SC_UARTTXIDLE) {}
return 0;
}
// ensure port is configured for UART
if(SC1_MODE != SC1_MODE_UART) {
return _LLIO_ERROR;
}
while(size--) {
//spin until data register has room for more data
while ((SC1_UARTSTAT&SC_UARTTXFREE)!=SC_UARTTXFREE) {}
SC1_DATA = *buffer;
buffer++;
++nChars;
}
return nChars;
}
#ifdef __GNUC__
int fflush (FILE *f)
#endif
#ifdef __ICCARM__
size_t fflush(int handle)
#endif
{
return __write(_LLIO_STDOUT, NULL, 0);
}
static void halInternalUart1TxIsr(void)
{
// Nothing for now, as ouput is blocking from the __write function
}
//////////////////////////////////////////////////////////////////////////////
// Receive
// IAR Standard library hook for serial input
size_t __read(int handle, unsigned char * buffer, size_t size)
{
int nChars = 0;
/* This template only reads from "standard in", for all other file
* handles it returns failure. */
if (handle != _LLIO_STDIN)
{
return _LLIO_ERROR;
}
for(nChars = 0; (rxUsed>0) && (nChars < size); nChars++) {
ATOMIC(
*buffer++ = rxQ[rxTail];
rxTail = (rxTail+1) % RECEIVE_QUEUE_SIZE;
rxUsed--;
)
}
return nChars;
}
static void halInternalUart1RxIsr(void)
{
// At present we really don't care which interrupt(s)
// occurred, just that one did. Loop reading RXVALID
// data, processing any errors noted
// along the way.
while ( SC1_UARTSTAT & SC_UARTRXVAL ) {
int8u errors = SC1_UARTSTAT & (SC_UARTFRMERR |
SC_UARTRXOVF |
SC_UARTPARERR );
int8u incoming = (int8u) SC1_DATA;
if ( (errors == 0) && (rxUsed < (RECEIVE_QUEUE_SIZE-1)) ) {
rxQ[rxHead] = incoming;
rxHead = (rxHead+1) % RECEIVE_QUEUE_SIZE;
rxUsed++;
} else {
// IAR standard library doesn't allow for any error handling in the
// case of rx errors or not having space in the receive queue, so the
// errors are just silently dropped.
}
} // end of while ( SC1_UARTSTAT & SC1_UARTRXVAL )
}
//////////////////////////////////////////////////////////////////////////////
// Interrupts
void halSc1Isr(void)
{
int32u interrupt;
//this read and mask is performed in two steps otherwise the compiler
//will complain about undefined order of volatile access
interrupt = INT_SC1FLAG;
interrupt &= INT_SC1CFG;
while (interrupt != 0) {
INT_SC1FLAG = interrupt; // acknowledge the interrupts early
// RX events
if ( interrupt & (INT_SCRXVAL | // RX has data
INT_SCRXOVF | // RX Overrun error
INT_SC1FRMERR | // RX Frame error
INT_SC1PARERR ) // RX Parity error
) {
halInternalUart1RxIsr();
}
// TX events
if ( interrupt & (INT_SCTXFREE | // TX has room
INT_SCTXIDLE ) // TX idle (more room)
) {
halInternalUart1TxIsr();
}
interrupt = INT_SC1FLAG;
interrupt &= INT_SC1CFG;
}
}
/*******************************************************************************
* Function Name : __io_getcharNonBlocking
* Description : Non blocking read
* Input : none
* Output : dataByte: buffer containing the read byte if any
* Return : TRUE if there is a data, FALSE otherwise
*******************************************************************************/
boolean __io_getcharNonBlocking(int8u *data)
{
if (__read(_LLIO_STDIN,data,1))
return TRUE;
else
return FALSE;
}/* end serialReadByte() */
void __io_putchar( char c )
{
__write(_LLIO_STDOUT, (unsigned char *)&c, 1);
}
int __io_getchar()
{
unsigned char c;
__read(_LLIO_STDIN, &c, 1);
return (int)(c);
}
void __io_flush( void )
{
__write(_LLIO_STDOUT, NULL, 0);
}

View file

@ -0,0 +1,72 @@
/** @file hal/micro/cortexm3/uart.h
* @brief Header for STM32W uart drivers, supporting IAR's standard library
* IO routines.
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
#ifndef __UART_MIN_H__
#define __UART_MIN_H__
#ifdef __ICCARM__
#include <yfuns.h>
#endif
/**
* @brief A list of the possible values for the parity parameter to uartInit()
*/
typedef enum
{
PARITY_NONE = 0,
PARITY_ODD = 1,
PARITY_EVEN = 2
} SerialParity;
/**
* @brief Initialize the UART
*
* @param baudrate The baudrate which will be used for communication.
* Ex: 115200
*
* @param databits The number of data bits used for communication.
* Valid values are 7 or 8
*
* @param parity The type of parity used for communication.
* See the SerialParity enum for possible values
*
* @return stopbits The number of stop bits used for communication.
* Valid values are 1 or 2
*/
void uartInit(int32u baudrate, int8u databits, SerialParity parity, int8u stopbits);
#ifdef __ICCARM__
/**
* @brief Flush the output stream. DLib_Config_Full.h defines fflush(), but
* this library includes too much code so we compile with DLib_Config_Normal.h
* instead which does not define fflush(). Therefore, we manually define
* fflush() in the low level UART driver. This function simply redirects
* to the __write() function with a NULL buffer, triggering a flush.
*
* @param handle The output stream. Should be set to 'stdout' like normal.
*
* @return Zero, indicating success.
*/
size_t fflush(int handle);
/**
* @brief Define the stdout stream. Since we compile with DLib_Config_Normal.h
* it does not define 'stdout'. There is a low-level IO define '_LLIO_STDOUT'
* which is equivalent to stdout. Therefore, we define 'stdout' to be
* '_LLIO_STDOUT'.
*/
#define stdout _LLIO_STDOUT
#endif
/**
* @brief Read the input byte if any.
*/
boolean __io_getcharNonBlocking(int8u *data);
void __io_putchar( char c );
int __io_getchar(void);
void __io_flush( void );
#endif //__UART_MIN_H__

View file

@ -0,0 +1,362 @@
/** @file hal/micro/generic/compiler/platform-common.h
* See @ref platform_common for detailed documentation.
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
/** @addtogroup platform_common
* @brief Compiler and Platform specific definitions and typedefs common to
* all platforms.
*
* platform-common.h provides PLATFORM_HEADER defaults and common definitions.
* This head should never be included directly, it should only be included
* by the specific PLATFORM_HEADER used by your platform.
*
* See platform-common.h for source code.
*@{
*/
#ifndef PLATCOMMONOKTOINCLUDE
// This header should only be included by a PLATFORM_HEADER
#error platform-common.h should not be included directly
#endif
#ifndef __PLATFORMCOMMON_H__
#define __PLATFORMCOMMON_H__
////////////////////////////////////////////////////////////////////////////////
// Many of the common definitions must be explicitly enabled by the
// particular PLATFORM_HEADER being used
////////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////////////////
#ifdef _HAL_USE_COMMON_PGM_
/** \name Master Program Memory Declarations
* These are a set of defines for simple declarations of program memory.
*/
//@{
/**
* @brief Standard program memory delcaration.
*/
#define PGM const
/**
* @brief Char pointer to program memory declaration.
*/
#define PGM_P const char *
/**
* @brief Unsigned char pointer to program memory declaration.
*/
#define PGM_PU const unsigned char *
/**
* @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
* into nothing under gcc.
*/
#define PGM_NO_CONST
//@} \\END MASTER PROGRAM MEMORY DECLARATIONS
#endif //_HAL_USE_COMMON_PGM_
////////////////////////////////////////////////////////////////////////////////
#ifdef _HAL_USE_COMMON_DIVMOD_
/** \name Divide and Modulus Operations
* Some platforms can perform divide and modulus operations on 32 bit
* quantities more efficiently when the divisor is only a 16 bit quantity.
* C compilers will always promote the divisor to 32 bits before performing the
* operation, so the following utility functions are instead required to take
* advantage of this optimisation.
*/
//@{
/**
* @brief Provide a portable name for the int32u by int16u division
* library function (which can perform the division with only a single
* assembly instruction on some platforms)
*/
#define halCommonUDiv32By16(x, y) ((int16u) (((int32u) (x)) / ((int16u) (y))))
/**
* @brief Provide a portable name for the int32s by int16s division
* library function (which can perform the division with only a single
* assembly instruction on some platforms)
*/
#define halCommonSDiv32By16(x, y) ((int16s) (((int32s) (x)) / ((int16s) (y))))
/**
* @brief Provide a portable name for the int32u by int16u modulo
* library function (which can perform the division with only a single
* assembly instruction on some platforms)
*/
#define halCommonUMod32By16(x, y) ((int16u) (((int32u) (x)) % ((int16u) (y))))
/**
* @brief Provide a portable name for the int32s by int16s modulo
* library function (which can perform the division with only a single
* assembly instruction on some platforms)
*/
#define halCommonSMod32By16(x, y) ((int16s) (((int32s) (x)) % ((int16s) (y))))
//@} \\END DIVIDE and MODULUS OPERATIONS
#endif //_HAL_USE_COMMON_DIVMOD_
////////////////////////////////////////////////////////////////////////////////
#ifdef _HAL_USE_COMMON_MEMUTILS_
/** \name C Standard Library Memory Utilities
* These should be used in place of the standard library functions.
*
* These functions have the same parameters and expected results as their C
* Standard Library equivalents but may take advantage of certain implementation
* optimizations.
*
* Unless otherwise noted, these functions are utilized by the StStack and are
* therefore required to be implemented in the HAL. Additionally, unless otherwise
* noted, applications that find these functions useful may utilze them.
*/
//@{
/**
* @brief Refer to the C stdlib memcpy().
*/
void halCommonMemCopy(void *dest, const void *src, int8u bytes);
/**
* @brief Refer to the C stdlib memset().
*/
void halCommonMemSet(void *dest, int8u val, int16u bytes);
/**
* @brief Refer to the C stdlib memcmp().
*/
int8s halCommonMemCompare(const void *source0, const void *source1, int8u bytes);
/**
* @brief Works like C stdlib memcmp(), but takes a flash space source
* parameter.
*/
int8s halCommonMemPGMCompare(const void *source0, void PGM *source1, int8u bytes);
/**
* @brief Same as the C stdlib memcpy(), but handles copying from const
* program space.
*/
void halCommonMemPGMCopy(void* dest, void PGM *source, int8u bytes);
/**
* @brief Friendly convenience macro pointing to the full HAL function.
*/
#define MEMSET(d,v,l) halCommonMemSet(d,v,l)
#define MEMCOPY(d,s,l) halCommonMemCopy(d,s,l)
#define MEMCOMPARE(s0,s1,l) halCommonMemCompare(s0, s1, l)
#define MEMPGMCOMPARE(s0,s1,l) halCommonMemPGMCompare(s0, s1, l)
//@} // end of C Standard Library Memory Utilities
#endif //_HAL_USE_COMMON_MEMUTILS_
////////////////////////////////////////////////////////////////////////////////
// The following sections are common on all platforms
////////////////////////////////////////////////////////////////////////////////
////////////////////////////////////////////////////////////////////////////////
/**
* @name Generic Types
*@{
*/
/**
* @brief An alias for one, used for clarity.
*/
#define TRUE 1
/**
* @brief An alias for zero, used for clarity.
*/
#define FALSE 0
#ifndef NULL
/**
* @brief The null pointer.
*/
#define NULL ((void *)0)
#endif
//@} \\END Generic Types
/**
* @name Bit Manipulation Macros
*/
//@{
/**
* @brief Useful to reference a single bit of a byte.
*/
#define BIT(x) (1U << (x)) // Unsigned avoids compiler warnings re BIT(15)
/**
* @brief Useful to reference a single bit of an int32u type.
*/
#define BIT32(x) (((int32u) 1) << (x))
/**
* @brief Sets \c bit in the \c reg register or byte.
* @note Assuming \c reg is an IO register, some platforms
* can implement this in a single atomic operation.
*/
#define SETBIT(reg, bit) reg |= BIT(bit)
/**
* @brief Sets the bits in the \c reg register or the byte
* as specified in the bitmask \c bits.
* @note This is never a single atomic operation.
*/
#define SETBITS(reg, bits) reg |= (bits)
/**
* @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)
* can implement this in a single atomic operation.
*/
#define CLEARBIT(reg, bit) reg &= ~(BIT(bit))
/**
* @brief Clears the bits in the \c reg register or byte
* as specified in the bitmask \c bits.
* @note This is never a single atomic operation.
*/
#define CLEARBITS(reg, bits) reg &= ~(bits)
/**
* @brief Returns the value of \c bit within the register or byte \c reg.
*/
#define READBIT(reg, bit) (reg & (BIT(bit)))
/**
* @brief Returns the value of the bitmask \c bits within
* the register or byte \c reg.
*/
#define READBITS(reg, bits) (reg & (bits))
//@} \\END Bit Manipulation Macros
////////////////////////////////////////////////////////////////////////////////
/**
* @name Byte Manipulation Macros
*/
//@{
/**
* @brief Returns the low byte of the 16-bit value \c n as an \c int8u.
*/
#define LOW_BYTE(n) ((int8u)((n) & 0xFF))
/**
* @brief Returns the high byte of the 16-bit value \c n as an \c int8u.
*/
#define HIGH_BYTE(n) ((int8u)(LOW_BYTE((n) >> 8)))
/**
* @brief Returns the value built from the two \c int8u
* values \c high and \c low.
*/
#define HIGH_LOW_TO_INT(high, low) ( \
(( (int16u) (high) ) << 8) + \
( (int16u) ( (low) & 0xFF)) \
)
/**
* @brief Returns the low byte of the 32-bit value \c n as an \c int8u.
*/
#define BYTE_0(n) ((int8u)((n) & 0xFF))
/**
* @brief Returns the second byte of the 32-bit value \c n as an \c int8u.
*/
#define BYTE_1(n) ((int8u)(BYTE_0((n) >> 8)))
/**
* @brief Returns the third byte of the 32-bit value \c n as an \c int8u.
*/
#define BYTE_2(n) ((int8u)(BYTE_0((n) >> 16)))
/**
* @brief Returns the high byte of the 32-bit value \c n as an \c int8u.
*/
#define BYTE_3(n) ((int8u)(BYTE_0((n) >> 24)))
//@} \\END Byte manipulation macros
////////////////////////////////////////////////////////////////////////////////
/**
* @name Time Manipulation Macros
*/
//@{
/**
* @brief Returns the elapsed time between two 8 bit values.
* Result may not be valid if the time samples differ by more than 127
*/
#define elapsedTimeInt8u(oldTime, newTime) \
((int8u) ((int8u)(newTime) - (int8u)(oldTime)))
/**
* @brief Returns the elapsed time between two 16 bit values.
* Result may not be valid if the time samples differ by more than 32767
*/
#define elapsedTimeInt16u(oldTime, newTime) \
((int16u) ((int16u)(newTime) - (int16u)(oldTime)))
/**
* @brief Returns the elapsed time between two 32 bit values.
* Result may not be valid if the time samples differ by more than 2147483647
*/
#define elapsedTimeInt32u(oldTime, newTime) \
((int32u) ((int32u)(newTime) - (int32u)(oldTime)))
/**
* @brief Returns TRUE if t1 is greater than t2. Can only account for 1 wrap
* around of the variable before it is wrong.
*/
#define MAX_INT8U_VALUE 0xFF
#define timeGTorEqualInt8u(t1, t2) \
(elapsedTimeInt8u(t2, t1) <= ((MAX_INT8U_VALUE + 1) / 2))
/**
* @brief Returns TRUE if t1 is greater than t2. Can only account for 1 wrap
* around of the variable before it is wrong.
*/
#define MAX_INT16U_VALUE 0xFFFF
#define timeGTorEqualInt16u(t1, t2) \
(elapsedTimeInt16u(t2, t1) <= ((MAX_INT16U_VALUE + 1) / 2))
/**
* @brief Returns TRUE if t1 is greater than t2. Can only account for 1 wrap
* around of the variable before it is wrong.
*/
#define MAX_INT32U_VALUE 0xFFFFFFFF
#define timeGTorEqualInt32u(t1, t2) \
(elapsedTimeInt32u(t2, t1) <= ((MAX_INT32U_VALUE + 1) / 2))
//@} \\END Time manipulation macros
#endif //__PLATFORMCOMMON_H__
/** @} END addtogroup */

View file

@ -0,0 +1,65 @@
/** @file hal/micro/led.h
* @brief Header for led APIs
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
/** @addtogroup led
* @brief Sample API funtions for controlling LEDs.
*
* When specifying an LED to use, always use the BOARDLEDx definitions that
* are defined within the BOARD_HEADER.
*
* See led.h for source code.
*@{
*/
/** @brief Configures GPIOs pertaining to the control of LEDs.
*/
void halInitLed(void);
/** @brief Ensures that the definitions from the BOARD_HEADER
* are always used as parameters to the LED functions.
*/
typedef int8u HalBoardLed;
// 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
// affect stack-based parameters and local variables, which is the
// general case for led paramters.
/** @brief Atomically wraps an XOR or similar operation for a single GPIO
* pin attached to an LED.
*
* @param led Identifier (from BOARD_HEADER) for the LED to be toggled.
*/
void halToggleLed(HalBoardLed led);
/** @brief Turns on (sets) a GPIO pin connected to an LED so that the LED
* turns on.
*
* @param led Identifier (from BOARD_HEADER) for the LED to turn on.
*/
void halSetLed(HalBoardLed led);
/** @brief Turns off (clears) a GPIO pin connected to an LED, which turns
* off the LED.
*
* @param led Identifier (from BOARD_HEADER) for the LED to turn off.
*/
void halClearLed(HalBoardLed led);
/** @brief Called by the stack to indicate activity over the radio (for
* both transmission and reception). It is called once with \c turnOn TRUE and
* shortly thereafter with \c turnOn FALSE.
*
* Typically does something interesting, such as change the state of
* an LED.
*
* @param turnOn See Usage.
*/
void halStackIndicateActivity(boolean turnOn);
/** @} // END addtogroup
*/

View file

@ -0,0 +1,36 @@
/** @file mems.h
* @brief Header for MB851 mems APIS
*
*
* <!--(C) COPYRIGHT 2010 STMicroelectronics. All rights reserved. -->
*/
#ifndef _MEMS_H_
#define _MEMS_H_
#include "hal/micro/mems_regs.h"
/** @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
currently used by the device */
typedef struct {
int8u outx_l;
int8u outx_h;
int8u outy_l;
int8u outy_h;
int8u outz_l;
int8u outz_h;
} t_mems_data;
/** @brief Mems Initialization function
*/
int8u mems_Init(void);
/** @brief Get mems acceleration values
*/
int8u mems_GetValue(t_mems_data *mems_data);
#endif /* _MEMS_H_ */

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