Ajout FishPeper

This commit is contained in:
Serge NOEL
2026-04-21 12:19:15 +02:00
parent 6744da3f88
commit 0c361a2440
2160 changed files with 589301 additions and 1 deletions

View File

@@ -0,0 +1,129 @@
CC = sdcc
HAL_SRCS := hal_led.c \
hal_debug.c \
hal_uart.c \
hal_clocksource.c \
hal_timeout.c \
hal_wdt.c \
hal_delay.c \
hal_dma.c \
hal_spi.c \
hal_cc25xx.c \
hal_io.c \
hal_adc.c \
hal_storage.c \
hal_sbus.c \
hal_ppm.c \
hal_soft_serial.c
ARCH_SRCS := $(addprefix $(ARCH_DIR)/, $(HAL_SRCS))
ARCH_HEADERS := $(ARCH_SRCS:.c=.h)
BOARD_SRCS := $(GENERIC_SRCS) \
$(ARCH_SRCS)
INCLUDE_DIRS := $(INCLUDE_DIRS) \
/usr/share/sdcc/include \
$(SRC_DIR) \
$(ARCH_DIR) \
$(TARGET_DIR)
LDFLAGS_FLASH = --out-fmt-ihx \
--code-loc 0x0c00 \
--code-size $(FLASH_SIZE) \
--xram-loc 0xf000 \
--xram-size 0x300 \
--iram-size 0x100
#programmer binary
CC_TOOL ?= cc-tool
CFLAGS += --model-small \
--opt-code-speed \
$(addprefix -I,$(INCLUDE_DIRS))
ifdef DEBUG
CFLAGS += --debug
endif
HEADERS := $(BOARD_SRCS:.c=.h)
ADB = $(BOARD_SRCS:.c=.adb)
ASM = $(BOARD_SRCS:.c=.asm)
LNK = $(BOARD_SRCS:.c=.lnk)
LST = $(BOARD_SRCS:.c=.lst)
REL = $(BOARD_SRCS:.c=.rel)
RST = $(BOARD_SRCS:.c=.rst)
SYM = $(BOARD_SRCS:.c=.sym)
#we build two flavours:
# _full : includes the bootloader, use this for initial flashing
# _update: just the opensky fw, relocated to be stored after the bootloader
TARGET_FULL = $(OBJECT_DIR)/$(RESULT)_full.hex
TARGET_UPDATE = $(OBJECT_DIR)/$(RESULT)_update.hex
TARGET_NO_BL = $(OBJECT_DIR)/$(RESULT)_no_bl.hex
BL_DIR = arch/cc251x/bootloader
BL_HEX = bootloader.hex
PCDB = $(PROGS:.hex=.cdb)
PLNK = $(PROGS:.hex=.lnk)
PMAP = $(PROGS:.hex=.map)
PMEM = $(PROGS:.hex=.mem)
PAOM = $(PROGS:.hex=)
SREC_CAT_FOUND := $(shell command -v srec_cat 2> /dev/null)
TARGET_OBJS = $(addsuffix .rel,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $(BOARD_SRCS))))
TARGET_DEPS = $(addsuffix .d,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $(BOARD_SRCS))))
# Search path for standard files
#vpath %.c ./src
#vpath %.c ./$(ARCH_DIR)
board: $(TARGET_UPDATE) $(TARGET_FULL)
bootloader:
@echo "### Building bootloader ###"
$(MAKE) -C $(BL_DIR) \
STYLECHECK_DISABLED=1 \
FLASH_SIZE=$(FLASH_SIZE) \
CONFIG_INCLUDE_DIR=../../../$(TARGET_DIR) \
clean all
$(TARGET_FULL): $(TARGET_UPDATE) bootloader
@echo "merging bootloader and main code"
ifndef SREC_CAT_FOUND
$(error "could not find srec_cat binary. make sure to install the srecord package")
else
srec_cat -disable_sequence_warnings \
$(TARGET_UPDATE) -intel \
$(BL_DIR)/$(BL_HEX) -intel \
-o $(TARGET_FULL) -intel
@echo "done."
endif
$(TARGET_UPDATE): $(TARGET_OBJS)
$(V1) echo Linking: $(TARGET)
$(V1) $(CC) $(LDFLAGS_FLASH) $(CFLAGS) -o $@ $^
# this is just for development, DO NOT flash this for production
$(TARGET_NO_BL): $(TARGET_OBJS)
$(V1) $(CC) $(LDFLAGS_FLASH) $(CFLAGS) --code-loc 0x000 -o $@ $^
$(OBJECT_DIR)/$(TARGET)/%.rel: %.c
$(V1) mkdir -p $(dir $@)
$(V1) echo "%% $(notdir $<)" "$(STDOUT)" && \
$(CC) -c -o $@ $(CFLAGS) $<
clean:
$(V1) echo Cleaning: $(TARGET)
$(V1) rm -f $(ADB) $(ASM) $(LNK) $(LST) $(TARGET_OBJS) $(RST) $(SYM)
$(V1) rm -f $(PROGS) $(PCDB) $(PLNK) $(PMAP) $(PMEM) $(PAOM)
$(V1) cd $(BL_DIR) && $(MAKE) clean
flash: $(OUTPUT_FULL)
$(CC_TOOL) -f -e -w $(TARGET_FULL)
flash_no_bl: $(OUTPUT_NO_BL)
$(CC_TOOL) -f -e -w $(TARGET_NO_BL)

View File

@@ -0,0 +1,172 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_adc.h"
#include "hal_defines.h"
#include "hal_cc25xx.h"
#include "portmacros.h"
#include "config.h"
#include "hal_dma.h"
#include "debug.h"
#include "delay.h"
#include "wdt.h"
// adc results
__xdata uint16_t hal_adc_data[2];
void hal_adc_init(void) {
hal_adc_data[0] = 0;
hal_adc_data[1] = 0;
// pin config -> dir = input
PORT2DIR(ADC_PORT) &= ~((1 << ADC1) | (1 << ADC0));
// set special function ADC for those pins:
ADCCFG = (1 << ADC1) | (1 << ADC0);
// set up adc:
// - external vref (avcc)
// - 10bit adc
// - stop on AIN7
ADCCON2 = ADCCON2_SREF_AVDD | ADCCON2_SDIV_10BIT | ADCCON2_SCH_AIN7;
// full speed, start conversion (bit0+1 always write as 1...)
ADCCON1 = ADCCON1_ST | ADCCON1_STSEL_FULL_SPEED | 0b11;
// configure DMA1 + DMA2:
hal_adc_dma_init(1, &hal_adc_data[0], DMA_TRIG_ADC_CH0 + ADC0);
hal_adc_dma_init(2, &hal_adc_data[1], DMA_TRIG_ADC_CH0 + ADC1);
// set pointer to the DMA configuration struct into DMA-channel 1-4
// configuration
SET_WORD(DMA1CFGH, DMA1CFGL, &hal_dma_config[1]);
hal_adc_dma_arm();
// for testing only, do not use under normal use
#if ADC_DO_TEST
adc_test();
#endif // ADC_DO_TEST
}
void hal_adc_dma_arm(void) {
DMAARM = (DMA_ARM_CH1 | DMA_ARM_CH2);
}
void hal_adc_process(void) {
if (hal_adc_dma_done()) {
// THIS OUTPUT BREAKS CONNECTIVITY! USE FOR DEBUGGING ONLY.
// fine, arm dma:
hal_adc_dma_arm();
} else {
// oops this should not happen
debug_putc('D');
// cancel and re arm dma
// DMAARM = DMA_ARM_ABORT | (DMA_ARM_CH1 | DMA_ARM_CH2);
}
}
void hal_adc_dma_init(uint8_t dma_id, uint16_t __xdata *dest_adr, uint8_t trig) {
hal_dma_config[dma_id].PRIORITY = DMA_PRI_LOW; // example used high...
hal_dma_config[dma_id].M8 = DMA_M8_USE_7_BITS;
hal_dma_config[dma_id].IRQMASK = DMA_IRQMASK_DISABLE;
hal_dma_config[dma_id].TRIG = trig;
hal_dma_config[dma_id].TMODE = DMA_TMODE_BLOCK;
hal_dma_config[dma_id].WORDSIZE = DMA_WORDSIZE_BYTE;
SET_WORD(hal_dma_config[dma_id].SRCADDRH, hal_dma_config[dma_id].SRCADDRL, &X_ADCL);
SET_WORD(hal_dma_config[dma_id].DESTADDRH, hal_dma_config[dma_id].DESTADDRL, dest_adr);
hal_dma_config[dma_id].VLEN = DMA_VLEN_USE_LEN;
SET_WORD(hal_dma_config[dma_id].LENH, hal_dma_config[dma_id].LENL, 2);
hal_dma_config[dma_id].SRCINC = DMA_SRCINC_1;
hal_dma_config[dma_id].DESTINC = DMA_DESTINC_1;
}
uint8_t hal_adc_dma_done(void) {
return ((DMAIRQ & (DMA_ARM_CH1 | DMA_ARM_CH2)) == (DMA_ARM_CH1 | DMA_ARM_CH2));
}
uint8_t hal_adc_get_scaled(uint8_t ch) {
uint16_t adc_data;
// adc data is HHHHHHHHLLLL0000 -> shift >>6 to get 10bit
// the cc2510 is _ALWAYS_ outputting data in two's complement format
// thus we shift >>7 to get 9 bit two's complement
// NOTE: the chip seems to have a bug, in contrast to the datasheet
// measuring a signal close to GND seems to deliver negative values (!)
// therefore we have to check for negative numbers and set them to zero
if (ch == 0) {
// convert to 8 bit (see above)
adc_data = hal_adc_data[1] >> 7;
if (adc_data & (1 << 8)) adc_data = 0; // bugfix: handle negative numbers
// return fixed value
return adc_data;
} else {
adc_data = hal_adc_data[0] >> 7;
if (adc_data & (1 << 8)) adc_data = 0; // bugfix: handle negative numbers
#ifdef ADC1_USE_ACS712
// acs712 is connected to ADC1
// when powered by 5V we can use a trick
// to get a good resolution:
// use inverted power inputs to get
// 0A = 2.5V
// 30A = 0.0V
return 255-(adc_data);
#else
return adc_data;
#endif // ADC1_USE_ACS712
}
}
#if ADC_DO_TEST
void hal_adc_test(void) {
debug("adc: running test\n"); debug_flush();
while (1) {
debug("adc: re-arming adc\n"); debug_flush();
hal_adc_dma_arm();
debug("adc: waiting for adc completion\n"); debug_flush();
while (!hal_adc_dma_done()) {
debug_putc('.');
delay_ms(1);
}
debug("\nadc: done. res[0] = "); debug_flush();
debug_put_uint16(hal_adc_data[0]>>4);
debug_putc('x'); debug_put_hex8(hal_adc_data[0]>>12);
debug_put_hex8((hal_adc_data[0]>>4)&0xff);
debug(", res[1] = "); debug_flush();
debug_put_uint16(hal_adc_data[1]>>4);
debug_putc('x'); debug_put_hex8(hal_adc_data[1]>>12);
debug_put_hex8((hal_adc_data[1]>>4)&0xff);
debug_put_newline();
delay_ms(100);
// reset wdt
wdt_reset();
}
}
#endif // ADC_DO_TEST

View File

@@ -0,0 +1,41 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_ADC_H_
#define HAL_ADC_H_
#include <stdint.h>
#ifdef ADC_PORT
#define ADC_ENABLED
#endif // ADC_PORT
// adc results
extern __xdata uint16_t hal_adc_data[2];
void hal_adc_init(void);
uint8_t hal_adc_get_scaled(uint8_t ch);
void hal_adc_dma_arm(void);
void hal_adc_dma_init(uint8_t dma_id, uint16_t __xdata *dest_adr, uint8_t trig);
uint8_t hal_adc_dma_done(void);
void hal_adc_test(void);
void hal_adc_process(void);
#endif // HAL_ADC_H_

View File

@@ -0,0 +1,231 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_cc25xx.h"
#include "cc25xx.h"
#include "hal_defines.h"
#include "hal_dma.h"
#include "delay.h"
#include "timeout.h"
#include "debug.h"
#include "led.h"
#include "frsky.h"
#include <cc2510fx.h>
EXTERNAL_MEMORY volatile uint8_t hal_cc25xx_mode;
void hal_cc25xx_init(void) {
// set highest prio for ch0 (RF)
IP1 |= (1<<0);
IP0 |= (1<<0);
hal_cc25xx_mode = CC25XX_MODE_RX;
// if we support LNA/PA make sure to config the pin as output:
#ifdef RF_LNA_PORT
PORT2DIR(RF_LNA_PORT) |= (1 << RF_LNA_PIN);
PORT2DIR(RF_PA_PORT) |= (1 << RF_PA_PIN);
// set default to LNA active
RF_PA_DISABLE();
RF_LNA_ENABLE();
#endif // RF_LNA_PORT
// if we support Diversity make sure to config the pin as output:
#ifdef RF_ANTENNA_SWITCH_PORT
PORT2DIR(RF_ANTENNA_SWITCH_PORT) |= (1 << RF_ANTENNA_SWITCH_PIN);
// select first antenna
RF_ANTENNA_SELECT_A();
#endif // RF_ANTENNA_SWITCH_PORT
// if we support HIGH GAIN mode config pin as output:
#ifdef RF_HIGH_GAIN_MODE_PORT
PORT2DIR(RF_HIGH_GAIN_MODE_PORT) |= (1 << RF_HIGH_GAIN_MODE_PIN);
// enable high gain mode?
#ifdef RF_HIGH_GAIN_MODE_ENABLED
RF_HIGH_GAIN_MODE_ENABLE();
#else
RF_HIGH_GAIN_MODE_DISABLE();
#endif // RF_HIGH_GAIN_MODE_ENABLED
#endif // RF_HIGH_GAIN_MODE_PORT
// if we support Bypass mode make sure to config the pin as output:
#ifdef RF_BYPASS_PORT
PORT2DIR(RF_BYPASS_MODE_PORT) |= (1 << RF_BYPASS_MODE_PIN);
// set default to Bypass off
#ifdef RF_BYPASS_MODE_ENABLED
RF_BYPASS_MODE_ENABLE();
#else
RF_BYPASS_MODE_DISABLE();
#endif // RF_BYPASS_MODE_ENABLED
#endif // RF_BYPASS_PORT
}
uint32_t hal_cc25xx_set_antenna(uint8_t id) {
// select antenna 0 or 1:
#ifdef RF_ANTENA_SWITCH_PORT
if (id) {
RF_ANTENNA_SELECT_B();
} else {
RF_ANTENNA_SELECT_A();
}
#endif // RF_ANTENNA_SWITCH_PORT
return id;
}
void hal_cc25xx_disable_rf_interrupt(void) {
IEN2 &= ~(IEN2_RFIE);
RFIM = 0;
}
void hal_cc25xx_enter_rxmode(void) {
#ifdef RF_LNA_PORT
RF_LNA_ENABLE();
delay_us(20);
RF_PA_DISABLE();
delay_us(5);
#endif // RF_LNA_PORT
// set up dma for radio--->buffer
hal_cc25xx_setup_rf_dma(CC25XX_MODE_RX);
// configure interrupt for every received packet
IEN2 |= (IEN2_RFIE);
// mask done irq
RFIM = (1<<4);
// interrupts should be enabled globally already..
// skip this! sei();
}
void hal_cc25xx_enter_txmode(void) {
#ifdef RF_LNA_PORT
RF_LNA_DISABLE();
delay_us(20);
RF_PA_ENABLE();
delay_us(5);
#endif // RF_LNA_PORT
// abort ch0
DMAARM = DMA_ARM_ABORT | DMA_ARM_CH0;
hal_cc25xx_setup_rf_dma(CC25XX_MODE_TX);
}
void hal_cc25xx_setup_rf_dma(uint8_t mode) {
// CPU has priority over DMA
// Use 8 bits for transfer count
// No DMA interrupt when done
// DMA triggers on radio
// Single transfer per trigger.
// One byte is transferred each time.
hal_dma_config[0].PRIORITY = DMA_PRI_HIGH;
hal_dma_config[0].M8 = DMA_M8_USE_8_BITS;
hal_dma_config[0].IRQMASK = DMA_IRQMASK_DISABLE;
hal_dma_config[0].TRIG = DMA_TRIG_RADIO;
hal_dma_config[0].TMODE = DMA_TMODE_SINGLE;
hal_dma_config[0].WORDSIZE = DMA_WORDSIZE_BYTE;
// store mode
hal_cc25xx_mode = mode;
if (hal_cc25xx_mode == CC25XX_MODE_TX) {
// Transmitter specific DMA settings
// Source: radioPktBuffer
// Destination: RFD register
// Use the first byte read + 1
// Sets the maximum transfer count allowed (length byte + data)
// Data source address is incremented by 1 byte
// Destination address is constant
SET_WORD(hal_dma_config[0].SRCADDRH, hal_dma_config[0].SRCADDRL, frsky_packet_buffer);
SET_WORD(hal_dma_config[0].DESTADDRH, hal_dma_config[0].DESTADDRL, &X_RFD);
hal_dma_config[0].VLEN = DMA_VLEN_FIRST_BYTE_P_1;
SET_WORD(hal_dma_config[0].LENH, hal_dma_config[0].LENL, (FRSKY_PACKET_LENGTH+1));
hal_dma_config[0].SRCINC = DMA_SRCINC_1;
hal_dma_config[0].DESTINC = DMA_DESTINC_0;
} else {
// Receiver specific DMA settings:
// Source: RFD register
// Destination: radioPktBuffer
// Use the first byte read + 3 (incl. 2 status bytes)
// Sets maximum transfer count allowed (length byte + data + 2 status bytes)
// Data source address is constant
// Destination address is incremented by 1 byte for each write
SET_WORD(hal_dma_config[0].SRCADDRH, hal_dma_config[0].SRCADDRL, &X_RFD);
SET_WORD(hal_dma_config[0].DESTADDRH, hal_dma_config[0].DESTADDRL, frsky_packet_buffer);
hal_dma_config[0].VLEN = DMA_VLEN_FIRST_BYTE_P_3;
SET_WORD(hal_dma_config[0].LENH, hal_dma_config[0].LENL, (FRSKY_PACKET_LENGTH+3));
hal_dma_config[0].SRCINC = DMA_SRCINC_0;
hal_dma_config[0].DESTINC = DMA_DESTINC_1;
}
// Save pointer to the DMA configuration struct into DMA-channel 0
// configuration registers
SET_WORD(DMA0CFGH, DMA0CFGL, &hal_dma_config[0]);
// frsky_packet_received = 0;
}
void hal_cc25xx_enable_receive(void) {
// start receiving on dma channel 0
DMAARM = DMA_ARM_CH0;
}
void hal_cc25xx_rf_interrupt(void) __interrupt RF_VECTOR {
// clear int flag
RFIF &= ~(1<<4);
// clear general statistics reg
S1CON &= ~0x03;
if (hal_cc25xx_mode == CC25XX_MODE_RX) {
// mark as received:
frsky_packet_received = 1;
// re arm DMA channel 0
hal_cc25xx_enable_receive();
} else {
frsky_packet_sent = 1;
}
}
uint8_t hal_cc25xx_transmission_completed(void) {
// this flag is set in the RF isr
return (frsky_packet_sent);
}
void hal_cc25xx_transmit_packet(volatile uint8_t *buffer, uint8_t len) {
UNUSED(buffer);
UNUSED(len);
RFST = RFST_STX;
// start transmitting on dma channel 0
DMAARM = DMA_ARM_CH0;
// mark packet as not sent (will be modified in RF isr):
frsky_packet_sent = 0;
// tricky: this will force an int request and
// initiate the actual transmission
S1CON |= 0x03;
}

View File

@@ -0,0 +1,276 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_CC25XX_H_
#define HAL_CC25XX_H_
#include <stdint.h>
#include "hal_defines.h"
#include "config.h"
#include <cc2510fx.h>
#define CC25XX_FIFO FIFO
#define hal_cc25xx_set_register(reg, val) { reg = val; }
#define hal_cc25xx_strobe(val) { RFST = val; }
#define hal_cc25xx_get_register(r) (r)
#define hal_cc25xx_get_register_burst(r) (r)
#ifdef RF_LNA_PORT
#define RF_LNA_ENABLE() { PORT2BIT(RF_LNA_PORT, RF_LNA_PIN) = RF_LNA_ON_LEVEL; }
#define RF_LNA_DISABLE() { PORT2BIT(RF_LNA_PORT, RF_LNA_PIN) = ~RF_LNA_ON_LEVEL; }
#define RF_PA_ENABLE() { PORT2BIT(RF_PA_PORT, RF_PA_PIN) = RF_PA_ON_LEVEL; }
#define RF_PA_DISABLE() { PORT2BIT(RF_PA_PORT, RF_PA_PIN) = ~RF_PA_ON_LEVEL; }
#endif // RF_LNA_PORT
#ifdef RF_ANTENNA_SWITCH_PORT
#define RF_ANTENNA_SELECT_A() { PORT2BIT(RF_ANTENNA_SWITCH_PORT, RF_ANTENNA_SWITCH_PIN) = RF_ANTENNA_A_LEVEL; }
#define RF_ANTENNA_SELECT_B() { PORT2BIT(RF_ANTENNA_SWITCH_PORT, RF_ANTENNA_SWITCH_PIN) = ~RF_ANTENNA_A_LEVEL; }
#endif // RF_ANTENNA_SWITCH_PORT
#ifdef RF_HIGH_GAIN_MODE_PORT
#define RF_HIGH_GAIN_MODE_ENABLE() { \
PORT2BIT(RF_HIGH_GAIN_MODE_PORT, RF_HIGH_GAIN_MODE_PIN) = RF_HIGH_GAIN_MODE_ON_LEVEL; }
#define RF_HIGH_GAIN_MODE_DISBALE() { \
PORT2BIT(RF_HIGH_GAIN_MODE_PORT, RF_HIGH_GAIN_MODE_PIN) = ~RF_HIGH_GAIN_MODE_ON_LEVEL; }
#endif // RF_HIGH_GAIN_MODE_PORT
#ifdef RF_BYPASS_MODE_PORT
#define RF_BYPASS_MODE_ENABLE() { PORT2BIT(RF_BYPASS_MODE_PORT, RF_BYPASS_MODE_PIN) = RF_BYPASS_MODE_ON_LEVEL; }
#define RF_BYPASS_MODE_DISABLE() { PORT2BIT(RF_BYPASS_MODE_PORT, RF_BYPASS_MODE_PIN) = ~RF_BYPASS_MODE_ON_LEVEL; }
#endif // RF_BYPASS_MODE_PORT
uint32_t hal_cc25xx_set_antenna(uint8_t id);
#define hal_cc25xx_process_packet(packet_received, buffer, maxlen) {}
void hal_cc25xx_init(void);
#define hal_cc25xx_set_gdo_mode() {}
void hal_cc25xx_disable_rf_interrupt(void);
#define hal_cc25xx_rx_sleep() { delay_us(1000); }
#define hal_cc25xx_tx_sleep() { delay_us(900); }
void hal_cc25xx_enter_rxmode(void);
void hal_cc25xx_enter_txmode(void);
void hal_cc25xx_setup_rf_dma(uint8_t mode);
void hal_cc25xx_enable_receive(void);
void hal_cc25xx_transmit_packet(volatile uint8_t *buffer, uint8_t len);
uint8_t hal_cc25xx_transmission_completed(void);
void hal_cc25xx_rf_interrupt(void) __interrupt RF_VECTOR;
#define hal_cc25xx_partnum_valid(p, v) ((p == 0x81) && (v = 0x04))
#define PERCFG_U0CFG (1<<0)
#define PERCFG_U1CFG (1<<1)
#define PERCFG_T4CFG (1<<4)
#define PERCFG_T3CFG (1<<5)
#define PERCFG_T1CFG (1<<6)
#define IEN0_RFTXRXIE (1<<0)
#define IEN0_ADCIE (1<<1)
#define IEN0_URX0IE (1<<2)
#define IEN0_URX1IE (1<<3)
#define IEN0_ENCIE (1<<4)
#define IEN0_STIE (1<<5)
#define IEN0_EA (1<<7)
// bit 7 - unused
// bit 6 - unused
#define PICTL_P2IEN (1<<5)
#define PICTL_P0IENH (1<<4)
#define PICTL_P0IENL (1<<3)
#define PICTL_P2ICON (1<<2)
#define PICTL_P1ICON (1<<1)
#define PICTL_P0ICON (1<<0)
#define IEN1_P0IE (1<<5)
#define IEN1_T4IE (1<<4)
#define IEN1_T3IE (1<<3)
#define IEN1_T2IE (1<<2)
#define IEN1_T1IE (1<<1)
#define IEN1_DMAIE (1<<0)
#define IEN2_RFIE (1<<0)
#define IEN2_P2IE (1<<1)
#define IEN2_UTX0IE (1<<2)
#define IEN2_UTX1IE (1<<3)
#define IEN2_P1IE (1<<4)
#define IEN2_WDTIE (1<<5)
#define U0GCR_ORDER (1<<5)
#define U0GCR_CPHA (1<<6)
#define U0GCR_CPOL (1<<7)
#define U0CSR_TX_BYTE (1<<1)
#define U1GCR_ORDER (1<<5)
#define U1GCR_CPHA (1<<6)
#define U1GCR_CPOL (1<<7)
#define UxCSR_RX_ENABLE (1<<6)
#define UxCSR_RX_BYTE (1<<2)
#define UxCSR_TX_BYTE (1<<1)
#define RFST_SNOP 0x05
#define RFST_SIDLE 0x04
#define RFST_STX 0x03
#define RFST_SRX 0x02
#define RFST_SCAL 0x01
#define RFST_SFSTXON 0x00
// statemachine on cc2510 is different.
// instead of SF*X we should use SIDLE
#define RFST_SFTX RFST_SIDLE
#define RFST_SFRX RFST_SIDLE
// append status
#define CC2500_PKTCTRL1_APPEND_STATUS (1<<2)
// crc autoflush
#define CC2500_PKTCTRL1_CRC_AUTOFLUSH (1<<3)
// adress checks
#define CC2500_PKTCTRL1_FLAG_ADR_CHECK_00 ((0<<1) | (0<<0))
#define CC2500_PKTCTRL1_FLAG_ADR_CHECK_01 ((0<<1) | (1<<0))
#define CC2500_PKTCTRL1_FLAG_ADR_CHECK_10 ((1<<1) | (0<<0))
#define CC2500_PKTCTRL1_FLAG_ADR_CHECK_11 ((1<<1) | (1<<0))
#define CLKCON_TICKSPD_001 (0b00001000)
#define CLKCON_TICKSPD_010 (0b00010000)
#define CLKCON_TICKSPD_011 (0b00011000)
#define CLKCON_TICKSPD_100 (0b00100000)
#define CLKCON_TICKSPD_101 (0b00101000)
#define CLKCON_TICKSPD_110 (0b00110000)
#define CLKCON_TICKSPD_111 (0b00111000)
#define CLKCON_OSC32K (1<<7)
#define ADCCON2_SREF_INT (0b00<<6)
#define ADCCON2_SREF_EXT (0b01<<6)
#define ADCCON2_SREF_AVDD (0b10<<6)
#define ADCCON2_SREF_EXTDIFF (0b11<<6)
#define ADCCON2_SDIV_7BIT (0b00<<4)
#define ADCCON2_SDIV_9BIT (0b01<<4)
#define ADCCON2_SDIV_10BIT (0b10<<4)
#define ADCCON2_SDIV_12BIT (0b11<<4)
#define ADCCON2_SCH_AIN0 (0b0000<<0)
#define ADCCON2_SCH_AIN1 (0b0001<<0)
#define ADCCON2_SCH_AIN2 (0b0010<<0)
#define ADCCON2_SCH_AIN3 (0b0011<<0)
#define ADCCON2_SCH_AIN4 (0b0100<<0)
#define ADCCON2_SCH_AIN5 (0b0101<<0)
#define ADCCON2_SCH_AIN6 (0b0110<<0)
#define ADCCON2_SCH_AIN7 (0b0111<<0)
#define ADCCON2_SCH_AIN0AIN1 (0b1000<<0)
#define ADCCON2_SCH_AIN2AIN3 (0b1001<<0)
#define ADCCON2_SCH_AIN4AIN5 (0b1010<<0)
#define ADCCON2_SCH_AIN6AIN7 (0b1011<<0)
#define ADCCON2_SCH_GND (0b1100<<0)
#define ADCCON2_SCH_POSVREF (0b1101<<0)
#define ADCCON2_SCH_TEMP (0b1110<<0)
#define ADCCON2_SCH_VDD3 (0b1111<<0)
#define ADCCON1_ST (1<<6)
#define ADCCON1_STSEL_FULL_SPEED (0b01<<4)
#define WDCTL_EN (1<<3)
#define WDCTL_MODE (1<<2)
#define WDCTL_INT (0b11)
#define WDCTL_INT_1S (0b00)
#define FCTL_BUSY (1<<7)
#define FCTL_SWBUSY (1<<6)
#define FCTL_WRITE (1<<1)
#define FCTL_ERASE (1<<0)
#define T1CTL_MODE_SUSPEND (0b00<<0)
#define T1CTL_MODE_FREE_RUNNING (0b01<<0)
#define T1CTL_MODE_MODULO (0b10<<0)
#define T1CTL_MODE_UPDOWN (0b11<<0)
#define T1CTL_DIV_1 (0b00<<2)
#define T1CTL_DIV_8 (0b01<<2)
#define T1CTL_DIV_32 (0b10<<2)
#define T1CTL_DIV_128 (0b11<<2)
#define T1CTL_OVFIF (1<<4)
#define T1CTL_CH0_IF (1<<5)
#define T1CTL_CH1_IF (1<<6)
#define T1CTL_CH2_IF (1<<7)
#define T3CTL_MODE_SUSPEND (0b00<<0)
#define T3CTL_MODE_FREE_RUNNING (0b01<<0)
#define T3CTL_MODE_MODULO (0b10<<0)
#define T3CTL_MODE_UPDOWN (0b11<<0)
#define T3CTL_CLR (1<<2)
#define T3CTL_OVFIM (1<<3)
#define T3CTL_START (1<<4)
#define T3CTL_DIV_1 (0b000<<5)
#define T3CTL_DIV_2 (0b001<<5)
#define T3CTL_DIV_4 (0b010<<5)
#define T3CTL_DIV_8 (0b011<<5)
#define T3CTL_DIV_16 (0b100<<5)
#define T3CTL_DIV_32 (0b101<<5)
#define T3CTL_DIV_64 (0b110<<5)
#define T3CTL_DIV_128 (0b111<<5)
#define T4CTL_MODE_SUSPEND (0b00<<0)
#define T4CTL_MODE_FREE_RUNNING (0b01<<0)
#define T4CTL_MODE_MODULO (0b10<<0)
#define T4CTL_MODE_UPDOWN (0b11<<0)
#define T4CTL_CLR (1<<2)
#define T4CTL_OVFIM (1<<3)
#define T4CTL_START (1<<4)
#define T4CTL_DIV_1 (0b000<<5)
#define T4CTL_DIV_2 (0b001<<5)
#define T4CTL_DIV_4 (0b010<<5)
#define T4CTL_DIV_8 (0b011<<5)
#define T4CTL_DIV_16 (0b100<<5)
#define T4CTL_DIV_32 (0b101<<5)
#define T4CTL_DIV_64 (0b110<<5)
#define T4CTL_DIV_128 (0b111<<5)
#define T1CCTLx_CAP_NO (0b00<<0)
#define T1CCTLx_CAP_RISING (0b01<<0)
#define T1CCTLx_CAP_FALLING (0b10<<0)
#define T1CCTLx_CAP_BOTH (0b11<<0)
#define T1CCTLx_MODE_CAPTURE (0<<2)
#define T1CCTLx_MODE_COMPARE (1<<2)
#define T1CCTLx_CMP_SET (0b000<<3)
#define T1CCTLx_CMP_CLEAR (0b001<<3)
#define T1CCTLx_CMP_TOGGLE (0b010<<3)
#define T1CCTLx_CMP_SETCLR0 (0b011<<3)
#define T1CCTLx_CMP_CLRSET0 (0b100<<3)
#define T1CCTLx_CMP_RES0 (0b101<<3)
#define T1CCTLx_CMP_RES1 (0b110<<3)
#define T1CCTLx_CMP_RES2 (0b111<<3)
#define T1CCTLx_IM (1<<6)
#define T1CCTLx_CPSEL_RF (1<<7)
// add missing defines
#include <compiler.h>
SFRX(TEST2, 0xDF23);
SFRX(TEST1, 0xDF24);
SFRX(TEST0, 0xDF25);
#endif // HAL_CC25XX_H_

