Skip to content
Snippets Groups Projects

Compare revisions

Changes are shown as if the source revision was being merged into the target revision. Learn more about comparing revisions.

Source

Select target project
No results found

Target

Select target project
  • e-24/public/ahoi/firmware
1 result
Show changes
Showing
with 352 additions and 305 deletions
/**
* Copyright 2016-2020
* Copyright 2016-2023
*
* Bernd-Christian Renner, and
* Hamburg University of Technology (TUHH).
......@@ -38,6 +38,7 @@
#define FREQSETUP_H
#include "fixpoint.h"
#include "types.h"
#include <stdint.h>
#include <stdbool.h>
......@@ -60,56 +61,82 @@
#define FREQ_SFD_LEN 4
#define FREQ_SFD_SEQUENCE {1,0,0,1} // NOTE/TODO only "save" due to carrier changing? -> convert to data freqs
// sampling frequency when receiving
// allowed values for SAMPLING_FREQ
#define FREQ_200kHz 200000UL // all settings supported
// max. sampling frequency of device (in TX mode)
#ifndef SAMPLING_FREQ
# define SAMPLING_FREQ 200000 /* hertz */
# define SAMPLING_FREQ FREQ_200kHz
#endif
#define SAMPLING_CLK_DIV (PBA_SPEED / (2 * SAMPLING_FREQ))
#if SAMPLING_CLK_DIV * 2 * SAMPLING_FREQ != PBA_SPEED
#define SAMPLING_CLK_DIV (ADDA_TIMER_SPEED / (2 * SAMPLING_FREQ))
#if SAMPLING_CLK_DIV * 2 * SAMPLING_FREQ != ADDA_TIMER_SPEED
# error "cpu speed is not a multiple of sampling frequency"
#endif
// tx sending/sampling speed-up (vs. receiving sampling frequency)
// TODO better define a frequency here?
#ifndef TX_FACTOR
# define TX_FACTOR 1 // scaling for sending
// RX downscaling
#define RX_SAMPLING_DIV1 1
#define RX_SAMPLING_DIV2 2
#define RX_SAMPLING_DIV4 4
#ifndef RX_DOWNSAMPLE
# define RX_DOWNSAMPLE RX_SAMPLING_DIV1
#endif
// NOTE in order to unlock this feature, we must ensure that
// - FREQ_LIST is set up correctly
// - frequencies are chosen such that undersampling is possible (correct)
// - all occurances of timing and sample counts must be analyzed
/*
#if RX_DOWNSAMPLE != RX_SAMPLING_DIV1 && \
RX_DOWNSAMPLE != RX_SAMPLING_DIV2 && \
RX_DOWNSAMPLE != RX_SAMPLING_DIV4
*/
#if RX_DOWNSAMPLE != RX_SAMPLING_DIV1
# error "RX downsampling value not supported"
#endif
// sampling frequency when sending
#define TX_SAMPLING_CLK_DIV ((SAMPLING_CLK_DIV) / (TX_FACTOR))
#if TX_SAMPLING_CLK_DIV * TX_FACTOR != SAMPLING_CLK_DIV
# error "tx sampling frequency not a multiple of rx sampling frequency"
#define RX_SAMPLING_CLK_DIV ((SAMPLING_CLK_DIV) / (RX_DOWNSAMPLE))
#if RX_SAMPLING_CLK_DIV * RX_DOWNSAMPLE != SAMPLING_CLK_DIV
# error "RX sampling frequency not a multiple of sampling frequency"
#endif
#define SYNC_MOD_INDEX 1 // TODO only implemented for sending (do not change atm)
#define stringify(x) #x
#define RXFILE2(n, fs) stringify(freq-rx_48x_ ## n ## tap_ ## fs ## kHz.c)
#define RXFILE(n, fs) RXFILE2(n, fs)
#define TXFILE2(n, fs) stringify(freq-tx_48x_ ## n ## tap_ ## fs ## kHz.c)
#define TXFILE(n, fs) TXFILE2(n, fs)
#if SAMPLING_FREQ == 200000UL
#if SAMPLING_FREQ == FREQ_200kHz
# ifdef HIGHSPEED
# define FREQ_MSG "*** 200kHz, HIGHSPEED ***"
# define SAMPLES_PER_SYMBOL 256 // must be power of 2
# define TX_SAMPLES_PER_SYMBOL 256 // must be power of 2
# if RX_DOWNSAMPLE == RX_SAMPLING_DIV1
# define RX_SAMPLES_PER_SYMBOL 256
# elif RX_DOWNSAMPLE == RX_SAMPLING_DIV2
# define RX_SAMPLES_PER_SYMBOL 128
# elif RX_DOWNSAMPLE == RX_SAMPLING_DIV4
# define RX_SAMPLES_PER_SYMBOL 64
# endif
# else
# define FREQ_MSG "*** 200kHz ***"
# define SAMPLES_PER_SYMBOL 512 // must be power of 2
# define TX_SAMPLES_PER_SYMBOL 512 // must be power of 2
# if RX_DOWNSAMPLE == RX_SAMPLING_DIV1
# define RX_SAMPLES_PER_SYMBOL 512
# elif RX_DOWNSAMPLE == RX_SAMPLING_DIV2
# define RX_SAMPLES_PER_SYMBOL 256
# elif RX_DOWNSAMPLE == RX_SAMPLING_DIV4
# define RX_SAMPLES_PER_SYMBOL 128
# endif
# endif
# define FREQ_RX_LUT_FILE RXFILE(SAMPLES_PER_SYMBOL, 200)
# define FREQ_TX_LUT_FILE TXFILE(TX_SAMPLES_PER_SYMBOL, 200)
# define FREQ_RX_LUT_FILE RXFILE(RX_SAMPLES_PER_SYMBOL, 200)
#else
# error "RX sampling frequency not supported"
# error "sampling frequency not supported"
#endif
#if TX_FACTOR * SAMPLING_FREQ == 200000UL
# define FREQ_TX_LUT_FILE TXFILE(SAMPLES_PER_SYMBOL, 200)
# else
# error "TX sampling frequency not supported"
# endif
#define GAIN_LUT_FILE "gain_48x.c"
......@@ -124,15 +151,24 @@ enum {
TRANSDUCER_NUM
};
#define TRANSDUCER_DFLT TRANSDUCER_AS1
// only specify, unless not defined in config.mk
#ifndef TRANSDUCER_DFLT
# define TRANSDUCER_DFLT TRANSDUCER_AS1
#endif
// list all frequencies (NOTE these MUST match the actual
// implementation in the C-file)
#define FREQ_IDX(n) (n)
#ifdef INVERT_FREQBAND
# pragma message "using inverted frequency band"
# define FREQ_IDX(n) (FREQ_LIST_NUM-1-(n))
#else
# define FREQ_IDX(n) (n)
#endif
#define FREQ_LIST_NUM 49
#define SAMPLES_PER_SYMBOL_MASK (SAMPLES_PER_SYMBOL-1)
#define RX_SAMPLES_PER_SYMBOL_MASK (RX_SAMPLES_PER_SYMBOL-1)
extern const fp16_t * const FREQ_LIST[FREQ_LIST_NUM];
extern const fp16_t * const FREQ_TXLIST[FREQ_LIST_NUM];
......@@ -141,10 +177,10 @@ extern const fp16_t * const FREQ_TXLIST[FREQ_LIST_NUM];
#define SYNC_SEQ_NUM_MIN 2
#define SYNC_SEQ_NUM_MAX 8
#ifndef SYNC_SEQ_NUM_TX_DFLT
# define SYNC_SEQ_NUM_TX_DFLT 4
# define SYNC_SEQ_NUM_TX_DFLT 4
#endif
#ifndef SYNC_SEQ_NUM_RX_DFLT
# define SYNC_SEQ_NUM_RX_DFLT 3
# define SYNC_SEQ_NUM_RX_DFLT 3
#endif
#define SFD_SEQ_NUM_MAX (1 + (SYNC_SEQ_NUM_MAX - SYNC_SEQ_NUM_MIN))
......@@ -170,7 +206,7 @@ extern const fp16_t * const FREQ_TXLIST[FREQ_LIST_NUM];
#define SYNC_SYMBOLS_NUM_MAX (SYNC_SEQ_NUM_MAX * FREQ_SYNC_SEQ_LEN)
// rx signal threshold setup
#define SIGNAL_THRESHOLD_MAX (FP32_FROM_UINT(SAMPLES_PER_SYMBOL) / 2)
#define SIGNAL_THRESHOLD_MAX (FP32_FROM_UINT(RX_SAMPLES_PER_SYMBOL) / 2)
#define SIGNAL_THRESHOLD_DFLT (SIGNAL_THRESHOLD_MAX / 10) // 10%
//#define SIGNAL_THRESHOLD_DFLT (SIGNAL_THRESHOLD_MAX / 20) // 5%
//#define SIGNAL_THRESHOLD_DFLT (SIGNAL_THRESHOLD_MAX / 4) // 25%
......@@ -184,38 +220,32 @@ enum {
};
// minimum window size for peak detection during sync
//#define SIGNAL_WINDOW_SIZE (SAMPLES_PER_SYMBOL / 2)
#define SIGNAL_WINDOW_SIZE_MAX (SAMPLES_PER_SYMBOL / 4)
#define SIGNAL_WINDOW_SIZE_DFLT (SAMPLES_PER_SYMBOL / 8)
//#define SIGNAL_WINDOW_SIZE (RX_SAMPLES_PER_SYMBOL / 2)
#define SIGNAL_WINDOW_SIZE_MAX (RX_SAMPLES_PER_SYMBOL / 4)
#define SIGNAL_WINDOW_SIZE_DFLT (RX_SAMPLES_PER_SYMBOL / 8)
// NOTE should be at least SIGNAL_WINDOW_SIZE_MAX
#define SIGNAL_WINDOW_MAX_DELAY (SAMPLES_PER_SYMBOL / 4)
#define SIGNAL_WINDOW_MAX_DELAY (RX_SAMPLES_PER_SYMBOL / 4)
// turn-around times for mode switching
//#define TXRX_TURNAROUND_TICKS 250 // num samples needed for tx -> rx
//#define RXTX_TURNAROUND_TICKS 250 // num samples needed for rx -> tx
// time in milli seconds
// conversion between time and ticks
#define MS_TO_TICKS(t) (((t) * SAMPLING_FREQ) / 1000UL)
#define US_TO_TICKS(t) (((t) * SAMPLING_FREQ) / 1000000UL)
#define TICKS_TO_MS(t) (((t) * 1000UL) / SAMPLING_FREQ)
#define TICKS_TO_US(t) (((t) * 1000000ULL) / SAMPLING_FREQ)
#define TXRX_TURNAROUND_TICKS MS_TO_TICKS(12) // num samples needed for tx -> rx
#define RXTX_TURNAROUND_TICKS MS_TO_TICKS(12) // num samples needed for rx -> tx
#define MS_TO_RXCNT(t) (((t) * SAMPLING_FREQ + RX_DOWNSAMPLE/2) / (1000UL * RX_DOWNSAMPLE))
#define US_TO_RXCNT(t) (((t) * SAMPLING_FREQ + RX_DOWNSAMPLE/2) / (1000000UL * RX_DOWNSAMPLE))
#define RXCNT_TO_MS(t) (((t) * 1000UL * RX_DOWNSAMPLE) / SAMPLING_FREQ)
#define RXCNT_TO_US(t) (((t) * 1000000ULL * RX_DOWNSAMPLE) / SAMPLING_FREQ)
// FIXME move these to tx amp implementation?
// problem 1: above should be constant! ALWAYS, platform indep, or modems will not work with each other!
// problem 2: below depend on the actual hardware!
//#define SAMPLES_TXSWITCH_WAIT US_TO_TICKS(500)
//#define SAMPLES_TX_STABILIZE MS_TO_TICKS(4)
// timings for TX enable
#define TXON_SUPPLY_STABILIZE_NS MS_TO_TICKS(4) // time for supply to come up
// turn-around times for mode switching
#define TXRX_TURNAROUND_TICKS MS_TO_TICKS(12) // num ticks needed for tx -> rx
#define RXTX_TURNAROUND_TICKS MS_TO_TICKS(12) // num ticks needed for rx -> tx
// FIXME move these to tx amp implementation?
// timings for TX disable
#define TXOFF_OUTPUT_SETTLE_NS US_TO_TICKS(500) // time for amp output to settle after transmission
#define TXOFF_SWITCH_DELAY_NS US_TO_TICKS(500) // time to delay after switching hydrophone
#define TXOFF_OUTPUT_SETTLE_TICKS US_TO_TICKS(500) // time for amp output to settle after transmission
#define TXOFF_SWITCH_DELAY_TICKS US_TO_TICKS(500) // time to delay after switching hydrophone
/*
......@@ -273,7 +303,7 @@ freq_getNumSfdTries(void);
// frequency look-up tables for preamble / sync
// contains 2*SAMPLES_PER_SYMBOL values, where
// contains 2*RX_SAMPLES_PER_SYMBOL values, where
// - even indices are sine values
// - odd indices are cosine values
//extern const fp16_t * const FREQ_SYNC_SPACE[FREQ_SYNC_NUM_MAX];
......@@ -417,12 +447,12 @@ fp16_t
freq_getTxGainByIndex(uint8_t i);
uint16_t
rx_sample_cnt_t
freq_getSignalWindowSize(void);
void
freq_setSignalWindowSize(uint16_t newSize);
freq_setSignalWindowSize(rx_sample_cnt_t newSize);
// change transducer gain table; index h must be from TRANSDUCER_*
......
/**
* Copyright 2016-2018
* Copyright 2016-2023
*
* Bernd-Christian Renner, and
* Hamburg University of Technology (TUHH).
......@@ -85,8 +85,11 @@ filterraw_set(uint8_t stage, uint8_t ioval)
return true;
} else if (stage == FILTER_STAGE_AMP) {
stageValues[stage] = ioval;
return ad5245_send(RX_POTI_CMD_WRITE, ioval);
// FIXME ad5245 uses DMA to prevent rx problems when changing the gain!
// - dma is generally nice, but here this may cause problems
// if this command is called several times during AGC (inconsistent data)
stageValues[stage] = ioval; // FIXME this should only be set, if the call succeeds
return ad5245_send(AD5245_ADDR_0, AD5245_CMD_WRITE, ioval);
} else {
// must not occur
......@@ -130,5 +133,4 @@ void
filterraw_init(void)
{
// TODO init IO for switch connected to PC0
ad5245_init();
}
/**
* Copyright 2016-2018
* Copyright 2016-2023
*
* Bernd-Christian Renner, and
* Hamburg University of Technology (TUHH).
......@@ -63,7 +63,7 @@ rxamp_enable()
gpio_set(RXEN_PIN);
// wait for circuitry to come up
adda_wait(RX_ENABLE_TICKS);
adda_waitTimerTicks(RX_ENABLE_TICKS);
// gain IC may be switched off (depending on hardware option) during TX,
// so restore last setting; this is not necessary, if AGC is enabled
......
......@@ -37,7 +37,8 @@
#include "hal_txamp.h"
#include "txamp.h"
#include "hal_gpio.h"
#include "dev_mcp4551.h"
#include "hal_adda.h"
#include "dev_ad5245.h"
#pragma message "building BRIDGE TX AMP"
......@@ -46,19 +47,19 @@ const char * TXAMP_NAME = "tx-bridge";
// see circuit, amp connected to wiper and terminal A
// gain = (100 + 75 + (256-x)/256 * 10e3) / 10e3
static const uint16_t
static const uint8_t
TXGAIN[] = {
5, // 0dB
79, // -3dB
132, // -6dB
170, // -9dB
196, // -12dB
215, // -15dB
228, // -18dB
80, // -3dB
133, // -6dB
171, // -9dB
197, // -12dB
216, // -15dB
229, // -18dB
238, // -21dB
244, // -24dB
249, // -27dB
252 // -30dB
245, // -24dB
250, // -27dB
253 // -30dB
};
#define TXGAIN_DFLT 0
......@@ -81,23 +82,13 @@ txamp_init(void)
bool
txamp_setGainLevel(uint8_t lvl)
{
//bool ret;
if (lvl >= NUM_TXGAIN) {
return false;
}
// NOTE poti is only on, when TX board is active, so store value only
txLvl = lvl;
return true;
// TXB version 5 and above switch the poti off, when not active;
// hence, we can only send the new setting when TX is on.
//ret = mcp4561_send(POTI_CMD_WRITE_DATA, TXGAIN[lvl]);
//if (ret) {
// txLvl = lvl;
//}
//
//return ret;
}
......@@ -115,25 +106,17 @@ txamp_getNumGainLevels(void)
}
uint16_t
txamp_getDacEnableNumSamples(void)
{
return 1;
}
const fp16_t *
txamp_getDacEnableSequence(void)
{
const static fp16_t seq[1] = { 0x0000 };
return seq;
}
void
txamp_enable()
{
gpio_set(TXEN_PIN);
// wait for 3V to come up
adda_waitTimerTicks(TX_ENABLE_TICKS);
// set txgain here (before switching the output), as poti is only on
// when TX is enabled
ad5245_send(AD5245_ADDR_1, AD5245_CMD_WRITE, TXGAIN[txLvl]);
}
......@@ -148,9 +131,6 @@ txamp_disable()
void
txamp_connectOutput()
{
// use volatile write here to prevent memory corruption of poti
mcp4551_send(MCP4551_CMD_WRITE_DATA, TXGAIN[txLvl]);
// only enable output, after gain has been set
gpio_set(TXRX_SW_PIN);
}
......
/**
* Copyright 2016-2018
* Copyright 2016-2023
*
* Bernd-Christian Renner, and
* Hamburg University of Technology (TUHH).
......@@ -37,7 +37,9 @@
#ifndef TX_AMP_H_
#define TX_AMP_H_
#include "dev_dac8830.h"
#include "dev_dac8830.h" // NOTE this is required to let mcu_adda.c use device-dependent constants
#include "freqsetup.h"
#define TX_ENABLE_TICKS MS_TO_TICKS(4) //!< time to power-up TX board (3V)
#endif /* TX_AMP_H_ */
/**
* Copyright 2016-2018
* Copyright 2016-2023
*
* Bernd-Christian Renner, and
* Hamburg University of Technology (TUHH).
......@@ -47,9 +47,7 @@ const char * TXAMP_NAME = "tx-single";
// check effective TX sampling frequency
// defined in makefile or freqsetup.h (default values)
#if TX_FACTOR * SAMPLING_FREQ == 150000UL
# include "lut/freq-sw_050kHz.c"
#elif TX_FACTOR * SAMPLING_FREQ == 200000UL
#if SAMPLING_FREQ == FREQ_200kHz
# include "lut/freq-sw_200kHz.c"
#else
# error "no DAC enable sequence available for TX sampling rate"
......@@ -86,20 +84,6 @@ txamp_getNumGainLevels(void)
}
uint16_t
txamp_getDacEnableNumSamples(void)
{
return SAMPLES_DAC_ENABLE;
}
const fp16_t *
txamp_getDacEnableSequence(void)
{
return DAC_TURNON_SIGNAL;
}
void
txamp_enable()
{
......
/**
* Copyright 2016-2018
* Copyright 2016-2023
*
* Bernd-Christian Renner, and
* Hamburg University of Technology (TUHH).
......@@ -40,36 +40,29 @@
#include "mcu_i2c.h"
#include "hal_debug.h"
#define AD5245_ADDR ((uint8_t)(0x2C)) //!< I2C slave address of the digital potentiometer (ad5245)
//!< I2C slave addresses of the digital potentiometer
enum {
AD5245_ADDR_0 = ((uint8_t)(0x2C)), // A0 tied to GND
AD5245_ADDR_1 = ((uint8_t)(0x2D)) // A1 tied to VDD
};
/**
* \defgroup ad5142_commands Commands for the digital potentiometer (ad5245)
* @{
*/
/// commands for the potentiometer (ad5245)
#define RX_POTI_CMD_MASK 0x60
#define AD5245_CMD_MASK 0x60
enum {
RX_POTI_CMD_WRITE = 0x00, ///< write data byte provided
RX_POTI_CMD_RESET = 0x40, ///< reset wiper to midscale
RX_POTI_CMD_SHUTDOWN = 0x20, ///< connect wiper to terminal B but retain wiper register
AD5245_CMD_WRITE = 0x00, ///< write data byte provided
AD5245_CMD_RESET = 0x40, ///< reset wiper to midscale
AD5245_CMD_SHUTDOWN = 0x20, ///< connect wiper to terminal B but retain wiper register
};
/** @} */
/**
* @brief initialisation of ad5245 - nothing to do at the moment
*
* @retval true if the initialisation was successful
*/
static inline bool
ad5245_init(void)
{
return true;
}
/**
* @brief send a command to the digital potentiometer (ad5245)
*
......@@ -83,7 +76,7 @@ ad5245_init(void)
__attribute__((__always_inline__))
#endif
static inline bool
ad5245_send(uint8_t cmd, uint8_t data)
ad5245_send(uint8_t dev, uint8_t cmd, uint8_t data)
{
// FIXME
// i2c is shared, so we must make sure that the call
......@@ -95,18 +88,14 @@ ad5245_send(uint8_t cmd, uint8_t data)
// filterio; however, an idle resource has to be signaled
// which means a split phase concept ... sounds
// complex to implement (and is specific to the M4/i2c)
// ASSERT(dev >= AD5245_ADDR_0 && dev <= AD5245_ADDR_1)
uint8_t temp[2];
temp[0] = cmd & RX_POTI_CMD_MASK;
temp[1] = data;
// NOTE dma is generally nice, but here this may cause problems
// if this command is called several times during AGC
if (i2c_transmitDMA(AD5245_ADDR, temp, 2)) {
//while (!(i2c_getTxStatus())) { /* busy wait */ }
return true;
} else {
return false;
}
uint8_t tmp[2];
tmp[0] = cmd & AD5245_CMD_MASK;
tmp[1] = data;
return i2c_transmitDMA(dev, tmp, 2);
}
......
/**
* Copyright 2016-2018
* Copyright 2016-2023
*
* Timo Kortbrae,
* Bernd-Christian Renner, and
......@@ -59,8 +59,8 @@ void
adda_activateTransmission(void);
/* read sampling time of latest retrieved sample (via getSample()) */
sample_time_t
adda_getSampleTime(void);
rx_sample_cnt_t
adda_getSampleCnt(void);
/* read a sample from SPI/DAC */
bool
......@@ -83,10 +83,10 @@ sample_time_t
adda_getTimerTicks(void);
sample_time_t
adda_getSampleLag(void);
adda_getRxSampleLagTicks(void);
// wait (block) for a time (in number of ticks)
void
adda_wait(sample_time_t dt);
adda_waitTimerTicks(sample_time_t dt);
#endif
/**
* Copyright 2016-2020
* Copyright 2016-2023
*
* Bernd-Christian Renner, and
* Hamburg University of Technology (TUHH).
......@@ -59,16 +59,8 @@ uint8_t
txamp_getNumGainLevels(void);
uint16_t
txamp_getDacEnableNumSamples(void);
const fp16_t *
txamp_getDacEnableSequence(void);
/*
* enable txamp circuitry and disconnect hydrophone from rxamp
* enable txamp circuitry, do not connect hydrophones to TXAMP
*/
void
txamp_enable(void);
......
/**
* Copyright 2016-2019
* Copyright 2016-2023
*
* Bernd-Christian Renner,
* Timo Kortbrae,
......@@ -85,7 +85,7 @@ static volatile sample_time_t timerTicks = 0;
// state of TX circuit
static bool txEnabled = false;
static sample_time_t sampleTime = 0;
static rx_sample_cnt_t sampleCnt = 0;
static void ISR_ADC(void);
static void ISR_DAC(void);
......@@ -118,7 +118,8 @@ writeDAC(uint16_t val)
static void
switchToDacISR(void)
{
timer_newFreq(TX_SAMPLING_CLK_DIV);
// TODO wait for next clock tick
timer_newFreq(SAMPLING_CLK_DIV);
// switch to DAC
irq_disable_global();
......@@ -131,7 +132,8 @@ switchToDacISR(void)
static void
switchToAdcISR(void)
{
timer_newFreq(SAMPLING_CLK_DIV);
// TODO wait for next clock tick
timer_newFreq(RX_SAMPLING_CLK_DIV);
// switch to DAC
irq_disable_global();
......@@ -144,7 +146,8 @@ switchToAdcISR(void)
static void
switchToTimerISR(void)
{
timer_newFreq(SAMPLING_CLK_DIV);
// TODO wait for next clock tick
timer_newFreq(RX_SAMPLING_CLK_DIV);
// switch to timer
irq_disable_global();
......@@ -158,10 +161,10 @@ switchToTimerISR(void)
* Public Functions *
******************************************************************************/
sample_time_t
adda_getSampleTime()
rx_sample_cnt_t
adda_getSampleCnt()
{
return sampleTime;
return sampleCnt;
}
......@@ -183,7 +186,7 @@ adda_getSample(fp16_t * sample)
agc_checkAction(timerTicks);
// retrieve sample from queue and increase sample timer
sampleTime++;
sampleCnt++;
*sample = (fp16_t)sq_get(&SQRX);
aci_sample_logSample(*sample); // fp16_t
return true;
......@@ -240,7 +243,7 @@ adda_activateSampling(void)
sample_time_t start = adda_getTimerTicks();
// NOTE simply wait and let DAC callback handle neutral output
adda_wait(TX_FACTOR * TXOFF_OUTPUT_SETTLE_NS);
adda_waitTimerTicks(TXOFF_OUTPUT_SETTLE_TICKS);
pin_debug_clear(DEBUG_PIN_3);
......@@ -251,13 +254,14 @@ adda_activateSampling(void)
// we therefore connect RX (and disconnect TX) before switching off TX
txamp_disconnectOutput();
// TODO verify this is in the right position now
// NOTE simply wait and let DAC callback handle neutral output
adda_waitTimerTicks(TXOFF_SWITCH_DELAY_TICKS);
// enable rx earlier to let supply come up!
// NOTE this will black execution for a few ms
// NOTE this will block execution for a few ms
rxamp_enable();
// NOTE simply wait and let DAC callback handle neutral output
adda_wait(TX_FACTOR * TXOFF_SWITCH_DELAY_NS);
pin_debug_set(DEBUG_PIN_3);
// disable send circuit
......@@ -265,16 +269,15 @@ adda_activateSampling(void)
txamp_disable();
// explicitly power-down DAC and switch to timer ISR
switchToTimerISR();
// TODO add power down function for DAC in HAL
switchToTimerISR();
spi_chipSelect(DAC_CHANNEL);
spi_transmit((void *)&SPI_TX_ShdnSample);
// wait remaining time
sample_time_t dt = adda_getTimerTicks() - start;
if (dt < TXRX_TURNAROUND_TICKS) {
adda_wait(TXRX_TURNAROUND_TICKS - dt);
adda_waitTimerTicks(TXRX_TURNAROUND_TICKS - dt);
}
} else {
txamp_disconnectOutput();
......@@ -308,24 +311,27 @@ adda_activateTransmission()
// track entry time
sample_time_t start = adda_getTimerTicks();
//startTransmit = false;
sq_init(&SQTX);
// switch to timer, no need to collect ADC samples any longer
switchToTimerISR();
// switch to DAC
spi_clockMode(TXAMP_SPI_MODE);
switchToDacISR();
// empty transmit queue (for samples)
sq_init(&SQTX);
// enable receive path
// power-up/down
rxamp_disable();
txamp_enable();
txamp_enable(); // NOTE blocking call!
// set marker directly after DAC init!
// set marker directly after enabling TX
txEnabled = true;
// switch to DAC
spi_clockMode(TXAMP_SPI_MODE);
switchToDacISR();
// wait remaining time
sample_time_t dt = adda_getTimerTicks() - start;
if (dt < RXTX_TURNAROUND_TICKS) {
adda_wait(RXTX_TURNAROUND_TICKS - dt);
adda_waitTimerTicks(RXTX_TURNAROUND_TICKS - dt);
}
// connect hydrophone to TX circuitry (and disconnect RX) after
......@@ -341,21 +347,21 @@ adda_activateTransmission()
sample_time_t
adda_getTimerTicks(void)
{
return timerTicks / TX_FACTOR;
return timerTicks;
}
sample_time_t
adda_getSampleLag(void)
adda_getRxSampleLagTicks(void)
{
return sq_size(&SQRX);
return sq_size(&SQRX) * RX_DOWNSAMPLE;
}
void
adda_wait(sample_time_t dt)
adda_waitTimerTicks(sample_time_t dt)
{
sample_time_t start;
......@@ -385,13 +391,12 @@ adda_wait(sample_time_t dt)
******************************************************************************/
/*! \brief no IO / simply count ticks; this is currently used for startup
* and may be used for state transitions in the future (rx <-> tx)
*/
INTERRUPT static void
ISR_TIMER(void)
{
timer_resetInterruptFlag();
timerTicks += TX_FACTOR;
timerTicks += RX_DOWNSAMPLE;
}
......@@ -405,7 +410,7 @@ ISR_ADC(void)
pin_debug_toggle(DEBUG_PIN_7);
// timer (slower rx speed)
timerTicks += TX_FACTOR;
timerTicks += RX_DOWNSAMPLE;
register fp16_t s;
s = fp16_scaledFromUint16(SPI_RX_Buf, RX_ADC_RESOLUTION);
......@@ -437,6 +442,10 @@ static void
INTERRUPT ISR_DAC(void)
{
timer_resetInterruptFlag();
// timer (faster tx speed)
timerTicks++;
// select chip
spi_chipSelect(DAC_CHANNEL);
......@@ -454,9 +463,6 @@ INTERRUPT ISR_DAC(void)
}
pin_debug_toggle(DEBUG_PIN_6);
}
// timer (faster tx speed)
timerTicks++;
}
......
/**
* Copyright 2016-2021
* Copyright 2016-2023
*
* Timo Kortbrae,
* Jan Heitmann,
......@@ -60,9 +60,19 @@
* \defgroup timer_config configuration for adc/dac and uart timer
* @{
*/
// TODO
// @180 MHz => 180000000 and 25
// @163.2 MHz => 163200000 and 25
// @153.6 MHz => 153600000 and 25 (too slow)
// @144 MHz => 144000000 and 15 or 25
// PLL and clock setup in initialize_hardware.c (so this is a lot of magic number stuff)
#define CPU_SPEED 180000000U // desired MCU speed
// #define CPU_SPEED 163200000U // desired MCU speed
// #define HSE_VALUE 16000000U // external crystal speed, defined in stm32f4xx_hal_conf.h
// ADDA_TIMER_SPEED must be divisible by 2*SAMPLING_FREQ (checked in freqsetup.h)
#define ADDA_TIMER_PRESCALER 25
#define CPU_SPEED 180000000
#define PBA_SPEED (CPU_SPEED / ADDA_TIMER_PRESCALER)
#define ADDA_TIMER_SPEED (CPU_SPEED / ADDA_TIMER_PRESCALER)
/** @} */
......@@ -83,6 +93,7 @@
#define MODEM_GPIO_8 (gpio_t){GPIOC, GPIO_PIN_8}
#define MODEM_GPIO_9 (gpio_t){GPIOC, GPIO_PIN_9}
#define MODEM_GPIO_10 (gpio_t){GPIOC, GPIO_PIN_10}
/** @} */
/**
......
#
# Copyright 2016-2020
# Copyright 2016-2023
#
# Timo Kortbrae,
# Jan Heitmann,
......@@ -109,10 +109,6 @@ CFLAGS += -DHSE_VALUE=16000000U
CFLAGS += -mcpu=cortex-m4 -mthumb -mfloat-abi=hard -mfpu=fpv4-sp-d16
# setup sampling rate for receiving (SAMPLING_FREQ) and sending (TX_FACTOR)
# supported combinations
CFLAGS += -DSAMPLING_FREQ=200000 -DTX_FACTOR=1
# linker setup
LINKER_SCRIPT = $(PRJ_PATH)/hal/mcu/stm32f4/lib/linker_scripts
......
/**
* Copyright 2016-2021
* Copyright 2016-2023
*
* Timo Kortbrae,
* Jan Heitmann,
......@@ -60,9 +60,19 @@
* \defgroup timer_config configuration for adc/dac and uart timer
* @{
*/
// TODO
// @180 MHz => 180000000 and 25
// @163.2 MHz => 163200000 and 25
// @153.6 MHz => 153600000 and 25 (too slow)
// @144 MHz => 144000000 and 15 or 25
// PLL and clock setup in initialize_hardware.c (so this is a lot of magic number stuff)
#define CPU_SPEED 180000000U // desired MCU speed
// #define CPU_SPEED 163200000U // desired MCU speed
// #define HSE_VALUE 16000000U // external crystal speed, defined in stm32f4xx_hal_conf.h
// ADDA_TIMER_SPEED must be divisible by 2*SAMPLING_FREQ (checked in freqsetup.h)
#define ADDA_TIMER_PRESCALER 25
#define CPU_SPEED 180000000
#define PBA_SPEED (CPU_SPEED / ADDA_TIMER_PRESCALER)
#define ADDA_TIMER_SPEED (CPU_SPEED / ADDA_TIMER_PRESCALER)
/** @} */
......@@ -83,6 +93,7 @@
#define MODEM_GPIO_8 (gpio_t){GPIOC, GPIO_PIN_8}
#define MODEM_GPIO_9 (gpio_t){GPIOC, GPIO_PIN_9}
#define MODEM_GPIO_10 (gpio_t){GPIOC, GPIO_PIN_10}
/** @} */
/**
......@@ -137,7 +148,7 @@
/**
* \defgroup spi_configuration SPI Configuration - Pins and DMA Streams
* \defgroup spi_configuration SPI Configuration - Pins, DMA Streams, IRQs
* @{
*/
......@@ -172,10 +183,60 @@
#define CFG_SPI_IRQn SPI2_IRQn
#define CFG_SPI_IRQHandler SPI2_IRQHandler
#define CFG_SPI_IRQn_PRIO 0, 0 // was 0, 1
/**
* \defgroup i2c_configuration I2C Configuration - Pins and IRQs
* @{
*/
/* Definition for I2C1 clock resources */
#define I2C1_CLK_ENABLE() __HAL_RCC_I2C1_CLK_ENABLE()
#define DMA1_CLK_ENABLE() __HAL_RCC_DMA1_CLK_ENABLE()
#define I2C1_SDA_GPIO_CLK_ENABLE() __HAL_RCC_GPIOB_CLK_ENABLE()
#define I2C1_SCL_GPIO_CLK_ENABLE() __HAL_RCC_GPIOB_CLK_ENABLE()
#define I2C1_FORCE_RESET() __HAL_RCC_I2C1_FORCE_RESET()
#define I2C1_RELEASE_RESET() __HAL_RCC_I2C1_RELEASE_RESET()
/* Definition for I2C1 Pins */
#define I2C1_SCL_PIN GPIO_PIN_6
#define I2C1_SCL_GPIO_PORT GPIOB
#define I2C1_SCL_AF GPIO_AF4_I2C1
#define I2C1_SDA_PIN GPIO_PIN_7
#define I2C1_SDA_GPIO_PORT GPIOB
#define I2C1_SDA_AF GPIO_AF4_I2C1
/* Definition for I2C1's DMA */
#define I2C1_TX_DMA_CHANNEL DMA_CHANNEL_1
#define I2C1_TX_DMA_STREAM DMA1_Stream7
#define I2C1_RX_DMA_CHANNEL DMA_CHANNEL_1
#define I2C1_RX_DMA_STREAM DMA1_Stream0
/* Definition for I2C1's DMA NVIC */
#define I2C1_DMA_TX_IRQn DMA1_Stream7_IRQn
#define I2C1_DMA_RX_IRQn DMA1_Stream0_IRQn
#define I2C1_DMA_TX_IRQHandler DMA1_Stream7_IRQHandler
#define I2C1_DMA_RX_IRQHandler DMA1_Stream0_IRQHandler
#define I2C1_DMA_TX_IRQn_PRIO 2, 1 // was 0, x
#define I2C1_DMA_RX_IRQn_PRIO 2, 0 // was 0, x
#define I2C1_ER_IRQn_PRIO 2, 1 // was 0, x
#define I2C1_EV_IRQn_PRIO 2, 2 // was 0, x
#define I2C_CLK_SPEED 400000 /* Hz */
#define I2C_TIMEOUT 1
//#define I2C_RXBUF_SIZE 256 //!< i2c rx buffer size
#define I2C_TXBUF_SIZE 256 //!< i2c tx buffer size
#define I2C_ADDRESS ((uint8_t)(0x2F << 1)) //!< shifted by one because bit 0 is W/R bit
/**
* \defgroup uart_configuration UART Configuration - Pins
* \defgroup uart_configuration UART Configuration - Pins and IRQs
* @{
*/
......@@ -194,6 +255,7 @@
#define CFG_USART_IRQn USART1_IRQn
#define CFG_USART_IRQHandler USART1_IRQHandler
#define CFG_USART_IRQn_PRIO 3, 0 // was 0, 0
#define UART_SEND_TIMEOUT 10000 //!< timeout for uart send function that doesn't use dma
#define UART_BAUD_RATE 115200 //!< baudrate of uart peripheral
......@@ -202,13 +264,30 @@
/**
* adc configurations
*/
#define CFG_ADC_INSTANCE ADC1
#define CFG_ADC_CHANNEL ADC_CHANNEL_8
#define CFG_ADC_CLK_ENABLE() __HAL_RCC_ADC1_CLK_ENABLE()
#define CFG_ADC_PIN GPIO_PIN_0
#define CFG_ADC_GPIO_PORT GPIOB
#define CFG_ADC_IRQn ADC_IRQn
#define CFG_ADC_IRQHandler ADC_IRQHandler
#define CFG_ADC_INSTANCE ADC1
#define CFG_ADC_CHANNEL ADC_CHANNEL_8
#define CFG_ADC_CLK_ENABLE() __HAL_RCC_ADC1_CLK_ENABLE()
#define CFG_ADC_PIN GPIO_PIN_0
#define CFG_ADC_GPIO_PORT GPIOB
#define CFG_ADC_IRQn ADC_IRQn
#define CFG_ADC_IRQHandler ADC_IRQHandler
#define CFG_ADC_IRQn_PRIO 9, 0 // was unset
/**
* sample timer configuration
*/
#define CFG_SAMPLETIME_IRQn TIM2_IRQn
//#define CFG_ADC_IRQHandler
#define CFG_SAMPLETIME_IRQn_PRIO 1, 0 // was unset
/**
* alive timer configuration
*/
#define CFG_ALIVE_IRQn TIM3_IRQn
//#define CFG_ADC_IRQHandler
#define CFG_ALIVE_IRQn_PRIO 9, 1 // was unset
/**
......
......@@ -173,22 +173,17 @@ SystemClock_Config(void)
RCC_OscInitTypeDef RCC_OscInitStruct;
#if defined(HSE_VALUE) && (HSE_VALUE != 0)
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
RCC_OscInitStruct.PLL.PLLM = (HSE_VALUE/1000000u); // HSE_VALUE has to be a multiple of 1 MHz
#else
// Use HSI and activate PLL with HSI as source.
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI;
RCC_OscInitStruct.HSIState = RCC_HSI_ON;
RCC_OscInitStruct.HSICalibrationValue = 16; // 16 is the average default value
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI;
RCC_OscInitStruct.PLL.PLLM = (HSI_VALUE/1000000u); // HSI_VALUE has to be a multiple of 1 MHz
#endif
RCC_OscInitStruct.PLL.PLLN = 360;
RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; // 180 MHz
RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSE;
RCC_OscInitStruct.HSEState = RCC_HSE_ON;
RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSE;
RCC_OscInitStruct.PLL.PLLM = (HSE_VALUE/1000000u); // HSE_VALUE has to be a multiple of 1 MHz
//RCC_OscInitStruct.PLL.PLLM = (HSE_VALUE/800000u); // HSE_VALUE has to be a multiple of 800 kHz
// PLLN clock must be in 50...432
RCC_OscInitStruct.PLL.PLLN = 360; // 2*180MHz / 1MHz
//RCC_OscInitStruct.PLL.PLLN = 408; // 2*163.2MHz / 800kHz // PLL clock, 50...432
//RCC_OscInitStruct.PLL.PLLN = 384; // 2*153.6MHz / 800kHz // PLL clock, 50...432
RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; // PLLN/PLLP = Clock frequency
RCC_OscInitStruct.PLL.PLLQ = 7; // necessary if e.g. usb would be used (not needed for this project)
RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; // activate pll
HAL_RCC_OscConfig(&RCC_OscInitStruct);
......
/**
* Copyright 2016-2020
* Copyright 2016-2023
*
* Bernd-Christian Renner, and
* Hamburg University of Technology (TUHH).
......@@ -656,6 +656,7 @@ SysTick_Handler(void)
// default implementation in case this gets activated somewhere
// deep in STM's HAL and stalls the program as a consequence,
// (@see Default_Handler above)
HAL_IncTick();
}
......
......@@ -105,10 +105,6 @@ CFLAGS += -DHSE_VALUE=16000000U
CFLAGS += -mcpu=cortex-m4 -mthumb -mfloat-abi=hard -mfpu=fpv4-sp-d16
# setup sampling rate for receiving (SAMPLING_FREQ) and sending (TX_FACTOR)
# supported combinations
CFLAGS += -DSAMPLING_FREQ=200000 -DTX_FACTOR=1
# linker setup
LINKER_SCRIPT = $(PRJ_PATH)/hal/mcu/stm32f4/lib/linker_scripts
......
......@@ -115,7 +115,7 @@ HAL_ADC_MspInit(ADC_HandleTypeDef *hadc)
HAL_GPIO_Init(CFG_ADC_GPIO_PORT, &GPIO_InitStruct);
HAL_NVIC_SetPriority(CFG_ADC_IRQn, 0, 1);
HAL_NVIC_SetPriority(CFG_ADC_IRQn, CFG_ADC_IRQn_PRIO);
HAL_NVIC_EnableIRQ(CFG_ADC_IRQn);
}
......
/**
* Copyright 2016-2019
* Copyright 2016-2023
*
* Timo Kortbrae,
* Jan Heitmann,
......@@ -44,6 +44,7 @@
*/
#include <stm32f4xx_hal.h>
#include <mcu_config.h>
#include <mcu_i2c.h>
......@@ -52,49 +53,7 @@
* Defines *
******************************************************************************/
/**
* \defgroup i2c_configuration I2C Configuration - Pins and DMA Streams
* @{
*/
/* Definition for I2C1 clock resources */
#define I2C1_CLK_ENABLE() __HAL_RCC_I2C1_CLK_ENABLE()
#define DMA1_CLK_ENABLE() __HAL_RCC_DMA1_CLK_ENABLE()
#define I2C1_SDA_GPIO_CLK_ENABLE() __HAL_RCC_GPIOB_CLK_ENABLE()
#define I2C1_SCL_GPIO_CLK_ENABLE() __HAL_RCC_GPIOB_CLK_ENABLE()
#define I2C1_FORCE_RESET() __HAL_RCC_I2C1_FORCE_RESET()
#define I2C1_RELEASE_RESET() __HAL_RCC_I2C1_RELEASE_RESET()
/* Definition for I2C1 Pins */
#define I2C1_SCL_PIN GPIO_PIN_6
#define I2C1_SCL_GPIO_PORT GPIOB
#define I2C1_SCL_AF GPIO_AF4_I2C1
#define I2C1_SDA_PIN GPIO_PIN_7
#define I2C1_SDA_GPIO_PORT GPIOB
#define I2C1_SDA_AF GPIO_AF4_I2C1
/* Definition for I2C1's DMA */
#define I2C1_TX_DMA_CHANNEL DMA_CHANNEL_1
#define I2C1_TX_DMA_STREAM DMA1_Stream7
#define I2C1_RX_DMA_CHANNEL DMA_CHANNEL_1
#define I2C1_RX_DMA_STREAM DMA1_Stream0
/* Definition for I2C1's DMA NVIC */
#define I2C1_DMA_TX_IRQn DMA1_Stream7_IRQn
#define I2C1_DMA_RX_IRQn DMA1_Stream0_IRQn
#define I2C1_DMA_TX_IRQHandler DMA1_Stream7_IRQHandler
#define I2C1_DMA_RX_IRQHandler DMA1_Stream0_IRQHandler
#define I2C_CLK_SPEED 400000
#define I2C_TIMEOUT 1
/** @} */
//#define I2C_RXBUF_SIZE 256 //!< i2c rx buffer size
#define I2C_TXBUF_SIZE 256 //!< i2c tx buffer size
#define I2C_ADDRESS ((uint8_t)(0x2F << 1)) //!< shifted by one because bit 0 is W/R bit
/******************************************************************************
* Variables & Declarations *
......@@ -251,21 +210,42 @@ i2c_receiveAddr(uint16_t slaveAddr, uint16_t memAddr, uint16_t memAddSize, uint8
* Callbacks *
******************************************************************************/
// ERROR VALUES
// #define HAL_I2C_ERROR_NONE ((uint32_t)0x00000000U) /*!< No error */
// #define HAL_I2C_ERROR_BERR ((uint32_t)0x00000001U) /*!< BERR error */
// #define HAL_I2C_ERROR_ARLO ((uint32_t)0x00000002U) /*!< ARLO error */
// #define HAL_I2C_ERROR_AF ((uint32_t)0x00000004U) /*!< AF error */
// #define HAL_I2C_ERROR_OVR ((uint32_t)0x00000008U) /*!< OVR error */
// #define HAL_I2C_ERROR_DMA ((uint32_t)0x00000010U) /*!< DMA transfer error */
// #define HAL_I2C_ERROR_TIMEOUT ((uint32_t)0x00000020U) /*!< Timeout Error */
// void HAL_I2C_MasterTxCpltCallback(I2C_HandleTypeDef *I2cHandle)
// {
// UNUSED(I2cHandle);
// txCompleted = true;
// }
// void HAL_I2C_MasterRxCpltCallback(I2C_HandleTypeDef *I2cHandle)
// {
// UNUSED(I2cHandle);
// rxCompleted = true;
// }
// void HAL_I2C_MemRxCpltCallback(I2C_HandleTypeDef *I2cHandle)
// {
// UNUSED(I2cHandle);
// rxCompleted = true;
// }
// __attribute__((used)) void
// HAL_I2C_ErrorCallback(I2C_HandleTypeDef * hi2c)
// {
// // I2cHandle->ErrorCode .. // see above
// UNUSED(hi2c);
// //pin_debug_set(DEBUG_PIN_1); // i2c debugging
// }
/******************************************************************************
......@@ -308,9 +288,9 @@ I2C1_DMA_TX_IRQHandler(void)
* Initialization of i2c and dma peripheral *
******************************************************************************/
void
HAL_I2C_MspInit(I2C_HandleTypeDef *hi2c)
{
void
HAL_I2C_MspInit(I2C_HandleTypeDef *hi2c)
{
static DMA_HandleTypeDef hdma_tx;
static DMA_HandleTypeDef hdma_rx;
......@@ -379,15 +359,15 @@ I2C1_DMA_TX_IRQHandler(void)
__HAL_LINKDMA(hi2c, hdmarx, hdma_rx);
// config NVIC for dma and i2c, enable IRQs
HAL_NVIC_SetPriority(I2C1_DMA_TX_IRQn, 0, 1);
HAL_NVIC_SetPriority(I2C1_DMA_TX_IRQn, I2C1_DMA_TX_IRQn_PRIO);
HAL_NVIC_EnableIRQ(I2C1_DMA_TX_IRQn);
HAL_NVIC_SetPriority(I2C1_DMA_RX_IRQn, 0, 0);
HAL_NVIC_SetPriority(I2C1_DMA_RX_IRQn, I2C1_DMA_RX_IRQn_PRIO);
HAL_NVIC_EnableIRQ(I2C1_DMA_RX_IRQn);
HAL_NVIC_SetPriority(I2C1_ER_IRQn, 0, 1);
HAL_NVIC_SetPriority(I2C1_ER_IRQn, I2C1_ER_IRQn_PRIO);
HAL_NVIC_EnableIRQ(I2C1_ER_IRQn);
HAL_NVIC_SetPriority(I2C1_EV_IRQn, 0, 2);
HAL_NVIC_SetPriority(I2C1_EV_IRQn, I2C1_EV_IRQn_PRIO);
HAL_NVIC_EnableIRQ(I2C1_EV_IRQn);
}
......
/**
* Copyright 2016-2021
* Copyright 2016-2023
*
* Timo Kortbrae,
* Jan Heitmann,
......@@ -46,6 +46,8 @@
#include <stdio.h>
#include <string.h>
#include "error.h"
#include <stm32f4xx_hal.h>
#include <mcu_spi.h>
#include <mcu_uart.h>
......@@ -101,7 +103,7 @@ spi_TxRx(uint8_t * rxPtr, uint8_t * txPtr)
{
spiHandle.pTxBuffPtr = (uint8_t *)txPtr;
spiHandle.pRxBuffPtr = (uint8_t *)rxPtr;
while((spiHandle.Instance->SR & SPI_FLAG_TXE) == RESET);
WAIT_TIMED((spiHandle.Instance->SR & SPI_FLAG_TXE) == RESET);
spiHandle.Instance->DR = *((uint16_t *)spiHandle.pTxBuffPtr);
__HAL_SPI_CLEAR_OVRFLAG(&spiHandle);
__HAL_SPI_ENABLE_IT(&spiHandle, (SPI_IT_RXNE));
......@@ -132,6 +134,7 @@ spi_init(void)
spiHandle.Instance = CFG_SPI_INSTANCE;
spiHandle.Init.Mode = SPI_MODE_MASTER;
spiHandle.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_4;
//spiHandle.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_2;
spiHandle.Init.Direction = SPI_DIRECTION_2LINES;
spiHandle.Init.CLKPhase = SPI_PHASE_1EDGE;
spiHandle.Init.CLKPolarity = SPI_POLARITY_HIGH;
......@@ -257,6 +260,6 @@ HAL_SPI_MspInit(SPI_HandleTypeDef *hspi)
GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_MEDIUM;//<- medium should be fast enough GPIO_SPEED_FAST;
HAL_GPIO_Init(CFG_SPI_MISO_GPIO_PORT, &GPIO_InitStruct);
HAL_NVIC_SetPriority(CFG_SPI_IRQn, 0, 1);
HAL_NVIC_SetPriority(CFG_SPI_IRQn, CFG_SPI_IRQn_PRIO);
HAL_NVIC_EnableIRQ(CFG_SPI_IRQn);
}
......@@ -181,14 +181,15 @@ alivetimer_handler()
void
HAL_TIM_Base_MspInit(TIM_HandleTypeDef *htim)
{
// peripheral and clock enable
// main clock (sampling)
TIM2_CLK_ENABLE();
HAL_NVIC_SetPriority(CFG_SAMPLETIME_IRQn, CFG_SAMPLETIME_IRQn_PRIO);
HAL_NVIC_EnableIRQ(CFG_SAMPLETIME_IRQn);
// NVIC for TIM2 and enable interrupt
HAL_NVIC_SetPriority(TIM2_IRQn, 1, 0);
HAL_NVIC_EnableIRQ(TIM2_IRQn);
// alive clock
TIM3_CLK_ENABLE();
HAL_NVIC_SetPriority(CFG_ALIVE_IRQn, CFG_ALIVE_IRQn_PRIO);
HAL_NVIC_EnableIRQ(CFG_ALIVE_IRQn);
}
......@@ -204,9 +205,9 @@ timer_init(void)
tim2Handle.Init.CounterMode = TIM_COUNTERMODE_UP;
HAL_TIM_Base_Init(&tim2Handle);
// TODO move values to board_config.h
TIM3 -> PSC = 45000;
TIM3 -> ARR = 500; // 1000;
TIM3 -> DIER = TIM_DIER_UIE;
TIM3 -> CR1 = TIM_CR1_CEN;
NVIC_EnableIRQ(TIM3_IRQn);
}