aboutsummaryrefslogtreecommitdiff
path: root/src/platforms
diff options
context:
space:
mode:
Diffstat (limited to 'src/platforms')
-rw-r--r--src/platforms/f4discovery/Makefile.inc2
-rw-r--r--src/platforms/f4discovery/platform.c2
-rw-r--r--src/platforms/f4discovery/platform.h8
-rw-r--r--src/platforms/libftdi/jtagtap.c14
-rw-r--r--src/platforms/libftdi/platform.c24
-rw-r--r--src/platforms/libftdi/swdptap.c10
-rw-r--r--src/platforms/native/platform.c37
-rw-r--r--src/platforms/native/platform.h25
-rw-r--r--src/platforms/stlink/platform.c33
-rw-r--r--src/platforms/stlink/platform.h22
-rw-r--r--src/platforms/stlink/usbdfu.c14
-rw-r--r--src/platforms/stm32/cdcacm.c8
-rw-r--r--src/platforms/stm32/dfu_f1.c6
-rw-r--r--src/platforms/stm32/dfu_f4.c14
-rw-r--r--src/platforms/stm32/dfucore.c35
-rw-r--r--src/platforms/stm32/jtagtap.c15
-rw-r--r--src/platforms/stm32/swdptap.c8
-rw-r--r--src/platforms/swlink/platform.c6
-rw-r--r--src/platforms/swlink/platform.h10
19 files changed, 178 insertions, 115 deletions
diff --git a/src/platforms/f4discovery/Makefile.inc b/src/platforms/f4discovery/Makefile.inc
index f67b278..88575bb 100644
--- a/src/platforms/f4discovery/Makefile.inc
+++ b/src/platforms/f4discovery/Makefile.inc
@@ -7,7 +7,7 @@ CFLAGS += -Istm32/include -mcpu=cortex-m4 -mthumb \
-DSTM32F4 -DF4DISCOVERY -I../libopencm3/include \
-Iplatforms/stm32
-LDFLAGS = -lopencm3_stm32f4 -Wl,--defsym,_stack=0x20020000 \
+LDFLAGS = -lopencm3_stm32f4 -Wl,--defsym,_stack=0x20006000 \
-Wl,-T,platforms/stm32/f4discovery.ld -nostartfiles -lc -lnosys \
-Wl,-Map=mapfile -mthumb -mcpu=cortex-m4 -Wl,-gc-sections \
-mfloat-abi=hard -mfpu=fpv4-sp-d16 \
diff --git a/src/platforms/f4discovery/platform.c b/src/platforms/f4discovery/platform.c
index 645a3c5..6ee36bd 100644
--- a/src/platforms/f4discovery/platform.c
+++ b/src/platforms/f4discovery/platform.c
@@ -53,7 +53,7 @@ int platform_init(void)
scb_reset_core();
}
- rcc_clock_setup_hse_3v3(&hse_8mhz_3v3[CLOCK_3V3_168MHZ]);
+ rcc_clock_setup_hse_3v3(&hse_8mhz_3v3[CLOCK_3V3_48MHZ]);
/* Enable peripherals */
rcc_peripheral_enable_clock(&RCC_AHB2ENR, RCC_AHB2ENR_OTGFSEN);
diff --git a/src/platforms/f4discovery/platform.h b/src/platforms/f4discovery/platform.h
index c1423b6..5523b9c 100644
--- a/src/platforms/f4discovery/platform.h
+++ b/src/platforms/f4discovery/platform.h
@@ -195,23 +195,23 @@ void uart_usb_buf_drain(uint8_t ep);
#define vasprintf vasiprintf
#ifdef INLINE_GPIO
-static inline void _gpio_set(u32 gpioport, u16 gpios)
+static inline void _gpio_set(uint32_t gpioport, uint16_t gpios)
{
GPIO_BSRR(gpioport) = gpios;
GPIO_BSRR(gpioport) = gpios;
}
#define gpio_set _gpio_set
-static inline void _gpio_clear(u32 gpioport, u16 gpios)
+static inline void _gpio_clear(uint32_t gpioport, uint16_t gpios)
{
GPIO_BSRR(gpioport) = gpios<<16;
GPIO_BSRR(gpioport) = gpios<<16;
}
#define gpio_clear _gpio_clear
-static inline u16 _gpio_get(u32 gpioport, u16 gpios)
+static inline uint16_t _gpio_get(uint32_t gpioport, uint16_t gpios)
{
- return (u16)GPIO_IDR(gpioport) & gpios;
+ return (uint16_t)GPIO_IDR(gpioport) & gpios;
}
#define gpio_get _gpio_get
#endif
diff --git a/src/platforms/libftdi/jtagtap.c b/src/platforms/libftdi/jtagtap.c
index c914646..91f6ae2 100644
--- a/src/platforms/libftdi/jtagtap.c
+++ b/src/platforms/libftdi/jtagtap.c
@@ -67,7 +67,7 @@ void jtagtap_reset(void)
jtagtap_soft_reset();
}
-void jtagtap_srst(void)
+void jtagtap_srst(bool assert)
{
platform_buffer_flush();
//ftdi_write_data(ftdic, "\x80\x88\xAB", 3);
@@ -84,7 +84,7 @@ jtagtap_tms_seq(uint32_t MS, int ticks)
//jtagtap_next(MS & 1, 1);
tmp[1] = ticks<7?ticks-1:6;
tmp[2] = 0x80 | (MS & 0x7F);
-
+
// assert(ftdi_write_data(ftdic, tmp, 3) == 3);
platform_buffer_write(tmp, 3);
MS >>= 7; ticks -= 7;
@@ -93,7 +93,7 @@ jtagtap_tms_seq(uint32_t MS, int ticks)
#endif
#ifndef PROVIDE_GENERIC_TAP_TDI_SEQ
-void
+void
jtagtap_tdi_seq(const uint8_t final_tms, const uint8_t *DI, int ticks)
{
char *tmp;
@@ -119,7 +119,7 @@ jtagtap_tdi_seq(const uint8_t final_tms, const uint8_t *DI, int ticks)
tmp[index++] = rticks - 1;
tmp[index++] = *DI;
}
-
+
if(final_tms) {
tmp[index++] = 0x4B;
tmp[index++] = 0;
@@ -131,7 +131,7 @@ jtagtap_tdi_seq(const uint8_t final_tms, const uint8_t *DI, int ticks)
#endif
#ifndef PROVIDE_GENERIC_TAP_TDI_TDO_SEQ
-void
+void
jtagtap_tdi_tdo_seq(uint8_t *DO, const uint8_t final_tms, const uint8_t *DI, int ticks)
{
uint8_t *tmp;
@@ -159,7 +159,7 @@ jtagtap_tdi_tdo_seq(uint8_t *DO, const uint8_t final_tms, const uint8_t *DI, int
tmp[index++] = rticks - 1;
tmp[index++] = *DI;
}
-
+
if(final_tms) {
rsize++;
tmp[index++] = 0x6B;
@@ -176,7 +176,7 @@ jtagtap_tdi_tdo_seq(uint8_t *DO, const uint8_t final_tms, const uint8_t *DI, int
printf("\n");*/
index = 0;
if(final_tms) rsize--;
-
+
while(rsize--) {
/*if(rsize) printf("%02X ", tmp[index]);*/
*DO++ = tmp[index++];
diff --git a/src/platforms/libftdi/platform.c b/src/platforms/libftdi/platform.c
index ec2a8f1..dc57a45 100644
--- a/src/platforms/libftdi/platform.c
+++ b/src/platforms/libftdi/platform.c
@@ -122,7 +122,7 @@ static struct cable_desc_s {
};
int platform_init(int argc, char **argv)
-{
+{
int err;
int c;
int index = 0;
@@ -167,40 +167,40 @@ int platform_init(int argc, char **argv)
ftdic = NULL;
}
if((ftdic = ftdi_new()) == NULL) {
- fprintf(stderr, "ftdi_new: %s\n",
+ fprintf(stderr, "ftdi_new: %s\n",
ftdi_get_error_string(ftdic));
abort();
}
if((err = ftdi_set_interface(ftdic, cable_desc[index].interface)) != 0) {
- fprintf(stderr, "ftdi_set_interface: %d: %s\n",
+ fprintf(stderr, "ftdi_set_interface: %d: %s\n",
err, ftdi_get_error_string(ftdic));
abort();
}
if((err = ftdi_usb_open_desc(
ftdic, cable_desc[index].vendor, cable_desc[index].product,
cable_desc[index].description, serial)) != 0) {
- fprintf(stderr, "unable to open ftdi device: %d (%s)\n",
+ fprintf(stderr, "unable to open ftdi device: %d (%s)\n",
err, ftdi_get_error_string(ftdic));
abort();
}
if((err = ftdi_set_latency_timer(ftdic, 1)) != 0) {
- fprintf(stderr, "ftdi_set_latency_timer: %d: %s\n",
+ fprintf(stderr, "ftdi_set_latency_timer: %d: %s\n",
err, ftdi_get_error_string(ftdic));
abort();
}
if((err = ftdi_set_baudrate(ftdic, 1000000)) != 0) {
- fprintf(stderr, "ftdi_set_baudrate: %d: %s\n",
+ fprintf(stderr, "ftdi_set_baudrate: %d: %s\n",
err, ftdi_get_error_string(ftdic));
abort();
}
if((err = ftdi_usb_purge_buffers(ftdic)) != 0) {
- fprintf(stderr, "ftdi_set_baudrate: %d: %s\n",
+ fprintf(stderr, "ftdi_set_baudrate: %d: %s\n",
err, ftdi_get_error_string(ftdic));
abort();
}
if((err = ftdi_write_data_set_chunksize(ftdic, BUF_SIZE)) != 0) {
- fprintf(stderr, "ftdi_write_data_set_chunksize: %d: %s\n",
+ fprintf(stderr, "ftdi_write_data_set_chunksize: %d: %s\n",
err, ftdi_get_error_string(ftdic));
abort();
}
@@ -216,8 +216,8 @@ int platform_init(int argc, char **argv)
assert(gdb_if_init() == 0);
jtag_scan(NULL);
-
- return 0;
+
+ return 0;
}
void platform_buffer_flush(void)
@@ -250,9 +250,9 @@ int vasprintf(char **strp, const char *fmt, va_list ap)
int size = 128, ret = 0;
*strp = malloc(size);
- while(*strp && ((ret = vsnprintf(*strp, size, fmt, ap)) == size))
+ while(*strp && ((ret = vsnprintf(*strp, size, fmt, ap)) == size))
*strp = realloc(*strp, size <<= 1);
-
+
return ret;
}
#endif
diff --git a/src/platforms/libftdi/swdptap.c b/src/platforms/libftdi/swdptap.c
index be329d8..cd3582b 100644
--- a/src/platforms/libftdi/swdptap.c
+++ b/src/platforms/libftdi/swdptap.c
@@ -40,7 +40,7 @@ int swdptap_init(void)
assert(ftdic != NULL);
if((err = ftdi_set_bitmode(ftdic, 0xAB, BITMODE_BITBANG)) != 0) {
- fprintf(stderr, "ftdi_set_bitmode: %d: %s\n",
+ fprintf(stderr, "ftdi_set_bitmode: %d: %s\n",
err, ftdi_get_error_string(ftdic));
abort();
}
@@ -49,11 +49,11 @@ int swdptap_init(void)
/* This must be investigated in more detail.
* As described in STM32 Reference Manual... */
- swdptap_seq_out(0xFFFF, 16);
+ swdptap_seq_out(0xFFFF, 16);
swdptap_reset();
- swdptap_seq_out(0xE79E, 16); /* 0b0111100111100111 */
+ swdptap_seq_out(0xE79E, 16); /* 0b0111100111100111 */
swdptap_reset();
- swdptap_seq_out(0, 16);
+ swdptap_seq_out(0, 16);
return 0;
}
@@ -85,7 +85,7 @@ static void swdptap_turnaround(uint8_t dir)
assert(ftdi_set_bitmode(ftdic, 0xAB, BITMODE_BITBANG) == 0);
}
-static uint8_t swdptap_bit_in(void)
+static uint8_t swdptap_bit_in(void)
{
uint8_t ret;
diff --git a/src/platforms/native/platform.c b/src/platforms/native/platform.c
index 3bd0816..214625e 100644
--- a/src/platforms/native/platform.c
+++ b/src/platforms/native/platform.c
@@ -82,7 +82,6 @@ int platform_init(void)
gpio_set_mode(JTAG_PORT, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL,
TMS_PIN | TCK_PIN | TDI_PIN);
-
/* This needs some fixing... */
/* Toggle required to sort out line drivers... */
gpio_port_write(GPIOA, 0x8100);
@@ -99,6 +98,25 @@ int platform_init(void)
* to release the device from reset if this floats. */
gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, GPIO7);
+ /* Enable SRST output. Original uses a NPN to pull down, so setting the
+ * output HIGH asserts. Mini is directly connected so use open drain output
+ * and set LOW to assert.
+ */
+ platform_srst_set_val(false);
+ gpio_set_mode(SRST_PORT, GPIO_MODE_OUTPUT_50_MHZ,
+ (platform_hwversion() == 0
+ ? GPIO_CNF_OUTPUT_PUSHPULL
+ : GPIO_CNF_OUTPUT_OPENDRAIN),
+ SRST_PIN);
+
+ /* Enable internal pull-up on PWR_BR so that we don't drive
+ TPWR locally or inadvertently supply power to the target. */
+ if (platform_hwversion () > 0) {
+ gpio_set (PWR_BR_PORT, PWR_BR_PIN);
+ gpio_set_mode(PWR_BR_PORT, GPIO_MODE_INPUT,
+ GPIO_CNF_INPUT_PULL_UPDOWN,
+ PWR_BR_PIN);
+ }
/* Setup heartbeat timer */
systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8);
@@ -122,10 +140,19 @@ int platform_init(void)
usbuart_init();
jtag_scan(NULL);
-
+
return 0;
}
+void platform_srst_set_val(bool assert)
+{
+ if (platform_hwversion() == 0) {
+ gpio_set_val(SRST_PORT, SRST_PIN, assert);
+ } else {
+ gpio_set_val(SRST_PORT, SRST_PIN, !assert);
+ }
+}
+
void platform_delay(uint32_t delay)
{
timeout_counter = delay;
@@ -249,15 +276,15 @@ const char *platform_target_voltage(void)
return gpio_get(GPIOB, GPIO0) ? "OK" : "ABSENT!";
static char ret[] = "0.0V";
- const u8 channel = 8;
- adc_set_regular_sequence(ADC1, 1, (u8*)&channel);
+ const uint8_t channel = 8;
+ adc_set_regular_sequence(ADC1, 1, (uint8_t*)&channel);
adc_start_conversion_direct(ADC1);
/* Wait for end of conversion. */
while (!adc_eoc(ADC1));
- u32 val = adc_read_regular(ADC1) * 99; /* 0-4095 */
+ uint32_t val = adc_read_regular(ADC1) * 99; /* 0-4095 */
ret[0] = '0' + val / 81910;
ret[2] = '0' + (val / 8191) % 10;
diff --git a/src/platforms/native/platform.h b/src/platforms/native/platform.h
index eb91f8b..62d565b 100644
--- a/src/platforms/native/platform.h
+++ b/src/platforms/native/platform.h
@@ -51,7 +51,8 @@ extern usbd_device *usbdev;
* LED2 = PB11 (Red LED : Error)
*
* TPWR = RB0 (input) -- analogue on mini design ADC1, ch8
- * nTRST = PB1
+ * nTRST = PB1 [blackmagic]
+ * PWR_BR = PB1 [blackmagic_mini] -- supply power to the target, active low
* SRST_OUT = PA2
* TDI = PA3
* TMS = PA4 (input for SWDP)
@@ -60,7 +61,7 @@ extern usbd_device *usbdev;
* nSRST = PA7 (input)
*
* USB cable pull-up: PA8
- * USB VBUS detect: PB13 -- New on mini design.
+ * USB VBUS detect: PB13 -- New on mini design.
* Enable pull up for compatibility.
* Force DFU mode button: PB12
*/
@@ -83,6 +84,8 @@ extern usbd_device *usbdev;
#define TRST_PORT GPIOB
#define TRST_PIN GPIO1
+#define PWR_BR_PORT GPIOB
+#define PWR_BR_PIN GPIO1
#define SRST_PORT GPIOA
#define SRST_PIN GPIO2
@@ -113,12 +116,15 @@ extern usbd_device *usbdev;
gpio_set_mode(USBUSART_PORT, GPIO_MODE_OUTPUT_2_MHZ, \
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, USBUSART_TX_PIN);
+#define SRST_SET_VAL(x) \
+ platform_srst_set_val(x)
+
#define USB_DRIVER stm32f103_usb_driver
#define USB_IRQ NVIC_USB_LP_CAN_RX0_IRQ
#define USB_ISR usb_lp_can_rx0_isr
/* Interrupt priorities. Low numbers are high priority.
* For now USART1 preempts USB which may spin while buffer is drained.
- * TIM3 is used for traceswo capture and must be highest priority.
+ * TIM3 is used for traceswo capture and must be highest priority.
*/
#define IRQ_PRI_USB (2 << 4)
#define IRQ_PRI_USBUSART (1 << 4)
@@ -165,14 +171,14 @@ extern const char *morse_msg;
#define SET_ERROR_STATE(state) {gpio_set_val(LED_PORT, LED_ERROR, state);}
#define PLATFORM_SET_FATAL_ERROR_RECOVERY() {setjmp(fatal_error_jmpbuf);}
-#define PLATFORM_FATAL_ERROR(error) { \
+#define PLATFORM_FATAL_ERROR(error) do { \
if(running_status) gdb_putpacketz("X1D"); \
else gdb_putpacketz("EFF"); \
running_status = 0; \
target_list_free(); \
morse("TARGET LOST.", 1); \
longjmp(fatal_error_jmpbuf, (error)); \
-}
+} while (0)
int platform_init(void);
void morse(const char *msg, char repeat);
@@ -195,21 +201,21 @@ void uart_usb_buf_drain(uint8_t ep);
#define vasprintf vasiprintf
#ifdef INLINE_GPIO
-static inline void _gpio_set(u32 gpioport, u16 gpios)
+static inline void _gpio_set(uint32_t gpioport, uint16_t gpios)
{
GPIO_BSRR(gpioport) = gpios;
}
#define gpio_set _gpio_set
-static inline void _gpio_clear(u32 gpioport, u16 gpios)
+static inline void _gpio_clear(uint32_t gpioport, uint16_t gpios)
{
GPIO_BRR(gpioport) = gpios;
}
#define gpio_clear _gpio_clear
-static inline u16 _gpio_get(u32 gpioport, u16 gpios)
+static inline uint16_t _gpio_get(uint32_t gpioport, uint16_t gpios)
{
- return (u16)GPIO_IDR(gpioport) & gpios;
+ return (uint16_t)GPIO_IDR(gpioport) & gpios;
}
#define gpio_get _gpio_get
#endif
@@ -219,3 +225,4 @@ static inline u16 _gpio_get(u32 gpioport, u16 gpios)
#define disconnect_usb() gpio_set_mode(USB_PU_PORT, GPIO_MODE_INPUT, 0, USB_PU_PIN);
void assert_boot_pin(void);
void setup_vbus_irq(void);
+void platform_srst_set_val(bool assert);
diff --git a/src/platforms/stlink/platform.c b/src/platforms/stlink/platform.c
index e8435b9..03509ea 100644
--- a/src/platforms/stlink/platform.c
+++ b/src/platforms/stlink/platform.c
@@ -92,18 +92,23 @@ int platform_init(void)
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO8);
}
/* Setup GPIO ports */
- gpio_set_mode(TMS_PORT, GPIO_MODE_OUTPUT_50_MHZ,
+ gpio_set_mode(TMS_PORT, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, TMS_PIN);
- gpio_set_mode(TCK_PORT, GPIO_MODE_OUTPUT_50_MHZ,
+ gpio_set_mode(TCK_PORT, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, TCK_PIN);
- gpio_set_mode(TDI_PORT, GPIO_MODE_OUTPUT_50_MHZ,
+ gpio_set_mode(TDI_PORT, GPIO_MODE_OUTPUT_50_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, TDI_PIN);
-
- gpio_set_mode(LED_PORT, GPIO_MODE_OUTPUT_2_MHZ,
+ uint16_t srst_pin = platform_hwversion() == 0 ?
+ SRST_PIN_V1 : SRST_PIN_V2;
+ gpio_set(SRST_PORT, srst_pin);
+ gpio_set_mode(SRST_PORT, GPIO_MODE_OUTPUT_50_MHZ,
+ GPIO_CNF_OUTPUT_OPENDRAIN, srst_pin);
+
+ gpio_set_mode(LED_PORT, GPIO_MODE_OUTPUT_2_MHZ,
GPIO_CNF_OUTPUT_PUSHPULL, led_idle_run);
/* Setup heartbeat timer */
- systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8);
+ systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8);
systick_set_reload(900000); /* Interrupt us at 10 Hz */
SCB_SHPR(11) &= ~((15 << 4) & 0xff);
SCB_SHPR(11) |= ((14 << 4) & 0xff);
@@ -117,7 +122,7 @@ int platform_init(void)
cdcacm_init();
jtag_scan(NULL);
-
+
return 0;
}
@@ -127,12 +132,22 @@ void platform_delay(uint32_t delay)
while(timeout_counter);
}
+void platform_srst_set_val(bool assert)
+{
+ uint16_t pin;
+ pin = platform_hwversion() == 0 ? SRST_PIN_V1 : SRST_PIN_V2;
+ if (assert)
+ gpio_clear(SRST_PORT, pin);
+ else
+ gpio_set(SRST_PORT, pin);
+}
+
void sys_tick_handler(void)
{
- if(running_status)
+ if(running_status)
gpio_toggle(LED_PORT, led_idle_run);
- if(timeout_counter)
+ if(timeout_counter)
timeout_counter--;
}
diff --git a/src/platforms/stlink/platform.h b/src/platforms/stlink/platform.h
index 09fab96..a9e405b 100644
--- a/src/platforms/stlink/platform.h
+++ b/src/platforms/stlink/platform.h
@@ -59,7 +59,7 @@ extern usbd_device *usbdev;
* nSRST = PA7 (input)
*
* USB cable pull-up: PA8
- * USB VBUS detect: PB13 -- New on mini design.
+ * USB VBUS detect: PB13 -- New on mini design.
* Enable pull up for compatibility.
* Force DFU mode button: PB12
*/
@@ -79,6 +79,10 @@ extern usbd_device *usbdev;
#define SWDIO_PIN TMS_PIN
#define SWCLK_PIN TCK_PIN
+#define SRST_PORT GPIOB
+#define SRST_PIN_V1 GPIO1
+#define SRST_PIN_V2 GPIO0
+
#define LED_PORT GPIOA
/* Use PC14 for a "dummy" uart led. So we can observere at least with scope*/
#define LED_PORT_UART GPIOC
@@ -98,6 +102,9 @@ extern usbd_device *usbdev;
gpio_set_mode(USBUSART_PORT, GPIO_MODE_OUTPUT_2_MHZ, \
GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, USBUSART_TX_PIN);
+#define SRST_SET_VAL(x) \
+ platform_srst_set_val(x)
+
#define USB_DRIVER stm32f103_usb_driver
#define USB_IRQ NVIC_USB_LP_CAN_RX0_IRQ
#define USB_ISR usb_lp_can_rx0_isr
@@ -145,18 +152,19 @@ extern uint16_t led_idle_run;
#define SET_IDLE_STATE(state) {gpio_set_val(LED_PORT, led_idle_run, state);}
#define PLATFORM_SET_FATAL_ERROR_RECOVERY() {setjmp(fatal_error_jmpbuf);}
-#define PLATFORM_FATAL_ERROR(error) { \
+#define PLATFORM_FATAL_ERROR(error) do { \
if(running_status) gdb_putpacketz("X1D"); \
else gdb_putpacketz("EFF"); \
running_status = 0; \
target_list_free(); \
longjmp(fatal_error_jmpbuf, (error)); \
-}
+} while (0)
int platform_init(void);
void morse(const char *msg, char repeat);
const char *platform_target_voltage(void);
void platform_delay(uint32_t delay);
+void platform_srst_set_val(bool assert);
/* <cdcacm.c> */
void cdcacm_init(void);
@@ -173,21 +181,21 @@ void uart_usb_buf_drain(uint8_t ep);
#define vasprintf vasiprintf
#ifdef INLINE_GPIO
-static inline void _gpio_set(u32 gpioport, u16 gpios)
+static inline void _gpio_set(uint32_t gpioport, uint16_t gpios)
{
GPIO_BSRR(gpioport) = gpios;
}
#define gpio_set _gpio_set
-static inline void _gpio_clear(u32 gpioport, u16 gpios)
+static inline void _gpio_clear(uint32_t gpioport, uint16_t gpios)
{
GPIO_BRR(gpioport) = gpios;
}
#define gpio_clear _gpio_clear
-static inline u16 _gpio_get(u32 gpioport, u16 gpios)
+static inline uint16_t _gpio_get(uint32_t gpioport, uint16_t gpios)
{
- return (u16)GPIO_IDR(gpioport) & gpios;
+ return (uint16_t)GPIO_IDR(gpioport) & gpios;
}
#define gpio_get _gpio_get
#endif
diff --git a/src/platforms/stlink/usbdfu.c b/src/platforms/stlink/usbdfu.c
index f688c1c..76a19b0 100644
--- a/src/platforms/stlink/usbdfu.c
+++ b/src/platforms/stlink/usbdfu.c
@@ -40,13 +40,13 @@ static int stlink_test_nrst(void)
* 11 for ST-Link V1, e.g. on VL Discovery, tag as rev 0
* 10 for ST-Link V2, e.g. on F4 Discovery, tag as rev 1
*/
- rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPCEN);
- gpio_set_mode(GPIOC, GPIO_MODE_INPUT,
- GPIO_CNF_INPUT_PULL_UPDOWN, GPIO14 | GPIO13);
- gpio_set(GPIOC, GPIO14 | GPIO13);
- for (i = 0; i < 100; i++)
- rev = (~(gpio_get(GPIOC, GPIO14 | GPIO13)) >> 13) & 3;
-
+ for (i = 0; i < 0x200; i++) {
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPCEN);
+ gpio_set_mode(GPIOC, GPIO_MODE_INPUT,
+ GPIO_CNF_INPUT_PULL_UPDOWN, GPIO14 | GPIO13);
+ gpio_set(GPIOC, GPIO14 | GPIO13);
+ rev = (~(gpio_get(GPIOC, GPIO14 | GPIO13)) >> 13) & 3;
+ }
switch (rev) {
case 0:
pin = GPIO1;
diff --git a/src/platforms/stm32/cdcacm.c b/src/platforms/stm32/cdcacm.c
index 93b0f33..010117f 100644
--- a/src/platforms/stm32/cdcacm.c
+++ b/src/platforms/stm32/cdcacm.c
@@ -480,7 +480,7 @@ int cdcacm_get_dtr(void)
return cdcacm_gdb_dtr;
}
-static void cdcacm_set_config(usbd_device *dev, u16 wValue)
+static void cdcacm_set_config(usbd_device *dev, uint16_t wValue)
{
configured = wValue;
@@ -536,8 +536,10 @@ void cdcacm_init(void)
get_dev_unique_id(serial_no);
- usbdev = usbd_init(&USB_DRIVER, &dev, &config, usb_strings, sizeof(usb_strings)/sizeof(char *));
- usbd_set_control_buffer_size(usbdev, sizeof(usbd_control_buffer));
+ usbdev = usbd_init(&USB_DRIVER, &dev, &config, usb_strings,
+ sizeof(usb_strings)/sizeof(char *),
+ usbd_control_buffer, sizeof(usbd_control_buffer));
+
usbd_register_set_config_callback(usbdev, cdcacm_set_config);
nvic_set_priority(USB_IRQ, IRQ_PRI_USB);
diff --git a/src/platforms/stm32/dfu_f1.c b/src/platforms/stm32/dfu_f1.c
index 827712d..08cbb02 100644
--- a/src/platforms/stm32/dfu_f1.c
+++ b/src/platforms/stm32/dfu_f1.c
@@ -48,7 +48,7 @@ void dfu_flash_program_buffer(uint32_t baseaddr, void *buf, int len)
{
for(int i = 0; i < len; i += 2)
flash_program_half_word(baseaddr + i,
- *(u16*)(buf+i));
+ *(uint16_t*)(buf+i));
}
uint32_t dfu_poll_timeout(uint8_t cmd, uint32_t addr, uint16_t blocknum)
@@ -77,12 +77,12 @@ void dfu_protect_enable(void)
void dfu_jump_app_if_valid(void)
{
/* Boot the application if it's valid */
- if((*(volatile u32*)APP_ADDRESS & 0x2FFE0000) == 0x20000000) {
+ if((*(volatile uint32_t*)APP_ADDRESS & 0x2FFE0000) == 0x20000000) {
/* Set vector table base address */
SCB_VTOR = APP_ADDRESS & 0x1FFFFF; /* Max 2 MByte Flash*/
/* Initialise master stack pointer */
asm volatile ("msr msp, %0"::"g"
- (*(volatile u32*)APP_ADDRESS));
+ (*(volatile uint32_t*)APP_ADDRESS));
/* Jump to application */
(*(void(**)())(APP_ADDRESS + 4))();
}
diff --git a/src/platforms/stm32/dfu_f4.c b/src/platforms/stm32/dfu_f4.c
index 960ec23..1421b19 100644
--- a/src/platforms/stm32/dfu_f4.c
+++ b/src/platforms/stm32/dfu_f4.c
@@ -26,17 +26,17 @@
#include "usbdfu.h"
-static u32 sector_addr[] = {0x8000000, 0x8004000, 0x8008000, 0x800c000,
+static uint32_t sector_addr[] = {0x8000000, 0x8004000, 0x8008000, 0x800c000,
0x8010000, 0x8020000, 0x8040000, 0x8060000,
0x8080000, 0x80a0000, 0x80c0000, 0x80e0000,
0x8100000, 0};
-static u16 sector_erase_time[12]= {500, 500, 500, 500,
+static uint16_t sector_erase_time[12]= {500, 500, 500, 500,
1100,
2600, 2600, 2600, 2600, 2600, 2600, 2600};
-static u8 sector_num = 0xff;
+static uint8_t sector_num = 0xff;
/* Find the sector number for a given address*/
-static void get_sector_num(u32 addr)
+static void get_sector_num(uint32_t addr)
{
int i = 0;
while(sector_addr[i+1]) {
@@ -60,7 +60,7 @@ void dfu_flash_program_buffer(uint32_t baseaddr, void *buf, int len)
{
for(int i = 0; i < len; i += 4)
flash_program_word(baseaddr + i,
- *(u32*)(buf+i),
+ *(uint32_t*)(buf+i),
FLASH_PROGRAM_X32);
}
@@ -93,12 +93,12 @@ void dfu_jump_app_if_valid(void)
/* Boot the application if it's valid */
/* Vector table may be anywhere in 128 kByte RAM
CCM not handled*/
- if((*(volatile u32*)APP_ADDRESS & 0x2FFC0000) == 0x20000000) {
+ if((*(volatile uint32_t*)APP_ADDRESS & 0x2FFC0000) == 0x20000000) {
/* Set vector table base address */
SCB_VTOR = APP_ADDRESS & 0x1FFFFF; /* Max 2 MByte Flash*/
/* Initialise master stack pointer */
asm volatile ("msr msp, %0"::"g"
- (*(volatile u32*)APP_ADDRESS));
+ (*(volatile uint32_t*)APP_ADDRESS));
/* Jump to application */
(*(void(**)())(APP_ADDRESS + 4))();
}
diff --git a/src/platforms/stm32/dfucore.c b/src/platforms/stm32/dfucore.c
index 2786e9a..a01616f 100644
--- a/src/platforms/stm32/dfucore.c
+++ b/src/platforms/stm32/dfucore.c
@@ -34,19 +34,19 @@
usbd_device *usbdev;
/* We need a special large control buffer for this device: */
-u8 usbd_control_buffer[1024];
+uint8_t usbd_control_buffer[1024];
-static u32 max_address;
+static uint32_t max_address;
static enum dfu_state usbdfu_state = STATE_DFU_IDLE;
static char *get_dev_unique_id(char *serial_no);
static struct {
- u8 buf[sizeof(usbd_control_buffer)];
- u16 len;
- u32 addr;
- u16 blocknum;
+ uint8_t buf[sizeof(usbd_control_buffer)];
+ uint16_t len;
+ uint32_t addr;
+ uint16_t blocknum;
} prog;
const struct usb_device_descriptor dev = {
@@ -121,13 +121,13 @@ static const char *usb_strings[] = {
DFU_IFACE_STRING,
};
-static u32 get_le32(const void *vp)
+static uint32_t get_le32(const void *vp)
{
- const u8 *p = vp;
- return ((u32)p[3] << 24) + ((u32)p[2] << 16) + (p[1] << 8) + p[0];
+ const uint8_t *p = vp;
+ return ((uint32_t)p[3] << 24) + ((uint32_t)p[2] << 16) + (p[1] << 8) + p[0];
}
-static u8 usbdfu_getstatus(u32 *bwPollTimeout)
+static uint8_t usbdfu_getstatus(uint32_t *bwPollTimeout)
{
switch(usbdfu_state) {
case STATE_DFU_DNLOAD_SYNC:
@@ -157,7 +157,7 @@ usbdfu_getstatus_complete(usbd_device *dev, struct usb_setup_data *req)
flash_unlock();
if(prog.blocknum == 0) {
- u32 addr = get_le32(prog.buf + 1);
+ uint32_t addr = get_le32(prog.buf + 1);
if (addr < APP_ADDRESS ||
(addr >= max_address)) {
flash_lock();
@@ -171,7 +171,7 @@ usbdfu_getstatus_complete(usbd_device *dev, struct usb_setup_data *req)
prog.addr = addr;
}
} else {
- u32 baseaddr = prog.addr +
+ uint32_t baseaddr = prog.addr +
((prog.blocknum - 2) *
dfu_function.wTransferSize);
dfu_flash_program_buffer(baseaddr, prog.buf, prog.len);
@@ -193,7 +193,7 @@ usbdfu_getstatus_complete(usbd_device *dev, struct usb_setup_data *req)
}
static int usbdfu_control_request(usbd_device *dev,
- struct usb_setup_data *req, u8 **buf, u16 *len,
+ struct usb_setup_data *req, uint8_t **buf, uint16_t *len,
void (**complete)(usbd_device *dev, struct usb_setup_data *req))
{
(void)dev;
@@ -227,7 +227,7 @@ static int usbdfu_control_request(usbd_device *dev,
/* Upload not supported for now */
return 0;
case DFU_GETSTATUS: {
- u32 bwPollTimeout = 0; /* 24-bit integer in DFU class spec */
+ uint32_t bwPollTimeout = 0; /* 24-bit integer in DFU class spec */
(*buf)[0] = usbdfu_getstatus(&bwPollTimeout);
(*buf)[1] = bwPollTimeout & 0xFF;
@@ -255,8 +255,9 @@ void dfu_init(const usbd_driver *driver)
{
get_dev_unique_id(serial_no);
- usbdev = usbd_init(driver, &dev, &config, usb_strings, 4);
- usbd_set_control_buffer_size(usbdev, sizeof(usbd_control_buffer));
+ usbdev = usbd_init(driver, &dev, &config, usb_strings, 4,
+ usbd_control_buffer, sizeof(usbd_control_buffer));
+
usbd_register_control_callback(usbdev,
USB_REQ_TYPE_CLASS | USB_REQ_TYPE_INTERFACE,
USB_REQ_TYPE_TYPE | USB_REQ_TYPE_RECIPIENT,
@@ -292,7 +293,7 @@ static char *get_dev_unique_id(char *s)
/* Calculated the upper flash limit from the exported data
in theparameter block*/
- max_address = (*(u32 *) FLASH_SIZE_R) <<10;
+ max_address = (*(uint32_t *) FLASH_SIZE_R) <<10;
/* Fetch serial number from chip's unique ID */
for(i = 0; i < 8; i++) {
s[7-i] = ((unique_id >> (4*i)) & 0xF) + '0';
diff --git a/src/platforms/stm32/jtagtap.c b/src/platforms/stm32/jtagtap.c
index d6e298b..78dd300 100644
--- a/src/platforms/stm32/jtagtap.c
+++ b/src/platforms/stm32/jtagtap.c
@@ -50,13 +50,16 @@ void jtagtap_reset(void)
jtagtap_soft_reset();
}
-void jtagtap_srst(void)
+void jtagtap_srst(bool assert)
{
-#ifdef SRST_PORT
- volatile int i;
- gpio_set(SRST_PORT, SRST_PIN);
- for(i = 0; i < 10000; i++) asm("nop");
- gpio_clear(SRST_PORT, SRST_PIN);
+ (void)assert;
+#ifdef SRST_SET_VAL
+ SRST_SET_VAL(assert);
+ if(assert) {
+ int i;
+ for(i = 0; i < 10000; i++)
+ asm volatile("nop");
+ }
#endif
}
diff --git a/src/platforms/stm32/swdptap.c b/src/platforms/stm32/swdptap.c
index 72fb0f9..e7049d3 100644
--- a/src/platforms/stm32/swdptap.c
+++ b/src/platforms/stm32/swdptap.c
@@ -73,9 +73,9 @@ int swdptap_init(void)
/* This must be investigated in more detail.
* As described in STM32 Reference Manual... */
swdptap_reset();
- swdptap_seq_out(0xE79E, 16); /* 0b0111100111100111 */
+ swdptap_seq_out(0xE79E, 16); /* 0b0111100111100111 */
swdptap_reset();
- swdptap_seq_out(0, 16);
+ swdptap_seq_out(0, 16);
return 0;
}
@@ -132,7 +132,7 @@ void swdptap_seq_out(uint32_t MS, int ticks)
while(ticks--) {
swdptap_bit_out(MS & 1);
- MS >>= 1;
+ MS >>= 1;
}
}
@@ -146,7 +146,7 @@ void swdptap_seq_out_parity(uint32_t MS, int ticks)
while(ticks--) {
swdptap_bit_out(MS & 1);
parity ^= MS;
- MS >>= 1;
+ MS >>= 1;
}
swdptap_bit_out(parity & 1);
}
diff --git a/src/platforms/swlink/platform.c b/src/platforms/swlink/platform.c
index 1aa45b1..1b45cfb 100644
--- a/src/platforms/swlink/platform.c
+++ b/src/platforms/swlink/platform.c
@@ -86,7 +86,7 @@ int platform_init(void)
AFIO_MAPR = data;
/* Setup heartbeat timer */
- systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8);
+ systick_set_clocksource(STK_CTRL_CLKSOURCE_AHB_DIV8);
systick_set_reload(900000); /* Interrupt us at 10 Hz */
SCB_SHPR(11) &= ~((15 << 4) & 0xff);
SCB_SHPR(11) |= ((14 << 4) & 0xff);
@@ -112,10 +112,10 @@ void platform_delay(uint32_t delay)
void sys_tick_handler(void)
{
- if(running_status)
+ if(running_status)
gpio_toggle(LED_PORT, led_idle_run);
- if(timeout_counter)
+ if(timeout_counter)
timeout_counter--;
}
diff --git a/src/platforms/swlink/platform.h b/src/platforms/swlink/platform.h
index c7eaca5..d0c9618 100644
--- a/src/platforms/swlink/platform.h
+++ b/src/platforms/swlink/platform.h
@@ -53,7 +53,7 @@ extern usbd_device *usbdev;
* nSRST = PA7 (input)
*
* USB cable pull-up: PA8
- * USB VBUS detect: PB13 -- New on mini design.
+ * USB VBUS detect: PB13 -- New on mini design.
* Enable pull up for compatibility.
* Force DFU mode button: PB9 Low
*/
@@ -179,21 +179,21 @@ void uart_usb_buf_drain(uint8_t ep);
#define vasprintf vasiprintf
#ifdef INLINE_GPIO
-static inline void _gpio_set(u32 gpioport, u16 gpios)
+static inline void _gpio_set(uint32_t gpioport, uint16_t gpios)
{
GPIO_BSRR(gpioport) = gpios;
}
#define gpio_set _gpio_set
-static inline void _gpio_clear(u32 gpioport, u16 gpios)
+static inline void _gpio_clear(uint32_t gpioport, uint16_t gpios)
{
GPIO_BRR(gpioport) = gpios;
}
#define gpio_clear _gpio_clear
-static inline u16 _gpio_get(u32 gpioport, u16 gpios)
+static inline uint16_t _gpio_get(uint32_t gpioport, uint16_t gpios)
{
- return (u16)GPIO_IDR(gpioport) & gpios;
+ return (uint16_t)GPIO_IDR(gpioport) & gpios;
}
#define gpio_get _gpio_get
#endif