View File

@@ -0,0 +1,50 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_clocksource.h"
#include "hal_cc25xx.h"
#include "led.h"
void hal_clocksource_init(void) {
// for debugging clocksource problems
led_red_on();
led_green_on();
// power up osc (?)
SLEEP &= ~CLOCKSOURCE_OSC_PD_BIT;
// wait for XOSC stable
while (!CLOCKSOURCE_XOSC_STABLE()) {}
NOP();
// start crystal osc as HS clocksource, OSC32 is int rc osc
CLKCON = 0x80;
// wait for selection to be active
while (!CLOCKSOURCE_XOSC_STABLE()) {}
NOP();
// power down the unused oscillator
SLEEP |= CLOCKSOURCE_OSC_PD_BIT;
// for debugging clocksource problems
led_red_off();
led_green_off();
}

View File

@@ -0,0 +1,47 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_CLOCKSOURCE_H_
#define HAL_CLOCKSOURCE_H_
#include "hal_cc25xx.h"
void hal_clocksource_init(void);
// bit mask used to check the stability of XOSC
#define CLOCKSOURCE_XOSC_STABLE_BIT 0x40
// bit mak used to check the stability of the High-frequency RC oscillator
#define CLOCKSOURCE_HFRC_STB_BIT 0x20
// bit maks used to power down system clock oscillators
#define CLOCKSOURCE_OSC_PD_BIT 0x04
// bit mask used to control the system clock oscillator
#define CLOCKSOURCE_MAIN_OSC_BITS 0x7F
// bit mask used to select/check the system clock oscillator
#define CLOCKSOURCE_OSC_BIT 0x40
// macros to check for stable oscs:
#define CLOCKSOURCE_HFRC_OSC_STABLE() (SLEEP & (CLOCKSOURCE_HFRC_STB_BIT))
#define CLOCKSOURCE_XOSC_STABLE() (SLEEP & (CLOCKSOURCE_XOSC_STABLE_BIT))
#define CLOCKSOURCE_XOSC 0
#define CLOCKSOURCE_HFRC 1
#endif // HAL_CLOCKSOURCE_H_

View File

@@ -0,0 +1,160 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_debug.h"
#include "hal_defines.h"
void hal_debug_init(void) {
__xdata union hal_uart_config_t uart_config;
#ifndef DEBUG_UART
#error "ERROR: DEBUG_UART not defined"
#endif // DEBUG_UART
#if DEBUG_UART == USART0_P0
// USART0 use ALT1 -> Clear flag -> Port P0_3 = TX
PERCFG &= ~(PERCFG_U0CFG);
// configure pin P0_3 (TX) as special function:
P0SEL |= (1<<3);
// set P0_5 as normal IO
P1SEL &= ~(1<<5);
// make tx pin output:
P0DIR |= (1<<3);
#elif DEBUG_UART == USART0_P1
// USART0 use ALT2 -> Set flag -> Port P1_5 = TX
PERCFG |= (PERCFG_U0CFG);
// configure pin P1_5 (TX) as special function
P1SEL |= (1<<5);
// set P0_3 as normal IO
P0SEL &= ~(1<<3);
// make tx pin output:
P1DIR |= (1<<5);
#elif DEBUG_UART == USART1_P0
// USART1 use ALT1 -> Clear flag -> Port P0_4 = TX
PERCFG &= ~(PERCFG_U1CFG);
// USART1 has priority when USART0 is also enabled
P2DIR = (P2DIR & 0x3F) | 0b01000000;
// configure pin P0_4 special function:
P0SEL |= (1<<4);
// configure P1_6 as normal IO
P1SEL &= ~(1<<6);
// make sure all P1 pins switch to normal GPIO
// P1SEL &= ~(0xF0);
// make tx pin output:
P0DIR |= (1<<4);
#else
#error "ERROR: UNSUPPORTED DEBUG UART"
#endif // DEBUG_UART == ...
// this assumes cpu runs from XOSC (26mhz) !
// set baudrate
#if (DEBUG_UART == USART0_P0) || (DEBUG_UART == USART0_P1)
U0BAUD = CC2510_BAUD_M_115200;
U0GCR = (U0GCR & ~0x1F) | (CC2510_BAUD_E_115200);
#else
U1BAUD = CC2510_BAUD_M_115200;
U1GCR = (U1GCR & ~0x1F) | (CC2510_BAUD_E_115200);
#endif // DEBUG_UART == ...
// set up config
uart_config.bit.START = 0; // startbit level = low
uart_config.bit.STOP = 1; // stopbit level = high
uart_config.bit.SPB = 0; // 1 stopbit
uart_config.bit.PARITY = 0; // no parity
uart_config.bit.BIT9 = 0; // 8bit
uart_config.bit.D9 = 0; // 8 Bits
uart_config.bit.FLOW = 0; // no hw flow control
uart_config.bit.ORDER = 0; // lsb first
hal_debug_set_mode(&uart_config);
// enable interrupts:
sei();
}
static void hal_debug_set_mode(EXTERNAL_MEMORY union hal_uart_config_t *cfg) {
#if (DEBUG_UART == USART0_P0) || (DEBUG_UART == USART0_P1)
// enable uart mode
U0CSR |= 0x80;
// store config to UxUCR register
U0UCR = cfg->byte & (0x7F);
// store config to U1GCR: (msb/lsb)
if (cfg->bit.ORDER) {
U0GCR |= U0GCR_ORDER;
} else {
U0GCR &= ~U0GCR_ORDER;
}
// interrupt prio to 0 (0..3=highest)
IP0 &= ~(1<<2);
IP1 &= ~(1<<2);
#else
// enable uart mode
U1CSR |= 0x80;
// store config to UxUCR register
U1UCR = cfg->byte & (0x7F);
// store config to U1GCR: (msb/lsb)
if (cfg->bit.ORDER) {
U1GCR |= U1GCR_ORDER;
} else {
U1GCR &= ~U1GCR_ORDER;
}
// interrupt prio to 0 (0..3=highest)
IP0 &= ~(1<<3);
IP1 &= ~(1<<3);
#endif // DEBUG_UART == ...
}
void hal_debug_start_transmission(uint8_t ch) {
#if (DEBUG_UART == USART0_P0) || (DEBUG_UART == USART0_P1)
// clear flags
UTX0IF = 0;
U0CSR &= ~UxCSR_TX_BYTE;
// enable TX int:
IEN2 |= (IEN2_UTX0IE);
// send this char
U0DBUF = ch;
#else
// clear flags
UTX1IF = 0;
U1CSR &= ~UxCSR_TX_BYTE;
// enable TX int:
IEN2 |= (IEN2_UTX1IE);
// send this char
U1DBUF = ch;
#endif // DEBUG_UART == ...
}

View File

@@ -0,0 +1,53 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_DEBUG_H_
#define HAL_DEBUG_H_
#include "hal_cc25xx.h"
#include "hal_uart.h"
#include <stdint.h>
void hal_debug_init(void);
void hal_debug_start_transmission(uint8_t ch);
#if (DEBUG_UART == USART0_P0) || (DEBUG_UART == USART0_P1)
#define hal_debug_int_enabled() (IEN2 & (IEN2_UTX0IE))
#else
#define hal_debug_int_enabled() (IEN2 & (IEN2_UTX1IE))
#endif // DEBUG_UART == ...
#define hal_debug_int_enable() { sei(); }
#define hal_debug_int_disable() { cli(); }
static void hal_debug_set_mode(__xdata union hal_uart_config_t *cfg);
#if (DEBUG_UART == USART0_P0) || (DEBUG_UART == USART0_P1)
#define DEBUG_ISR(void) hal_uart_tx_interrupt(void) __interrupt UTX0_VECTOR
#define HAL_DEBUG_ISR_FLAG_SET() (1)
#define HAL_DEBUG_ISR_CLEAR_FLAG() { UTX0IF = 0; }
#define HAL_DEBUG_ISR_DISABLE() { IEN2 &= ~(IEN2_UTX0IE); }
#define HAL_DEBUG_TX_DATA(data) { U0DBUF = data; }
#else
#define DEBUG_ISR(void) hal_uart_tx_interrupt(void) __interrupt UTX1_VECTOR
#define HAL_DEBUG_ISR_FLAG_SET() (1)
#define HAL_DEBUG_ISR_CLEAR_FLAG() { UTX1IF = 0; }
#define HAL_DEBUG_ISR_DISABLE() { IEN2 &= ~(IEN2_UTX1IE); }
#define HAL_DEBUG_TX_DATA(data) { U1DBUF = data; }
#endif // DEBUG_UART == ...
#endif // HAL_DEBUG_H_

View File

@@ -0,0 +1,29 @@
#ifndef __HAL_DEFINES_H__
#define __HAL_DEFINES_H__
#define EXTERNAL_MEMORY __xdata
#define EXTERNAL_DATA __data
#define inline
#define sei() { IEN0 |= IEN0_EA; }
#define cli() { IEN0 &= ~IEN0_EA; }
#ifndef NOP
#define NOP() { __asm nop __endasm; }
#endif
#define NOP45() { NOP(); NOP(); NOP(); NOP(); NOP(); NOP(); NOP(); NOP();
#define HI(a) (uint8_t) ((uint16_t)(a) >> 8 )
#define LO(a) (uint8_t) (uint16_t)(a)
#define SET_WORD(H, L, val) { (H) = HI(val); (L) = LO(val); }
// necessary for timer registers. todo: check if necessary for others as well...
#define SET_WORD_LO_FIRST(H, L, val) {(L) = LO(val); (H) = HI(val); }
#define UNUSED(x) (void)(x);
#define USART0_P0 0
#define USART0_P1 1
#define USART1_P0 2
#define USART1_P1 3
#endif // __HAL_DEFINES_H__

View File

@@ -0,0 +1,58 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_delay.h"
// busy wait delay loop. not 100% accurate
void hal_delay_ms(uint16_t ms) {
#define DELAY_MS_LOOP_A 86
#define DELAY_MS_LOOP_B 30
while (ms--) {
// this asm snippet gives us roughly 1ms delay:
__asm
mov r1, #DELAY_MS_LOOP_A
00000$: // delay_ms_loop_outer
dec r1
mov a, r1
jz 00002$
mov r2, #DELAY_MS_LOOP_B
00001$: // delay_ms_loop_inner
dec r2
mov a, r2
jz 00000$
sjmp 00001$
00002$: // delay_ms_done
__endasm;
}
}
// busy wait delay loop
// this is more or less accurate
void hal_delay_us(uint16_t us) {
#define DELAY_US_LOOP 1
while (us--) {
__asm
nop
nop
nop
__endasm;
}
}

View File

@@ -0,0 +1,28 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_DELAY_H_
#define HAL_DELAY_H_
#include <stdint.h>
void hal_delay_ms(uint16_t ms);
void hal_delay_us(uint16_t us);
#define hal_delay_45nop(void) { uint8_t n=45; while (n--) { NOP(); } }
#endif // HAL_DELAY_H_

View File

@@ -0,0 +1,26 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "main.h"
#include "hal_dma.h"
// dma config
// dma0 can be given independently but 1-4 has
// to be given in one consequent array...
__xdata HAL_DMA_DESC hal_dma_config[5];

View File

@@ -0,0 +1,152 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_DMA_H_
#define HAL_DMA_H_
#include <stdint.h>
// HAL_DMA CONFIG
// see https:// e2e.ti.com/support/wireless_connectivity/f/156/t/16922
typedef struct {
uint8_t SRCADDRH;
uint8_t SRCADDRL;
uint8_t DESTADDRH;
uint8_t DESTADDRL;
uint8_t LENH : 5;
uint8_t VLEN : 3;
uint8_t LENL : 8;
uint8_t TRIG : 5;
uint8_t TMODE : 2;
uint8_t WORDSIZE : 1;
uint8_t PRIORITY : 2;
uint8_t M8 : 1;
uint8_t IRQMASK : 1;
uint8_t DESTINC : 2;
uint8_t SRCINC : 2;
} HAL_DMA_DESC;
extern __xdata HAL_DMA_DESC hal_dma_config[5];
// Use LEN for transfer count
#define DMA_VLEN_USE_LEN 0x00
// Transfer the number of bytes specified by the first byte +1
#define DMA_VLEN_FIRST_BYTE_P_1 0x01
// Transfer the number of bytes indicated by the first byte (itself included)
#define DMA_VLEN_FIRST_BYTE 0x02
// Transfer the number of bytes specified by the first byte +2
#define DMA_VLEN_FIRST_BYTE_P_2 0x03
// Transfer the number of bytes specified by the first byte +3
#define DMA_VLEN_FIRST_BYTE_P_3 0x04
// The maximum length is always decided by the first byte
#define DMA_LEN_MAX 0xFF
// Transfer a byte at a time
#define DMA_WORDSIZE_BYTE 0x00
// Transfer a 16-bit word at a time
#define DMA_WORDSIZE_WORD 0x01
// Transfer a single byte/word after each DMA trigger
#define DMA_TMODE_SINGLE 0x00
// Transfer block of data (length len) after each DMA trigger
#define DMA_TMODE_BLOCK 0x01
// Transfer single byte/word (after len transfers, rearm DMA)
#define DMA_TMODE_SINGLE_REPEATED 0x02
// Transfer block of data (after len transfers, rearm DMA)
#define DMA_TMODE_BLOCK_REPEATED 0x03
#define DMA_TRIG_NONE 0 // No trigger, setting DMAREQ.DMAREQx bit starts transfer
#define DMA_TRIG_PREV 1 // DMA channel is triggered by completion of previous channel
#define DMA_TRIG_T1_CH0 2 // Timer 1, compare, channel 0
#define DMA_TRIG_T1_CH1 3 // Timer 1, compare, channel 1
#define DMA_TRIG_T1_CH2 4 // Timer 1, compare, channel 2
#define DMA_TRIG_T2_COMP 5 // Timer 2, compare
#define DMA_TRIG_T2_OVFL 6 // Timer 2, overflow
#define DMA_TRIG_T3_CH0 7 // Timer 3, compare, channel 0
#define DMA_TRIG_T3_CH1 8 // Timer 3, compare, channel 1
#define DMA_TRIG_T4_CH0 9 // Timer 4, compare, channel 0
#define DMA_TRIG_T4_CH1 10 // Timer 4, compare, channel 1
#define DMA_TRIG_ST 11 // Sleep Timer compare
#define DMA_TRIG_IOC_0 12 // Port 0 I/O pin input transition
#define DMA_TRIG_IOC_1 13 // Port 1 I/O pin input transition
#define DMA_TRIG_URX0 14 // USART0 RX complete
#define DMA_TRIG_UTX0 15 // USART0 TX complete
#define DMA_TRIG_URX1 16 // USART1 RX complete
#define DMA_TRIG_UTX1 17 // USART1 TX complete
#define DMA_TRIG_FLASH 18 // Flash data write complete
#define DMA_TRIG_RADIO 19 // RF packet byte received/transmit
#define DMA_TRIG_ADC_CHALL 20 // ADC end of a conversion in a sequence, sample ready
#define DMA_TRIG_ADC_CH0 21 // ADC end of conversion channel 0 in sequence, sample ready
#define DMA_TRIG_ADC_CH1 22 // ADC end of conversion channel 1 in sequence, sample ready
#define DMA_TRIG_ADC_CH2 23 // ADC end of conversion channel 2 in sequence, sample ready
#define DMA_TRIG_ADC_CH3 24 // ADC end of conversion channel 3 in sequence, sample ready
#define DMA_TRIG_ADC_CH4 25 // ADC end of conversion channel 4 in sequence, sample ready
#define DMA_TRIG_ADC_CH5 26 // ADC end of conversion channel 5 in sequence, sample ready
#define DMA_TRIG_ADC_CH6 27 // ADC end of conversion channel 6 in sequence, sample ready
#define DMA_TRIG_ADC_CH7 28 // ADC end of conversion channel 7 in sequence, sample ready
#define DMA_TRIG_ENC_DW 29 // AES encryption processor requests download input data
#define DMA_TRIG_ENC_UP 30 // AES encryption processor requests upload output data
// Increment source pointer by 0 bytes/words after each transfer
#define DMA_SRCINC_0 0x00
// Increment source pointer by 1 bytes/words after each transfer
#define DMA_SRCINC_1 0x01
// Increment source pointer by 2 bytes/words after each transfer
#define DMA_SRCINC_2 0x02
// Decrement source pointer by 1 bytes/words after each transfer
#define DMA_SRCINC_M1 0x03
// Increment destination pointer by 0 bytes/words after each transfer
#define DMA_DESTINC_0 0x00
// Increment destination pointer by 1 bytes/words after each transfer
#define DMA_DESTINC_1 0x01
// Increment destination pointer by 2 bytes/words after each transfer
#define DMA_DESTINC_2 0x02
// Decrement destination pointer by 1 bytes/words after each transfer
#define DMA_DESTINC_M1 0x03
// Disable interrupt generation
#define DMA_IRQMASK_DISABLE 0x00
// Enable interrupt generation upon DMA channel done
#define DMA_IRQMASK_ENABLE 0x01
#define DMA_M8_USE_8_BITS 0x00 // Use all 8 bits for transfer count
#define DMA_M8_USE_7_BITS 0x01 // Use 7 LSB for transfer count
// Low, CPU has priority
#define DMA_PRI_LOW 0x00
// Guaranteed, DMA at least every second try
#define DMA_PRI_GUARANTEED 0x01
// High, DMA has priority
#define DMA_PRI_HIGH 0x02
// Highest, DMA has priority. Reserved for DMA port access.
#define DMA_PRI_ABSOLUTE 0x03
#define DMA_ARM_ABORT 0x80
#define DMA_ARM_CH0 (1<<0)
#define DMA_ARM_CH1 (1<<1)
#define DMA_ARM_CH2 (1<<2)
#define DMA_ARM_CH3 (1<<3)
#define DMA_ARM_CH4 (1<<4)
#define DMAIRQ_DMAIF0 (1<<0)
#define DMAIRQ_DMAIF1 (1<<1)
#define DMAIRQ_DMAIF2 (1<<2)
#define DMAIRQ_DMAIF3 (1<<3)
#define DMAIRQ_DMAIF4 (1<<4)
#endif // HAL_DMA_H_

View File

@@ -0,0 +1,56 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_io.h"
#include "portmacros.h"
#include "config.h"
#include "hal_cc25xx.h"
void hal_io_init(void) {
// set bind pin as input
PORT2DIR(BIND_PORT) &= ~(1 << BIND_PIN);
// set pullup/down
PORT2INP(BIND_PORT) &= ~(1 << BIND_PIN);
#ifdef BIND2_PORT
// this board allows two bind buttons, both will work
// set bind2 pin as input
PORT2DIR(BIND2_PORT) &= ~(1 << BIND2_PIN);
// set pullup/down
PORT2INP(BIND2_PORT) &= ~(1 << BIND2_PIN);
#endif // BIND2_PORT
}
uint8_t hal_io_bind_request(void) {
// test bind button
if (!(BIND_PORT & (1 << BIND_PIN))) {
// LOW -> button pressed
return 1;
}
#ifdef BIND2_PORT
if (!(BIND2_PORT & (1 << BIND2_PIN))) {
// LOW -> button2 pressed
return 1;
}
#endif // BIND2_PORT
// no button pressed...
return 0;
}

View File

@@ -0,0 +1,29 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_IO_H_
#define HAL_IO_H_
#include "portmacros.h"
#include "config.h"
#include <stdint.h>
void hal_io_init(void);
uint8_t hal_io_bind_request(void);
#endif // HAL_IO_H_

View File

@@ -0,0 +1,22 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_led.h"
// nothing to do

View File

@@ -0,0 +1,44 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_LED_H_
#define HAL_LED_H_
#include "portmacros.h"
#include "config.h"
#include "hal_cc25xx.h"
// use helper macros to do expansion to *DIR etc
// LEDS
#define LED_GREEN_DIR PORT2DIR(LED_GREEN_PORT)
#define LED_RED_DIR PORT2DIR(LED_RED_PORT)
#define LED_RED_BIT PORT2BIT(LED_RED_PORT, LED_RED_PIN)
#define LED_GREEN_BIT PORT2BIT(LED_GREEN_PORT, LED_GREEN_PIN)
#define hal_led_green_init() { LED_GREEN_DIR |= (1 << LED_GREEN_PIN); led_green_off(); }
#define hal_led_green_on() { LED_GREEN_BIT = 1; }
#define hal_led_green_off() { LED_GREEN_BIT = 0; }
#define hal_led_green_toggle() { LED_GREEN_BIT = !LED_GREEN_BIT; }
#define hal_led_red_init() { LED_RED_DIR |= (1 << LED_RED_PIN); led_red_off(); }
#define hal_led_red_on() { LED_RED_BIT = 1; }
#define hal_led_red_off() { LED_RED_BIT = 0; }
#define hal_led_red_toggle() { LED_RED_BIT = !LED_RED_BIT; }
#endif // HAL_LED_H_

View File

@@ -0,0 +1,116 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_ppm.h"
#include "ppm.h"
#ifndef SBUS_ENABLED
void hal_ppm_init(void) {
// no int on overflow:
OVFIM = 0;
// set channels to compare interupt:
// CH0: off
T1CCTL0 = 0;
// CH1: off
T1CCTL1 = 0;
// CH2: toggle pin on cmp match, will generate sync pulses
#if PPM_INVERTED
// inverted, set on match, clear on zero
T1CCTL2 = T1CCTLx_MODE_COMPARE | T1CCTLx_CMP_SETCLR0;
#else
// non-inverted, clear on match, set on zero
T1CCTL2 = T1CCTLx_MODE_COMPARE | T1CCTLx_CMP_CLRSET0;
#endif // PPM_INVERTED
// configure peripheral alternative1 for timer 1:
// use alt config 1 -> clr flag -> P0_4 = output
PERCFG &= ~(PERCFG_T1CFG);
// USART1 use ALT2 in order to free up P0_4 for peripheral func
PERCFG |= PERCFG_U1CFG;
// select P0_4 for peripheral function
// NOTE: make sure to set usart1 to alt2 config!
P0SEL |= (1 << PPM_OUT_PIN);
// select P0_4 as output
P0DIR |= (1 << PPM_OUT_PIN);
// prescaler = 128
// tickspeed = 26MHz / 8 = 3,25MHz (TICKSPD is set in timeout.c!)
// 1us = 3.25 ticks -> 2ms = 6500 ticks, 4ms = 13000
T1CTL = T1CTL_MODE_MODULO | T1CTL_DIV_1;
// ch2 cmp: sync pulse length
SET_WORD_LO_FIRST(T1CC2H, T1CC2L, PPM_SYNC_PULS_LEN_TICKS);
// overflow:
SET_WORD_LO_FIRST(T1CC0H, T1CC0L, HAL_PPM_US_TO_TICKCOUNT(1000));
ppm_output_index = 0;
// clear pending interrupt flags (IRCON is reset by hw)
T1CTL &= ~(T1CTL_CH0_IF | T1CTL_CH1_IF | T1CTL_CH2_IF | T1CTL_OVFIF);
// overflow causes an int -> reload next channel data
OVFIM = 1;
// enable T1 interrups
T1IE = 1;
}
void hal_ppm_failsafe_exit() {
// configure p0_4 as peripheral:
P0SEL |= (1<<4);
// reset counter:
SET_WORD_LO_FIRST(T1CNTH, T1CNTL, 0);
// re enable timer interrupts:
OVFIM = 1;
// disable T1 interrups
T1IE = 1;
}
void hal_ppm_failsafe_enter(void) {
// disable interrupts
OVFIM = 0;
// disable T1 interrups
T1IE = 0;
// configure p0_4 as normal i/o:
P0SEL &= ~(1<<4);
// set pins to failsafe level:
#if PPM_INVERTED
// clear on zero -> default is high
P0 |= (1<<4);
#else
// set on zero -> default is low
P0 &= ~(1<<4);
#endif // PPM_INVERTED
}
#endif // SBUS_ENABLED

View File

@@ -0,0 +1,68 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_PPM_H_
#define HAL_PPM_H_
#include "config.h"
#include "hal_cc25xx.h"
#include <stdint.h>
#ifdef SBUS_ENABLED
#define hal_ppm_init() {}
#else
void hal_ppm_init(void);
void hal_ppm_failsafe_exit(void);
void hal_ppm_failsafe_enter(void);
void hal_ppm_timer1_interrupt(void) __interrupt T1_VECTOR;
/*
static void hal_ppm_init_rcc(void);
static void hal_ppm_init_gpio(void);
static void hal_ppm_init_timer(void);
static void hal_ppm_init_nvic(void);
static void hal_ppm_init_ocx(uint8_t ch, TIM_TypeDef *TIMx, TIM_OCInitTypeDef *tim_oc_init);
*/
// from frsky to ticks coresponding to 1000...2000 us
// frsky seems to send us*1.5 (~1480...3020) -> divide by 1.5 (=*2/3) to get us
// us -> ticks = ((_us*13)/4) -> (((_frsky*2/3)*13)/4) = ((_frsky*13)/6)
#define HAL_PPM_FRSKY_TO_TICKCOUNT(_frsky) (((_frsky << 3) + (_frsky << 2)+(_frsky))/6)
// from us to ticks:
// ((_us*13)/4) = ((_us * (8+4+1))/4) = (((_us<<3)+(_us<<2)+(_us))>>2)
#define HAL_PPM_US_TO_TICKCOUNT(_us) (((_us << 3) + (_us << 2)+(_us)) >> 2)
#define PPM_TIMER_ISR(void) hal_ppm_timer1_interrupt(void) __interrupt T1_VECTOR
#define HAL_PPM_UPDATE_CCVALUE(val) SET_WORD_LO_FIRST(T1CC0H, T1CC0L, val)
#define HAL_PPM_ISR_DISABLE() { cli(); }
#define HAL_PPM_ISR_ENABLE() { sei(); }
#define HAL_PPM_ISR_FLAG_SET() (1)
#define HAL_PPM_ISR_CLEAR_FLAG() { \
T1CTL &= ~(T1CTL_CH0_IF | T1CTL_CH1_IF | T1CTL_CH2_IF | T1CTL_OVFIF);}
#endif // SBUS_ENABLED
#endif // HAL_PPM_H_

View File

@@ -0,0 +1,22 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "sbus.h"

View File

@@ -0,0 +1,36 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_SBUS_H_
#define HAL_SBUS_H_
#include <stdint.h>
#include "hal_defines.h"
#include "hal_uart.h"
// this helper routine will invert the data
// stored in buffer in case the sbus is set
// to inverted
#ifdef SBUS_INVERTED
#define HAL_SBUS_PREPARE_DATA(a) (0xFF ^ (a))
#else
#define HAL_SBUS_PREPARE_DATA(a) (a)
#endif // SBUS_INVERTED
#endif // HAL_SBUS_H_

View File

@@ -0,0 +1,151 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_soft_serial.h"
#include "soft_serial.h"
#include "debug.h"
#include "delay.h"
#include "led.h"
#include "wdt.h"
#include "config.h"
#include "portmacros.h"
#include "hal_cc25xx.h"
#ifndef HUB_TELEMETRY_ON_SBUS_UART
void hal_soft_serial_init(void) {
debug("hal_soft_serial: init\n"); debug_flush();
hal_soft_serial_init_gpio();
hal_soft_serial_init_interrupts();
}
void hal_soft_serial_init_gpio(void) {
// set gpio as input
PORT2DIR(HUB_TELEMETRY_PORT) &= ~(1 << HUB_TELEMETRY_PIN);
}
void hal_soft_serial_init_interrupts(void) {
OVFIM = 0;
// disable compare modes
T4CCTL0 = 0;
T4CCTL1 = 0;
// tickspeed = 26MHz / 8 = 3,25MHz (TICKSPD is set in hal_timeout.c!)
// 1us = 3.25 ticks -> DIV2 -> 1us = 1.625 ticks
T4CTL = T4CTL_DIV_2 | // /2
T4CTL_START | // start
T4CTL_OVFIM | // OVInt enabled
T4CTL_CLR | // clear
T4CTL_MODE_MODULO; // 01 = count to CC and the overflow
// ch0 cmp: bit length
T4CC0 = HAL_SOFTSERIAL_BIT_DURATION_TICKS;
// clear pending interrupt flags (IRCON is reset by hw)
T4OVFIF = 0;
// overflow causes an int -> reload next channel data
OVFIM = 1;
// enable T4 interrups
IEN1 |= IEN1_T4IE;
// clear pending port ints
P0IFG = 0;
P0IF = 0;
// enable interrupts on P0 4...7
PICTL |= PICTL_P0IENH;
P0SEL &= ~(1<<6);
// set edge:
#ifdef HUB_TELEMETRY_INVERTED
// rising edge triggers isr
PICTL &= ~PICTL_P0ICON;
#else
// falling edge triggers isr
PICTL |= PICTL_P0ICON;
#endif // HUB_TELEMETRY_INVERTED
// T4 highest int prio (group4)
IP0 |= (1 << 4);
IP1 |= (1 << 4);
// P0 highest int prio (group5)
IP0 |= (1 << 5);
IP1 |= (1 << 5);
// enable interrupts from P0
P0IF = 0;
P0IFG = 0;
IEN1 |= IEN1_P0IE;
}
void hal_soft_serial_update_interrupt(void) __interrupt T4_VECTOR {
if (T4OVFIF) {
// DEBUG_PIN_TOGGLE();
// re-arm for the next bit
HAL_SOFT_SERIAL_UPDATE_TOP_VALUE(HAL_SOFTSERIAL_BIT_DURATION_TICKS-1);
if (soft_serial_process_databit()) {
// finished transmission, disable UP and enable IC isr
IEN1 |= IEN1_P0IE;
IEN1 &= ~IEN1_T4IE;
}
// clear pending interrupt flags (IRCON is reset by hw)
T4OVFIF = 0;
P0IFG = 0;
P0IF = 0;
}
}
void hal_soft_serial_startbit_interrupt(void) __interrupt P0INT_VECTOR {
uint8_t isr_cause = P0IFG;
// clear int flags WARNING: order seems to be important! CLR first IFG then IF!
P0IFG = 0;
// clear P0 int flags (important: several P0 pins can cause the isr, clean all of them!)
P0IF = 0;
if (isr_cause & (1 << HUB_TELEMETRY_PIN)) {
// DEBUG_PIN_TOGGLE();
// reset t3 counter:
T4CTL |= T4CTL_CLR;
// disable IC interrupt (only compare match interrupts will follow)
IEN1 &= ~IEN1_P0IE;
// enable overflow isr
IEN1 |= IEN1_T4IE;
// this is the startbit -> re synchronize the timer to this
// by setting the next cc interrupt to 1/2 bit length:
HAL_SOFT_SERIAL_UPDATE_TOP_VALUE((HAL_SOFTSERIAL_BIT_DURATION_TICKS / 2)-1);
// clear pending int flags
P0IF = 0;
T4OVFIF = 0;
// process
soft_serial_process_startbit();
}
}
#endif // HUB_TELEMETRY_ON_SBUS_UART

View File

@@ -0,0 +1,49 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_SOFT_SERIAL_H_
#define HAL_SOFT_SERIAL_H_
#include "hal_cc25xx.h"
#include "cc2510fx.h"
#include "config.h"
#ifndef HUB_TELEMETRY_ON_SBUS_UART
void hal_soft_serial_init(void);
void hal_soft_serial_init_gpio(void);
void hal_soft_serial_init_interrupts(void);
// at 9600 baud a bit duration is 1/9600s = 104.166667us
// the counter counts in 1/1.625th of us -> 104.1667us * 1.625
// = 169,27... -> 169 -> 0.16% error (thats ok..)
#define HAL_SOFTSERIAL_BIT_DURATION_TICKS (169)
#define HUB_TELEMETRY_PIN_HI() (HUB_TELEMETRY_PORT & (1 << HUB_TELEMETRY_PIN))
#define HUB_TELEMETRY_PIN_LO() (!HUB_TELEMETRY_PIN_HI())
#define HAL_SOFT_SERIAL_UPDATE_TOP_VALUE(x) { T4CC0 = x; }
extern void hal_soft_serial_update_interrupt(void) __interrupt T4_VECTOR;
extern void hal_soft_serial_startbit_interrupt(void) __interrupt P0INT_VECTOR;
#endif // HUB_TELEMETRY_ON_SBUS_UART
#endif // HAL_SOFT_SERIAL_H_

