summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorjaseg <git-bigdata-wsl-arch@jaseg.de>2020-03-21 14:19:01 +0100
committerjaseg <git-bigdata-wsl-arch@jaseg.de>2020-03-21 14:19:01 +0100
commit3beecbc4fa60773ffbdf04ce1908a86be5908551 (patch)
tree3a470e3e86662804a090141d8843c46ce8620191
parent37338e2ad8ca226119121432b65f6c61134e60ac (diff)
downloadmaster-thesis-3beecbc4fa60773ffbdf04ce1908a86be5908551.tar.gz
master-thesis-3beecbc4fa60773ffbdf04ce1908a86be5908551.tar.bz2
master-thesis-3beecbc4fa60773ffbdf04ce1908a86be5908551.zip
Basic JTAG working
-rw-r--r--controller/fw/Makefile1
-rw-r--r--controller/fw/src/adc.c16
-rw-r--r--controller/fw/src/main.c50
-rw-r--r--controller/fw/src/mspdebug_wrapper.c120
-rw-r--r--controller/fw/src/mspdebug_wrapper.h3
-rw-r--r--controller/fw/src/serial.c12
-rw-r--r--controller/fw/src/serial.h5
-rw-r--r--controller/fw/src/spi_flash.c3
-rw-r--r--controller/fw/src/spi_flash.h2
9 files changed, 147 insertions, 65 deletions
diff --git a/controller/fw/Makefile b/controller/fw/Makefile
index 11b68b8..e96d35f 100644
--- a/controller/fw/Makefile
+++ b/controller/fw/Makefile
@@ -52,6 +52,7 @@ C_SOURCES += src/protocol.c
C_SOURCES += src/serial.c
C_SOURCES += src/con_usart.c
C_SOURCES += src/dma_util.c
+C_SOURCES += src/gpio_helpers.c
C_SOURCES += tinyprintf/tinyprintf.c
C_SOURCES += $(MSPDEBUG_DIR)/drivers/jtaglib.c
diff --git a/controller/fw/src/adc.c b/controller/fw/src/adc.c
index 027fd11..02d729a 100644
--- a/controller/fw/src/adc.c
+++ b/controller/fw/src/adc.c
@@ -64,26 +64,10 @@ void adc_init() {
TIM1->CCR1 = 1;
TIM1->BDTR = TIM_BDTR_MOE;
- /* DEBUG */
- TIM1->DIER = TIM_DIER_CC1IE;
- NVIC_EnableIRQ(TIM1_CC_IRQn);
- NVIC_SetPriority(TIM1_CC_IRQn, 130);
- /* END DEBUG */
-
TIM1->CR1 = TIM_CR1_CEN;
TIM1->EGR = TIM_EGR_UG;
}
-void TIM1_CC_IRQHandler(void) {
- TIM1->SR &= ~TIM_SR_CC1IF;
- static int foo=0;
- foo++;
- if (foo == 500) {
- foo = 0;
- GPIOA->ODR ^= 1<<6;
- }
-}
-
void DMA2_Stream0_IRQHandler(void) {
uint8_t isr = (DMA2->LISR >> DMA_LISR_FEIF0_Pos) & 0x3f;
GPIOA->BSRR = 1<<11;
diff --git a/controller/fw/src/main.c b/controller/fw/src/main.c
index d2795df..aec1fdc 100644
--- a/controller/fw/src/main.c
+++ b/controller/fw/src/main.c
@@ -14,6 +14,7 @@
#include "freq_meas.h"
#include "dsss_demod.h"
#include "con_usart.h"
+#include "mspdebug_wrapper.h"
static struct spi_flash_if spif;
@@ -26,6 +27,8 @@ unsigned int apb2_timer_speed = 0;
struct leds leds;
+ssize_t jt_spi_flash_read_block(void *usr, int addr, size_t len, uint8_t *out);
+
void __libc_init_array(void) { /* we don't need this. */ }
void __assert_func (unused_a const char *file, unused_a int line, unused_a const char *function, unused_a const char *expr) {
asm volatile ("bkpt");
@@ -116,8 +119,11 @@ static void clock_setup(void)
static void led_setup(void)
{
- RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN;
+ RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN | RCC_AHB1ENR_GPIOBEN;
+ /* onboard leds */
GPIOA->MODER |= (1<<GPIO_MODER_MODER6_Pos) | (1<<GPIO_MODER_MODER7_Pos);
+ GPIOB->MODER |= (1<<GPIO_MODER_MODER11_Pos) | (1<<GPIO_MODER_MODER12_Pos) | (1<<GPIO_MODER_MODER13_Pos)| (1<<GPIO_MODER_MODER14_Pos);
+ GPIOB->BSRR = 0xf << 11;
}
static void spi_flash_if_set_cs(bool val) {
@@ -174,6 +180,21 @@ void spi_flash_test(void) {
}
#endif
+static struct jtag_img_descriptor {
+ size_t devmem_img_start;
+ size_t spiflash_img_start;
+ size_t img_len;
+} jtag_img = {
+ .devmem_img_start = 0x00c000,
+ .spiflash_img_start = 0x000000,
+ .img_len = 0x060000,
+};
+
+ssize_t jt_spi_flash_read_block(void *usr, int addr, size_t len, uint8_t *out) {
+ struct jtag_img_descriptor *desc = (struct jtag_img_descriptor *)usr;
+ return spif_read(&spif, desc->spiflash_img_start + addr, len, (char *)out);
+}
+
static unsigned int measurement_errors = 0;
static struct dsss_demod_state demod_state;
static uint32_t freq_sample_ts = 0;
@@ -216,6 +237,15 @@ int main(void)
dsss_demod_init(&demod_state);
con_printf("Booted.\r\n");
+ int i=0;
+ while (23) {
+ mspd_jtag_init();
+ con_printf("%d flash result: %d\r\n", i,
+ mspd_jtag_flash_and_reset(jtag_img.devmem_img_start, jtag_img.img_len, jt_spi_flash_read_block, &jtag_img));
+ for (int i=0; i<168*1000*5; i++)
+ asm volatile ("nop");
+ i++;
+ }
while (23) {
if (adc_fft_buf_ready_idx != -1) {
for (int i=0; i<168*1000*2; i++)
@@ -223,6 +253,18 @@ int main(void)
GPIOA->BSRR = 1<<11;
memcpy(adc_fft_buf[!adc_fft_buf_ready_idx], adc_fft_buf[adc_fft_buf_ready_idx] + FMEAS_FFT_LEN/2, sizeof(adc_fft_buf[0][0]) * FMEAS_FFT_LEN/2);
GPIOA->BSRR = 1<<11<<16;
+ GPIOB->ODR ^= 1<<14;
+
+ bool clip_low=false, clip_high=false;
+ const int clip_thresh = 100;
+ for (size_t i=FMEAS_FFT_LEN/2; i<FMEAS_FFT_LEN; i++) {
+ int val = adc_fft_buf[adc_fft_buf_ready_idx][i];
+ if (val < clip_thresh)
+ clip_low = true;
+ if (val > FMEAS_ADC_MAX-clip_thresh)
+ clip_high = true;
+ }
+ GPIOB->ODR = (GPIOB->ODR & ~(3<<11)) | (!clip_low<<11) | (!clip_high<<12);
for (int i=0; i<168*1000*2; i++)
asm volatile ("nop");
@@ -232,7 +274,7 @@ int main(void)
if (adc_buf_measure_freq(adc_fft_buf[adc_fft_buf_ready_idx], &out)) {
con_printf("%012d: measurement error\r\n", freq_sample_ts);
measurement_errors++;
- GPIOA->BSRR = 1<<7;
+ GPIOB->BSRR = 1<<13;
debug_last_freq = NAN;
} else {
@@ -240,9 +282,9 @@ int main(void)
con_printf("%012d: %2d.%03d Hz\r\n", freq_sample_ts, (int)out, (int)(out * 1000) % 1000);
/* frequency ok led */
if (48 < out && out < 52)
- GPIOA->BSRR = 1<<7<<16;
+ GPIOB->BSRR = 1<<13<<16;
else
- GPIOA->BSRR = 1<<7;
+ GPIOB->BSRR = 1<<13;
GPIOA->BSRR = 1<<12;
dsss_demod_step(&demod_state, out, freq_sample_ts);
diff --git a/controller/fw/src/mspdebug_wrapper.c b/controller/fw/src/mspdebug_wrapper.c
index eda91cc..c1f6061 100644
--- a/controller/fw/src/mspdebug_wrapper.c
+++ b/controller/fw/src/mspdebug_wrapper.c
@@ -6,32 +6,86 @@
#include "jtaglib.h"
#include "sr_global.h"
+#include "gpio_helpers.h"
#include "mspdebug_wrapper.h"
+#include "con_usart.h"
#include <stm32f407xx.h>
#define BLOCK_SIZE 512 /* bytes */
+static void sr_delay_inst(void);
+
static struct jtdev sr_jtdev;
+static struct jtdev sr_jtdev_default;
+
+enum sr_gpio_types {
+ SR_GPIO_TCK,
+ SR_GPIO_TMS,
+ SR_GPIO_TDI,
+ SR_GPIO_RST,
+ SR_GPIO_TST,
+ SR_GPIO_TDO,
+ SR_NUM_GPIOS
+};
+
+struct {
+ GPIO_TypeDef *gpio;
+ int pin;
+ int mode;
+} gpios[SR_NUM_GPIOS] = {
+ [SR_GPIO_TCK] = {GPIOE, 10, 1},
+ [SR_GPIO_TMS] = {GPIOE, 11, 1},
+ [SR_GPIO_TDI] = {GPIOE, 12, 1},
+ [SR_GPIO_RST] = {GPIOE, 9, 1},
+ [SR_GPIO_TST] = {GPIOE, 14, 1},
+ [SR_GPIO_TDO] = {GPIOE, 13, 0},
+};
+
+void sr_delay_inst() {
+ for (int i=0; i<10; i++)
+ asm volatile("nop");
+}
+void mspd_jtag_init() {
+ for (int i=0; i<SR_NUM_GPIOS; i++)
+ gpio_pin_setup(gpios[i].gpio, gpios[i].pin, gpios[i].mode, 3, 0, 0);
+}
-int flash_and_reset(size_t img_start, size_t img_len, ssize_t (*read_block)(int addr, size_t len, uint8_t *out))
+int mspd_jtag_flash_and_reset(size_t img_start, size_t img_len, ssize_t (*read_block)(void *usr, int addr, size_t len, uint8_t *out), void *usr)
{
union {
uint8_t bytes[BLOCK_SIZE];
uint16_t words[BLOCK_SIZE/2];
} block;
+ memcpy(&sr_jtdev, &sr_jtdev_default, sizeof(sr_jtdev));
/* Initialize JTAG connection */
unsigned int jtag_id = jtag_init(&sr_jtdev);
- if (sr_jtdev.failed)
+ if (sr_jtdev.failed) {
+ con_printf("Couldn't initialize device\r\n");
return -EPIPE;
+ }
+ con_printf("JTAG device ID: 0x%02x\r\n", jtag_id);
if (jtag_id != 0x89 && jtag_id != 0x91)
return -EINVAL;
+ /* FIXME DEBUG */
+
+ con_printf("Memory dump:\r\n");
+ for (size_t i=0; i<256;) {
+ con_printf("%04x: ", i);
+ for (size_t j=0; j<16; i+=2, j+=2) {
+ con_printf("%04x ", jtag_read_mem(&sr_jtdev, 16, 0xc000 + i));
+ }
+ con_printf("\r\n");
+ }
+ return 0;
+ /* END DEBUG */
+
/* Clear flash */
jtag_erase_flash(&sr_jtdev, JTAG_ERASE_MAIN, 0);
if (sr_jtdev.failed)
@@ -39,7 +93,7 @@ int flash_and_reset(size_t img_start, size_t img_len, ssize_t (*read_block)(int
/* Write flash */
for (size_t p = img_start; p < img_start + img_len; p += BLOCK_SIZE) {
- ssize_t nin = read_block(p, BLOCK_SIZE, block.bytes);
+ ssize_t nin = read_block(usr, p, BLOCK_SIZE, block.bytes);
if (nin < 0)
return nin;
@@ -74,9 +128,18 @@ int flash_and_reset(size_t img_start, size_t img_len, ssize_t (*read_block)(int
/* mspdebug HAL shim */
int printc_err(const char *fmt, ...) {
- UNUSED(fmt);
- /* ignore */
- return 0;
+ va_list va;
+ va_start(va, fmt);
+ int rc = usart_printf_blocking_va(&con_usart, fmt, va);
+ if (rc)
+ return rc;
+
+ size_t i;
+ for (i=0; fmt[i]; i++)
+ ;
+ if (i > 0 && fmt[i-1] == '\n')
+ usart_putc_nonblocking(&con_usart, '\r');
+ return rc;
}
@@ -90,33 +153,11 @@ static void sr_jtdev_connect(struct jtdev *p) {
/* ignore */
}
-enum sr_gpio_types {
- SR_GPIO_TCK,
- SR_GPIO_TMS,
- SR_GPIO_TDI,
- SR_GPIO_RST,
- SR_GPIO_TST,
- SR_GPIO_TDO,
- SR_NUM_GPIOS
-};
-
-struct {
- GPIO_TypeDef *gpio;
- uint16_t num;
-} gpios[SR_NUM_GPIOS] = {
- [SR_GPIO_TCK] = {GPIOD, 8},
- [SR_GPIO_TMS] = {GPIOD, 9},
- [SR_GPIO_TDI] = {GPIOD, 10},
- [SR_GPIO_RST] = {GPIOD, 11},
- [SR_GPIO_TST] = {GPIOD, 12},
- [SR_GPIO_TDO] = {GPIOD, 13},
-};
-
static void sr_gpio_write(int num, int out) {
if (out)
- gpios[num].gpio->BSRR = 1<<gpios[num].num;
+ gpios[num].gpio->BSRR = 1<<gpios[num].pin;
else
- gpios[num].gpio->BSRR = 1<<gpios[num].num<<16;
+ gpios[num].gpio->BSRR = 1<<gpios[num].pin<<16;
}
static void sr_jtdev_tck(struct jtdev *p, int out) {
@@ -136,7 +177,7 @@ static void sr_jtdev_tdi(struct jtdev *p, int out) {
static void sr_jtdev_rst(struct jtdev *p, int out) {
UNUSED(p);
- sr_gpio_write(SR_GPIO_RST, out);
+ sr_gpio_write(SR_GPIO_RST, !out);
}
static void sr_jtdev_tst(struct jtdev *p, int out) {
@@ -146,24 +187,25 @@ static void sr_jtdev_tst(struct jtdev *p, int out) {
static int sr_jtdev_tdo_get(struct jtdev *p) {
UNUSED(p);
- return !!(gpios[SR_GPIO_TST].gpio->IDR & (1<<gpios[SR_GPIO_TST].num));
+ return !!(gpios[SR_GPIO_TDO].gpio->IDR & (1<<gpios[SR_GPIO_TDO].pin));
}
static void sr_jtdev_tclk(struct jtdev *p, int out) {
UNUSED(p);
- sr_gpio_write(SR_GPIO_TST, out);
+ sr_gpio_write(SR_GPIO_TDI, out);
}
static int sr_jtdev_tclk_get(struct jtdev *p) {
UNUSED(p);
- return !!(gpios[SR_GPIO_TDI].gpio->IDR & (1<<gpios[SR_GPIO_TDI].num));
+ return !!(gpios[SR_GPIO_TDI].gpio->ODR & (1<<gpios[SR_GPIO_TDI].pin));
}
static void sr_jtdev_tclk_strobe(struct jtdev *p, unsigned int count) {
UNUSED(p);
while (count--) {
- gpios[SR_GPIO_TDI].gpio->BSRR = 1<<gpios[SR_GPIO_TDI].num;
- gpios[SR_GPIO_TDI].gpio->BSRR = 1<<gpios[SR_GPIO_TDI].num<<16;
+ gpios[SR_GPIO_TDI].gpio->BSRR = 1<<gpios[SR_GPIO_TDI].pin;
+ sr_delay_inst();
+ gpios[SR_GPIO_TDI].gpio->BSRR = 1<<gpios[SR_GPIO_TDI].pin<<16;
}
}
@@ -211,3 +253,9 @@ static struct jtdev sr_jtdev = {
.f = &sr_jtdev_vtable
};
+static struct jtdev sr_jtdev_default = {
+ 0,
+ .f = &sr_jtdev_vtable
+};
+
+
diff --git a/controller/fw/src/mspdebug_wrapper.h b/controller/fw/src/mspdebug_wrapper.h
index 245d9fb..c3f5ac7 100644
--- a/controller/fw/src/mspdebug_wrapper.h
+++ b/controller/fw/src/mspdebug_wrapper.h
@@ -1,6 +1,7 @@
#ifndef __MSPDEBUG_WRAPPER_H__
#define __MSPDEBUG_WRAPPER_H__
-int flash_and_reset(size_t img_start, size_t img_len, ssize_t (*read_block)(int addr, size_t len, uint8_t *out));
+void mspd_jtag_init(void);
+int mspd_jtag_flash_and_reset(size_t img_start, size_t img_len, ssize_t (*read_block)(void *usr, int addr, size_t len, uint8_t *out), void *usr);
#endif /* __MSPDEBUG_WRAPPER_H__ */
diff --git a/controller/fw/src/serial.c b/controller/fw/src/serial.c
index 2d09f80..12df28a 100644
--- a/controller/fw/src/serial.c
+++ b/controller/fw/src/serial.c
@@ -165,18 +165,22 @@ int usart_flush(volatile struct usart_desc *us) {
return 0;
}
-int usart_printf(volatile struct usart_desc *us, char *fmt, ...) {
+int usart_printf(volatile struct usart_desc *us, const char *fmt, ...) {
va_list va;
va_start(va, fmt);
tfp_format((void *)us, usart_putc_nonblocking_tpf, fmt, va);
return usart_flush(us);
}
-int usart_printf_blocking(volatile struct usart_desc *us, char *fmt, ...) {
- va_list va;
- va_start(va, fmt);
+int usart_printf_blocking_va(volatile struct usart_desc *us, const char *fmt, va_list va) {
tfp_format((void *)us, usart_putc_blocking_tpf, fmt, va);
usart_wait_chunk_free(us);
return usart_flush(us);
}
+int usart_printf_blocking(volatile struct usart_desc *us, const char *fmt, ...) {
+ va_list va;
+ va_start(va, fmt);
+ return usart_printf_blocking_va(us, fmt, va);
+}
+
diff --git a/controller/fw/src/serial.h b/controller/fw/src/serial.h
index bad4374..73d2323 100644
--- a/controller/fw/src/serial.h
+++ b/controller/fw/src/serial.h
@@ -78,7 +78,8 @@ int usart_putc_blocking(volatile struct usart_desc *us, char c);
void usart_dma_stream_irq(volatile struct usart_desc *us);
int usart_flush(volatile struct usart_desc *us);
-int usart_printf(volatile struct usart_desc *us, char *fmt, ...);
-int usart_printf_blocking(volatile struct usart_desc *us, char *fmt, ...);
+int usart_printf(volatile struct usart_desc *us, const char *fmt, ...);
+int usart_printf_blocking(volatile struct usart_desc *us, const char *fmt, ...);
+int usart_printf_blocking_va(volatile struct usart_desc *us, const char *fmt, va_list va);
#endif // __SERIAL_H__
diff --git a/controller/fw/src/spi_flash.c b/controller/fw/src/spi_flash.c
index 305be8f..639c2b6 100644
--- a/controller/fw/src/spi_flash.c
+++ b/controller/fw/src/spi_flash.c
@@ -96,7 +96,7 @@ void spif_init(struct spi_flash_if *spif, size_t page_size, SPI_TypeDef *spi, vo
spif->cs(1);
}
-void spif_read(struct spi_flash_if *spif, size_t addr, size_t len, char* data) {
+ssize_t spif_read(struct spi_flash_if *spif, size_t addr, size_t len, char* data) {
spif_enable_write(spif);
spif->cs(0);
@@ -109,6 +109,7 @@ void spif_read(struct spi_flash_if *spif, size_t addr, size_t len, char* data) {
data[i] = spi_read(spif);
spif->cs(1);
+ return len;
}
void spif_write(struct spi_flash_if *spif, size_t addr, size_t len, const char* data) {
diff --git a/controller/fw/src/spi_flash.h b/controller/fw/src/spi_flash.h
index 2be8933..6443f11 100644
--- a/controller/fw/src/spi_flash.h
+++ b/controller/fw/src/spi_flash.h
@@ -22,7 +22,7 @@ struct spi_flash_if {
void spif_init(struct spi_flash_if *spif, size_t page_size, SPI_TypeDef *spi, void (*cs)(bool val));
void spif_write(struct spi_flash_if *spif, size_t addr, size_t len, const char* data);
-void spif_read(struct spi_flash_if *spif, size_t addr, size_t len, char* data);
+ssize_t spif_read(struct spi_flash_if *spif, size_t addr, size_t len, char* data);
void spif_clear_mem(struct spi_flash_if *spif);
void spif_clear_sector(struct spi_flash_if *spif, size_t addr);