View File

@@ -0,0 +1,24 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_spi.h"
void hal_spi_init(void) {
}

View File

@@ -0,0 +1,26 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_SPI_H_
#define HAL_SPI_H_
void hal_spi_init(void);
#endif // HAL_SPI_H_

View File

@@ -0,0 +1,205 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_storage.h"
#include <cc2510fx.h>
#include "debug.h"
#include "main.h"
#include "delay.h"
#include "wdt.h"
__xdata HAL_DMA_DESC flash_dma_config;
// no ini value -> sdcc does not init this!
__code __at(STORAGE_LOCATION) uint8_t storage_on_flash[STORAGE_PAGE_SIZE];
void hal_storage_init(void) {
debug("hal_storage: init\n"); debug_flush();
}
void hal_storage_write(uint8_t *buffer, uint16_t len) {
hal_storage_flash_write((uint16_t)storage_on_flash, buffer, len);
}
void hal_storage_read(uint8_t *storage_ptr, uint16_t len) {
uint16_t i;
debug("hal_storage: loading from flash: "); debug_flush();
// copy from persistant flash to ram:
for (i = 0; i < len; i++) {
storage_ptr[i] = storage_on_flash[i];
debug_put_hex8(storage_on_flash[i]); debug_putc(' '); debug_flush();
wdt_reset();
}
}
static void hal_storage_flash_write(uint16_t address, uint8_t *data, uint16_t len) {
uint16_t i = 0;
uint8_t *flash_ptr = 0;
debug("hal_storage: will write page at 0x"); debug_flush();
debug_put_hex8(address >> 8);
debug_put_hex8(address & 0xff);
debug_put_newline();
// this is VERY important:
// make sure to write an even number of bytes!
// simply write one extra byte
if (len & 0x0001) {
debug("flash: corrected len to even\n");
len++;
}
// disable interrupts
cli();
// cancel _ALL_ ongoing DMA transfers:
DMAARM = DMA_ARM_ABORT | 0x1F;
// high prio
flash_dma_config.PRIORITY = DMA_PRI_HIGH;
// irrelevant since we use LEN for transfer count
flash_dma_config.M8 = DMA_M8_USE_8_BITS;
// disable ints from this ch
flash_dma_config.IRQMASK = DMA_IRQMASK_DISABLE;
// use dma flash data write complete trigger
flash_dma_config.TRIG = DMA_TRIG_FLASH;
// single mode, see datasheet
flash_dma_config.TMODE = DMA_TMODE_SINGLE;
// one byte
flash_dma_config.WORDSIZE = DMA_WORDSIZE_BYTE;
// set src: address of data to be written
SET_WORD(flash_dma_config.SRCADDRH, flash_dma_config.SRCADDRL, data);
// destination is flash controller data reg
SET_WORD(flash_dma_config.DESTADDRH, flash_dma_config.DESTADDRL, &X_FWDATA);
// use LEN
flash_dma_config.VLEN = DMA_VLEN_USE_LEN;
// set length
SET_WORD(flash_dma_config.LENH, flash_dma_config.LENL, len);
// set srcinc to 1 byte
flash_dma_config.SRCINC = DMA_SRCINC_1;
// fixed, always write to FWDATA
flash_dma_config.DESTINC = DMA_DESTINC_0;
// Save pointer to the DMA configuration struct into DMA-channel 0
// configuration registers
SET_WORD(DMA0CFGH, DMA0CFGL, flash_dma_config);
// waiting for the flash controller to be ready
while (FCTL & FCTL_BUSY) {}
// configure flash controller for 26mhz clock
FWT = 0x2A; // (21 * 26) / (16);
// set up address:
SET_WORD(FADDRH, FADDRL, ((uint16_t)address)>>1);
// re enable ints
sei();
debug("hal_storage: erasing page\n"); debug_flush();
// disable interrupts
cli();
// clear any pending flags
DMAIRQ = 0;
// erase that page
// has to be 2byte aligned. use a hack to place it at a given adress:
hal_storage_flash_erase_page();
// Wait for the erase operation to complete
while (FCTL & FCTL_BUSY) {}
// FCTL = 0;
// re enable ints
sei();
debug("hal_storage: erase done\n"); debug_flush();
debug("hal_storage: will write ["); debug_flush();
i = 0;
while (i < len) {
debug_put_hex8(((uint8_t *)data)[i++]);
debug_put_hex8(((uint8_t *)data)[i++]);
debug_putc(' ');
debug_flush();
}
debug("]\n");
debug("hal_storage: will write flash now\n"); debug_flush();
// disable interrupts
cli();
// arm the DMA channel, so that a DMA trigger will initiate DMA writing
DMAARM = DMA_ARM_CH0;
NOP();
// enable flash write. this generates a DMA trigger.
// must be aligned on a 2-byte boundary and is therefor implemented in assembly!
hal_storage_flash_enable_write();
// wait for dma finish
while (!(DMAIRQ & DMAIRQ_DMAIF0)) {
wdt_reset();
}
// wait until flash controller not busy
while (FCTL & (FCTL_BUSY | FCTL_SWBUSY)) {}
sei();
// by now, the transfer is completed, so the transfer count is reached.
// the DMA channel 0 interrupt flag is then set, so we clear it here.
DMAIRQ &= ~DMAIRQ_DMAIF0;
debug("hal_storage: read back [");
// copy from persistant flash to ram:
flash_ptr = address;
for (i = 0; i < len; i++) {
debug_put_hex8(*flash_ptr++); debug_putc(' '); debug_flush();
wdt_reset();
}
debug("]\n");
debug("hal_storage: write done");
}
void hal_storage_flash_enable_write(void) {
__asm
.even // IMPORTANT: PLACE THIS ON A 2BYTE BOUNDARY!
ORL _FCTL, #0x02; // FCTL |= FCTL_WRITE
NOP;
__endasm;
}
void hal_storage_flash_erase_page(void) {
__asm
.even // IMPORTANT: PLACE THIS ON A 2BYTE BOUNDARY!
ORL _FCTL, #0x01; // FCTL |= FCTL_ERASE
NOP; // required sequence!
__endasm;
}

View File

@@ -0,0 +1,45 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_STORAGE_H_
#define HAL_STORAGE_H_
#include <stdint.h>
#include "hal_cc25xx.h"
#include "hal_dma.h"
// place data on end of flash
// FIXME: this is for a cc2510f16 with flash size 0x4000, needs to be adjusted for bigger mcus
#define STORAGE_PAGE_SIZE 1024
#define STORAGE_LOCATION (0x4000-STORAGE_PAGE_SIZE)
// place persistant storage:
extern __code __at(STORAGE_LOCATION) uint8_t storage_on_flash[STORAGE_PAGE_SIZE];
extern __xdata HAL_DMA_DESC flash_dma_config;
void hal_storage_init(void);
void hal_storage_write(uint8_t *buffer, uint16_t len);
void hal_storage_read(uint8_t *storage_ptr, uint16_t len);
static void hal_storage_flash_write(uint16_t address, uint8_t *data, uint16_t len);
void hal_storage_flash_enable_write(void);
void hal_storage_flash_erase_page(void);
#endif // HAL_STORAGE_H_

View File

@@ -0,0 +1,135 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_timeout.h"
#include "delay.h"
#include "debug.h"
#include "timeout.h"
#include "hal_cc25xx.h"
// do not place this in xdata (faster this way)
volatile uint16_t hal_timeout_countdown;
volatile uint16_t hal_timeout2_countdown;
void hal_timeout_init(void) {
debug("hal_timeout: init\n"); debug_flush();
// timer clock
CLKCON = (CLKCON & ~CLKCON_TICKSPD_111) | CLKCON_TICKSPD_011;
// prepare timer3 for 1/25th ms steps:
// TICKSPD 011 -> /8 = 3250 kHz timer clock input
T3CTL = T3CTL_DIV_2 | // /2
T3CTL_START | // start
T3CTL_OVFIM | // OVInt enabled
T3CTL_CLR | // clear
T3CTL_MODE_MODULO; // 01 = count to CC and the overflow
// 3250/2/65 = 25khz
T3CC0 = 65-1;
// enable int
IEN1 |= (IEN1_T3IE);
timeout_set(0);
/*LED_RED_OFF();
while (1) {
timeout_set(990);
LED_GREEN_OFF();
while (!timeout_timed_out()) {}
timeout_set(10);
LED_GREEN_ON();
while (!timeout_timed_out()) {}
}*/
/* // TEST timings
P0DIR |= (1<<7);
while (1) {
timeout_set(1);
while (!timeout_timed_out()) {}
P0 |= (1<<7);
LED_RED_ON();
delay_ms(100);
P0 &= ~(1<<7);
LED_RED_OFF();
}*/
}
// prepare a new timeout
void hal_timeout_set(uint16_t timeout_ms) {
// disable T3ints:
IEN1 &= ~(IEN1_T3IE);
// clear counter
// T3CTL |= (1<<2);
// clear pending ints
// T3IF = 0;
// prepare timeout val:
hal_timeout_countdown = (timeout_ms * 25);
// clear pending ints
// T3IF = 0;
// re enable interrupts
IEN1 |= IEN1_T3IE;
}
uint8_t hal_timeout_timed_out(void) {
if (hal_timeout_countdown == 0) {
return 1;
} else {
return 0;
}
}
// prepare a new timeout
void hal_timeout2_set_100us(uint16_t timeout_100us) {
hal_timeout2_countdown = (timeout_100us * 25) / 10;
}
// prepare a new timeout
void hal_timeout2_set(uint16_t timeout_ms) {
hal_timeout2_countdown = (timeout_ms * 25);
}
uint8_t hal_timeout2_timed_out(void) {
if (hal_timeout2_countdown == 0) {
return 1;
} else {
return 0;
}
}
void hal_timeout_interrupt(void) __interrupt T3_VECTOR {
// clear flag
T3IF = 0;
if (hal_timeout_countdown != 0) {
hal_timeout_countdown--;
}
if (hal_timeout2_countdown != 0) {
hal_timeout2_countdown--;
}
}

View File

@@ -0,0 +1,38 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_TIMEOUT_H_
#define HAL_TIMEOUT_H_
#include <stdint.h>
#include "cc2510fx.h"
extern volatile uint16_t hal_timeout_countdown;
void hal_timeout_init(void);
void hal_timeout_set(uint16_t timeout_ms);
uint8_t hal_timeout_timed_out(void);
void hal_timeout2_set(uint16_t ms);
void hal_timeout2_set_100us(uint16_t hus);
uint8_t hal_timeout2_timed_out(void);
void hal_timeout_interrupt(void) __interrupt T3_VECTOR;
#endif // HAL_TIMEOUT_H_

View File

@@ -0,0 +1,258 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "cc2510fx.h"
#include "hal_cc25xx.h"
#include "hal_uart.h"
#include "hal_defines.h"
#include "hal_delay.h"
#include "config.h"
#include "hal_dma.h"
#include "uart.h"
#include "debug.h"
#include "wdt.h"
#include "delay.h"
#include "led.h"
void hal_uart_init(void) {
EXTERNAL_MEMORY union hal_uart_config_t sbus_uart_config;
#if SBUS_UART == USART0_P1
// -> USART0_P1
// use ALT2 -> Set flag -> P1_5 = TX / P1_4 = RX
PERCFG |= (PERCFG_U0CFG);
// configure pins as peripheral:
P1SEL |= (1<<5) | (1<<4);
// make sure all P0 pins switch to normal GPIO
P0SEL &= ~(0x3C);
// make tx pin output:
P1DIR |= (1<<5);
#elif SBUS_UART == USART1_P0
// USART1 use ALT1 -> Clear flag -> Port P0_4 = TX
PERCFG &= ~(PERCFG_U1CFG);
// USART1 has priority when USART0 is also enabled
P2DIR = (P2DIR & 0x3F) | 0b01000000;
// configure pin P0_4 (TX) and P0_5 (RX) as special function:
P0SEL |= (1<<4) | (1<<5);
// make sure all P1 pins switch to normal GPIO
// P1SEL &= ~(0xF0);
// make tx pin output:
P0DIR |= (1<<4);
#elif SBUS_UART == USART1_P1
// USART1 use ALT2 -> SET flag -> Port P1_6 = TX
PERCFG |= (PERCFG_U1CFG);
// USART1 has priority when USART0 is also enabled
P2DIR = (P2DIR & 0x3F) | 0b01000000;
// configure pin P1_6 (TX) and P1_7(RX) as special function:
P1SEL |= (1<<6) | (1<<7);
// make tx pin output:
P1DIR |= (1<<6);
#else
#error "UNSUPPORTED UART"
#endif // SBUS_UART == ...
// set baudrate
#if (SBUS_UART == USART0_P1) || (SBUS_UART == USART0_P0)
U0BAUD = CC2510_BAUD_M_100000;
U0GCR = (U0GCR & ~0x1F) | (CC2510_BAUD_E_100000);
#else
U1BAUD = CC2510_BAUD_M_100000;
U1GCR = (U1GCR & ~0x1F) | (CC2510_BAUD_E_100000);
#endif // SBUS_UART == ...
// set up config for USART -> 8E2
#ifdef SBUS_INVERTED
// this is a really nice feature of the cc2510:
// we can invert the idle level of the usart
// by setting STOP to zero. by inverting
// the parity, the startbit, and the data
// by using the SBUS_PREPARE_DATA() macro
// we can effectively invert the usart in software :)
sbus_uart_config.bit.START = 1; // startbit level = low
sbus_uart_config.bit.STOP = 0; // stopbit level = high
sbus_uart_config.bit.D9 = 1; // UNEven parity
#else
// standard usart, non-inverted mode
// NOTE: most sbus implementations use inverted mode
sbus_uart_config.bit.START = 0; // startbit level = low
sbus_uart_config.bit.STOP = 1; // stopbit level = high
sbus_uart_config.bit.D9 = 0; // Even parity
#endif // SBUS_INVERTED
sbus_uart_config.bit.SPB = 1; // 1 = 2 stopbits
sbus_uart_config.bit.PARITY = 1; // 1 = parity enabled, D9=0 -> even parity
sbus_uart_config.bit.BIT9 = 1; // 8bit
sbus_uart_config.bit.FLOW = 0; // no hw flow control
sbus_uart_config.bit.ORDER = 0; // lsb first
// activate uart config
hal_uart_set_mode(&sbus_uart_config);
// use dma channel 3 for transmission:
hal_dma_config[3].PRIORITY = DMA_PRI_LOW;
hal_dma_config[3].M8 = DMA_M8_USE_7_BITS;
hal_dma_config[3].IRQMASK = DMA_IRQMASK_DISABLE;
#if (SBUS_UART == USART0_P1) || (SBUS_UART == USART0_P0)
hal_dma_config[3].TRIG = DMA_TRIG_UTX0;
#else
hal_dma_config[3].TRIG = DMA_TRIG_UTX1;
#endif // SBUS_UART == ...
hal_dma_config[3].TMODE = DMA_TMODE_SINGLE;
hal_dma_config[3].WORDSIZE = DMA_WORDSIZE_BYTE;
// source address will be set during tx start
SET_WORD(hal_dma_config[3].SRCADDRH, hal_dma_config[3].SRCADDRL, 0);
#if (SBUS_UART == USART0_P1) || (SBUS_UART == USART0_P0)
SET_WORD(hal_dma_config[3].DESTADDRH, hal_dma_config[3].DESTADDRL, &X_U0DBUF);
#else
SET_WORD(hal_dma_config[3].DESTADDRH, hal_dma_config[3].DESTADDRL, &X_U1DBUF);
#endif // SBUS_UART == ...
hal_dma_config[3].VLEN = DMA_VLEN_USE_LEN;
// len will be set during tx start
SET_WORD(hal_dma_config[3].LENH, hal_dma_config[3].LENL, 0);
// configure src and dest increments
hal_dma_config[3].SRCINC = DMA_SRCINC_1;
hal_dma_config[3].DESTINC = DMA_DESTINC_0;
// set pointer to the DMA configuration struct into DMA-channel 1-4
// configuration, should have happened in adc.c already...
SET_WORD(DMA1CFGH, DMA1CFGL, &hal_dma_config[1]);
// arm the relevant DMA channel for UART TX, and apply 45 NOP's
// to allow the DMA configuration to load
// -> do a sleep instead of those nops...
DMAARM |= DMA_ARM_CH3;
hal_delay_45nop();
#ifdef HUB_TELEMETRY_ON_SBUS_UART
// activate serial rx interrupt
#if (SBUS_UART == USART0_P1) || (SBUS_UART == USART0_P0)
URX0IF = 0;
// enable receiption
U0CSR |= UxCSR_RX_ENABLE;
// enable RX interrupt
URX0IE = 1;
#else
URX1IF = 0;
// enable receiption
U1CSR |= UxCSR_RX_ENABLE;
// enable RX interrupt
URX1IE = 1;
#endif // HUB_TELEMETRY_ON_SBUS_UART
// enable global ints
EA = 1;
#endif // SBUS_UART == ...
}
static void hal_uart_set_mode(EXTERNAL_MEMORY union hal_uart_config_t *cfg) {
#if (SBUS_UART == USART0_P1) || (SBUS_UART == USART0_P0)
// enable uart mode
U0CSR |= 0x80;
// store config to U1UCR register
U0UCR = cfg->byte & (0x7F);
// store config to U1GCR: (msb/lsb)
if (cfg->bit.ORDER) {
U0GCR |= U0GCR_ORDER;
} else {
U0GCR &= ~U0GCR_ORDER;
}
// interrupt prio to 1 (0..3=highest)
IP0 |= (1<<2);
IP1 &= ~(1<<2);
#else
// enable uart mode
U1CSR |= 0x80;
// store config to U1UCR register
U1UCR = cfg->byte & (0x7F);
// store config to U1GCR: (msb/lsb)
if (cfg->bit.ORDER) {
U1GCR |= U1GCR_ORDER;
} else {
U1GCR &= ~U1GCR_ORDER;
}
// interrupt prio to 1 (0..3=highest)
IP0 |= (1<<3);
IP1 &= ~(1<<3);
#endif // SBUS_UART
}
void hal_uart_start_transmission(uint8_t *data, uint8_t len) {
// important: src addr start is data[1]
SET_WORD(hal_dma_config[3].SRCADDRH, hal_dma_config[3].SRCADDRL, &data[1]);
// configure length of transfer
SET_WORD(hal_dma_config[3].LENH, hal_dma_config[3].LENL, len);
// time to send this frame!
// re-arm dma:
DMAARM |= DMA_ARM_CH3;
// 45 nops to make sure the dma config is loaded
hal_delay_45nop();
// send the very first UART byte to trigger a UART TX session:
#if (SBUS_UART == USART0_P1) || (SBUS_UART == USART0_P0)
U0DBUF = data[0];
#else
U1DBUF = data[0];
#endif // SBUS_UART
}
#ifdef HUB_TELEMETRY_ON_SBUS_UART
void HAL_UART_RX_ISR(void) {
uint8_t rx;
HAL_UART_RX_ISR_CLEAR_FLAG(); // THIS SHOULD NEVER BE THE LAST LINE IN AN ISR!
#ifdef SBUS_INVERTED
rx = 0xFF ^ HAL_UART_RX_GETCH(); // remove data inversion
#else
rx = HAL_UART_RX_GETCH();
#endif // SBUS_INVERTED
if (uart_rx_callback != 0) {
// execute callback
uart_rx_callback(rx);
}
}
#endif // HUB_TELEMETRY_ON_SBUS_UART

View File

@@ -0,0 +1,68 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_UART_H_
#define HAL_UART_H_
#include <stdint.h>
#include "hal_defines.h"
// for a 26MHz Crystal:
#define CC2510_BAUD_E_115200 12
#define CC2510_BAUD_M_115200 34
// best match for 100kbit/s = 99975.5859375 bit/s
// baudrate = (((256.0 + baud_m)*2.0**baud_e) / (2**28)) * 26000000.0
#define CC2510_BAUD_E_100000 11
#define CC2510_BAUD_M_100000 248
#define CC2510_BAUD_E_57600 11
#define CC2510_BAUD_M_57600 34
union hal_uart_config_t{
uint8_t byte;
struct {
uint8_t START : 1; // start bit level
uint8_t STOP : 1; // stop bit level
uint8_t SPB : 1; // stop bits (0=1, 1=2)
uint8_t PARITY: 1; // parity (on/off)
uint8_t BIT9 : 1; // 9 bit mode
uint8_t D9 : 1; // 9th bit level or parity type
uint8_t FLOW : 1; // flow control
uint8_t ORDER : 1; // data bit order (LSB or MSB first)
} bit;
};
void hal_uart_init(void);
static void hal_uart_set_mode(EXTERNAL_MEMORY union hal_uart_config_t *cfg);
void hal_uart_start_transmission(uint8_t *data, uint8_t len);
#ifdef HUB_TELEMETRY_ON_SBUS_UART
#if (SBUS_UART == USART0_P1) || (SBUS_UART == USART0_P0)
#define HAL_UART_RX_ISR(void) hal_uart_rx_interrupt(void) __interrupt URX0_VECTOR
#define HAL_UART_RX_ISR_CLEAR_FLAG() { URX0IF = 0; }
#define HAL_UART_RX_GETCH() (U0DBUF)
#else
#define HAL_UART_RX_ISR(void) hal_uart_rx_interrupt(void) __interrupt URX1_VECTOR
#define HAL_UART_RX_ISR_CLEAR_FLAG() { URX1IF = 0; }
#define HAL_UART_RX_GETCH() (U1DBUF)
#endif // SBUS_UART == ...
void HAL_UART_RX_ISR(void);
#endif // HUB_TELEMETRY_ON_SBUS_UART
#endif // HAL_UART_H_

View File

@@ -0,0 +1,50 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_wdt.h"
#include "debug.h"
#include "led.h"
#include "delay.h"
#include "hal_cc25xx.h"
void hal_wdt_init(void) {
// check if 32khz clock source is rcosc:
if (!(CLKCON & CLKCON_OSC32K)) {
debug("wdt: error! low speed clock not based on int rc");
led_green_on();
while (1) {
led_red_on();
delay_ms(200);
led_red_off();
delay_ms(200);
}
}
// set wdt interval to approx 1 second
WDCTL = (WDCTL & ~WDCTL_INT) | WDCTL_INT_1S;
// enable wdt. NOTE: this can not be disabled in software!
WDCTL = (WDCTL & ~WDCTL_MODE) | WDCTL_EN;
}
void hal_wdt_reset(void) {
// reset wdt (special sequence)
WDCTL = (WDCTL & 0x0F) | 0b10100000;
WDCTL = (WDCTL & 0x0F) | 0b01010000;
}

View File

@@ -0,0 +1,26 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_WDT_H_
#define HAL_WDT_H_
void hal_wdt_init(void);
void hal_wdt_reset(void);
#endif // HAL_WDT_H_

View File

@@ -0,0 +1,13 @@
#ifndef __PORTMACROS_H__
#define __PORTMACROS_H__
#define PORT2DIR_(X) X ## DIR
#define PORT2DIR(PORTNAME) PORT2DIR_(PORTNAME)
#define PORT2BIT_(X,N) X ## _ ## N
#define PORT2BIT(PORTNAME, PIN) PORT2BIT_(PORTNAME,PIN)
#define PORT2INP_(X) X ## INP
#define PORT2INP(PORTNAME) PORT2INP_(PORTNAME)
#endif

View File

@@ -0,0 +1,34 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_adc.h"
#include "debug.h"
#include "wdt.h"
void hal_adc_init(void) {
}
void hal_adc_process(void) {
}
uint8_t hal_adc_get_scaled(uint8_t ch) {
return 0;
}

View File

@@ -0,0 +1,29 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_ADC_H_
#define HAL_ADC_H_
#include "main.h"
#include <stdint.h>
void hal_adc_init(void);
uint8_t hal_adc_get_scaled(uint8_t ch);
void hal_adc_process(void);
#endif // HAL_ADC_H_

View File

@@ -0,0 +1,253 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_cc25xx.h"
#include "hal_spi.h"
#include "hal_io.h"
#include "cc25xx.h"
#include "debug.h"
#include "timeout.h"
#include <string.h>
#include <stdio.h>
void hal_cc25xx_init(void) {
hal_spi_init();
hal_cc25xx_init_gpio();
}
static void hal_cc25xx_init_gpio(void) {
hal_cc25xx_enter_rxmode();
}
inline uint32_t hal_cc25xx_set_antenna(uint8_t id) {
return id;
}
const char *registers[] = {
"IOCFG2", // 0x00
"IOCFG1",
"IOCFG0",
"FIFOTHR",
"SYNC1",
"SYNC0",
"PKTLEN",
"PKTCTRL1",
"PKTCTRL0",
"ADDR",
"CHANNR",
"FSCTRL1",
"FSCTRL0",
"FREQ2",
"FREQ1",
"FREQ0",
"MDMCFG4", // 0x10
"MDMCFG3",
"MDMCFG2",
"MDMCFG1",
"MDMCFG0",
"DEVIATN",
"MCSM2",
"MCSM1",
"MCSM0",
"FOCCFG",
"BSCFG",
"AGCCTRL2",
"AGCCTRL1",
"AGCCTRL0",
"WOREVT1",
"WOREVT0",
"WORCTRL", // 0x20
"FREND1",
"FREND0",
"FSCAL3",
"FSCAL2",
"FSCAL1",
"FSCAL0",
"RCCTRL1",
"RCCTRL0",
"FSTEST",
"PTEST",
"AGCTEST",
"TEST2",
"TEST1",
"TEST0",
"RESERVED",
"PARTNUM", // 0x30
"VERSION",
"FREQEST",
"LQI",
"RSSI",
"MARCSTATE",
"WORTIME1",
"WORTIME0",
"PKTSTATUS",
"VCO_VC_DAC",
"TXBYTES",
"RXBYTES",
"RCCTRL1_STATUS",
"RCCTRL0_STATUS",
"PA_TABLE0" // 0x3E
};
inline void hal_cc25xx_set_gdo_mode(void) {
cc25xx_set_register(IOCFG0, 0x01); // 6);
// cc25xx_set_register(IOCFG1, ???);
cc25xx_set_register(IOCFG2, 0x01); // 6);
}
static int count = 0;
inline void hal_cc25xx_set_register(uint8_t address, uint8_t data) {
uint8_t buffer[2] = {address, data};
hal_spi_dma_xfer(buffer, sizeof(buffer));
// printf("\nset_register 0x%x (0x%x) '%s' data 0x%x\n", \
// address & 0x3f, address, registers[address & 0x3f], data);
}
inline uint8_t hal_cc25xx_get_register(uint8_t address) {
uint8_t buffer[2] = {address | 0x80, 0xff};
hal_spi_dma_xfer(buffer, sizeof(buffer));
// printf("\nget_register 0x%x (0x%x) '%s' got 0x%x\n", \
// address & 0x3f, address, registers[address & 0x3f], buffer[1]);
return buffer[1];
}
static const char *stobes[] = {
"RFST_SRES",
"RFST_SFSTXON",
"RFST_SXOFF",
"RFST_SCAL",
"RFST_SRX",
"RFST_STX",
"RFST_SIDLE",
"RFST_SWOR",
"RFST_SPWD",
"RFST_SFRX",
"RFST_SFTX",
"RFST_SWORRST",
"RFST_SNOP"
};
inline void hal_cc25xx_strobe(uint8_t address) {
uint8_t buffer[1] = {address};
hal_spi_dma_xfer(buffer, sizeof(buffer));
// printf("strobe 0x%x '%s' got 0x%x\n", address & 0x3f, stobes[address - 0x30], buffer[0]);
// debug("s"); debug_put_hex8(status); debug_put_newline();
}
uint8_t hal_cc25xx_get_status(void) {
uint8_t buffer[2] = {0xff, 0xff};
hal_spi_dma_xfer(buffer, sizeof(buffer));
return buffer[1];
}
uint8_t hal_cc25xx_transmission_completed(void) {
return 1; // return ((hal_cc25xx_get_status() & (0x70)) == CC2500_STATUS_STATE_RX);
}
inline void hal_cc25xx_enter_rxmode(void) {
hal_io_set_amp(0);
}
inline void hal_cc25xx_enter_txmode(void) {
hal_io_set_amp(1);
}
inline void hal_cc25xx_enable_receive(void) {
// switch on rx again
hal_cc25xx_enter_rxmode();
}
inline void hal_cc25xx_read_fifo(uint8_t *buf, uint8_t len) {
hal_cc25xx_register_read_multi(CC25XX_FIFO | READ_FLAG | BURST_FLAG, buf, len);
}
inline void hal_cc25xx_register_read_multi(uint8_t address, uint8_t *buffer, uint8_t len) {
uint8_t buffer2[len + 1];
buffer2[0] = address;
memset(buffer2+1, 0xFF, len);
hal_spi_dma_xfer(buffer2, len+1);
memcpy(buffer, buffer2+1, len);
}
inline void hal_cc25xx_register_write_multi(uint8_t address, uint8_t *buffer, uint8_t len) {
uint8_t buffer2[len + 1];
buffer2[0] = address | BURST_FLAG;
memcpy(buffer2+1, buffer, len);
hal_spi_dma_xfer(buffer2, len+1);
}
inline void hal_cc25xx_process_packet(volatile uint8_t *packet_received,
volatile uint8_t *buffer, uint8_t maxlen) {
if (hal_spi_get_gdo0() == 1) {
// data received, fetch data
// timeout_set_100us(5);
*packet_received = 0;
// there is a bug in the cc2500
// see p3 http:// www.ti.com/lit/er/swrz002e/swrz002e.pdf
// workaround: read len register very quickly twice:
uint8_t len1, len2, len, i;
// try this 10 times befor giving up:
for (i = 0; i < 10; i++) {
len1 = hal_cc25xx_get_register_burst(RXBYTES) & 0x7F;
len2 = hal_cc25xx_get_register_burst(RXBYTES) & 0x7F;
if (len1 == len2) break;
}
// valid len found?
if (len1 == len2 && len1 > 0) {
// debug("process_packet got: "); debug_put_uint8(len1);
// debug(" expecting: "); debug_put_uint8(maxlen);
len = len1;
// packet received, grab data
uint8_t tmp_buffer[len];
hal_cc25xx_read_fifo(tmp_buffer, len);
// only accept valid packet lenbghts:
if (len == maxlen) {
uint8_t i;
for (i = 0; i < maxlen; i++) {
buffer[i] = tmp_buffer[i];
}
*packet_received = 1;
// debug(" OK");
}
// debug("\n"); debug_flush();
} else {
// no, ignore this
len = 0;
}
}
}
void hal_cc25xx_transmit_packet(volatile uint8_t *buffer, uint8_t len) {
// flush tx fifo
hal_cc25xx_strobe(RFST_SFTX);
// copy to fifo
hal_cc25xx_register_write_multi(CC25XX_FIFO, (uint8_t *)buffer, buffer[0]+1);
// and send!
hal_cc25xx_strobe(RFST_STX);
}

View File

@@ -0,0 +1,188 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_CC25XX_H_
#define HAL_CC25XX_H_
#include <stdint.h>
void hal_cc25xx_init(void);
void hal_cc25xx_set_register(uint8_t reg, uint8_t val);
uint8_t hal_cc25xx_get_register(uint8_t address);
void hal_cc25xx_strobe(uint8_t val);
void hal_cc25xx_enable_receive(void);
void hal_cc25xx_enable_transmit(void);
void hal_cc25xx_enter_rxmode(void);
void hal_cc25xx_enter_txmode(void);
#define hal_cc25xx_rx_sleep() { delay_us(1352); }
#define hal_cc25xx_tx_sleep() { delay_us(1250); }
// not used on d4rii
#define hal_cc25xx_disable_rf_interrupt() {}
#define hal_cc25xx_setup_rf_dma(mode) {}
#define hal_cc25xx_partnum_valid(p, v) ((p == 0x80) && (v = 0x03))
uint8_t hal_cc25xx_get_status(void);
static void hal_cc25xx_init_gpio(void);
uint32_t hal_cc25xx_set_antenna(uint8_t id);
void hal_cc25xx_set_gdo_mode(void);
uint8_t hal_cc25xx_get_gdo_status(void);
void hal_cc25xx_process_packet(volatile uint8_t *packet_received,
volatile uint8_t *buffer, uint8_t maxlen);
void hal_cc25xx_transmit_packet(volatile uint8_t *buffer, uint8_t len);
void hal_cc25xx_read_fifo(uint8_t *buf, uint8_t len);
void hal_cc25xx_register_read_multi(uint8_t address, uint8_t *buffer, uint8_t len);
uint8_t hal_cc25xx_transmission_completed(void);
// adress checks
#define CC2500_PKTCTRL1_FLAG_ADR_CHECK_00 ((0<<1) | (0<<0))
#define CC2500_PKTCTRL1_FLAG_ADR_CHECK_01 ((0<<1) | (1<<0))
#define CC2500_PKTCTRL1_FLAG_ADR_CHECK_10 ((1<<1) | (0<<0))
#define CC2500_PKTCTRL1_FLAG_ADR_CHECK_11 ((1<<1) | (1<<0))
// append status bytes?
#define CC2500_PKTCTRL1_APPEND_STATUS (1<<2)
// crc autoflush
#define CC2500_PKTCTRL1_CRC_AUTOFLUSH (1<<3)
// Flags
#define BURST_FLAG 0b01000000
#define WRITE_FLAG 0b00000000
#define READ_FLAG 0b10000000
// Definitions for burst/single access to registers
#define CC2500_WRITE_SINGLE 0x00
#define CC2500_WRITE_BURST 0x40
#define CC2500_READ_SINGLE 0x80
#define CC2500_READ_BURST 0xC0
#define CC2500_STATUS_STATE_IDLE (0<<4)
#define CC2500_STATUS_STATE_RX (1<<4)
#define CC2500_STATUS_STATE_TX (2<<4)
#define CC2500_STATUS_STATE_FSTXON (3<<4)
#define CC2500_STATUS_STATE_CALIBRATE (4<<4)
#define CC2500_STATUS_STATE_SETTLING (5<<4)
#define CC2500_STATUS_STATE_RXFIFO_OVF (6<<4)
#define CC2500_STATUS_STATE_TXFIFO_OVF (7<<4)
#define hal_cc25xx_get_register_burst(x) hal_cc25xx_get_register(x | READ_FLAG | BURST_FLAG)
// strobes
#define RFST_SRES 0x30
#define RFST_SFSTXON 0x31
#define RFST_SXOFF 0x32
#define RFST_SCAL 0x33
#define RFST_SRX 0x34
#define RFST_STX 0x35
#define RFST_SIDLE 0x36
#define RFST_SWOR 0x38
#define RFST_SPWD 0x39
#define RFST_SFRX 0x3A
#define RFST_SFTX 0x3B
#define RFST_SWORRST 0x3C
#define RFST_SNOP 0x3D
// Status registers
#define PARTNUM 0x30|BURST_FLAG
#define VERSION 0x31|BURST_FLAG
#define FREQEST 0x32|BURST_FLAG
#define LQI 0x33|BURST_FLAG
#define RSSI 0x34|BURST_FLAG
#define MARCSTATE 0x35|BURST_FLAG
#define WORTIME1 0x36|BURST_FLAG
#define WORTIME0 0x37|BURST_FLAG
#define PKTSTATUS 0x38|BURST_FLAG
#define VCO_VC_DAC 0x39|BURST_FLAG
#define TXBYTES 0x3A|BURST_FLAG
#define RXBYTES 0x3B|BURST_FLAG
#define RCCTRL1_STATUS 0x3C|BURST_FLAG
#define RCCTRL0_STATUS 0x3D|BURST_FLAG
// Status byte states
#define STB_IDLE 0x00
#define STB_RX 0x10
#define STB_TX 0x20
#define STB_FSTXON 0x30
#define STB_CALIBRATE 0x40
#define STB_SETTLING 0x50
#define STB_RX_OVF 0x60
#define STB_TX_UNDF 0x70
// Config registers addresses
#define IOCFG2 0x00
#define IOCFG1 0x01
#define IOCFG0 0x02
#define FIFOTHR 0x03
#define SYNC1 0x04
#define SYNC0 0x05
#define PKTLEN 0x06
#define PKTCTRL1 0x07
#define PKTCTRL0 0x08
#define ADDR 0x09
#define CHANNR 0x0A
#define FSCTRL1 0x0B
#define FSCTRL0 0x0C
#define FREQ2 0x0D
#define FREQ1 0x0E
#define FREQ0 0x0F
#define MDMCFG4 0x10
#define MDMCFG3 0x11
#define MDMCFG2 0x12
#define MDMCFG1 0x13
#define MDMCFG0 0x14
#define DEVIATN 0x15
#define MCSM2 0x16
#define MCSM1 0x17
#define MCSM0 0x18
#define FOCCFG 0x19
#define BSCFG 0x1A
#define AGCCTRL2 0x1B
#define AGCCTRL1 0x1C
#define AGCCTRL0 0x1D
#define WOREVT1 0x1E
#define WOREVT0 0x1F
#define WORCTRL 0x20
#define FREND1 0x21
#define FREND0 0x22
#define FSCAL3 0x23
#define FSCAL2 0x24
#define FSCAL1 0x25
#define FSCAL0 0x26
#define RCCTRL1 0x27
#define RCCTRL0 0x28
#define FSTEST 0x29
#define PTEST 0x2A
#define AGCTEST 0x2B
#define TEST2 0x2C
#define TEST1 0x2D
#define TEST0 0x2E
#define PA_TABLE0 0x3E
// FIFO
#define CC25XX_FIFO 0x3F
#endif // HAL_CC25XX_H_

View File

@@ -0,0 +1,7 @@
#ifndef __HAL_CLOCKSOURCE_H__
#define __HAL_CLOCKSOURCE_H__
// no necessary for stm32, it is done in system startup
#define hal_clocksource_init() {}
#endif // __HAL_CLOCKSOURCE_H__

View File

@@ -0,0 +1,56 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_debug.h"
#include "debug.h"
#include "led.h"
#include <fcntl.h>
#include <unistd.h>
#include <stdio.h>
void hal_debug_init(void) {
}
void hal_debug_init_nvic(uint8_t enable) {
}
static void hal_debug_init_mode(void) {
}
static void hal_debug_enable(void) {
}
void hal_debug_start_transmission(uint8_t ch) {
fwrite(&ch, 1, 1, stdout);
}
void hal_debug_int_enable(void) {
}
uint8_t hal_debug_int_enabled(void) {
return 0;
}
static void hal_debug_init_gpio(void) {
}
static void hal_debug_init_rcc(void) {
}

View File

@@ -0,0 +1,37 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_DEBUG_H_
#define HAL_DEBUG_H_
#include <stdint.h>
void hal_debug_init(void);
void hal_debug_start_transmission(uint8_t ch);
uint8_t hal_debug_int_enabled(void);
void hal_debug_int_enable(void);
#define hal_debug_int_disable() {}
#define DEBUG_ISR(void) hal_debug_tx_interrupt(void)
#define HAL_DEBUG_ISR_FLAG_SET() (1)
#define HAL_DEBUG_ISR_CLEAR_FLAG() { }
#define HAL_DEBUG_ISR_DISABLE() { }
#define HAL_DEBUG_TX_DATA(data) { }
#endif // HAL_DEBUG_H_

View File

@@ -0,0 +1,15 @@
#ifndef __HAL_DEFINES_H__
#define __HAL_DEFINES_H__
#define EXTERNAL_MEMORY
#define EXTERNAL_DATA
#define HI(a) (uint8_t) ((uint16_t)(a) >> 8 )
#define LO(a) (uint8_t) (uint16_t)(a)
#define SET_WORD(H, L, val) { (H) = HI(val); (L) = LO(val); }
// necessary for timer registers. todo: check if necessary for others as well...
#define SET_WORD_LO_FIRST(H, L, val) {(L) = LO(val); (H) = HI(val); }
#define UNUSED(x) (void)(x);
#endif // __HAL_DEFINES_H__

View File

@@ -0,0 +1,9 @@
#ifndef __HAL_DELAY_H__
#define __HAL_DELAY_H__
#include "hal_timeout.h"
#define hal_delay_us(us) hal_timeout_delay_us(us)
#define hal_delay_ms(ms) hal_timeout_delay_us((ms) * 1000)
#endif // __HAL_DELAY_H__

View File

@@ -0,0 +1 @@
/* not used by rasp */

133
OpenSky/arch/rasp/hal_io.c Normal file
View File

@@ -0,0 +1,133 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_io.h"
#include "hal_cc25xx.h"
#include "delay.h"
#include <stdio.h>
#include <stdlib.h>
#include <fcntl.h>
#include <sys/mman.h>
#include <unistd.h>
#include <sched.h>
#define BLOCK_SIZE (4*1024)
// I/O access
volatile static unsigned *gpio;
// GPIO setup macros. Always use INP_GPIO(x) before using OUT_GPIO(x) or SET_GPIO_ALT(x,y)
#define INP_GPIO(g) *(gpio+((g)/10)) &= ~(7 << (((g) % 10)*3))
#define OUT_GPIO(g) *(gpio+((g)/10)) |= (1 << (((g)% 10)*3))
#define SET_GPIO_ALT(g, a) *(gpio+(((g)/10))) |= \
(((a) <= 3 ? (a) + 4:(a) == 4 ? 3 : 2) << (((g) % 10) * 3))
#define GPIO_SET *(gpio + 7) // sets bits which are 1 ignores bits which are 0
#define GPIO_CLR *(gpio + 10) // clears bits which are 1 ignores bits which are 0
#define GET_GPIO(g) (*(gpio + 13) & (1 << g)) // 0 if LOW, (1<<g) if HIGH
#define GPIO_PULL *(gpio + 37) // Pull up/pull down
#define GPIO_PULLCLK0 *(gpio + 38) // Pull up/pull down clock
void setup_io() {
void *gpio_map;
int mem_fd;
/* open /dev/mem */
if ((mem_fd = open("/dev/gpiomem", O_RDWR | O_SYNC | O_CLOEXEC) ) < 1) {
printf("can't open /dev/gpiomem \n");
exit(-1);
}
/* mmap GPIO */
gpio_map = mmap(
NULL, // Any adddress in our space will do
BLOCK_SIZE, // Map length
PROT_READ|PROT_WRITE, // Enable reading & writting to mapped memory
MAP_SHARED, // Shared with other processes
mem_fd, // File to map
0x200000); // GPIO controller
close(mem_fd); // No need to keep mem_fd open after mmap
if (gpio_map == MAP_FAILED) {
printf("mmap error %d\n", (int)gpio_map); // errno also set!
exit(-1);
}
// Always use volatile pointer!
gpio = (volatile unsigned *)gpio_map;
}
#define GDO0 23
#define LNA 2
#define PA 3
#define PPM 21
#define BIND 26
int hal_spi_get_gdo0(void) {
int res = GET_GPIO(GDO0);
if (res != 0)
return res != 0;
}
void hal_io_init(void) {
struct sched_param param;
param.sched_priority = sched_get_priority_max(SCHED_FIFO);
if (sched_setscheduler(0, SCHED_FIFO, &param) == -1) {
printf("Unable to set scheduler priority, this might impact your performance.");
}
setup_io();
INP_GPIO(GDO0); // must use INP_GPIO before we can use OUT_GPIO
INP_GPIO(LNA);
INP_GPIO(PA);
OUT_GPIO(LNA);
OUT_GPIO(PA);
OUT_GPIO(PPM);
OUT_GPIO(PPM);
INP_GPIO(BIND);
}
void hal_io_set_amp(int pa) {
if (pa == HAL_PA) {
GPIO_CLR = 1 << LNA;
delay_us(20);
GPIO_SET = 1 << PA;
delay_us(5);
} else {
GPIO_CLR = 1 << PA;
delay_us(20);
GPIO_SET = 1 << LNA;
delay_us(5);
}
}
void hal_io_set_ppm(int state) {
if (state)
GPIO_SET = 1 << PPM;
else
GPIO_CLR = 1 << PPM;
}
uint8_t hal_io_bind_request(void) {
return !!GET_GPIO(BIND);
}

View File

@@ -0,0 +1,35 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_IO_H_
#define HAL_IO_H_
#include <stdint.h>
void hal_io_init(void);
uint8_t hal_io_bind_request(void);
int hal_spi_get_gdo0(void);
#define HAL_PA 1
#define HAL_LNA 0
void hal_io_set_amp(int pa);
void hal_io_set_ppm(int state);
#endif // HAL_IO_H_

View File

@@ -0,0 +1,19 @@
#ifndef __HAL_LED__H_
#define __HAL_LED__H_
#include <stdint.h>
void hal_led_init(uint16_t pin);
#define hal_led_green_init() {}
#define hal_led_green_on() {}
#define hal_led_green_off() {}
#define hal_led_green_toggle() {}
#define hal_led_red_init() {}
#define hal_led_red_on() {}
#define hal_led_red_off() {}
#define hal_led_red_toggle() {}
#endif // __HAL_LED__H_

View File

@@ -0,0 +1,71 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_ppm.h"
#include "hal_io.h"
#include "hal_timeout.h"
#include "ppm.h"
#include "wdt.h"
#include "led.h"
#if SBUS_ENABLED == 1
void hal_ppm_init(void) {
}
void hal_ppm_tick() {
}
#else
static int state = 1;
static int failsafe = 0;
void hal_ppm_init(void) {
hal_io_set_ppm(state);
}
void hal_ppm_failsafe_enter(void) {
failsafe = 1;
}
void hal_ppm_failsafe_exit(void) {
failsafe = 0;
}
void hal_ppm_update_cvalue(int us) {
// Keep singal up, until the last 200ms of the count.
hal_timeout_add_ppm(us - HAL_PPM_US_TO_TICKCOUNT(200));
}
void hal_ppm_tick() {
if (state == 1) {
state = 0;
if (!failsafe)
hal_io_set_ppm(state);
// Then lower the signal for another 200ms..
hal_timeout_add_ppm(HAL_PPM_US_TO_TICKCOUNT(200));
} else {
state = 1;
if (!failsafe)
hal_io_set_ppm(state);
// Call the code, that will call hal_ppm_update_cvalue back to us.
hal_ppm_irq_callback();
}
}
#endif // SBUS_ENABLED

View File

@@ -0,0 +1,43 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_PPM_H_
#define HAL_PPM_H_
void hal_ppm_init(void);
void hal_ppm_failsafe_exit(void);
void hal_ppm_failsafe_enter(void);
void hal_ppm_tick();
void hal_ppm_update_cvalue(int us);
void hal_ppm_irq_callback(void);
#define HAL_PPM_US_TO_TICKCOUNT(us) ((us * 1)-1)
#define HAL_PPM_FRSKY_TO_TICKCOUNT(_frsky) ((_frsky)*2*2/3)
#define PPM_TIMER_ISR(void) hal_ppm_irq_callback(void)
#define HAL_PPM_UPDATE_CCVALUE(x) hal_ppm_update_cvalue(x)
#define HAL_PPM_ISR_DISABLE() { }
#define HAL_PPM_ISR_ENABLE() { }
#define HAL_PPM_ISR_FLAG_SET() (1)
#define HAL_PPM_ISR_CLEAR_FLAG() {}
#endif // HAL_PPM_H_

View File

@@ -0,0 +1,66 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include <stdio.h>
#include <unistd.h> // Used for UART
#include <fcntl.h> // Used for UART
#include <asm/termios.h> // Used for UART
#include "hal_sbus.h"
#include "debug.h"
#include "delay.h"
#include "sbus.h"
#if SBUS_ENABLED
static int uart0_filestream = -1;
void hal_sbus_init(EXTERNAL_MEMORY uint8_t *sbus_data_ptr) {
// open in non blocking read/write mode
uart0_filestream = open("/dev/ttyAMA0", O_WRONLY | O_NOCTTY | O_NDELAY);
if (uart0_filestream == -1) {
printf("Error - Unable to open UART. Ensure it is not in use by another application\n");
}
// USART configuration:
// 100000bps inverted serial stream, 8 bits, even parity, 2 stop bits
// no hw flow control
struct termios2 options;
options.c_cflag = BOTHER | CS8 | CLOCAL | PARENB | CSTOPB;
options.c_iflag = 0;
options.c_oflag = 0;
options.c_lflag = 0;
options.c_ispeed = 100000;
options.c_ospeed = 100000;
if (ioctl(uart0_filestream, TCSETS2, &options) != 0) {
printf("ioctl TCSETS2 failed");
}
}
void hal_sbus_start_transmission(uint8_t *data, uint8_t len) {
if (uart0_filestream != -1) {
int count = write(uart0_filestream, data, len);
if (count < len) {
printf("UART TX error sent %u of %u\n", count, len);
}
// printf("%d bytes written\n", len);
}
}
#endif // SBUS_ENABLED

View File

@@ -0,0 +1,38 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_SBUS_H_
#define HAL_SBUS_H_
#include <stdint.h>
#include "hal_defines.h"
void hal_sbus_init(EXTERNAL_MEMORY uint8_t *data_ptr);
void hal_sbus_start_transmission(uint8_t *buffer, uint8_t len);
// this helper routine will invert the data
// stored in buffer in case the sbus is set
// to inverted
#if SBUS_INVERTED
#define HAL_SBUS_PREPARE_DATA(a) (0xFF ^ (a))
#else
#define HAL_SBUS_PREPARE_DATA(a) (a)
#endif // SBUS_INVERTED
#endif // HAL_SBUS_H_

View File

@@ -0,0 +1,32 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_soft_serial.h"
#include "soft_serial.h"
#include "debug.h"
#include "delay.h"
#include "led.h"
#include "wdt.h"
#include "config.h"
#include "hal_cc25xx.h"
void hal_soft_serial_init(void) {
}

View File

@@ -0,0 +1,31 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_SOFT_SERIAL_H_
#define HAL_SOFT_SERIAL_H_
#include "soft_serial.h"
#include "config.h"
void hal_soft_serial_init(void);
#define HUB_TELEMETRY_PIN_LO() (0)
#define HUB_TELEMETRY_PIN_HI() (!HUB_TELEMETRY_PIN_LO())
#endif // HAL_SOFT_SERIAL_H_

118
OpenSky/arch/rasp/hal_spi.c Normal file
View File

@@ -0,0 +1,118 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include <stdint.h>
#include <unistd.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <fcntl.h>
#include <sys/ioctl.h>
#include <sys/stat.h>
#include <linux/types.h>
#include <linux/spi/spidev.h>
#include "hal_spi.h"
static void pabort(const char *s) {
perror(s);
abort();
}
static const char *device = "/dev/spidev0.0";
static uint8_t bits = 8;
static uint32_t speed = 1000000;
static int fd = -1;
static uint32_t mode = 0;
static uint16_t delay = 20;
void hal_spi_init(void) {
int ret = 0;
/*
* Open device
*/
fd = open(device, O_RDWR);
if (fd < 0)
pabort("can't open device");
/*
* spi mode
*/
ret = ioctl(fd, SPI_IOC_WR_MODE, &mode);
if (ret == -1)
pabort("can't set spi mode");
ret = ioctl(fd, SPI_IOC_RD_MODE, &mode);
if (ret == -1)
pabort("can't get spi mode");
/*
* bits per word
*/
ret = ioctl(fd, SPI_IOC_WR_BITS_PER_WORD, &bits);
if (ret == -1)
pabort("can't set bits per word");
ret = ioctl(fd, SPI_IOC_RD_BITS_PER_WORD, &bits);
if (ret == -1)
pabort("can't get bits per word");
/*
* max speed hz
*/
ret = ioctl(fd, SPI_IOC_WR_MAX_SPEED_HZ, &speed);
if (ret == -1)
pabort("can't set max speed hz");
ret = ioctl(fd, SPI_IOC_RD_MAX_SPEED_HZ, &speed);
if (ret == -1)
pabort("can't get max speed hz");
printf("spi: mode: 0x%x\n", mode);
printf("spi: bits per word: %d\n", bits);
printf("spi: max speed: %d Hz (%f MHz)\n", speed, speed/1000000.0);
}
void hal_spi_dma_xfer(uint8_t *buffer, uint8_t len) {
int ret;
uint8_t rx;
#if LOG_SPI
int i;
for (i=0; i < len; i++)
fprintf(stderr, "> %x\n", buffer[i]);
#endif // LOG_SPI
struct spi_ioc_transfer tr = {
.tx_buf = (uint64_t)buffer,
.rx_buf = (uint64_t)buffer,
.len = len,
.delay_usecs = delay,
.speed_hz = speed,
.bits_per_word = bits,
};
ret = ioctl(fd, SPI_IOC_MESSAGE(1), &tr);
if (ret < 1)
pabort("can't send spi message");
#if LOG_SPI
for (i=0; i < len; i++)
fprintf(stderr, "< %x\n", buffer[i]);
fprintf(stderr, "\n");
#endif // LOG_SPI
}

View File

@@ -0,0 +1,30 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_SPI_H_
#define HAL_SPI_H_
#include <stdint.h>
#include "config.h"
#include "delay.h"
void hal_spi_init(void);
void hal_spi_dma_xfer(uint8_t *buffer, uint8_t len);
#endif // HAL_SPI_H_

View File

@@ -0,0 +1,49 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_storage.h"
#include "debug.h"
#include "main.h"
#include "delay.h"
#include "wdt.h"
#include <stdio.h>
#include <string.h>
void hal_storage_init(void) {
debug("hal_storage: init\n"); debug_flush();
}
void hal_storage_write(uint8_t *buffer, uint16_t len) {
FILE *f = fopen("flash_storage.bin", "w");
fwrite(buffer, len, 1, f);
fclose(f);
}
void hal_storage_read(uint8_t *storage_ptr, uint16_t len) {
FILE *f = fopen("flash_storage.bin", "r");
if (!f) {
memset(storage_ptr, 0, len);
return;
}
fread(storage_ptr, len, 1, f);
fclose(f);
}

View File

@@ -0,0 +1,29 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_STORAGE_H_
#define HAL_STORAGE_H_
#include <stdint.h>
#include "config.h"
void hal_storage_init(void);
void hal_storage_write(uint8_t *buffer, uint16_t len);
void hal_storage_read(uint8_t *storage_ptr, uint16_t len);
#endif // HAL_STORAGE_H_

View File

@@ -0,0 +1,154 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_timeout.h"
#include "hal_ppm.h"
#include "debug.h"
#include "wdt.h"
#include <time.h>
#include <string.h>
#include <errno.h>
struct timespec timer_1;
struct timespec timer_2;
struct timespec timer_ppm;
void hal_timeout_init(void) {
memset(&timer_1, 0, sizeof(timer_1));
memset(&timer_2, 0, sizeof(timer_2));
clock_gettime(CLOCK_REALTIME, &timer_ppm);
}
/* Returns true if a is greather then b */
static inline uint8_t timeval_gt(const struct timespec *a, const struct timespec *b) {
if (a->tv_sec > b->tv_sec)
return 1;
if (a->tv_sec == b->tv_sec && a->tv_nsec > b->tv_nsec)
return 1;
return 0;
}
static inline void timer_add(struct timespec *timer, int us) {
timer->tv_nsec += us * 1000;
if (timer->tv_nsec > 1000000000) {
timer->tv_nsec -= 1000000000;
timer->tv_sec += 1;
}
}
/* Subtract the struct timeval values X and Y,
storing the result in RESULT.
Return 1 if the difference is negative, otherwise 0. */
static inline int timeval_subtract(struct timespec *result,
struct timespec *x, struct timespec *y) {
/* Perform the carry for the later subtraction by updating y. */
if (x->tv_nsec < y->tv_nsec) {
int nsec = (y->tv_nsec - x->tv_nsec) / 1000000000 + 1;
y->tv_nsec -= 1000000000 * nsec;
y->tv_sec += nsec;
}
if (x->tv_nsec - y->tv_nsec > 1000000000) {
int nsec = (x->tv_nsec - y->tv_nsec) / 1000000000;
y->tv_nsec += 1000000000 * nsec;
y->tv_sec -= nsec;
}
/* Compute the time remaining to wait.
tv_nsec is certainly positive. */
result->tv_sec = x->tv_sec - y->tv_sec;
result->tv_nsec = x->tv_nsec - y->tv_nsec;
/* Return 1 if result is negative. */
return x->tv_sec < y->tv_sec;
}
void hal_timeout_set_100us(uint32_t hus) {
clock_gettime(CLOCK_REALTIME, &timer_1);
timer_add(&timer_1, hus * 100);
}
void hal_timeout2_set_100us(uint32_t hus) {
clock_gettime(CLOCK_REALTIME, &timer_2);
timer_add(&timer_2, hus * 100);
}
void hal_timeout_set(uint32_t ms) {
clock_gettime(CLOCK_REALTIME, &timer_1);
timer_add(&timer_1, ms * 1000);
}
uint8_t hal_timeout_timed_out(void) {
struct timespec now;
clock_gettime(CLOCK_REALTIME, &now);
if (timeval_gt(&now, &timer_ppm)) {
hal_ppm_tick();
}
return timeval_gt(&now, &timer_1);
}
uint8_t hal_timeout2_timed_out(void) {
struct timespec now;
clock_gettime(CLOCK_REALTIME, &now);
if (timeval_gt(&now, &timer_ppm)) {
hal_ppm_tick();
}
return timeval_gt(&now, &timer_2);
}
void hal_timeout_delay_us(int32_t timeout_us) {
struct timespec now, sleep, delay_timer, rem;
clock_gettime(CLOCK_REALTIME, &now);
memcpy(&delay_timer, &now, sizeof(struct timespec));
timer_add(&delay_timer, timeout_us);
do {
/* If ppm happens before delay timer times out. (delay_timer gt timer_ppm) */
if (timeval_gt(&delay_timer, &timer_ppm)) {
/* Calculate how far to sleep */
if (timeval_subtract(&sleep, &now, &timer_ppm) > 0) {
nanosleep(&sleep, &rem);
}
/* Get current time again */
clock_gettime(CLOCK_REALTIME, &now);
if (timeval_gt(&now, &timer_ppm)) {
hal_ppm_tick();
}
/* Loop, as a new ppm timer might be scheduled again before the delay ends */
continue;
}
/* Calculate how long to sleep */
if (timeval_subtract(&sleep, &now, &delay_timer) > 0) {
nanosleep(&sleep, &rem);
}
} while (0);
}
void hal_timeout_add_ppm(uint32_t us) {
timer_add(&timer_ppm, us);
}

View File

@@ -0,0 +1,40 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_TIMEOUT_H_
#define HAL_TIMEOUT_H_
#include <stdint.h>
void hal_timeout_init(void);
void hal_timeout_set(uint32_t ms);
void hal_timeout_set_100us(uint32_t hus);
uint8_t hal_timeout_timed_out(void);
void hal_timeout_delay_us(int32_t timeout);
void hal_timeout2_set(uint32_t ms);
void hal_timeout2_set_100us(uint32_t hus);
uint8_t hal_timeout2_timed_out(void);
void hal_timeout_add_ppm(uint32_t us);
// void hal_timeout_delay_100us(uint32_t timeout);
uint32_t hal_timeout_time_remaining(void);
#endif // HAL_TIMEOUT_H_

View File

@@ -0,0 +1,66 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include <stdio.h>
#include <unistd.h> // Used for UART
#include <fcntl.h> // Used for UART
#include <asm/termios.h> // Used for UART
#include "hal_uart.h"
#include "debug.h"
#include "delay.h"
#include "sbus.h"
#if SBUS_ENABLED
static int uart0_filestream = -1;
void hal_uart_init(EXTERNAL_MEMORY uint8_t *sbus_data_ptr) {
// Open in non blocking read/write mode
uart0_filestream = open("/dev/ttyAMA0", O_WRONLY | O_NOCTTY | O_NDELAY);
if (uart0_filestream == -1) {
printf("Error - Unable to open UART. Ensure it is not in use by another application\n");
}
// USART configuration:
// 100000bps inverted serial stream, 8 bits, even parity, 2 stop bits
// no hw flow control
struct termios2 options;
options.c_cflag = BOTHER | CS8 | CLOCAL | PARENB | CSTOPB;
options.c_iflag = 0;
options.c_oflag = 0;
options.c_lflag = 0;
options.c_ispeed = 100000;
options.c_ospeed = 100000;
if (ioctl(uart0_filestream, TCSETS2, &options) != 0) {
printf("ioctl TCSETS2 failed");
}
}
void hal_uart_start_transmission(uint8_t *data, uint8_t len) {
if (uart0_filestream != -1) {
int count = write(uart0_filestream, data, len);
if (count < len) {
printf("UART TX error sent %u of %u\n", count, len);
}
// printf("%d bytes written\n", len);
}
}
#endif // SBUS_ENABLED

View File

@@ -0,0 +1,29 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_UART_H_
#define HAL_UART_H_
#include <stdint.h>
#include "hal_defines.h"
void hal_uart_init(EXTERNAL_MEMORY uint8_t *data_ptr);
void hal_uart_start_transmission(uint8_t *buffer, uint8_t len);
#endif // HAL_UART_H_

View File

@@ -0,0 +1,29 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_wdt.h"
#include "debug.h"
#include "delay.h"
void hal_wdt_init(void) {
}
inline void hal_wdt_reset(void) {
}

View File

@@ -0,0 +1,26 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_WDT_H_
#define HAL_WDT_H_
void hal_wdt_init(void);
void hal_wdt_reset(void);
#endif // HAL_WDT_H_

View File

@@ -0,0 +1,784 @@
/**************************************************************************// **
* @file core_cm3.c
* @brief CMSIS Cortex-M3 Core Peripheral Access Layer Source File
* @version V1.30
* @date 30. October 2009
*
* @note
* Copyright (C) 2009 ARM Limited. All rights reserved.
*
* @par
* ARM Limited (ARM) is supplying this software for use with Cortex-M
* processor based microcontrollers. This file can be freely distributed
* within development tools that are supporting such ARM based processors.
*
* @par
* THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED
* OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE.
* ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR
* CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER.
*
******************************************************************************/
#include <stdint.h>
/* define compiler specific symbols */
#if defined ( __CC_ARM )
#define __ASM __asm /*!< asm keyword for ARM Compiler */
#define __INLINE __inline /*!< inline keyword for ARM Compiler */
#elif defined ( __ICCARM__ )
#define __ASM __asm /*!< asm keyword for IAR Compiler */
#define __INLINE inline /*!< inline keyword for IAR Compiler. Only avaiable in High optimization mode! */
#elif defined ( __GNUC__ )
#define __ASM __asm /*!< asm keyword for GNU Compiler */
#define __INLINE inline /*!< inline keyword for GNU Compiler */
#elif defined ( __TASKING__ )
#define __ASM __asm /*!< asm keyword for TASKING Compiler */
#define __INLINE inline /*!< inline keyword for TASKING Compiler */
#endif
/* ################### Compiler specific Intrinsics ########################### */
#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/
/* ARM armcc specific functions */
/**
* @brief Return the Process Stack Pointer
*
* @return ProcessStackPointer
*
* Return the actual process stack pointer
*/
__ASM uint32_t __get_PSP(void)
{
mrs r0, psp
bx lr
}
/**
* @brief Set the Process Stack Pointer
*
* @param topOfProcStack Process Stack Pointer
*
* Assign the value ProcessStackPointer to the MSP
* (process stack pointer) Cortex processor register
*/
__ASM void __set_PSP(uint32_t topOfProcStack)
{
msr psp, r0
bx lr
}
/**
* @brief Return the Main Stack Pointer
*
* @return Main Stack Pointer
*
* Return the current value of the MSP (main stack pointer)
* Cortex processor register
*/
__ASM uint32_t __get_MSP(void)
{
mrs r0, msp
bx lr
}
/**
* @brief Set the Main Stack Pointer
*
* @param topOfMainStack Main Stack Pointer
*
* Assign the value mainStackPointer to the MSP
* (main stack pointer) Cortex processor register
*/
__ASM void __set_MSP(uint32_t mainStackPointer)
{
msr msp, r0
bx lr
}
/**
* @brief Reverse byte order in unsigned short value
*
* @param value value to reverse
* @return reversed value
*
* Reverse byte order in unsigned short value
*/
__ASM uint32_t __REV16(uint16_t value)
{
rev16 r0, r0
bx lr
}
/**
* @brief Reverse byte order in signed short value with sign extension to integer
*
* @param value value to reverse
* @return reversed value
*
* Reverse byte order in signed short value with sign extension to integer
*/
__ASM int32_t __REVSH(int16_t value)
{
revsh r0, r0
bx lr
}
#if (__ARMCC_VERSION < 400000)
/**
* @brief Remove the exclusive lock created by ldrex
*
* Removes the exclusive lock which is created by ldrex.
*/
__ASM void __CLREX(void)
{
clrex
}
/**
* @brief Return the Base Priority value
*
* @return BasePriority
*
* Return the content of the base priority register
*/
__ASM uint32_t __get_BASEPRI(void)
{
mrs r0, basepri
bx lr
}
/**
* @brief Set the Base Priority value
*
* @param basePri BasePriority
*
* Set the base priority register
*/
__ASM void __set_BASEPRI(uint32_t basePri)
{
msr basepri, r0
bx lr
}
/**
* @brief Return the Priority Mask value
*
* @return PriMask
*
* Return state of the priority mask bit from the priority mask register
*/
__ASM uint32_t __get_PRIMASK(void)
{
mrs r0, primask
bx lr
}
/**
* @brief Set the Priority Mask value
*
* @param priMask PriMask
*
* Set the priority mask bit in the priority mask register
*/
__ASM void __set_PRIMASK(uint32_t priMask)
{
msr primask, r0
bx lr
}
/**
* @brief Return the Fault Mask value
*
* @return FaultMask
*
* Return the content of the fault mask register
*/
__ASM uint32_t __get_FAULTMASK(void)
{
mrs r0, faultmask
bx lr
}
/**
* @brief Set the Fault Mask value
*
* @param faultMask faultMask value
*
* Set the fault mask register
*/
__ASM void __set_FAULTMASK(uint32_t faultMask)
{
msr faultmask, r0
bx lr
}
/**
* @brief Return the Control Register value
*
* @return Control value
*
* Return the content of the control register
*/
__ASM uint32_t __get_CONTROL(void)
{
mrs r0, control
bx lr
}
/**
* @brief Set the Control Register value
*
* @param control Control value
*
* Set the control register
*/
__ASM void __set_CONTROL(uint32_t control)
{
msr control, r0
bx lr
}
#endif /* __ARMCC_VERSION */
#elif (defined (__ICCARM__)) /*------------------ ICC Compiler -------------------*/
/* IAR iccarm specific functions */
#pragma diag_suppress=Pe940
/**
* @brief Return the Process Stack Pointer
*
* @return ProcessStackPointer
*
* Return the actual process stack pointer
*/
uint32_t __get_PSP(void)
{
__ASM("mrs r0, psp");
__ASM("bx lr");
}
/**
* @brief Set the Process Stack Pointer
*
* @param topOfProcStack Process Stack Pointer
*
* Assign the value ProcessStackPointer to the MSP
* (process stack pointer) Cortex processor register
*/
void __set_PSP(uint32_t topOfProcStack)
{
__ASM("msr psp, r0");
__ASM("bx lr");
}
/**
* @brief Return the Main Stack Pointer
*
* @return Main Stack Pointer
*
* Return the current value of the MSP (main stack pointer)
* Cortex processor register
*/
uint32_t __get_MSP(void)
{
__ASM("mrs r0, msp");
__ASM("bx lr");
}
/**
* @brief Set the Main Stack Pointer
*
* @param topOfMainStack Main Stack Pointer
*
* Assign the value mainStackPointer to the MSP
* (main stack pointer) Cortex processor register
*/
void __set_MSP(uint32_t topOfMainStack)
{
__ASM("msr msp, r0");
__ASM("bx lr");
}
/**
* @brief Reverse byte order in unsigned short value
*
* @param value value to reverse
* @return reversed value
*
* Reverse byte order in unsigned short value
*/
uint32_t __REV16(uint16_t value)
{
__ASM("rev16 r0, r0");
__ASM("bx lr");
}
/**
* @brief Reverse bit order of value
*
* @param value value to reverse
* @return reversed value
*
* Reverse bit order of value
*/
uint32_t __RBIT(uint32_t value)
{
__ASM("rbit r0, r0");
__ASM("bx lr");
}
/**
* @brief LDR Exclusive (8 bit)
*
* @param *addr address pointer
* @return value of (*address)
*
* Exclusive LDR command for 8 bit values)
*/
uint8_t __LDREXB(uint8_t *addr)
{
__ASM("ldrexb r0, [r0]");
__ASM("bx lr");
}
/**
* @brief LDR Exclusive (16 bit)
*
* @param *addr address pointer
* @return value of (*address)
*
* Exclusive LDR command for 16 bit values
*/
uint16_t __LDREXH(uint16_t *addr)
{
__ASM("ldrexh r0, [r0]");
__ASM("bx lr");
}
/**
* @brief LDR Exclusive (32 bit)
*
* @param *addr address pointer
* @return value of (*address)
*
* Exclusive LDR command for 32 bit values
*/
uint32_t __LDREXW(uint32_t *addr)
{
__ASM("ldrex r0, [r0]");
__ASM("bx lr");
}
/**
* @brief STR Exclusive (8 bit)
*
* @param value value to store
* @param *addr address pointer
* @return successful / failed
*
* Exclusive STR command for 8 bit values
*/
uint32_t __STREXB(uint8_t value, uint8_t *addr)
{
__ASM("strexb r0, r0, [r1]");
__ASM("bx lr");
}
/**
* @brief STR Exclusive (16 bit)
*
* @param value value to store
* @param *addr address pointer
* @return successful / failed
*
* Exclusive STR command for 16 bit values
*/
uint32_t __STREXH(uint16_t value, uint16_t *addr)
{
__ASM("strexh r0, r0, [r1]");
__ASM("bx lr");
}
/**
* @brief STR Exclusive (32 bit)
*
* @param value value to store
* @param *addr address pointer
* @return successful / failed
*
* Exclusive STR command for 32 bit values
*/
uint32_t __STREXW(uint32_t value, uint32_t *addr)
{
__ASM("strex r0, r0, [r1]");
__ASM("bx lr");
}
#pragma diag_default=Pe940
#elif (defined (__GNUC__)) /*------------------ GNU Compiler ---------------------*/
/* GNU gcc specific functions */
/**
* @brief Return the Process Stack Pointer
*
* @return ProcessStackPointer
*
* Return the actual process stack pointer
*/
uint32_t __get_PSP(void) __attribute__( ( naked ) );
uint32_t __get_PSP(void)
{
uint32_t result=0;
__ASM volatile ("MRS %0, psp\n\t"
"MOV r0, %0 \n\t"
"BX lr \n\t" : "=r" (result) );
return(result);
}
/**
* @brief Set the Process Stack Pointer
*
* @param topOfProcStack Process Stack Pointer
*
* Assign the value ProcessStackPointer to the MSP
* (process stack pointer) Cortex processor register
*/
void __set_PSP(uint32_t topOfProcStack) __attribute__( ( naked ) );
void __set_PSP(uint32_t topOfProcStack)
{
__ASM volatile ("MSR psp, %0\n\t"
"BX lr \n\t" : : "r" (topOfProcStack) );
}
/**
* @brief Return the Main Stack Pointer
*
* @return Main Stack Pointer
*
* Return the current value of the MSP (main stack pointer)
* Cortex processor register
*/
uint32_t __get_MSP(void) __attribute__( ( naked ) );
uint32_t __get_MSP(void)
{
uint32_t result=0;
__ASM volatile ("MRS %0, msp\n\t"
"MOV r0, %0 \n\t"
"BX lr \n\t" : "=r" (result) );
return(result);
}
/**
* @brief Set the Main Stack Pointer
*
* @param topOfMainStack Main Stack Pointer
*
* Assign the value mainStackPointer to the MSP
* (main stack pointer) Cortex processor register
*/
void __set_MSP(uint32_t topOfMainStack) __attribute__( ( naked ) );
void __set_MSP(uint32_t topOfMainStack)
{
__ASM volatile ("MSR msp, %0\n\t"
"BX lr \n\t" : : "r" (topOfMainStack) );
}
/**
* @brief Return the Base Priority value
*
* @return BasePriority
*
* Return the content of the base priority register
*/
uint32_t __get_BASEPRI(void)
{
uint32_t result=0;
__ASM volatile ("MRS %0, basepri_max" : "=r" (result) );
return(result);
}
/**
* @brief Set the Base Priority value
*
* @param basePri BasePriority
*
* Set the base priority register
*/
void __set_BASEPRI(uint32_t value)
{
__ASM volatile ("MSR basepri, %0" : : "r" (value) );
}
/**
* @brief Return the Priority Mask value
*
* @return PriMask
*
* Return state of the priority mask bit from the priority mask register
*/
uint32_t __get_PRIMASK(void)
{
uint32_t result=0;
__ASM volatile ("MRS %0, primask" : "=r" (result) );
return(result);
}
/**
* @brief Set the Priority Mask value
*
* @param priMask PriMask
*
* Set the priority mask bit in the priority mask register
*/
void __set_PRIMASK(uint32_t priMask)
{
__ASM volatile ("MSR primask, %0" : : "r" (priMask) );
}
/**
* @brief Return the Fault Mask value
*
* @return FaultMask
*
* Return the content of the fault mask register
*/
uint32_t __get_FAULTMASK(void)
{
uint32_t result=0;
__ASM volatile ("MRS %0, faultmask" : "=r" (result) );
return(result);
}
/**
* @brief Set the Fault Mask value
*
* @param faultMask faultMask value
*
* Set the fault mask register
*/
void __set_FAULTMASK(uint32_t faultMask)
{
__ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) );
}
/**
* @brief Return the Control Register value
*
* @return Control value
*
* Return the content of the control register
*/
uint32_t __get_CONTROL(void)
{
uint32_t result=0;
__ASM volatile ("MRS %0, control" : "=r" (result) );
return(result);
}
/**
* @brief Set the Control Register value
*
* @param control Control value
*
* Set the control register
*/
void __set_CONTROL(uint32_t control)
{
__ASM volatile ("MSR control, %0" : : "r" (control) );
}
/**
* @brief Reverse byte order in integer value
*
* @param value value to reverse
* @return reversed value
*
* Reverse byte order in integer value
*/
uint32_t __REV(uint32_t value)
{
uint32_t result=0;
__ASM volatile ("rev %0, %1" : "=r" (result) : "r" (value) );
return(result);
}
/**
* @brief Reverse byte order in unsigned short value
*
* @param value value to reverse
* @return reversed value
*
* Reverse byte order in unsigned short value
*/
uint32_t __REV16(uint16_t value)
{
uint32_t result=0;
__ASM volatile ("rev16 %0, %1" : "=r" (result) : "r" (value) );
return(result);
}
/**
* @brief Reverse byte order in signed short value with sign extension to integer
*
* @param value value to reverse
* @return reversed value
*
* Reverse byte order in signed short value with sign extension to integer
*/
int32_t __REVSH(int16_t value)
{
uint32_t result=0;
__ASM volatile ("revsh %0, %1" : "=r" (result) : "r" (value) );
return(result);
}
/**
* @brief Reverse bit order of value
*
* @param value value to reverse
* @return reversed value
*
* Reverse bit order of value
*/
uint32_t __RBIT(uint32_t value)
{
uint32_t result=0;
__ASM volatile ("rbit %0, %1" : "=r" (result) : "r" (value) );
return(result);
}
/**
* @brief LDR Exclusive (8 bit)
*
* @param *addr address pointer
* @return value of (*address)
*
* Exclusive LDR command for 8 bit value
*/
uint8_t __LDREXB(uint8_t *addr)
{
uint8_t result=0;
__ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) );
return(result);
}
/**
* @brief LDR Exclusive (16 bit)
*
* @param *addr address pointer
* @return value of (*address)
*
* Exclusive LDR command for 16 bit values
*/
uint16_t __LDREXH(uint16_t *addr)
{
uint16_t result=0;
__ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) );
return(result);
}
/**
* @brief LDR Exclusive (32 bit)
*
* @param *addr address pointer
* @return value of (*address)
*
* Exclusive LDR command for 32 bit values
*/
uint32_t __LDREXW(uint32_t *addr)
{
uint32_t result=0;
__ASM volatile ("ldrex %0, [%1]" : "=r" (result) : "r" (addr) );
return(result);
}
/**
* @brief STR Exclusive (8 bit)
*
* @param value value to store
* @param *addr address pointer
* @return successful / failed
*
* Exclusive STR command for 8 bit values
*/
uint32_t __STREXB(uint8_t value, uint8_t *addr)
{
uint32_t result=0;
__ASM volatile ("strexb %0, %2, [%1]" : "=r" (result) : "r" (addr), "r" (value) );
return(result);
}
/**
* @brief STR Exclusive (16 bit)
*
* @param value value to store
* @param *addr address pointer
* @return successful / failed
*
* Exclusive STR command for 16 bit values
*/
uint32_t __STREXH(uint16_t value, uint16_t *addr)
{
uint32_t result=0;
__ASM volatile ("strexh %0, %2, [%1]" : "=r" (result) : "r" (addr), "r" (value) );
return(result);
}
/**
* @brief STR Exclusive (32 bit)
*
* @param value value to store
* @param *addr address pointer
* @return successful / failed
*
* Exclusive STR command for 32 bit values
*/
uint32_t __STREXW(uint32_t value, uint32_t *addr)
{
uint32_t result=0;
__ASM volatile ("strex %0, %2, [%1]" : "=r" (result) : "r" (addr), "r" (value) );
return(result);
}
#elif (defined (__TASKING__)) /*------------------ TASKING Compiler ---------------------*/
/* TASKING carm specific functions */
/*
* The CMSIS functions have been implemented as intrinsics in the compiler.
* Please use "carm -?i" to get an up to date list of all instrinsics,
* Including the CMSIS ones.
*/
#endif

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,210 @@
/* Generated by startup_generator */
#include "stm32f10x.h"
#include <core_cm3.h>
#include "led.h"
extern void _estack(void); // to force type checking
void Reset_Handler(void);
void default_handler (void) {
uint64_t i;
led_red_on();
while (1) {
for (i=0; i<0x00FFFFF; i++) {}
led_green_off();
for (i=0; i<0x00FFFFF; i++) {}
led_green_on();
}
while (1);
}
void __attribute__ ((weak)) __libc_init_array (void) {}
// Linker supplied pointers
extern unsigned long _sidata;
extern unsigned long _sdata;
extern unsigned long _edata;
extern unsigned long _sbss;
extern unsigned long _ebss;
extern int main(void);
void Reset_Handler(void) {
unsigned long *src, *dst;
src = &_sidata;
dst = &_sdata;
// Copy data initializers
while (dst < &_edata)
*(dst++) = *(src++);
// Zero bss
dst = &_sbss;
while (dst < &_ebss)
*(dst++) = 0;
SystemInit();
__libc_init_array();
main();
while (1) {}
}
/* Vector Table */
void NMI_Handler (void) __attribute__ ((weak, alias ("default_handler")));
void HardFault_Handler (void) __attribute__ ((weak, alias ("default_handler")));
void MemMange_Handler (void) __attribute__ ((weak, alias ("default_handler")));
void BusFault_Handler (void) __attribute__ ((weak, alias ("default_handler")));
void UsageFault_Handler (void) __attribute__ ((weak, alias ("default_handler")));
void SVC_Handler (void) __attribute__ ((weak, alias ("default_handler")));
void DebugMon_Handler (void) __attribute__ ((weak, alias ("default_handler")));
void PendSV_Handler (void) __attribute__ ((weak, alias ("default_handler")));
void SysTick_Handler (void) __attribute__ ((weak, alias ("default_handler")));
void WWDG_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void PVD_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void TAMPER_STAMP_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void RTC_WKUP_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void FLASH_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void RCC_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void EXTI0_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void EXTI1_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void EXTI2_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void EXTI3_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void EXTI4_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void DMA1_Channel1_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void DMA1_Channel2_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void DMA1_Channel3_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void DMA1_Channel4_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void DMA1_Channel5_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void DMA1_Channel6_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void DMA1_Channel7_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void ADC1_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void EXTI9_5_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void TIM1_BRK_TIM15_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void TIM1_UP_TIM16_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void TIM1_TRG_COM_TIM17_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void TIM1_CC_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void TIM2_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void TIM3_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void TIM4_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void I2C1_EV_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void I2C1_ER_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void I2C2_EV_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void I2C2_ER_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void SPI1_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void SPI2_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void USART1_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void USART2_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void USART3_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void EXTI15_10_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void RTCAlarm_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void CEC_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void TIM12_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void TIM13_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void TIM14_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void ADC3_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void FSMC_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void TIM5_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void SPI3_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void UART4_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void UART5_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void TIM6_DAC_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void TIM7_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void DMA2_Channel1_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void DMA2_Channel2_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void DMA2_Channel3_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void DMA2_Channel4_5_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
void DMA2_Channel5_IRQHandler (void) __attribute__ ((weak, alias ("default_handler")));
__attribute__ ((section(".isr_vector")))
void (* const g_pfnVectors[])(void) = {
_estack,
Reset_Handler,
NMI_Handler,
HardFault_Handler,
MemMange_Handler,
BusFault_Handler,
UsageFault_Handler,
0, 0, 0, 0,
SVC_Handler,
DebugMon_Handler,
0,
PendSV_Handler,
SysTick_Handler,
WWDG_IRQHandler,
PVD_IRQHandler,
TAMPER_STAMP_IRQHandler,
RTC_WKUP_IRQHandler,
FLASH_IRQHandler,
RCC_IRQHandler,
EXTI0_IRQHandler,
EXTI1_IRQHandler,
EXTI2_IRQHandler,
EXTI3_IRQHandler,
EXTI4_IRQHandler,
DMA1_Channel1_IRQHandler,
DMA1_Channel2_IRQHandler,
DMA1_Channel3_IRQHandler,
DMA1_Channel4_IRQHandler,
DMA1_Channel5_IRQHandler,
DMA1_Channel6_IRQHandler,
DMA1_Channel7_IRQHandler,
ADC1_IRQHandler,
0, 0, 0, 0,
EXTI9_5_IRQHandler,
TIM1_BRK_TIM15_IRQHandler,
TIM1_UP_TIM16_IRQHandler,
TIM1_TRG_COM_TIM17_IRQHandler,
TIM1_CC_IRQHandler,
TIM2_IRQHandler,
TIM3_IRQHandler,
TIM4_IRQHandler,
I2C1_EV_IRQHandler,
I2C1_ER_IRQHandler,
I2C2_EV_IRQHandler,
I2C2_ER_IRQHandler,
SPI1_IRQHandler,
SPI2_IRQHandler,
USART1_IRQHandler,
USART2_IRQHandler,
USART3_IRQHandler,
EXTI15_10_IRQHandler,
RTCAlarm_IRQHandler,
CEC_IRQHandler,
TIM12_IRQHandler,
TIM13_IRQHandler,
TIM14_IRQHandler,
0,
ADC3_IRQHandler,
FSMC_IRQHandler,
0,
TIM5_IRQHandler,
SPI3_IRQHandler,
UART4_IRQHandler,
UART5_IRQHandler,
TIM6_DAC_IRQHandler,
TIM7_IRQHandler,
DMA2_Channel1_IRQHandler,
DMA2_Channel2_IRQHandler,
DMA2_Channel3_IRQHandler,
DMA2_Channel4_5_IRQHandler,
DMA2_Channel5_IRQHandler,
0, 0, 0, 0, 0, 0, 0, 0,
0,
#if defined (STM32F10X_LD_VL) || (defined STM32F10X_MD_VL)
[0x1CC/4] = 0xF108F85F
#elif defined (STM32F10X_HD_VL)
[0x1E0/4] = 0xF108F85F
#endif
};

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,23 @@
#ifndef __STM32F10x_CONF_H
#define __STM32F10x_CONF_H
#ifdef USE_FULL_ASSERT
/**
* @brief The assert_param macro is used for function's parameters check.
* @param expr: If expr is false, it calls assert_failed function
* which reports the name of the source file and the source
* line number of the call that failed.
* If expr is true, it returns no value.
* @retval None
*/
#define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__))
/* Exported functions ------------------------------------------------------- */
void assert_failed(uint8_t* file, uint32_t line);
#else
#define assert_param(expr) ((void)0)
#endif /* USE_FULL_ASSERT */
#endif /* __STM32F10x_CONF_H */
/******************* (C) COPYRIGHT 2010 STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,992 @@
/**
******************************************************************************
* @file USART/Printf/system_stm32f10x.c
* @author MCD Application Team
* @version V3.5.0
* @date 08-April-2011
* @brief CMSIS Cortex-M3 Device Peripheral Access Layer System Source File.
*
* 1. This file provides two functions and one global variable to be called from
* user application:
* - SystemInit(): Setups the system clock (System clock source, PLL Multiplier
* factors, AHB/APBx prescalers and Flash settings).
* This function is called at startup just after reset and
* before branch to main program. This call is made inside
* the "startup_stm32f10x_xx.s" file.
*
* - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
* by the user application to setup the SysTick
* timer or configure other parameters.
*
* - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
* be called whenever the core clock is changed
* during program execution.
*
* 2. After each device reset the HSI (8 MHz) is used as system clock source.
* Then SystemInit() function is called, in "startup_stm32f10x_xx.s" file, to
* configure the system clock before to branch to main program.
*
* 3. If the system clock source selected by user fails to startup, the SystemInit()
* function will do nothing and HSI still used as system clock source. User can
* add some code to deal with this issue inside the SetSysClock() function.
*
* 4. The default value of HSE crystal is set to 8 MHz (or 25 MHz, depedning on
* the product used), refer to "HSE_VALUE" define in "stm32f10x.h" file.
* When HSE is used as system clock source, directly or through PLL, and you
* are using different crystal you have to adapt the HSE value to your own
* configuration.
*
******************************************************************************
* @attention
*
* 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.
*
* <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/** @addtogroup CMSIS
* @{
*/
/** @addtogroup stm32f10x_system
* @{
*/
/** @addtogroup STM32F10x_System_Private_Includes
* @{
*/
#include "stm32f10x.h"
/**
* @}
*/
/** @addtogroup STM32F10x_System_Private_TypesDefinitions
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F10x_System_Private_Defines
* @{
*/
/*!< Uncomment the line corresponding to the desired System clock (SYSCLK)
frequency (after reset the HSI is used as SYSCLK source)
IMPORTANT NOTE:
==============
1. After each device reset the HSI is used as System clock source.
2. Please make sure that the selected System clock doesn't exceed your device's
maximum frequency.
3. If none of the define below is enabled, the HSI is used as System clock
source.
4. The System clock configuration functions provided within this file assume that:
- For Low, Medium and High density Value line devices an external 8MHz
crystal is used to drive the System clock.
- For Low, Medium and High density devices an external 8MHz crystal is
used to drive the System clock.
- For Connectivity line devices an external 25MHz crystal is used to drive
the System clock.
If you are using different crystal you have to adapt those functions accordingly.
*/
#define SYSCLK_FREQ_24MHz 24000000
/*!< Uncomment the following line if you need to use external SRAM mounted
on STM3210E-EVAL board (STM32 High density and XL-density devices) or on
STM32100E-EVAL board (STM32 High-density value line devices) as data memory */
#if defined (STM32F10X_HD) || (defined STM32F10X_XL) || (defined STM32F10X_HD_VL)
/* #define DATA_IN_ExtSRAM */
#endif
/*!< Uncomment the following line if you need to relocate your vector Table in
Internal SRAM. */
/* #define VECT_TAB_SRAM */
#define VECT_TAB_OFFSET 0x0 /*!< Vector Table base offset field.
This value must be a multiple of 0x200. */
/**
* @}
*/
/** @addtogroup STM32F10x_System_Private_Macros
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F10x_System_Private_Variables
* @{
*/
/*******************************************************************************
* Clock Definitions
*******************************************************************************/
uint32_t SystemCoreClock = SYSCLK_FREQ_24MHz; /*!< System Clock Frequency (Core Clock) */
__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
/**
* @}
*/
/** @addtogroup STM32F10x_System_Private_FunctionPrototypes
* @{
*/
static void SetSysClock(void);
static void SetSysClockTo24(void);
/**
* @}
*/
/** @addtogroup STM32F10x_System_Private_Functions
* @{
*/
/**
* @brief Setup the microcontroller system
* Initialize the Embedded Flash Interface, the PLL and update the
* SystemCoreClock variable.
* @note This function should be used only after reset.
* @param None
* @retval None
*/
void SystemInit (void) {
/* Reset the RCC clock configuration to the default reset state(for debug purpose) */
/* Set HSION bit */
RCC->CR |= (uint32_t)0x00000001;
/* Reset SW, HPRE, PPRE1, PPRE2, ADCPRE and MCO bits */
#ifndef STM32F10X_CL
RCC->CFGR &= (uint32_t)0xF8FF0000;
#else
RCC->CFGR &= (uint32_t)0xF0FF0000;
#endif /* STM32F10X_CL */
/* Reset HSEON, CSSON and PLLON bits */
RCC->CR &= (uint32_t)0xFEF6FFFF;
/* Reset HSEBYP bit */
RCC->CR &= (uint32_t)0xFFFBFFFF;
/* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE/OTGFSPRE bits */
RCC->CFGR &= (uint32_t)0xFF80FFFF;
#ifdef STM32F10X_CL
/* Reset PLL2ON and PLL3ON bits */
RCC->CR &= (uint32_t)0xEBFFFFFF;
/* Disable all interrupts and clear pending bits */
RCC->CIR = 0x00FF0000;
/* Reset CFGR2 register */
RCC->CFGR2 = 0x00000000;
#elif defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || (defined STM32F10X_HD_VL)
/* Disable all interrupts and clear pending bits */
RCC->CIR = 0x009F0000;
/* Reset CFGR2 register */
RCC->CFGR2 = 0x00000000;
#else
/* Disable all interrupts and clear pending bits */
RCC->CIR = 0x009F0000;
#endif /* STM32F10X_CL */
/* Configure the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers */
/* Configure the Flash Latency cycles and enable prefetch buffer */
SetSysClock();
#ifdef VECT_TAB_SRAM
SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM. */
#else
SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH. */
#endif
}
/**
* @brief Update SystemCoreClock variable according to Clock Register Values.
* The SystemCoreClock variable contains the core clock (HCLK), it can
* be used by the user application to setup the SysTick timer or configure
* other parameters.
*
* @note Each time the core clock (HCLK) changes, this function must be called
* to update SystemCoreClock variable value. Otherwise, any configuration
* based on this variable will be incorrect.
*
* @note - The system frequency computed by this function is not the real
* frequency in the chip. It is calculated based on the predefined
* constant and the selected clock source:
*
* - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
*
* - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
*
* - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
* or HSI_VALUE(*) multiplied by the PLL factors.
*
* (*) HSI_VALUE is a constant defined in stm32f1xx.h file (default value
* 8 MHz) but the real value may vary depending on the variations
* in voltage and temperature.
*
* (**) HSE_VALUE is a constant defined in stm32f1xx.h file (default value
* 8 MHz or 25 MHz, depedning on the product used), user has to ensure
* that HSE_VALUE is same as the real frequency of the crystal used.
* Otherwise, this function may have wrong result.
*
* - The result of this function could be not correct when using fractional
* value for HSE crystal.
* @param None
* @retval None
*/
void SystemCoreClockUpdate (void)
{
uint32_t tmp = 0, pllmull = 0, pllsource = 0;
#ifdef STM32F10X_CL
uint32_t prediv1source = 0, prediv1factor = 0, prediv2factor = 0, pll2mull = 0;
#endif /* STM32F10X_CL */
#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || (defined STM32F10X_HD_VL)
uint32_t prediv1factor = 0;
#endif /* STM32F10X_LD_VL or STM32F10X_MD_VL or STM32F10X_HD_VL */
/* Get SYSCLK source -------------------------------------------------------*/
tmp = RCC->CFGR & RCC_CFGR_SWS;
switch (tmp)
{
case 0x00: /* HSI used as system clock */
SystemCoreClock = HSI_VALUE;
break;
case 0x04: /* HSE used as system clock */
SystemCoreClock = HSE_VALUE;
break;
case 0x08: /* PLL used as system clock */
/* Get PLL clock source and multiplication factor ----------------------*/
pllmull = RCC->CFGR & RCC_CFGR_PLLMULL;
pllsource = RCC->CFGR & RCC_CFGR_PLLSRC;
#ifndef STM32F10X_CL
pllmull = ( pllmull >> 18) + 2;
if (pllsource == 0x00)
{
/* HSI oscillator clock divided by 2 selected as PLL clock entry */
SystemCoreClock = (HSI_VALUE >> 1) * pllmull;
}
else
{
#if defined (STM32F10X_LD_VL) || defined (STM32F10X_MD_VL) || (defined STM32F10X_HD_VL)
prediv1factor = (RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1;
/* HSE oscillator clock selected as PREDIV1 clock entry */
SystemCoreClock = (HSE_VALUE / prediv1factor) * pllmull;
#else
/* HSE selected as PLL clock entry */
if ((RCC->CFGR & RCC_CFGR_PLLXTPRE) != (uint32_t)RESET)
{/* HSE oscillator clock divided by 2 */
SystemCoreClock = (HSE_VALUE >> 1) * pllmull;
}
else
{
SystemCoreClock = HSE_VALUE * pllmull;
}
#endif
}
#else
pllmull = pllmull >> 18;
if (pllmull != 0x0D)
{
pllmull += 2;
}
else
{ /* PLL multiplication factor = PLL input clock * 6.5 */
pllmull = 13 / 2;
}
if (pllsource == 0x00)
{
/* HSI oscillator clock divided by 2 selected as PLL clock entry */
SystemCoreClock = (HSI_VALUE >> 1) * pllmull;
}
else
{/* PREDIV1 selected as PLL clock entry */
/* Get PREDIV1 clock source and division factor */
prediv1source = RCC->CFGR2 & RCC_CFGR2_PREDIV1SRC;
prediv1factor = (RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1;
if (prediv1source == 0)
{
/* HSE oscillator clock selected as PREDIV1 clock entry */
SystemCoreClock = (HSE_VALUE / prediv1factor) * pllmull;
}
else
{/* PLL2 clock selected as PREDIV1 clock entry */
/* Get PREDIV2 division factor and PLL2 multiplication factor */
prediv2factor = ((RCC->CFGR2 & RCC_CFGR2_PREDIV2) >> 4) + 1;
pll2mull = ((RCC->CFGR2 & RCC_CFGR2_PLL2MUL) >> 8 ) + 2;
SystemCoreClock = (((HSE_VALUE / prediv2factor) * pll2mull) / prediv1factor) * pllmull;
}
}
#endif /* STM32F10X_CL */
break;
default:
SystemCoreClock = HSI_VALUE;
break;
}
/* Compute HCLK clock frequency ----------------*/
/* Get HCLK prescaler */
tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
/* HCLK clock frequency */
SystemCoreClock >>= tmp;
}
/**
* @brief Configures the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers.
* @param None
* @retval None
*/
static void SetSysClock(void)
{
SetSysClockTo24();
}
/**
* @brief Setup the external memory controller. Called in startup_stm32f10x.s
* before jump to __main
* @param None
* @retval None
*/
#ifdef DATA_IN_ExtSRAM
/**
* @brief Setup the external memory controller.
* Called in startup_stm32f10x_xx.s/.c before jump to main.
* This function configures the external SRAM mounted on STM3210E-EVAL
* board (STM32 High density devices). This SRAM will be used as program
* data memory (including heap and stack).
* @param None
* @retval None
*/
void SystemInit_ExtMemCtl(void)
{
/*!< FSMC Bank1 NOR/SRAM3 is used for the STM3210E-EVAL, if another Bank is
required, then adjust the Register Addresses */
/* Enable FSMC clock */
RCC->AHBENR = 0x00000114;
/* Enable GPIOD, GPIOE, GPIOF and GPIOG clocks */
RCC->APB2ENR = 0x000001E0;
/* --------------- SRAM Data lines, NOE and NWE configuration ---------------*/
/*---------------- SRAM Address lines configuration -------------------------*/
/*---------------- NOE and NWE configuration --------------------------------*/
/*---------------- NE3 configuration ----------------------------------------*/
/*---------------- NBL0, NBL1 configuration ---------------------------------*/
GPIOD->CRL = 0x44BB44BB;
GPIOD->CRH = 0xBBBBBBBB;
GPIOE->CRL = 0xB44444BB;
GPIOE->CRH = 0xBBBBBBBB;
GPIOF->CRL = 0x44BBBBBB;
GPIOF->CRH = 0xBBBB4444;
GPIOG->CRL = 0x44BBBBBB;
GPIOG->CRH = 0x44444B44;
/*---------------- FSMC Configuration ---------------------------------------*/
/*---------------- Enable FSMC Bank1_SRAM Bank ------------------------------*/
FSMC_Bank1->BTCR[4] = 0x00001011;
FSMC_Bank1->BTCR[5] = 0x00000200;
}
#endif /* DATA_IN_ExtSRAM */
#ifdef SYSCLK_FREQ_HSE
/**
* @brief Selects HSE as System clock source and configure HCLK, PCLK2
* and PCLK1 prescalers.
* @note This function should be used only after reset.
* @param None
* @retval None
*/
static void SetSysClockToHSE(void)
{
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
/* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/
/* Enable HSE */
RCC->CR |= ((uint32_t)RCC_CR_HSEON);
/* Wait till HSE is ready and if Time out is reached exit */
do
{
HSEStatus = RCC->CR & RCC_CR_HSERDY;
StartUpCounter++;
} while ((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
if ((RCC->CR & RCC_CR_HSERDY) != RESET)
{
HSEStatus = (uint32_t)0x01;
}
else
{
HSEStatus = (uint32_t)0x00;
}
if (HSEStatus == (uint32_t)0x01)
{
#if !defined STM32F10X_LD_VL && !defined STM32F10X_MD_VL && !defined STM32F10X_HD_VL
/* Enable Prefetch Buffer */
FLASH->ACR |= FLASH_ACR_PRFTBE;
/* Flash 0 wait state */
FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY);
#ifndef STM32F10X_CL
FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_0;
#else
if (HSE_VALUE <= 24000000)
{
FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_0;
}
else
{
FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_1;
}
#endif /* STM32F10X_CL */
#endif
/* HCLK = SYSCLK */
RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
/* PCLK2 = HCLK */
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;
/* PCLK1 = HCLK */
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV1;
/* Select HSE as system clock source */
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
RCC->CFGR |= (uint32_t)RCC_CFGR_SW_HSE;
/* Wait till HSE is used as system clock source */
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x04)
{
}
}
else
{ /* If HSE fails to start-up, the application will have wrong clock
configuration. User can add here some code to deal with this error */
}
}
#elif defined SYSCLK_FREQ_24MHz
/**
* @brief Sets System clock frequency to 24MHz and configure HCLK, PCLK2
* and PCLK1 prescalers.
* @note This function should be used only after reset.
* @param None
* @retval None
*/
static void SetSysClockTo24(void)
{
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
/* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/
/* Enable HSE */
RCC->CR |= ((uint32_t)RCC_CR_HSEON);
/* Wait till HSE is ready and if Time out is reached exit */
do{
HSEStatus = RCC->CR & RCC_CR_HSERDY;
StartUpCounter++;
} while ((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
if ((RCC->CR & RCC_CR_HSERDY) != RESET) {
HSEStatus = (uint32_t)0x01;
} else {
HSEStatus = (uint32_t)0x00;
}
if (HSEStatus == (uint32_t)0x01) {
/* HCLK = SYSCLK */
RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
/* PCLK2 = HCLK */
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;
/* PCLK1 = HCLK */
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV1;
/* PLL configuration: = (HSE / 1) * 2 = 24 MHz */
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL));
// RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_PREDIV1 | RCC_CFGR_PLLXTPRE_PREDIV1_Div2 | RCC_CFGR_PLLMULL6);
// RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_PREDIV1 | RCC_CFGR_PLLMULL2);
RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLMULL2);
/* Enable PLL */
RCC->CR |= RCC_CR_PLLON;
/* Wait till PLL is ready */
while ((RCC->CR & RCC_CR_PLLRDY) == 0) { }
/* Select PLL as system clock source */
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL;
/* Wait till PLL is used as system clock source */
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x08)
{
}
}
else
{ /* If HSE fails to start-up, the application will have wrong clock
configuration. User can add here some code to deal with this error */
}
}
#elif defined SYSCLK_FREQ_36MHz
/**
* @brief Sets System clock frequency to 36MHz and configure HCLK, PCLK2
* and PCLK1 prescalers.
* @note This function should be used only after reset.
* @param None
* @retval None
*/
static void SetSysClockTo36(void)
{
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
/* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/
/* Enable HSE */
RCC->CR |= ((uint32_t)RCC_CR_HSEON);
/* Wait till HSE is ready and if Time out is reached exit */
do
{
HSEStatus = RCC->CR & RCC_CR_HSERDY;
StartUpCounter++;
} while ((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
if ((RCC->CR & RCC_CR_HSERDY) != RESET)
{
HSEStatus = (uint32_t)0x01;
}
else
{
HSEStatus = (uint32_t)0x00;
}
if (HSEStatus == (uint32_t)0x01)
{
/* Enable Prefetch Buffer */
FLASH->ACR |= FLASH_ACR_PRFTBE;
/* Flash 1 wait state */
FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY);
FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_1;
/* HCLK = SYSCLK */
RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
/* PCLK2 = HCLK */
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;
/* PCLK1 = HCLK */
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV1;
#ifdef STM32F10X_CL
/* Configure PLLs ------------------------------------------------------*/
/* PLL configuration: PLLCLK = PREDIV1 * 9 = 36 MHz */
RCC->CFGR &= (uint32_t)~(RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLSRC | RCC_CFGR_PLLMULL);
RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLSRC_PREDIV1 |
RCC_CFGR_PLLMULL9);
/*!< PLL2 configuration: PLL2CLK = (HSE / 5) * 8 = 40 MHz */
/* PREDIV1 configuration: PREDIV1CLK = PLL2 / 10 = 4 MHz */
RCC->CFGR2 &= (uint32_t)~(RCC_CFGR2_PREDIV2 | RCC_CFGR2_PLL2MUL |
RCC_CFGR2_PREDIV1 | RCC_CFGR2_PREDIV1SRC);
RCC->CFGR2 |= (uint32_t)(RCC_CFGR2_PREDIV2_DIV5 | RCC_CFGR2_PLL2MUL8 |
RCC_CFGR2_PREDIV1SRC_PLL2 | RCC_CFGR2_PREDIV1_DIV10);
/* Enable PLL2 */
RCC->CR |= RCC_CR_PLL2ON;
/* Wait till PLL2 is ready */
while ((RCC->CR & RCC_CR_PLL2RDY) == 0)
{
}
#else
/* PLL configuration: PLLCLK = (HSE / 2) * 9 = 36 MHz */
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL));
RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLXTPRE_HSE_Div2 | RCC_CFGR_PLLMULL9);
#endif /* STM32F10X_CL */
/* Enable PLL */
RCC->CR |= RCC_CR_PLLON;
/* Wait till PLL is ready */
while ((RCC->CR & RCC_CR_PLLRDY) == 0)
{
}
/* Select PLL as system clock source */
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL;
/* Wait till PLL is used as system clock source */
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x08)
{
}
}
else
{ /* If HSE fails to start-up, the application will have wrong clock
configuration. User can add here some code to deal with this error */
}
}
#elif defined SYSCLK_FREQ_48MHz
/**
* @brief Sets System clock frequency to 48MHz and configure HCLK, PCLK2
* and PCLK1 prescalers.
* @note This function should be used only after reset.
* @param None
* @retval None
*/
static void SetSysClockTo48(void)
{
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
/* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/
/* Enable HSE */
RCC->CR |= ((uint32_t)RCC_CR_HSEON);
/* Wait till HSE is ready and if Time out is reached exit */
do
{
HSEStatus = RCC->CR & RCC_CR_HSERDY;
StartUpCounter++;
} while ((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
if ((RCC->CR & RCC_CR_HSERDY) != RESET)
{
HSEStatus = (uint32_t)0x01;
}
else
{
HSEStatus = (uint32_t)0x00;
}
if (HSEStatus == (uint32_t)0x01)
{
/* Enable Prefetch Buffer */
FLASH->ACR |= FLASH_ACR_PRFTBE;
/* Flash 1 wait state */
FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY);
FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_1;
/* HCLK = SYSCLK */
RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
/* PCLK2 = HCLK */
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;
/* PCLK1 = HCLK */
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2;
#ifdef STM32F10X_CL
/* Configure PLLs ------------------------------------------------------*/
/* PLL2 configuration: PLL2CLK = (HSE / 5) * 8 = 40 MHz */
/* PREDIV1 configuration: PREDIV1CLK = PLL2 / 5 = 8 MHz */
RCC->CFGR2 &= (uint32_t)~(RCC_CFGR2_PREDIV2 | RCC_CFGR2_PLL2MUL |
RCC_CFGR2_PREDIV1 | RCC_CFGR2_PREDIV1SRC);
RCC->CFGR2 |= (uint32_t)(RCC_CFGR2_PREDIV2_DIV5 | RCC_CFGR2_PLL2MUL8 |
RCC_CFGR2_PREDIV1SRC_PLL2 | RCC_CFGR2_PREDIV1_DIV5);
/* Enable PLL2 */
RCC->CR |= RCC_CR_PLL2ON;
/* Wait till PLL2 is ready */
while ((RCC->CR & RCC_CR_PLL2RDY) == 0)
{
}
/* PLL configuration: PLLCLK = PREDIV1 * 6 = 48 MHz */
RCC->CFGR &= (uint32_t)~(RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLSRC | RCC_CFGR_PLLMULL);
RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLSRC_PREDIV1 |
RCC_CFGR_PLLMULL6);
#else
/* PLL configuration: PLLCLK = HSE * 6 = 48 MHz */
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL));
RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLMULL6);
#endif /* STM32F10X_CL */
/* Enable PLL */
RCC->CR |= RCC_CR_PLLON;
/* Wait till PLL is ready */
while ((RCC->CR & RCC_CR_PLLRDY) == 0)
{
}
/* Select PLL as system clock source */
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL;
/* Wait till PLL is used as system clock source */
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x08)
{
}
}
else
{ /* If HSE fails to start-up, the application will have wrong clock
configuration. User can add here some code to deal with this error */
}
}
#elif defined SYSCLK_FREQ_56MHz
/**
* @brief Sets System clock frequency to 56MHz and configure HCLK, PCLK2
* and PCLK1 prescalers.
* @note This function should be used only after reset.
* @param None
* @retval None
*/
static void SetSysClockTo56(void)
{
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
/* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/
/* Enable HSE */
RCC->CR |= ((uint32_t)RCC_CR_HSEON);
/* Wait till HSE is ready and if Time out is reached exit */
do
{
HSEStatus = RCC->CR & RCC_CR_HSERDY;
StartUpCounter++;
} while ((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
if ((RCC->CR & RCC_CR_HSERDY) != RESET)
{
HSEStatus = (uint32_t)0x01;
}
else
{
HSEStatus = (uint32_t)0x00;
}
if (HSEStatus == (uint32_t)0x01)
{
/* Enable Prefetch Buffer */
FLASH->ACR |= FLASH_ACR_PRFTBE;
/* Flash 2 wait state */
FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY);
FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_2;
/* HCLK = SYSCLK */
RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
/* PCLK2 = HCLK */
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;
/* PCLK1 = HCLK */
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2;
#ifdef STM32F10X_CL
/* Configure PLLs ------------------------------------------------------*/
/* PLL2 configuration: PLL2CLK = (HSE / 5) * 8 = 40 MHz */
/* PREDIV1 configuration: PREDIV1CLK = PLL2 / 5 = 8 MHz */
RCC->CFGR2 &= (uint32_t)~(RCC_CFGR2_PREDIV2 | RCC_CFGR2_PLL2MUL |
RCC_CFGR2_PREDIV1 | RCC_CFGR2_PREDIV1SRC);
RCC->CFGR2 |= (uint32_t)(RCC_CFGR2_PREDIV2_DIV5 | RCC_CFGR2_PLL2MUL8 |
RCC_CFGR2_PREDIV1SRC_PLL2 | RCC_CFGR2_PREDIV1_DIV5);
/* Enable PLL2 */
RCC->CR |= RCC_CR_PLL2ON;
/* Wait till PLL2 is ready */
while ((RCC->CR & RCC_CR_PLL2RDY) == 0)
{
}
/* PLL configuration: PLLCLK = PREDIV1 * 7 = 56 MHz */
RCC->CFGR &= (uint32_t)~(RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLSRC | RCC_CFGR_PLLMULL);
RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLSRC_PREDIV1 |
RCC_CFGR_PLLMULL7);
#else
/* PLL configuration: PLLCLK = HSE * 7 = 56 MHz */
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL));
RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLMULL7);
#endif /* STM32F10X_CL */
/* Enable PLL */
RCC->CR |= RCC_CR_PLLON;
/* Wait till PLL is ready */
while ((RCC->CR & RCC_CR_PLLRDY) == 0)
{
}
/* Select PLL as system clock source */
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL;
/* Wait till PLL is used as system clock source */
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x08)
{
}
}
else
{ /* If HSE fails to start-up, the application will have wrong clock
configuration. User can add here some code to deal with this error */
}
}
#elif defined SYSCLK_FREQ_72MHz
/**
* @brief Sets System clock frequency to 72MHz and configure HCLK, PCLK2
* and PCLK1 prescalers.
* @note This function should be used only after reset.
* @param None
* @retval None
*/
static void SetSysClockTo72(void)
{
__IO uint32_t StartUpCounter = 0, HSEStatus = 0;
/* SYSCLK, HCLK, PCLK2 and PCLK1 configuration ---------------------------*/
/* Enable HSE */
RCC->CR |= ((uint32_t)RCC_CR_HSEON);
/* Wait till HSE is ready and if Time out is reached exit */
do
{
HSEStatus = RCC->CR & RCC_CR_HSERDY;
StartUpCounter++;
} while ((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
if ((RCC->CR & RCC_CR_HSERDY) != RESET)
{
HSEStatus = (uint32_t)0x01;
}
else
{
HSEStatus = (uint32_t)0x00;
}
if (HSEStatus == (uint32_t)0x01)
{
/* Enable Prefetch Buffer */
FLASH->ACR |= FLASH_ACR_PRFTBE;
/* Flash 2 wait state */
FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY);
FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_2;
/* HCLK = SYSCLK */
RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1;
/* PCLK2 = HCLK */
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1;
/* PCLK1 = HCLK */
RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2;
#ifdef STM32F10X_CL
/* Configure PLLs ------------------------------------------------------*/
/* PLL2 configuration: PLL2CLK = (HSE / 5) * 8 = 40 MHz */
/* PREDIV1 configuration: PREDIV1CLK = PLL2 / 5 = 8 MHz */
RCC->CFGR2 &= (uint32_t)~(RCC_CFGR2_PREDIV2 | RCC_CFGR2_PLL2MUL |
RCC_CFGR2_PREDIV1 | RCC_CFGR2_PREDIV1SRC);
RCC->CFGR2 |= (uint32_t)(RCC_CFGR2_PREDIV2_DIV5 | RCC_CFGR2_PLL2MUL8 |
RCC_CFGR2_PREDIV1SRC_PLL2 | RCC_CFGR2_PREDIV1_DIV5);
/* Enable PLL2 */
RCC->CR |= RCC_CR_PLL2ON;
/* Wait till PLL2 is ready */
while ((RCC->CR & RCC_CR_PLL2RDY) == 0)
{
}
/* PLL configuration: PLLCLK = PREDIV1 * 9 = 72 MHz */
RCC->CFGR &= (uint32_t)~(RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLSRC | RCC_CFGR_PLLMULL);
RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLXTPRE_PREDIV1 | RCC_CFGR_PLLSRC_PREDIV1 |
RCC_CFGR_PLLMULL9);
#else
/* PLL configuration: PLLCLK = HSE * 9 = 72 MHz */
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE |
RCC_CFGR_PLLMULL));
RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLMULL9);
#endif /* STM32F10X_CL */
/* Enable PLL */
RCC->CR |= RCC_CR_PLLON;
/* Wait till PLL is ready */
while ((RCC->CR & RCC_CR_PLLRDY) == 0)
{
}
/* Select PLL as system clock source */
RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL;
/* Wait till PLL is used as system clock source */
while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x08)
{
}
}
else
{ /* If HSE fails to start-up, the application will have wrong clock
configuration. User can add here some code to deal with this error */
}
}
#endif
/**
* @}
*/
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,98 @@
/**
******************************************************************************
* @file system_stm32f10x.h
* @author MCD Application Team
* @version V3.5.0
* @date 11-March-2011
* @brief CMSIS Cortex-M3 Device Peripheral Access Layer System Header File.
******************************************************************************
* @attention
*
* 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.
*
* <h2><center>&copy; COPYRIGHT 2011 STMicroelectronics</center></h2>
******************************************************************************
*/
/** @addtogroup CMSIS
* @{
*/
/** @addtogroup stm32f10x_system
* @{
*/
/**
* @brief Define to prevent recursive inclusion
*/
#ifndef __SYSTEM_STM32F10X_H
#define __SYSTEM_STM32F10X_H
#ifdef __cplusplus
extern "C" {
#endif
/** @addtogroup STM32F10x_System_Includes
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F10x_System_Exported_types
* @{
*/
extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
/**
* @}
*/
/** @addtogroup STM32F10x_System_Exported_Constants
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F10x_System_Exported_Macros
* @{
*/
/**
* @}
*/
/** @addtogroup STM32F10x_System_Exported_Functions
* @{
*/
extern void SystemInit(void);
extern void SystemCoreClockUpdate(void);
/**
* @}
*/
#ifdef __cplusplus
}
#endif
#endif /*__SYSTEM_STM32F10X_H */
/**
* @}
*/
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

View File

@@ -0,0 +1,185 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_adc.h"
#include "debug.h"
#include "wdt.h"
#include "config.h"
#include "stm32f10x_rcc.h"
#include "stm32f10x_gpio.h"
#include "stm32f10x_dma.h"
#include "stm32f10x_adc.h"
// adc results
volatile uint16_t hal_adc_data[2];
void hal_adc_init(void) {
hal_adc_init_rcc();
hal_adc_init_gpio();
hal_adc_init_mode();
hal_adc_init_dma();
}
static void hal_adc_init_rcc(void) {
// ADC CLOCK = 24 / 4 = 6MHz
RCC_ADCCLKConfig(RCC_PCLK2_Div4);
// enable ADC clock
RCC_APBxPeriphClockCmd(ADC_CLK_RCC, ADC_CLK, ENABLE);
// enable dma clock
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
// periph clock enable for port
RCC_APBxPeriphClockCmd(ADC_GPIO_CLK_RCC, ADC_GPIO_CLK, ENABLE);
}
static void hal_adc_init_gpio(void) {
GPIO_InitTypeDef gpio_init;
// set up analog inputs
gpio_init.GPIO_Pin = ADC_IN1_PIN | ADC_IN2_PIN;
gpio_init.GPIO_Mode = GPIO_Mode_AIN;
GPIO_Init(ADC_GPIO, &gpio_init);
}
static void hal_adc_init_mode(void) {
ADC_InitTypeDef adc_init;
// ADC configuration
adc_init.ADC_Mode = ADC_Mode_Independent;
// convert multiple channels
adc_init.ADC_ScanConvMode = ENABLE;
// select continuous conversion mode
adc_init.ADC_ContinuousConvMode = ENABLE;
// select no external triggering
adc_init.ADC_ExternalTrigConv = ADC_ExternalTrigConv_None;
// right 12-bit data alignment in ADC data register
adc_init.ADC_DataAlign = ADC_DataAlign_Right;
// 2 channels conversion
adc_init.ADC_NbrOfChannel = 2;
// load structure values to control and status registers
ADC_Init(ADC, &adc_init);
// configure each channel
ADC_RegularChannelConfig(ADC, ADC_Channel_1, 1, ADC_SampleTime_41Cycles5);
ADC_RegularChannelConfig(ADC, ADC_Channel_2, 2, ADC_SampleTime_41Cycles5);
// Enable ADC
ADC_Cmd(ADC, ENABLE);
// enable DMA for ADC
ADC_DMACmd(ADC, ENABLE);
// Enable ADC1 reset calibration register
ADC_ResetCalibration(ADC);
// Check the end of ADC1 reset calibration register
while (ADC_GetResetCalibrationStatus(ADC)) {}
// Start ADC calibration
ADC_StartCalibration(ADC);
// Check the end of ADC1 calibration
while (ADC_GetCalibrationStatus(ADC)) {}
}
static void hal_adc_init_dma(void) {
DMA_InitTypeDef dma_init;
// reset DMA1 channe1 to default values
DMA_DeInit(ADC_DMA_CHANNEL);
// set up dma to convert 2 adc channels to two mem locations:
// channel will be used for memory to memory transfer
dma_init.DMA_M2M = DMA_M2M_Disable;
// setting normal mode (non circular)
dma_init.DMA_Mode = DMA_Mode_Circular;
// medium priority
dma_init.DMA_Priority = DMA_Priority_High;
// source and destination 16bit
dma_init.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord;
dma_init.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord;
// automatic memory destination increment enable.
dma_init.DMA_MemoryInc = DMA_MemoryInc_Enable;
// source address increment disable
dma_init.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
// Location assigned to peripheral register will be source
dma_init.DMA_DIR = DMA_DIR_PeripheralSRC;
// chunk of data to be transfered
dma_init.DMA_BufferSize = 2;
// source and destination start addresses
dma_init.DMA_PeripheralBaseAddr = (uint32_t)&ADC->DR;
dma_init.DMA_MemoryBaseAddr = (uint32_t)hal_adc_data;
// send values to DMA registers
DMA_Init(ADC_DMA_CHANNEL, &dma_init);
// Enable the DMA1 - Channel1
DMA_Cmd(ADC_DMA_CHANNEL, ENABLE);
// start conversion:
hal_adc_dma_arm();
#if ADC_DO_TEST
// TEST ADC
while (1) {
debug_putc('A');
wdt_reset();
if (ADC_GetFlagStatus(ADC, ADC_FLAG_EOC) == SET) {
uint16_t res = ADC_GetConversionValue(ADC);
debug("ADC = "); debug_put_uint16(res); debug_put_newline(); debug_flush();
ADC_ClearFlag(ADC, ADC_FLAG_EOC);
// start next ADC Software Conversion
ADC_SoftwareStartConvCmd(ADC, ENABLE);
}
}
#endif // ADC_DO_TEST
}
static void hal_adc_dma_arm(void) {
ADC_SoftwareStartConvCmd(ADC, ENABLE);
}
void hal_adc_process(void) {
// adc dma finished?
if (DMA_GetITStatus(ADC_DMA_TC_FLAG)) {
// fine, arm DMA again:
hal_adc_dma_arm();
} else {
// oops this should not happen
debug_putc('D');
// cancel and re arm dma ???
}
}
uint8_t hal_adc_get_scaled(uint8_t ch) {
if (ch < 2) {
// 12 bit adc -> scale to 8 bit -> shift by 4
return hal_adc_data[ch]>>4;
} else {
debug("hal_adc: channel index out of bounds ");
debug_put_uint8(ch);
debug("allowed 0,1)\n");
debug_flush();
return 0;
}
}

View File

@@ -0,0 +1,39 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_ADC_H_
#define HAL_ADC_H_
#include "main.h"
#include <stdint.h>
extern volatile uint16_t hal_adc_data[2];
void hal_adc_init(void);
static void hal_adc_init_rcc(void);
static void hal_adc_init_gpio(void);
static void hal_adc_init_mode(void);
static void hal_adc_init_dma(void);
static void hal_adc_dma_arm(void);
uint8_t hal_adc_get_scaled(uint8_t ch);
void hal_adc_process(void);
#endif // HAL_ADC_H_

View File

@@ -0,0 +1,289 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_cc25xx.h"
#include "hal_spi.h"
#include "cc25xx.h"
#include "stm32f10x_gpio.h"
#include "stm32f10x_rcc.h"
#include "debug.h"
#include "timeout.h"
#include <string.h>
void hal_cc25xx_init(void) {
hal_spi_init();
hal_cc25xx_init_gpio();
}
static void hal_cc25xx_init_gpio(void) {
GPIO_InitTypeDef gpio_init;
// antenna switch
// periph clock enable for port
RCC_APBxPeriphClockCmd(CC25XX_ANT_SW_CTX_GPIO_CLK_RCC, CC25XX_ANT_SW_CTX_GPIO_CLK, ENABLE);
RCC_APBxPeriphClockCmd(CC25XX_ANT_SW_CRX_GPIO_CLK_RCC, CC25XX_ANT_SW_CRX_GPIO_CLK, ENABLE);
// CTX:
gpio_init.GPIO_Pin = CC25XX_ANT_SW_CTX_PIN;
gpio_init.GPIO_Speed = GPIO_Speed_50MHz;
gpio_init.GPIO_Mode = GPIO_Mode_Out_PP;
GPIO_Init(CC25XX_ANT_SW_CTX_GPIO, &gpio_init);
// CRX:
gpio_init.GPIO_Pin = CC25XX_ANT_SW_CRX_PIN;
gpio_init.GPIO_Speed = GPIO_Speed_50MHz;
gpio_init.GPIO_Mode = GPIO_Mode_Out_PP;
GPIO_Init(CC25XX_ANT_SW_CRX_GPIO, &gpio_init);
// select first antenna
hal_cc25xx_set_antenna(0);
// PA/LNA:
// periph clock enable for port
RCC_APBxPeriphClockCmd(CC25XX_LNA_SW_CTX_GPIO_CLK_RCC, CC25XX_LNA_SW_CTX_GPIO_CLK, ENABLE);
RCC_APBxPeriphClockCmd(CC25XX_LNA_SW_CRX_GPIO_CLK_RCC, CC25XX_LNA_SW_CRX_GPIO_CLK, ENABLE);
// CTX:
gpio_init.GPIO_Pin = CC25XX_LNA_SW_CTX_PIN;
gpio_init.GPIO_Speed = GPIO_Speed_50MHz;
gpio_init.GPIO_Mode = GPIO_Mode_Out_PP;
GPIO_Init(CC25XX_LNA_SW_CTX_GPIO, &gpio_init);
// CRX:
gpio_init.GPIO_Pin = CC25XX_LNA_SW_CRX_PIN;
gpio_init.GPIO_Speed = GPIO_Speed_50MHz;
gpio_init.GPIO_Mode = GPIO_Mode_Out_PP;
GPIO_Init(CC25XX_LNA_SW_CRX_GPIO, &gpio_init);
hal_cc25xx_enter_rxmode();
// JTAG IS ON LNA pins! -> DISABLE JTAG!
RCC_APBxPeriphClockCmd(2, RCC_APB2Periph_AFIO, ENABLE);
GPIO_PinRemapConfig(GPIO_Remap_SWJ_JTAGDisable, ENABLE);
// GDO2
// periph clock enable for port
RCC_APBxPeriphClockCmd(CC25XX_GDO2_GPIO_CLK_RCC, CC25XX_GDO2_GPIO_CLK, ENABLE);
// configure GDO2 pin as Input floating
gpio_init.GPIO_Pin = CC25XX_GDO2_PIN;
gpio_init.GPIO_Mode = GPIO_Mode_IN_FLOATING;
GPIO_Init(CC25XX_GDO2_GPIO, &gpio_init);
}
inline uint32_t hal_cc25xx_set_antenna(uint8_t id) {
// select antenna 0 or 1:
if (id) {
CC25XX_ANT_SW_CTX_GPIO->BRR = (CC25XX_ANT_SW_CTX_PIN); // 0
CC25XX_ANT_SW_CRX_GPIO->BSRR = (CC25XX_ANT_SW_CRX_PIN); // 1
} else {
CC25XX_ANT_SW_CTX_GPIO->BSRR = (CC25XX_ANT_SW_CTX_PIN); // 1
CC25XX_ANT_SW_CRX_GPIO->BRR = (CC25XX_ANT_SW_CRX_PIN); // 0
}
return id;
}
inline void hal_cc25xx_set_gdo_mode(void) {
cc25xx_set_register(IOCFG0, 0x01); // 6);
// cc25xx_set_register(IOCFG1, ???);
cc25xx_set_register(IOCFG2, 0x01); // 6);
}
inline void hal_cc25xx_set_register(uint8_t address, uint8_t data) {
// select device
hal_spi_csn_lo();
// wait for ready signal
while (GPIO_ReadInputDataBit(CC25XX_SPI_GPIO, CC25XX_SPI_MISO_PIN) == 1) {}
hal_spi_tx(address);
hal_spi_tx(data);
// deslect
hal_spi_csn_hi();
}
inline uint8_t hal_cc25xx_get_register(uint8_t address) {
uint8_t result;
// select device:
hal_spi_csn_lo();
// wait for RDY signal:
while (GPIO_ReadInputDataBit(CC25XX_SPI_GPIO, CC25XX_SPI_MISO_PIN) == 1) {}
// request address (read request has bit7 set)
uint8_t status = hal_spi_tx(address | 0x80);
// debug_put_hex8(status);
// fetch result:
result = hal_spi_rx();
// deselect device
hal_spi_csn_hi();
// return result
return(result);
}
inline void hal_cc25xx_strobe(uint8_t address) {
hal_spi_csn_lo();
uint8_t status = hal_spi_tx(address);
// debug("s"); debug_put_hex8(status); debug_put_newline();
hal_spi_csn_hi();
}
inline uint8_t hal_cc25xx_get_status(void) {
hal_spi_csn_lo();
uint8_t status = hal_spi_tx(0xFF);
hal_spi_csn_hi();
return status;
}
uint8_t hal_cc25xx_transmission_completed(void) {
// after tx cc25xx goes back to RX (configured by mcsm1 register)
return ((hal_cc25xx_get_status() & (0x70)) == CC2500_STATUS_STATE_RX);
}
inline void hal_cc25xx_enter_rxmode(void) {
// add pa/lna config bit setting here
CC25XX_LNA_SW_CRX_GPIO->BSRR = (CC25XX_LNA_SW_CRX_PIN); // 1
delay_us(20);
CC25XX_LNA_SW_CTX_GPIO->BRR = (CC25XX_LNA_SW_CTX_PIN); // 0
delay_us(5);
}
inline void hal_cc25xx_enter_txmode(void) {
// add pa/lna config bit setting here
CC25XX_LNA_SW_CRX_GPIO->BRR = (CC25XX_LNA_SW_CRX_PIN); // 0
delay_us(20);
CC25XX_LNA_SW_CTX_GPIO->BSRR = (CC25XX_LNA_SW_CTX_PIN); // 1
delay_us(5);
}
inline void hal_cc25xx_enable_receive(void) {
// switch on rx again
hal_cc25xx_enter_rxmode();
}
inline uint8_t hal_cc25xx_get_gdo_status(void) {
if (GPIO_ReadInputDataBit(CC25XX_GDO2_GPIO, GPIO_Pin_3)) {
return 1;
} else {
return 0;
}
}
inline void hal_cc25xx_read_fifo(uint8_t *buf, uint8_t len) {
hal_cc25xx_register_read_multi(CC25XX_FIFO | READ_FLAG | BURST_FLAG, buf, len);
}
inline void hal_cc25xx_register_read_multi(uint8_t address, uint8_t *buffer, uint8_t len) {
// select device:
hal_spi_csn_lo();
// wait for ready signal
while (GPIO_ReadInputDataBit(CC25XX_SPI_GPIO, CC25XX_SPI_MISO_PIN) == 1) {}
// debug("read "); debug_put_uint8(len); debug_flush();
// request address (read request)
uint8_t status = hal_spi_tx(address);
// fill buffer with read commands:
memset(buffer, 0xFF, len);
hal_spi_dma_xfer(buffer, len);
/*
while (len--) {
*buf = hal_spi_rx();
buf++;
}*/
// deselect device
hal_spi_csn_hi();
}
inline void hal_cc25xx_register_write_multi(uint8_t address, uint8_t *buffer, uint8_t len) {
// s elect device:
hal_spi_csn_lo();
// wait for RDY signal:
while (GPIO_ReadInputDataBit(CC25XX_SPI_GPIO, CC25XX_SPI_MISO_PIN) == 1) {}
// request address (write request)
hal_spi_tx(address | BURST_FLAG);
// send array
hal_spi_dma_xfer(buffer, len);
// deselect device
hal_spi_csn_hi();
}
inline void hal_cc25xx_process_packet(volatile uint8_t *packet_received,
volatile uint8_t *buffer, uint8_t maxlen) {
if (hal_cc25xx_get_gdo_status() == 1) {
// data received, fetch data
// timeout_set_100us(5);
*packet_received = 0;
// there is a bug in the cc2500
// see p3 http:// www.ti.com/lit/er/swrz002e/swrz002e.pdf
// workaround: read len register very quickly twice:
uint8_t len1, len2, len, i;
// try this 10 times befor giving up:
for (i = 0; i < 10; i++) {
len1 = hal_cc25xx_get_register_burst(RXBYTES) & 0x7F;
len2 = hal_cc25xx_get_register_burst(RXBYTES) & 0x7F;
if (len1 == len2) break;
}
// valid len found?
if (len1 == len2) {
len = len1;
// packet received, grab data
uint8_t tmp_buffer[len];
hal_cc25xx_read_fifo(tmp_buffer, len);
// only accept valid packet lenbghts:
if (len == maxlen) {
uint8_t i;
for (i = 0; i < maxlen; i++) {
buffer[i] = tmp_buffer[i];
}
*packet_received = 1;
}
} else {
// no, ignore this
len = 0;
}
}
}
void hal_cc25xx_transmit_packet(volatile uint8_t *buffer, uint8_t len) {
// flush tx fifo
hal_cc25xx_strobe(RFST_SFTX);
// copy to fifo
hal_cc25xx_register_write_multi(CC25XX_FIFO, (uint8_t *)buffer, buffer[0]+1);
// and send!
hal_cc25xx_strobe(RFST_STX);
}

View File

@@ -0,0 +1,186 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_CC25XX_H__
#define HAL_CC25XX_H__
#include <stdint.h>
void hal_cc25xx_init(void);
void hal_cc25xx_set_register(uint8_t reg, uint8_t val);
uint8_t hal_cc25xx_get_register(uint8_t address);
void hal_cc25xx_strobe(uint8_t val);
void hal_cc25xx_enable_receive(void);
void hal_cc25xx_enable_transmit(void);
void hal_cc25xx_enter_rxmode(void);
void hal_cc25xx_enter_txmode(void);
#define hal_cc25xx_rx_sleep() { delay_us(1352); }
#define hal_cc25xx_tx_sleep() { delay_us(1250); }
// not used on d4rii
#define hal_cc25xx_disable_rf_interrupt() {}
#define hal_cc25xx_setup_rf_dma(mode) {}
#define hal_cc25xx_partnum_valid(p, v) ((p == 0x80) && (v = 0x03))
uint8_t hal_cc25xx_get_status(void);
static void hal_cc25xx_init_gpio(void);
uint32_t hal_cc25xx_set_antenna(uint8_t id);
void hal_cc25xx_set_gdo_mode(void);
uint8_t hal_cc25xx_get_gdo_status(void);
void hal_cc25xx_process_packet(volatile uint8_t *packet_received,
volatile uint8_t *buffer, uint8_t maxlen);
void hal_cc25xx_transmit_packet(volatile uint8_t *buffer, uint8_t len);
void hal_cc25xx_read_fifo(uint8_t *buf, uint8_t len);
void hal_cc25xx_register_read_multi(uint8_t address, uint8_t *buffer, uint8_t len);
uint8_t hal_cc25xx_transmission_completed(void);
// adress checks
#define CC2500_PKTCTRL1_FLAG_ADR_CHECK_00 ((0<<1) | (0<<0))
#define CC2500_PKTCTRL1_FLAG_ADR_CHECK_01 ((0<<1) | (1<<0))
#define CC2500_PKTCTRL1_FLAG_ADR_CHECK_10 ((1<<1) | (0<<0))
#define CC2500_PKTCTRL1_FLAG_ADR_CHECK_11 ((1<<1) | (1<<0))
// append status bytes?
#define CC2500_PKTCTRL1_APPEND_STATUS (1<<2)
// crc autoflush
#define CC2500_PKTCTRL1_CRC_AUTOFLUSH (1<<3)
// Flags
#define BURST_FLAG 0b01000000
#define WRITE_FLAG 0b00000000
#define READ_FLAG 0b10000000
// Definitions for burst/single access to registers
#define CC2500_WRITE_SINGLE 0x00
#define CC2500_WRITE_BURST 0x40
#define CC2500_READ_SINGLE 0x80
#define CC2500_READ_BURST 0xC0
#define CC2500_STATUS_STATE_IDLE (0<<4)
#define CC2500_STATUS_STATE_RX (1<<4)
#define CC2500_STATUS_STATE_TX (2<<4)
#define CC2500_STATUS_STATE_FSTXON (3<<4)
#define CC2500_STATUS_STATE_CALIBRATE (4<<4)
#define CC2500_STATUS_STATE_SETTLING (5<<4)
#define CC2500_STATUS_STATE_RXFIFO_OVF (6<<4)
#define CC2500_STATUS_STATE_TXFIFO_OVF (7<<4)
#define hal_cc25xx_get_register_burst(x) hal_cc25xx_get_register(x | READ_FLAG | BURST_FLAG)
// strobes
#define RFST_SRES 0x30
#define RFST_SFSTXON 0x31
#define RFST_SXOFF 0x32
#define RFST_SCAL 0x33
#define RFST_SRX 0x34
#define RFST_STX 0x35
#define RFST_SIDLE 0x36
#define RFST_SWOR 0x38
#define RFST_SPWD 0x39
#define RFST_SFRX 0x3A
#define RFST_SFTX 0x3B
#define RFST_SWORRST 0x3C
#define RFST_SNOP 0x3D
// Status registers
#define PARTNUM 0x30|BURST_FLAG
#define VERSION 0x31|BURST_FLAG
#define FREQEST 0x32|BURST_FLAG
#define LQI 0x33|BURST_FLAG
#define RSSI 0x34|BURST_FLAG
#define MARCSTATE 0x35|BURST_FLAG
#define WORTIME1 0x36|BURST_FLAG
#define WORTIME0 0x37|BURST_FLAG
#define PKTSTATUS 0x38|BURST_FLAG
#define VCO_VC_DAC 0x39|BURST_FLAG
#define TXBYTES 0x3A|BURST_FLAG
#define RXBYTES 0x3B|BURST_FLAG
#define RCCTRL1_STATUS 0x3C|BURST_FLAG
#define RCCTRL0_STATUS 0x3D|BURST_FLAG
// Status byte states
#define STB_IDLE 0x00
#define STB_RX 0x10
#define STB_TX 0x20
#define STB_FSTXON 0x30
#define STB_CALIBRATE 0x40
#define STB_SETTLING 0x50
#define STB_RX_OVF 0x60
#define STB_TX_UNDF 0x70
// Config registers addresses
#define IOCFG2 0x00
#define IOCFG1 0x01
#define IOCFG0 0x02
#define FIFOTHR 0x03
#define SYNC1 0x04
#define SYNC0 0x05
#define PKTLEN 0x06
#define PKTCTRL1 0x07
#define PKTCTRL0 0x08
#define ADDR 0x09
#define CHANNR 0x0A
#define FSCTRL1 0x0B
#define FSCTRL0 0x0C
#define FREQ2 0x0D
#define FREQ1 0x0E
#define FREQ0 0x0F
#define MDMCFG4 0x10
#define MDMCFG3 0x11
#define MDMCFG2 0x12
#define MDMCFG1 0x13
#define MDMCFG0 0x14
#define DEVIATN 0x15
#define MCSM2 0x16
#define MCSM1 0x17
#define MCSM0 0x18
#define FOCCFG 0x19
#define BSCFG 0x1A
#define AGCCTRL2 0x1B
#define AGCCTRL1 0x1C
#define AGCCTRL0 0x1D
#define WOREVT1 0x1E
#define WOREVT0 0x1F
#define WORCTRL 0x20
#define FREND1 0x21
#define FREND0 0x22
#define FSCAL3 0x23
#define FSCAL2 0x24
#define FSCAL1 0x25
#define FSCAL0 0x26
#define RCCTRL1 0x27
#define RCCTRL0 0x28
#define FSTEST 0x29
#define PTEST 0x2A
#define AGCTEST 0x2B
#define TEST2 0x2C
#define TEST1 0x2D
#define TEST0 0x2E
#define PA_TABLE0 0x3E
// FIFO
#define CC25XX_FIFO 0x3F
#endif // HAL_CC25XX_H_

View File

@@ -0,0 +1,22 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_clocksource.h"
// nothing to do here

View File

@@ -0,0 +1,26 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_CLOCKSOURCE_H_
#define HAL_CLOCKSOURCE_H_
// not necessary for stm32, it is done in system startup
#define hal_clocksource_init() {}
#endif // HAL_CLOCKSOURCE_H_

View File

@@ -0,0 +1,108 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_uart.h"
#include "stm32f10x_rcc.h"
#include "stm32f10x_usart.h"
#include "misc.h" // this is actually a stm32 include (nvic stuff)
#include "debug.h"
#include "led.h"
volatile uint8_t hal_debug_txe_is_on;
void hal_debug_init(void) {
hal_debug_txe_is_on = 0;
hal_debug_init_nvic(0);
hal_debug_init_rcc();
hal_debug_init_gpio();
hal_debug_init_mode();
hal_debug_enable();
}
void hal_debug_init_nvic(uint8_t enable) {
// enable interrupts
NVIC_InitTypeDef nvic_init;
// configure the NVIC Preemption Priority Bits
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_0);
// enable the USART interrupt
nvic_init.NVIC_IRQChannel = DEBUG_USART_IRQn;
nvic_init.NVIC_IRQChannelPreemptionPriority = NVIC_PRIO_DEBUG_UART;
nvic_init.NVIC_IRQChannelSubPriority = 0;
nvic_init.NVIC_IRQChannelCmd = enable ? ENABLE : DISABLE;
NVIC_Init(&nvic_init);
}
static void hal_debug_init_mode(void) {
USART_InitTypeDef uart_init;
// USART configuration:
// 115200 baud, 8N1
// no hw flow control
uart_init.USART_BaudRate = 115200;
uart_init.USART_WordLength = USART_WordLength_8b;
uart_init.USART_StopBits = USART_StopBits_1;
uart_init.USART_Parity = USART_Parity_No;
uart_init.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
uart_init.USART_Mode = USART_Mode_Tx;
USART_Init(DEBUG_USART, &uart_init);
}
static void hal_debug_enable(void) {
// enable uart
USART_Cmd(DEBUG_USART, ENABLE);
}
void hal_debug_start_transmission(uint8_t ch) {
// enable TXE int
USART_ITConfig(DEBUG_USART, USART_IT_TXE, ENABLE);
hal_debug_txe_is_on = 1;
// send first byte
USART_SendData(DEBUG_USART, ch);
}
uint8_t hal_debug_int_enabled(void) {
// is the txe int enabled?
return hal_debug_txe_is_on;
}
static void hal_debug_init_gpio(void) {
GPIO_InitTypeDef gpio_init;
// Configure USART TX as alternate function push-pull
gpio_init.GPIO_Pin = DEBUG_USART_TX_PIN;
gpio_init.GPIO_Speed = GPIO_Speed_50MHz;
gpio_init.GPIO_Mode = GPIO_Mode_AF_PP;
GPIO_Init(DEBUG_USART_GPIO, &gpio_init);
}
static void hal_debug_init_rcc(void) {
// configure clocks for uart:
// enable GPIO clock
RCC_APBxPeriphClockCmd(DEBUG_USART_GPIO_CLK_RCC,
DEBUG_USART_GPIO_CLK | RCC_APB2Periph_AFIO, ENABLE);
// enable USART clock
RCC_APBxPeriphClockCmd(DEBUG_USART_CLK_RCC, DEBUG_USART_CLK, ENABLE);
}

View File

@@ -0,0 +1,53 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_DEBUG_H_
#define HAL_DEBUG_H_
#include "stm32f10x_gpio.h"
#include "stm32f10x_usart.h"
#include "config.h"
#include "hal_uart.h"
extern volatile uint8_t hal_debug_txe_is_on;
void hal_debug_init(void);
void hal_debug_start_transmission(uint8_t ch);
#define hal_debug_int_enable() { hal_debug_init_nvic(1); }
#define hal_debug_int_disable() { hal_debug_init_nvic(0); }
uint8_t hal_debug_int_enabled(void);
void hal_debug_init_nvic(uint8_t enable);
static void hal_debug_init_rcc(void);
static void hal_debug_init_gpio(void);
static void hal_debug_init_mode(void);
static void hal_debug_enable(void);
#define DEBUG_ISR(void) DEBUG_USART_IRQHANDLER(void)
#define HAL_DEBUG_ISR_FLAG_SET() (USART_GetITStatus(DEBUG_USART, USART_IT_TXE) != RESET)
#define HAL_DEBUG_ISR_CLEAR_FLAG() { }
#define HAL_DEBUG_ISR_DISABLE() {\
USART_ITConfig(DEBUG_USART, USART_IT_TXE, DISABLE); hal_debug_txe_is_on = 0; }
#define HAL_DEBUG_TX_DATA(data) {\
USART_SendData(DEBUG_USART, data); }
#endif // HAL_DEBUG_H_

View File

@@ -0,0 +1,16 @@
#ifndef __HAL_DEFINES_H__
#define __HAL_DEFINES_H__
#include "stm32f10x_rcc.h"
#define EXTERNAL_MEMORY
#define EXTERNAL_DATA
// auto selector for APB1/APB2:
#define RCC_APBxPeriphClockCmd(rcc, p, s) { if (rcc == 1) { RCC_APB1PeriphClockCmd(p,s); } else { RCC_APB2PeriphClockCmd(p, s); } }
#define RCC_APBxPeriphResetCmd(rcc, p, s) { if (rcc == 1) { RCC_APB1PeriphResetCmd(p,s); } else { RCC_APB2PeriphResetCmd(p, s); } }
#define LO(w) (w & 0xFF)
#define HI(w) ((w>>8) & 0xFF)
#endif // __HAL_DEFINES_H__

View File

@@ -0,0 +1,36 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_delay.h"
inline void hal_delay_us(uint32_t us) {
// based on https:// github.com/leaflabs/libmaple
us *= 8;
// fudge for function call overhead
us--;
us--;
us--;
asm volatile(" mov r0, %[us] \n\t"
"1: subs r0, #1 \n\t"
" bhi 1b \n\t"
:
: [us] "r" (us)
: "r0");
}

View File

@@ -0,0 +1,29 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_DELAY_H_
#define HAL_DELAY_H_
#include "hal_timeout.h"
#define hal_delay_ms(ms) hal_timeout_delay_ms(ms)
void hal_delay_us(uint32_t us);
#endif // HAL_DELAY_H_

View File

@@ -0,0 +1,20 @@
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_dma.h"
// nothing to do here...

View File

@@ -0,0 +1,6 @@
#ifndef __HAL_DMA_H__
#define __HAL_DMA_H__
// NOTHING
#endif

View File

@@ -0,0 +1,54 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_io.h"
#include "hal_defines.h"
#include "config.h"
#include "led.h"
#include "stm32f10x_rcc.h"
#include "stm32f10x_gpio.h"
void hal_io_init(void) {
// configure bind io as input:
GPIO_InitTypeDef gpio_init;
// periph clock enable for port
RCC_APBxPeriphClockCmd(BIND_JUMPER_GPIO_CLK_RCC, BIND_JUMPER_GPIO_CLK, ENABLE);
// configure bind input as pullup
gpio_init.GPIO_Pin = BIND_JUMPER_PIN;
gpio_init.GPIO_Speed = GPIO_Speed_50MHz;
gpio_init.GPIO_Mode = GPIO_Mode_IPU;
GPIO_Init(BIND_JUMPER_GPIO, &gpio_init);
}
uint8_t hal_io_bind_request(void) {
// Returs pin state (1 if HIGH, 0 if LOW)
if (GPIO_ReadInputDataBit(BIND_JUMPER_GPIO, BIND_JUMPER_PIN)) {
// HIGH -> button not pressed
return 0;
} else {
// LOW -> button pressed
return 1;
}
}

View File

@@ -0,0 +1,28 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_IO_H_
#define HAL_IO_H_
#include <stdint.h>
void hal_io_init(void);
uint8_t hal_io_bind_request(void);
#endif // HAL_IO_H_

View File

@@ -0,0 +1,35 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_led.h"
#include "hal_defines.h"
#include "stm32f10x_rcc.h"
void hal_led_init(uint16_t pin) {
GPIO_InitTypeDef gpio_init;
// periph clock enable for port
RCC_APBxPeriphClockCmd(LED_GPIO_CLK_RCC, LED_GPIO_CLK, ENABLE);
// configure led output as push-pull
gpio_init.GPIO_Pin = pin;
gpio_init.GPIO_Speed = GPIO_Speed_50MHz;
gpio_init.GPIO_Mode = GPIO_Mode_Out_PP;
GPIO_Init(LED_GPIO, &gpio_init);
}

View File

@@ -0,0 +1,41 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_LED_H_
#define HAL_LED_H_
#include "stm32f10x_gpio.h"
#include "config.h"
void hal_led_init(uint16_t pin);
#define hal_led_green_init() { hal_led_init(LED_GREEN_PIN); }
#define hal_led_green_on() { LED_GPIO->BSRR = (LED_GREEN_PIN); }
#define hal_led_green_off() { LED_GPIO->BRR = (LED_GREEN_PIN); }
#define hal_led_green_toggle() { \
LED_GPIO->BSRR = (LED_GPIO->ODR ^ LED_GREEN_PIN) | (LED_GREEN_PIN << 16);}
#define hal_led_red_init() { hal_led_init(LED_RED_PIN); }
#define hal_led_red_on() { LED_GPIO->BSRR = (LED_RED_PIN); }
#define hal_led_red_off() { LED_GPIO->BRR = (LED_RED_PIN); }
#define hal_led_red_toggle() { \
LED_GPIO->BSRR = (LED_GPIO->ODR ^ LED_RED_PIN) | (LED_RED_PIN << 16);}
#endif // HAL_LED_H_

View File

@@ -0,0 +1,168 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_ppm.h"
#include "ppm.h"
#include "wdt.h"
#include "led.h"
#include "stm32f10x_rcc.h"
#include "stm32f10x_gpio.h"
#include "stm32f10x_tim.h"
#include "misc.h" // stm32 nvic stuff
#ifndef SBUS_ENABLED
void hal_ppm_init(void) {
hal_ppm_init_rcc();
hal_ppm_init_gpio();
hal_ppm_init_timer();
hal_ppm_init_nvic();
}
static void hal_ppm_init_rcc(void) {
// PCLK = HCLK set in system init...
// do not set it here...
// timer clock enable */
RCC_APBxPeriphClockCmd(PPM_TIMER_CLK_RCC, PPM_TIMER_CLK, ENABLE);
// gpio clock
RCC_APBxPeriphClockCmd(PPM_GPIO_CLK_RCC, PPM_GPIO_CLK, ENABLE);
// afio clk
RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE);
}
static void hal_ppm_init_gpio(void) {
GPIO_InitTypeDef gpio_init;
// activate AF for ppm gpio:
gpio_init.GPIO_Pin = PPM_PIN;
gpio_init.GPIO_Mode = GPIO_Mode_AF_PP;
gpio_init.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(PPM_GPIO, &gpio_init);
}
static void hal_ppm_init_timer(void) {
TIM_TimeBaseInitTypeDef tim_init;
TIM_OCInitTypeDef tim_oc_init;
TIM_TimeBaseStructInit(&tim_init);
// time base configuration: count to 1000us (will be set properly lateron)
tim_init.TIM_Period = HAL_PPM_US_TO_TICKCOUNT(1000);
// compute the prescaler value, we want a 0.5us resolution (= count with 2mhz):
tim_init.TIM_Prescaler = (uint16_t) (SystemCoreClock / 2000000) - 1;
tim_init.TIM_ClockDivision = 0;
tim_init.TIM_CounterMode = TIM_CounterMode_Up;
// set time base. NOTE: this will immediately trigger an INT!
TIM_TimeBaseInit(PPM_TIMER, &tim_init);
// clear IT flag (caused by TimeBaseInit()):
TIM_ClearITPendingBit(PPM_TIMER, TIM_IT_Update);
// Output Compare Active Mode configuration:
TIM_OCStructInit(&tim_oc_init);
#ifdef PPM_INVERTED
tim_oc_init.TIM_OCMode = TIM_OCMode_PWM2;
#else
tim_oc_init.TIM_OCMode = TIM_OCMode_PWM1;
#endif // PPM_INVERTED
tim_oc_init.TIM_OutputState = TIM_OutputState_Enable;
tim_oc_init.TIM_Pulse = PPM_SYNC_PULS_LEN_TICKS;
tim_oc_init.TIM_OCPolarity = TIM_OCPolarity_High;
hal_ppm_init_ocx(PPM_TIMER_CH, PPM_TIMER, &tim_oc_init);
// enable counter
TIM_Cmd(PPM_TIMER, ENABLE);
}
static void hal_ppm_init_nvic(void) {
NVIC_InitTypeDef nvic_init;
// strange, somehow the Timer IT Flags seem to be already enabled?!
TIM_ITConfig(PPM_TIMER, TIM_IT_Update, DISABLE);
TIM_ITConfig(PPM_TIMER, TIM_IT_Break, DISABLE);
TIM_ITConfig(PPM_TIMER, TIM_IT_CC1 | TIM_IT_CC2 | TIM_IT_CC3 | TIM_IT_CC4, DISABLE);
TIM_ITConfig(PPM_TIMER, TIM_IT_Trigger, DISABLE);
// enable timer interrupt
nvic_init.NVIC_IRQChannel = PPM_TIMER_IRQn;
nvic_init.NVIC_IRQChannelPreemptionPriority = NVIC_PRIO_PPM;
nvic_init.NVIC_IRQChannelSubPriority = 0;
nvic_init.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&nvic_init);
// enable ONLY update interrupt
TIM_ITConfig(PPM_TIMER, TIM_IT_Update, ENABLE);
}
void hal_ppm_failsafe_enter(void) {
// set output to static value ZERO
TIM_ITConfig(PPM_TIMER, TIM_IT_Update, DISABLE);
// set output to static low or high level:
GPIO_InitTypeDef gpio_init;
gpio_init.GPIO_Pin = PPM_PIN;
gpio_init.GPIO_Mode = GPIO_Mode_Out_PP;
gpio_init.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(PPM_GPIO, &gpio_init);
#if PPM_INVERTED
// clear on zero -> default is high
PPM_GPIO->BSRR = (PPM_PIN);
#else
// set on zero -> default is low
PPM_GPIO->BRR = (PPM_PIN);
#endif // PPM_INVERTED
}
void hal_ppm_failsafe_exit(void) {
// exit failsafe, back to pulse generation
hal_ppm_init_gpio();
// re-enable ppm output isr
TIM_ITConfig(PPM_TIMER, TIM_IT_Update, ENABLE);
}
static void hal_ppm_init_ocx(uint8_t ch, TIM_TypeDef *TIMx, TIM_OCInitTypeDef *tim_oc_init) {
switch (PPM_TIMER_CH) {
default:
break;
case(TIM_Channel_4):
TIM_OC4Init(TIMx, tim_oc_init);
TIM_OC4PreloadConfig(TIMx, TIM_OCPreload_Disable);
break;
case(TIM_Channel_3):
TIM_OC3Init(TIMx, tim_oc_init);
TIM_OC3PreloadConfig(TIMx, TIM_OCPreload_Disable);
break;
case(TIM_Channel_2):
TIM_OC2Init(TIMx, tim_oc_init);
TIM_OC2PreloadConfig(TIMx, TIM_OCPreload_Disable);
break;
case(TIM_Channel_1):
TIM_OC1Init(TIMx, tim_oc_init);
TIM_OC1PreloadConfig(TIMx, TIM_OCPreload_Disable);
break;
}
}
#endif // SBUS_ENABLED

View File

@@ -0,0 +1,53 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_PPM_H_
#define HAL_PPM_H_
#include "config.h"
#include "stm32f10x_tim.h"
void hal_ppm_init(void);
void hal_ppm_failsafe_exit(void);
void hal_ppm_failsafe_enter(void);
static void hal_ppm_init_rcc(void);
static void hal_ppm_init_gpio(void);
static void hal_ppm_init_timer(void);
static void hal_ppm_init_nvic(void);
static void hal_ppm_init_ocx(uint8_t ch, TIM_TypeDef *TIMx, TIM_OCInitTypeDef *tim_oc_init);
// counter runs with 2MHz = 0.5us resolution
#define HAL_PPM_US_TO_TICKCOUNT(us) ((us * 2)-1)
// from frsky to ticks coresponding to 1000...2000 us
// frsky seems to send us*1.5 (~1480...3020)
// -> divide by 1.5 (=*2/3) to get us -> multiply by 2 to get us
#define HAL_PPM_FRSKY_TO_TICKCOUNT(_frsky) ((_frsky)*2*2/3)
#define PPM_TIMER_ISR(void) PPM_TIMER_IRQHANDLER(void)
#define HAL_PPM_UPDATE_CCVALUE(x) { PPM_TIMER->ARR = x; }
#define HAL_PPM_ISR_DISABLE() { __disable_irq(); }
#define HAL_PPM_ISR_ENABLE() { __enable_irq(); }
#define HAL_PPM_ISR_FLAG_SET() (TIM_GetITStatus(PPM_TIMER, TIM_IT_Update) != RESET)
#define HAL_PPM_ISR_CLEAR_FLAG() { TIM_ClearITPendingBit(PPM_TIMER, TIM_IT_Update); }
#endif // HAL_PPM_H_

View File

@@ -0,0 +1,20 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_sbus.h"

View File

@@ -0,0 +1,26 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_SBUS_H_
#define HAL_SBUS_H_
// not used here
#define HAL_SBUS_PREPARE_DATA(a) (a)
#endif // HAL_SBUS_H_

View File

@@ -0,0 +1,190 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_soft_serial.h"
#include "debug.h"
#include "config.h"
#include "led.h"
#include "soft_serial.h"
#include "stm32f10x.h"
#include "stm32f10x_rcc.h"
#include "stm32f10x_gpio.h"
#include "stm32f10x_tim.h"
#include "misc.h" // stm32 nvic
#ifndef HUB_TELEMETRY_ON_SBUS_UART
void hal_soft_serial_init(void) {
hal_soft_serial_init_gpio();
hal_soft_serial_init_rcc();
hal_soft_serial_init_timer();
hal_soft_serial_init_nvic();
}
static void hal_soft_serial_init_rcc(void) {
// enable clocks
RCC_APBxPeriphClockCmd(SOFT_SERIAL_CLK_RCC, SOFT_SERIAL_CLK, ENABLE);
// timer clock enable
RCC_APBxPeriphClockCmd(SOFT_SERIAL_TIMER_CLK_RCC, SOFT_SERIAL_TIMER_CLK, ENABLE);
// release reset cmd (?)
RCC_APBxPeriphResetCmd(SOFT_SERIAL_TIMER_CLK_RCC, SOFT_SERIAL_TIMER_CLK, DISABLE);
}
static void hal_soft_serial_init_gpio(void) {
GPIO_InitTypeDef gpio_init;
// configure rx pin as input:
gpio_init.GPIO_Pin = SOFT_SERIAL_PIN;
gpio_init.GPIO_Speed = GPIO_Speed_50MHz;
gpio_init.GPIO_Mode = GPIO_Mode_IN_FLOATING;
GPIO_Init(SOFT_SERIAL_GPIO, &gpio_init);
}
static void hal_soft_serial_init_timer(void) {
TIM_TimeBaseInitTypeDef tim_init;
TIM_ICInitTypeDef tim_ic_init;
// time base configuration:
TIM_TimeBaseStructInit(&tim_init);
// this serial uart runs at 9600 baud, thus bitlength = 1/9600 = 104.166667 us
// a 1mhz counter gives us 1us resolution, a 24mhz counter gives us 1/24 us res
// the finer the better -> go for 24mhz counter = prescaler = 0 (:1)
tim_init.TIM_Prescaler = (uint16_t) (0);
// timer period = bit duration
tim_init.TIM_Period = 0xFFFF;
tim_init.TIM_ClockDivision = 0;
tim_init.TIM_CounterMode = TIM_CounterMode_Up;
// set time base. NOTE: this will immediately trigger an INT!
TIM_TimeBaseInit(SOFT_SERIAL_TIMER, &tim_init);
// clear IT flag (caused by TimeBaseInit()):
TIM_ClearITPendingBit(SOFT_SERIAL_TIMER, TIM_IT_Update);
TIM_ICStructInit(&tim_ic_init);
tim_ic_init.TIM_Channel = SOFT_SERIAL_TIMER_CH;
#ifdef HUB_TELEMETRY_INVERTED
#ifdef SOFT_SERIAL_PIN_HAS_INVERTER
// board has inverter -> invert twice = no inversion
tim_ic_init.TIM_ICPolarity = TIM_ICPolarity_Falling;
#else
tim_ic_init.TIM_ICPolarity = TIM_ICPolarity_Rising;
#endif // SOFT_SERIAL_PIN_HAS_INVERTER
#else
#ifdef SOFT_SERIAL_PIN_HAS_INVERTER
// board has inverter -> invert
tim_ic_init.TIM_ICPolarity = TIM_ICPolarity_Rising;
#else
tim_ic_init.TIM_ICPolarity = TIM_ICPolarity_Falling;
#endif // SOFT_SERIAL_PIN_HAS_INVERTER
#endif // HUB_TELEMETRY_INVERTED
tim_ic_init.TIM_ICSelection = TIM_ICSelection_DirectTI;
tim_ic_init.TIM_ICPrescaler = TIM_ICPSC_DIV1;
tim_ic_init.TIM_ICFilter = 0x0;
TIM_ICInit(SOFT_SERIAL_TIMER, &tim_ic_init);
TIM_ClearITPendingBit(SOFT_SERIAL_TIMER, SOFT_SERIAL_TIMER_IT_IC);
/*
// Output Compare Active Mode configuration:
TIM_OCStructInit(&tim_oc_init);
tim_oc_init.TIM_OCMode = TIM_OCMode_ disable;
tim_oc_init.TIM_OutputState = TIM_OutputState_ disable;
tim_oc_init.TIM_Pulse = PPM_SYNC_PULS_LEN_TICKS;
tim_oc_init.TIM_OCPolarity = TIM_OCPolarity_High;
hal_ppm_init_ocx(PPM_TIMER_CH, PPM_TIMER, &tim_oc_init);
*/
// enable counter
TIM_Cmd(SOFT_SERIAL_TIMER, ENABLE);
}
static void hal_soft_serial_init_nvic(void) {
NVIC_InitTypeDef nvic_init;
// strange, somehow the Timer IT Flags seem to be already enabled?!
TIM_ITConfig(SOFT_SERIAL_TIMER, TIM_IT_Update, DISABLE);
TIM_ITConfig(SOFT_SERIAL_TIMER, TIM_IT_Break, DISABLE);
TIM_ITConfig(SOFT_SERIAL_TIMER, TIM_IT_CC1 | TIM_IT_CC2 | TIM_IT_CC3 | TIM_IT_CC4, DISABLE);
TIM_ITConfig(SOFT_SERIAL_TIMER, TIM_IT_Trigger, DISABLE);
// enable input capture timer interrupt
nvic_init.NVIC_IRQChannel = SOFT_SERIAL_TIMER_IC_IRQn;
nvic_init.NVIC_IRQChannelPreemptionPriority = NVIC_PRIO_SOFT_SERIAL;
nvic_init.NVIC_IRQChannelSubPriority = 0;
nvic_init.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&nvic_init);
// enable update timer interrupt
nvic_init.NVIC_IRQChannel = SOFT_SERIAL_TIMER_UP_IRQn;
nvic_init.NVIC_IRQChannelPreemptionPriority = NVIC_PRIO_SOFT_SERIAL;
nvic_init.NVIC_IRQChannelSubPriority = 0;
nvic_init.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&nvic_init);
// for now enable ONLY the capture interrupt
TIM_ClearITPendingBit(SOFT_SERIAL_TIMER, SOFT_SERIAL_TIMER_IT_IC);
TIM_ITConfig(SOFT_SERIAL_TIMER, SOFT_SERIAL_TIMER_IT_IC, ENABLE);
}
void SOFT_SERIAL_TIMER_IC_IRQHandler(void) {
// handle startbit:
if (HAL_SOFT_SERIAL_IC_ISR_FLAG_SET()) {
// reset counter
TIM_SetCounter(SOFT_SERIAL_TIMER, 0);
// this is the startbit -> re synchronize the timer to this
// by setting the next cc interrupt to 1/2 bit length:
HAL_SOFT_SERIAL_UPDATE_TOP_VALUE(HAL_SOFTSERIAL_BIT_DURATION_TICKS / 2);
// disable IC interrupt (only compare match interrupts will trigger this isr)
HAL_SOFT_SERIAL_IC_ISR_DISABLE();
// enable overflow isr
HAL_SOFT_SERIAL_UP_ISR_ENABLE();
// clear flag - NOTE: this should never be done at the end of the isr!
HAL_SOFT_SERIAL_IC_ISR_FLAG_CLEAR();
// clear any pending update flags as well
HAL_SOFT_SERIAL_UP_ISR_FLAG_CLEAR();
// process
soft_serial_process_startbit();
}
}
void SOFT_SERIAL_TIMER_UP_IRQHandler(void) {
if (HAL_SOFT_SERIAL_UP_ISR_FLAG_SET()) {
// clear flag - NOTE: this should never be done at the end of the isr!
HAL_SOFT_SERIAL_UP_ISR_FLAG_CLEAR();
// re-arm for the next bit
HAL_SOFT_SERIAL_UPDATE_TOP_VALUE(HAL_SOFTSERIAL_BIT_DURATION_TICKS);
if (soft_serial_process_databit()) {
// finished transmission, disable UP and enable IC isr
HAL_SOFT_SERIAL_UP_ISR_DISABLE();
HAL_SOFT_SERIAL_IC_ISR_FLAG_CLEAR();
HAL_SOFT_SERIAL_IC_ISR_ENABLE();
}
}
}
#endif // if not HUB_TELEMETRY_ON_SBUS_UART

View File

@@ -0,0 +1,73 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_SOFT_SERIAL_H_
#define HAL_SOFT_SERIAL_H_
#include "config.h"
#include "soft_serial.h"
#include "stm32f10x_gpio.h"
// at 9600 baud a bit duration is 1/9600s = 104.166667us
// the counter counts in 1/24th of us -> 104.1667us * 24 =
#define HAL_SOFTSERIAL_BIT_DURATION_TICKS 2500
void hal_soft_serial_init(void);
static void hal_soft_serial_init_rcc(void);
static void hal_soft_serial_init_gpio(void);
static void hal_soft_serial_init_timer(void);
static void hal_soft_serial_init_nvic(void);
#define HUB_TELEMETRY_PIN_LO_RAW() (GPIO_ReadInputDataBit(SOFT_SERIAL_GPIO, SOFT_SERIAL_PIN) == 0)
#define HUB_TELEMETRY_PIN_HI_RAW() (!HUB_TELEMETRY_PIN_LO_RAW())
#ifdef SOFT_SERIAL_PIN_HAS_INVERTER
#define HUB_TELEMETRY_PIN_LO() HUB_TELEMETRY_PIN_HI_RAW()
#define HUB_TELEMETRY_PIN_HI() HUB_TELEMETRY_PIN_LO_RAW()
#else
#define HUB_TELEMETRY_PIN_LO() HUB_TELEMETRY_PIN_LO_RAW()
#define HUB_TELEMETRY_PIN_HI() HUB_TELEMETRY_PIN_HI_RAW()
#endif // SOFT_SERIAL_PIN_HAS_INVERTER
#define HAL_SOFT_SERIAL_IC_ISR_DISABLE() {\
TIM_ITConfig(SOFT_SERIAL_TIMER, SOFT_SERIAL_TIMER_IT_IC, DISABLE); }
#define HAL_SOFT_SERIAL_IC_ISR_ENABLE() {\
TIM_ITConfig(SOFT_SERIAL_TIMER, SOFT_SERIAL_TIMER_IT_IC, ENABLE); }
#define HAL_SOFT_SERIAL_IC_ISR_FLAG_SET() \
(TIM_GetITStatus(SOFT_SERIAL_TIMER, SOFT_SERIAL_TIMER_IT_IC) != RESET)
#define HAL_SOFT_SERIAL_IC_ISR_FLAG_CLEAR() {\
TIM_ClearITPendingBit(SOFT_SERIAL_TIMER, SOFT_SERIAL_TIMER_IT_IC); }
#define HAL_SOFT_SERIAL_UP_ISR_DISABLE() {\
TIM_ITConfig(SOFT_SERIAL_TIMER, SOFT_SERIAL_TIMER_IT_UP, DISABLE); }
#define HAL_SOFT_SERIAL_UP_ISR_ENABLE() {\
TIM_ITConfig(SOFT_SERIAL_TIMER, SOFT_SERIAL_TIMER_IT_UP, ENABLE); }
#define HAL_SOFT_SERIAL_UP_ISR_FLAG_SET() \
(TIM_GetITStatus(SOFT_SERIAL_TIMER, SOFT_SERIAL_TIMER_IT_UP) != RESET)
#define HAL_SOFT_SERIAL_UP_ISR_FLAG_CLEAR() {\
TIM_ClearITPendingBit(SOFT_SERIAL_TIMER, SOFT_SERIAL_TIMER_IT_UP); }
#define HAL_SOFT_SERIAL_UPDATE_TOP_VALUE(x) { SOFT_SERIAL_TIMER->ARR = x; }
void SOFT_SERIAL_TIMER_IC_IRQHandler(void);
void SOFT_SERIAL_TIMER_UP_IRQHandler(void);
#endif // HAL_SOFT_SERIAL_H_

View File

@@ -0,0 +1,194 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_spi.h"
#include "debug.h"
#include "led.h"
#include "config.h"
#include "stm32f10x_gpio.h"
#include "stm32f10x_spi.h"
#include "stm32f10x_rcc.h"
#include "stm32f10x_dma.h"
void hal_spi_init(void) {
hal_spi_init_rcc();
hal_spi_init_gpio();
hal_spi_init_mode();
hal_spi_init_dma();
hal_spi_enable();
}
static void hal_spi_init_rcc(void) {
// enable clocks
RCC_APB2PeriphClockCmd(CC25XX_SPI_GPIO_CLK | RCC_APB2Periph_AFIO, ENABLE);
RCC_APBxPeriphClockCmd(CC25XX_SPI_CLK_RCC, CC25XX_SPI_CLK, ENABLE);
}
static void hal_spi_enable(void) {
SPI_Cmd(CC25XX_SPI, ENABLE);
}
static void hal_spi_init_mode(void) {
SPI_InitTypeDef spi_init;
// mode config
spi_init.SPI_Direction = SPI_Direction_2Lines_FullDuplex;
spi_init.SPI_Mode = SPI_Mode_Master;
spi_init.SPI_DataSize = SPI_DataSize_8b;
spi_init.SPI_CPOL = SPI_CPOL_Low;
spi_init.SPI_CPHA = SPI_CPHA_1Edge;
spi_init.SPI_NSS = SPI_NSS_Soft;
spi_init.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8; // = 3 MHz
spi_init.SPI_FirstBit = SPI_FirstBit_MSB;
spi_init.SPI_CRCPolynomial = 7;
SPI_Init(CC25XX_SPI, &spi_init);
}
static void hal_spi_init_dma(void) {
DMA_InitTypeDef dma_init;
// Enable DMA1 Peripheral Clock
RCC_AHBPeriphClockCmd(CC25XX_SPI_DMA_CLOCK, ENABLE);
// Configure SPI RX Channel
dma_init.DMA_DIR = DMA_DIR_PeripheralSRC;
dma_init.DMA_PeripheralBaseAddr = (uint32_t)&CC25XX_SPI->DR;
dma_init.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
dma_init.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
dma_init.DMA_MemoryBaseAddr = 0; // will be set later
dma_init.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
dma_init.DMA_MemoryInc = DMA_MemoryInc_Enable;
dma_init.DMA_BufferSize = 1; // will be set later
dma_init.DMA_Mode = DMA_Mode_Normal;
dma_init.DMA_Priority = DMA_Priority_VeryHigh;
dma_init.DMA_M2M = DMA_M2M_Disable;
DMA_Init(CC25XX_SPI_RX_DMA_CHANNEL, &dma_init);
// configure SPI TX Channel
dma_init.DMA_DIR = DMA_DIR_PeripheralDST;
dma_init.DMA_PeripheralBaseAddr = (uint32_t)&CC25XX_SPI->DR;
dma_init.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
dma_init.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
dma_init.DMA_MemoryBaseAddr = 0; // will be set later
dma_init.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
dma_init.DMA_MemoryInc = DMA_MemoryInc_Enable;
dma_init.DMA_BufferSize = 1; // will be set later
dma_init.DMA_Mode = DMA_Mode_Normal;
dma_init.DMA_Priority = DMA_Priority_VeryHigh;
dma_init.DMA_M2M = DMA_M2M_Disable;
DMA_Init(CC25XX_SPI_TX_DMA_CHANNEL, &dma_init);
// start disabled
DMA_Cmd(CC25XX_SPI_TX_DMA_CHANNEL, DISABLE);
DMA_Cmd(CC25XX_SPI_RX_DMA_CHANNEL, DISABLE);
}
// data in buffer will be sent and will be overwritten with
// the data read back from the spi slave
void hal_spi_dma_xfer(uint8_t *buffer, uint8_t len) {
// debug("xfer "); debug_put_uint8(len); debug(")\n");
// TX: transfer buffer to slave
CC25XX_SPI_TX_DMA_CHANNEL->CMAR = (uint32_t)buffer;
CC25XX_SPI_TX_DMA_CHANNEL->CNDTR = len;
// RX: read back data from slave
CC25XX_SPI_RX_DMA_CHANNEL->CMAR = (uint32_t)buffer;
CC25XX_SPI_RX_DMA_CHANNEL->CNDTR = len;
// enable both dma
DMA_Cmd(CC25XX_SPI_RX_DMA_CHANNEL, ENABLE);
DMA_Cmd(CC25XX_SPI_TX_DMA_CHANNEL, ENABLE);
// debug("DMA EN\n"); debug_flush();
// trigger the SPI TX + RX dma
SPI_I2S_DMACmd(CC25XX_SPI, SPI_I2S_DMAReq_Rx | SPI_I2S_DMAReq_Tx, ENABLE);
// debug("TRIG\n"); debug_flush();
#if 0
// Wait until the command is sent to the DR
while (!DMA_GetFlagStatus(CC25XX_SPI_TX_DMA_TC_FLAG)) {}
// debug("ACTIVE\n"); debug_flush();
// wait for tx to be finished:
while (DMA_GetFlagStatus(CC25XX_SPI_TX_DMA_TC_FLAG)) {}
while (DMA_GetFlagStatus(CC25XX_SPI_RX_DMA_TC_FLAG)) {}
// wait for SPI to be no longer busy
while (SPI_I2S_GetFlagStatus(CC25XX_SPI, SPI_I2S_FLAG_BSY) != RESET) {}
// debug("!BUSY\n"); debug_flush();
#endif // 0
while (SPI_I2S_GetFlagStatus(CC25XX_SPI, SPI_I2S_FLAG_TXE) == RESET) {}
while (SPI_I2S_GetFlagStatus(CC25XX_SPI, SPI_I2S_FLAG_BSY) != RESET) {}
// while ((SPI1->SR & 2) == 0); // wait while TXE flag is 0 (TX is not empty)
// while ((SPI1->SR & (1 << 7)) != 0); // wait while BSY flag is 1 (SPI is busy)
// disable DMA
DMA_Cmd(CC25XX_SPI_RX_DMA_CHANNEL, DISABLE);
DMA_Cmd(CC25XX_SPI_TX_DMA_CHANNEL, DISABLE);
// clear DMA flags
SPI_I2S_DMACmd(CC25XX_SPI, SPI_I2S_DMAReq_Rx | SPI_I2S_DMAReq_Tx, DISABLE);
}
static void hal_spi_init_gpio(void) {
GPIO_InitTypeDef gpio_init;
// configure SCK and MOSI pins as Alternate Function Push-Pull
gpio_init.GPIO_Pin = CC25XX_SPI_SCK_PIN | CC25XX_SPI_MOSI_PIN;
gpio_init.GPIO_Speed = GPIO_Speed_50MHz;
gpio_init.GPIO_Mode = GPIO_Mode_AF_PP;
GPIO_Init(CC25XX_SPI_GPIO, &gpio_init);
// configure CSN as Push-Pull
gpio_init.GPIO_Pin = CC25XX_SPI_CSN_PIN;
gpio_init.GPIO_Speed = GPIO_Speed_50MHz;
gpio_init.GPIO_Mode = GPIO_Mode_Out_PP;
GPIO_Init(CC25XX_SPI_GPIO, &gpio_init);
// configure MISO pin as Input floating
gpio_init.GPIO_Pin = CC25XX_SPI_MISO_PIN;
gpio_init.GPIO_Mode = GPIO_Mode_IN_FLOATING;
GPIO_Init(CC25XX_SPI_GPIO, &gpio_init);
}
uint8_t hal_spi_tx(uint8_t address) {
// wait for SPI Tx buffer empty
while (SPI_I2S_GetFlagStatus(CC25XX_SPI, SPI_I2S_FLAG_TXE) == RESET) {}
// send SPI data
SPI_I2S_SendData(CC25XX_SPI, address);
// read response
while (SPI_I2S_GetFlagStatus(CC25XX_SPI, SPI_I2S_FLAG_RXNE) == RESET) {}
uint8_t result = SPI_I2S_ReceiveData(CC25XX_SPI);
return result;
}
uint8_t hal_spi_rx(void) {
return hal_spi_tx(0xff);
}

View File

@@ -0,0 +1,40 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_SPI_H_
#define HAL_SPI_H_
#include <stdint.h>
#include "config.h"
#include "delay.h"
void hal_spi_init(void);
static void hal_spi_init_gpio(void);
static void hal_spi_init_mode(void);
static void hal_spi_init_dma(void);
static void hal_spi_init_rcc(void);
static void hal_spi_enable(void);
void hal_spi_dma_xfer(uint8_t *buffer, uint8_t len);
#define hal_spi_csn_lo() { CC25XX_SPI_GPIO->BRR = (CC25XX_SPI_CSN_PIN); delay_us(1); }
#define hal_spi_csn_hi() { delay_us(1); CC25XX_SPI_GPIO->BSRR = (CC25XX_SPI_CSN_PIN); }
uint8_t hal_spi_tx(uint8_t address);
uint8_t hal_spi_rx(void);
uint8_t hal_spi_read_address(uint8_t address);
#endif // HAL_SPI_H_

View File

@@ -0,0 +1,485 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_storage.h"
#include "delay.h"
#include "debug.h"
#include "timeout.h"
#include "stm32f10x_i2c.h"
#include "stm32f10x_rcc.h"
#define HAL_STORAGE_I2C_DEBUG 1
#define EEPROM_I2C_TIMEOUT 20
#define EEPROM_I2C_FLAG_TIMEOUT 10
void hal_storage_init(void) {
hal_storage_init_i2c();
}
void hal_storage_write(uint8_t *buffer, uint16_t len) {
// verify write size
if (!hal_storage_check_len(len)) return;
// disable write protection
hal_storage_wp_disable();
delay_ms(1);
// execute write
if (!hal_storage_i2c_write_buffer(0, buffer, (uint8_t)len)) {
debug("hal_storage: ERROR! failed to write buffer\n");
debug_flush();
}
// re-enable write protection
delay_ms(1);
hal_storage_wp_enable();
}
void hal_storage_read(uint8_t *storage_ptr, uint16_t len) {
// verify read size
if (!hal_storage_check_len(len)) return;
if (!hal_storage_i2c_read_buffer(0, storage_ptr, (uint8_t)len)) {
debug("hal_storage: ERROR! failed to read buffer\n");
debug_flush();
}
}
static void hal_storage_init_i2c(void) {
// disable i2c:
I2C_Cmd(EEPROM_I2C, DISABLE);
I2C_DeInit(EEPROM_I2C);
hal_storage_init_i2c_rcc();
hal_storage_init_i2c_gpio();
}
static void hal_storage_init_i2c_rcc(void) {
// peripheral clock for i2c
RCC_APBxPeriphClockCmd(EEPROM_I2C_CLK_RCC, EEPROM_I2C_CLK, ENABLE);
// gpio clock
RCC_APBxPeriphClockCmd(EEPROM_GPIO_CLK_RCC, EEPROM_GPIO_CLK, ENABLE);
}
static void hal_storage_init_i2c_mode(void) {
I2C_InitTypeDef i2c_init;
i2c_init.I2C_Mode = I2C_Mode_I2C;
i2c_init.I2C_DutyCycle = I2C_DutyCycle_2;
i2c_init.I2C_OwnAddress1 = EEPROM_I2C_ADDRESS;
i2c_init.I2C_Ack = I2C_Ack_Enable;
i2c_init.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
i2c_init.I2C_ClockSpeed = 200000;
// apply I2C configuration
I2C_Init(EEPROM_I2C, &i2c_init);
// enable i2c
I2C_Cmd(EEPROM_I2C, ENABLE);
}
static void hal_storage_init_i2c_gpio(void) {
GPIO_InitTypeDef gpio_init;
uint8_t i;
// gpio init:
// reset i2c bus by setting clk as output and sending manual clock pulses
gpio_init.GPIO_Pin = EEPROM_I2C_SCL_PIN;
gpio_init.GPIO_Mode = GPIO_Mode_Out_OD;
gpio_init.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(EEPROM_GPIO, &gpio_init);
gpio_init.GPIO_Pin = EEPROM_I2C_SDA_PIN;
gpio_init.GPIO_Mode = GPIO_Mode_IN_FLOATING;
gpio_init.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(EEPROM_GPIO, &gpio_init);
if (1) {
debug("hal_storage: freeing i2c bus with clock train\n");
debug_flush();
// send 100khz clock train for some 100ms
timeout_set(100);
while (!timeout_timed_out()) {
if (GPIO_ReadInputDataBit(EEPROM_GPIO, EEPROM_I2C_SDA_PIN) == 1) {
debug("hal_storage: i2c free again\n");
break;
}
EEPROM_GPIO->BSRR = EEPROM_I2C_SCL_PIN;
delay_us(10);
EEPROM_GPIO->BRR = EEPROM_I2C_SCL_PIN;
delay_us(10);
}
// send stop condition:
gpio_init.GPIO_Pin = EEPROM_I2C_SDA_PIN;
gpio_init.GPIO_Mode = GPIO_Mode_Out_OD;
gpio_init.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(EEPROM_GPIO, &gpio_init);
// clock is low
EEPROM_GPIO->BRR = EEPROM_I2C_SCL_PIN;
delay_us(10);
// sda = lo
EEPROM_GPIO->BRR = EEPROM_I2C_SDA_PIN;
delay_us(10);
// clock goes high
EEPROM_GPIO->BSRR = EEPROM_I2C_SCL_PIN;
delay_us(10);
}
// init mode before setting to AF
hal_storage_init_i2c_mode();
// SDA & SCL
gpio_init.GPIO_Pin = EEPROM_I2C_SDA_PIN | EEPROM_I2C_SCL_PIN;
gpio_init.GPIO_Mode = GPIO_Mode_AF_OD;
gpio_init.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(EEPROM_GPIO, &gpio_init);
// WP = write protection
gpio_init.GPIO_Pin = EEPROM_WP_PIN;
gpio_init.GPIO_Mode = GPIO_Mode_Out_PP;
gpio_init.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_Init(EEPROM_GPIO, &gpio_init);
// WP = HI = protected
hal_storage_wp_enable();
}
static uint32_t hal_storage_check_len(uint16_t len) {
if (len > 255) {
debug("hal_storage: ERROR, invalid data len ");
debug_put_uint16(len);
debug(" (max is 255)!\n");
debug_flush();
// invalid
return 0;
} else {
// safe
return 1;
}
}
static uint32_t hal_storage_i2c_read_buffer(uint16_t address, uint8_t *buffer, uint8_t len) {
if (HAL_STORAGE_I2C_DEBUG) {
debug("hal_storage: i2c read_buffer(0x");
debug_put_hex8(address>>8);
debug_put_hex8(address&0xFF);
debug(", ..., ");
debug_put_uint16(len);
debug(")\n");
debug_flush();
}
timeout_set(EEPROM_I2C_TIMEOUT);
while (I2C_GetFlagStatus(EEPROM_I2C, I2C_FLAG_BUSY)) {
if (timeout_timed_out()) {
debug("hal_i2c: bus busy... timeout!\n");
return 0;
}
}
// send start
I2C_GenerateSTART(EEPROM_I2C, ENABLE);
// set on EV5 and clear it (cleared by reading SR1 then writing to DR)
timeout_set(EEPROM_I2C_FLAG_TIMEOUT);
while (!I2C_CheckEvent(EEPROM_I2C, I2C_EVENT_MASTER_MODE_SELECT)) {
if (timeout_timed_out()) {
debug("hal_i2c: master flag error... timeout!\n");
return 0;
}
}
// send EEPROM address for write
I2C_Send7bitAddress(EEPROM_I2C, EEPROM_I2C_ADDRESS, I2C_Direction_Transmitter);
// test on EV6 and clear it
timeout_set(EEPROM_I2C_FLAG_TIMEOUT);
while (!I2C_CheckEvent(EEPROM_I2C, I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED)) {
if (timeout_timed_out()) {
debug("hal_i2c: transmitter flag error... timeout!\n");
return 0;
}
}
// send the EEPROM's internal address to read from: Only one byte address
I2C_SendData(EEPROM_I2C, address);
// test on EV8 and clear it
timeout_set(EEPROM_I2C_FLAG_TIMEOUT);
while (!I2C_GetFlagStatus(EEPROM_I2C, I2C_FLAG_BTF) == RESET) {
if (timeout_timed_out()) {
debug("hal_i2c: btf flag error... timeout!\n");
return 0;
}
}
// send START condition a second time
I2C_GenerateSTART(EEPROM_I2C, ENABLE);
// set on EV5 and clear it (cleared by reading SR1 then writing to DR)
timeout_set(EEPROM_I2C_FLAG_TIMEOUT);
while (!I2C_CheckEvent(EEPROM_I2C, I2C_EVENT_MASTER_MODE_SELECT)) {
if (timeout_timed_out()) {
debug("hal_i2c: master flag error... timeout!\n");
return 0;
}
}
// send address (READ)
I2C_Send7bitAddress(EEPROM_I2C, EEPROM_I2C_ADDRESS, I2C_Direction_Receiver);
// test on EV6 and clear it
timeout_set(EEPROM_I2C_FLAG_TIMEOUT);
while (!I2C_CheckEvent(EEPROM_I2C, I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED)) {
if (timeout_timed_out()) {
debug("hal_i2c: receiver flag error... timeout!\n");
return 0;
}
}
if (HAL_STORAGE_I2C_DEBUG) {
debug("hal_storage: reading ");
debug_put_uint8(len);
debug("bytes: ");
debug_flush();
}
// do not use dma etc, we do not need highspeed. do polling:
uint16_t i;
for (i = 0; i < len; i++) {
// wait on ADDR flag to be set (ADDR is still not cleared at this level)
timeout_set(EEPROM_I2C_FLAG_TIMEOUT);
/* Test on EV7 and clear it */
while (!I2C_CheckEvent(EEPROM_I2C, I2C_EVENT_MASTER_BYTE_RECEIVED)) {
if (timeout_timed_out()) {
debug("hal_i2c: byte rx error... timeout!\n");
return 0;
}
}
// read byte received:
buffer[i] = I2C_ReceiveData(EEPROM_I2C);
if (HAL_STORAGE_I2C_DEBUG) {
debug_put_hex8(buffer[i]);
debug_putc(' ');
debug_flush();
}
if (i == (len-1)) {
// last byte? -> NACK
I2C_AcknowledgeConfig(EEPROM_I2C, DISABLE);
} else {
// more bytes -> ACK
I2C_AcknowledgeConfig(EEPROM_I2C, ENABLE);
}
// wait for read to finish
timeout_set(EEPROM_I2C_FLAG_TIMEOUT*100);
while (!I2C_CheckEvent(EEPROM_I2C, I2C_EVENT_SLAVE_BYTE_RECEIVED)) {
// while (I2C_GetFlagStatus(EEPROM_I2C, I2C_FLAG_RXNE) == RESET) {
if (timeout_timed_out()) {
debug("hal_i2c: read error... timeout!\n");
return 0;
}
}
}
// stop transmission
// clear ADDR register by reading SR1 then SR2 register (SR1 has already been read) */
(void)EEPROM_I2C->SR2;
// send STOP Condition
I2C_GenerateSTOP(EEPROM_I2C, ENABLE);
if (HAL_STORAGE_I2C_DEBUG) {
debug(". done.\n");
debug_flush();
}
// wait to make sure that STOP control bit has been cleared
timeout_set(EEPROM_I2C_FLAG_TIMEOUT);
while (EEPROM_I2C->CR1 & I2C_CR1_STOP) {
if (timeout_timed_out()) {
debug("hal_i2c: stop flag error... timeout!\n");
return 0;
}
}
// re-enable Acknowledgement to be ready for another reception
I2C_AcknowledgeConfig(EEPROM_I2C, ENABLE);
if (HAL_STORAGE_I2C_DEBUG) {
debug("hal_storage: read done\n");
debug_flush();
}
return 1;
}
static uint32_t hal_storage_i2c_write_buffer(uint8_t address, uint8_t *buffer, uint8_t len) {
if (HAL_STORAGE_I2C_DEBUG) {
debug("hal_storage: i2c write_buffer(0x");
debug_put_hex8(address>>8);
debug_put_hex8(address&0xFF);
debug(", ..., ");
debug_put_uint16(len);
debug(")\n");
debug_flush();
}
uint8_t i;
// check for out of bound condition
uint16_t last_byte = (uint16_t)address + (uint16_t) len;
if (last_byte > 255) {
debug("hal_storage: ERROR write request invalid. out of memory!\n");
debug_flush();
return 0;
}
// write data
for (i = 0; i < len; i++) {
if (!hal_storage_i2c_write_byte(address + i, buffer[i])) {
return 0;
}
}
return 1;
}
// single byte write is slow and ugly but will do
// we only use this once during binding...
static uint32_t hal_storage_i2c_write_byte(uint8_t address, uint8_t data) {
if (HAL_STORAGE_I2C_DEBUG) {
debug("hal_storage: i2c write_byte(0x");
debug_put_hex8(address>>8);
debug_put_hex8(address&0xFF);
debug(", 0x");
debug_put_hex8(data);
debug(")\n");
debug_flush();
}
timeout_set(EEPROM_I2C_TIMEOUT);
while (I2C_GetFlagStatus(EEPROM_I2C, I2C_FLAG_BUSY)) {
if (timeout_timed_out()) {
debug("hal_i2c: bus busy... timeout!\n");
return 0;
}
}
// send start
I2C_GenerateSTART(EEPROM_I2C, ENABLE);
// set on EV5 and clear it (cleared by reading SR1 then writing to DR)
timeout_set(EEPROM_I2C_FLAG_TIMEOUT);
while (!I2C_CheckEvent(EEPROM_I2C, I2C_EVENT_MASTER_MODE_SELECT)) {
if (timeout_timed_out()) {
debug("hal_i2c: master flag error... timeout!\n");
return 0;
}
}
// send EEPROM address for write
I2C_Send7bitAddress(EEPROM_I2C, EEPROM_I2C_ADDRESS, I2C_Direction_Transmitter);
// test on EV6 and clear it
timeout_set(EEPROM_I2C_FLAG_TIMEOUT);
while (!I2C_CheckEvent(EEPROM_I2C, I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED)) {
if (timeout_timed_out()) {
debug("hal_i2c: transmitter flag error... timeout!\n");
return 0;
}
}
// send the EEPROM's internal address to write to
I2C_SendData(EEPROM_I2C, address);
// test on EV8 and clear it
timeout_set(EEPROM_I2C_FLAG_TIMEOUT);
while (!I2C_CheckEvent(EEPROM_I2C, I2C_EVENT_MASTER_BYTE_TRANSMITTED)) {
if (timeout_timed_out()) {
debug("hal_i2c: address tx error... timeout!\n");
return 0;
}
}
// send data byte
I2C_SendData(EEPROM_I2C, data);
// test on EV8 and clear it
timeout_set(EEPROM_I2C_FLAG_TIMEOUT);
while (!I2C_CheckEvent(EEPROM_I2C, I2C_EVENT_MASTER_BYTE_TRANSMITTED)) {
if (timeout_timed_out()) {
debug("hal_i2c: data tx error... timeout!\n");
return 0;
}
}
// stop transmission
// clear ADDR register by reading SR1 then SR2 register (SR1 has already been read) */
(void)EEPROM_I2C->SR2;
// send STOP Condition
I2C_GenerateSTOP(EEPROM_I2C, ENABLE);
// wait to make sure that STOP control bit has been cleared
timeout_set(EEPROM_I2C_FLAG_TIMEOUT);
while (EEPROM_I2C->CR1 & I2C_CR1_STOP) {
if (timeout_timed_out()) {
debug("hal_i2c: stop flag error... timeout!\n");
return 0;
}
}
// wait for write cycle time (5ms)
delay_ms(5+1);
if (HAL_STORAGE_I2C_DEBUG) {
debug("hal_storage: write done\n");
debug_flush();
}
return 1;
}

View File

@@ -0,0 +1,45 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_STORAGE_H_
#define HAL_STORAGE_H_
#include <stdint.h>
#include "config.h"
#include "stm32f10x_gpio.h"
void hal_storage_init(void);
void hal_storage_write(uint8_t *buffer, uint16_t len);
void hal_storage_read(uint8_t *storage_ptr, uint16_t len);
static void hal_storage_init_i2c(void);
static void hal_storage_init_i2c_mode(void);
static void hal_storage_init_i2c_gpio(void);
static void hal_storage_init_i2c_rcc(void);
static uint32_t hal_storage_check_len(uint16_t len);
static uint32_t hal_storage_i2c_read_buffer(uint16_t address, uint8_t *buffer, uint8_t len);
static uint32_t hal_storage_i2c_write_buffer(uint8_t address, uint8_t *buffer, uint8_t len);
static uint32_t hal_storage_i2c_write_byte(uint8_t address, uint8_t data);
#define hal_storage_wp_enable() { EEPROM_GPIO->BSRR = EEPROM_WP_PIN; }
#define hal_storage_wp_disable() { EEPROM_GPIO->BRR = EEPROM_WP_PIN; }
#endif // HAL_STORAGE_H_

View File

@@ -0,0 +1,95 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#include "hal_timeout.h"
#include "debug.h"
#include "wdt.h"
volatile static __IO uint32_t hal_timeout_100us;
volatile static __IO uint32_t hal_timeout2_100us;
volatile static __IO uint32_t hal_timeout_100us_delay;
void hal_timeout_init(void) {
// configure 1ms sys tick:
if (SysTick_Config(SystemCoreClock / 10000)) {
debug("hal_timeout: failed to set systick timeout\n");
}
// set prio
NVIC_SetPriority(SysTick_IRQn, NVIC_PRIO_SYSTICK);
hal_timeout_100us = 0;
hal_timeout2_100us = 0;
hal_timeout_100us_delay = 0;
}
void hal_timeout_set_100us(__IO uint32_t hus) {
hal_timeout_100us = hus;
}
void hal_timeout2_set_100us(__IO uint32_t hus) {
hal_timeout2_100us = hus;
}
void hal_timeout_set(__IO uint32_t ms) {
hal_timeout_100us = 10*ms;
}
uint8_t hal_timeout_timed_out(void) {
// debug_put_uint16(hal_timeout_ms); debug("\n"); debug_flush();
return (hal_timeout_100us == 0);
}
uint8_t hal_timeout2_timed_out(void) {
// debug_put_uint16(hal_timeout_ms); debug("\n"); debug_flush();
return (hal_timeout2_100us == 0);
}
// seperate ms delay function
void hal_timeout_delay_ms(uint32_t timeout) {
hal_timeout_100us_delay = 10*timeout;
while (hal_timeout_100us_delay > 0) {
}
}
/*// seperate ms delay function
void hal_timeout_delay_100us(uint32_t timeout) {
hal_timeout_100us_delay = timeout;
while (hal_timeout_100us_delay > 0) {
}
}*/
void SysTick_Handler(void) {
if (hal_timeout_100us != 0) {
hal_timeout_100us--;
}
if (hal_timeout_100us_delay != 0) {
hal_timeout_100us_delay--;
}
if (hal_timeout2_100us != 0) {
hal_timeout2_100us--;
}
}
uint32_t hal_timeout_time_remaining(void) {
return hal_timeout_100us/10;
}

View File

@@ -0,0 +1,39 @@
/*
Copyright 2017 fishpepper <AT> gmail.com
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http:// www.gnu.org/licenses/>.
author: fishpepper <AT> gmail.com
*/
#ifndef HAL_TIMEOUT_H_
#define HAL_TIMEOUT_H_
#include "stm32f10x.h"
void hal_timeout_init(void);
void hal_timeout_set(__IO uint32_t ms);
void hal_timeout_set_100us(__IO uint32_t hus);
uint8_t hal_timeout_timed_out(void);
void hal_timeout_delay_ms(uint32_t timeout);
void hal_timeout2_set(__IO uint32_t ms);
void hal_timeout2_set_100us(__IO uint32_t hus);
uint8_t hal_timeout2_timed_out(void);
uint32_t hal_timeout_time_remaining(void);
void SysTick_Handler(void);
#endif // HAL_TIMEOUT_H_

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