diff --git a/src/DAP42.c b/src/DAP42.c
index 16dd542..d8d460f 100644
--- a/src/DAP42.c
+++ b/src/DAP42.c
@@ -80,7 +80,7 @@ int main(void) {
clock_setup();
tick_setup(1000);
gpio_setup();
- led_num(0);
+ LED_CONNECTED_OUT(0);
if (CDC_AVAILABLE) {
console_setup(DEFAULT_BAUDRATE);
@@ -97,7 +97,7 @@ int main(void) {
retarget(STDERR_FILENO, CONSOLE_USART);
}
- led_num(1);
+ LED_CONNECTED_OUT(1);
{
char serial[USB_SERIAL_NUM_LENGTH+1];
@@ -157,9 +157,15 @@ int main(void) {
int x;
for (x=0; x < 3; x++) {
iwdg_reset();
- led_num(7);
+ LED_CONNECTED_OUT(1);
+ LED_ACTIVITY_OUT(1);
+ LED_RUNNING_OUT(1);
+// led_num(1);
wait_ms(150);
- led_num(0);
+ LED_CONNECTED_OUT(0);
+ LED_ACTIVITY_OUT(0);
+ LED_RUNNING_OUT(0);
+// led_num(0);
wait_ms(150);
iwdg_reset();
}
diff --git a/src/stm32f103/DAP/CMSIS_DAP_hal.h b/src/stm32f103/DAP/CMSIS_DAP_hal.h
index 0a6e7a7..b6986e7 100644
--- a/src/stm32f103/DAP/CMSIS_DAP_hal.h
+++ b/src/stm32f103/DAP/CMSIS_DAP_hal.h
@@ -191,26 +191,44 @@ static __inline void PIN_nRESET_OUT (uint32_t bit) {
static __inline void LED_CONNECTED_OUT (uint32_t bit) {
if ((bit & 0x1) ^ LED_OPEN_DRAIN) {
+#ifndef LED_CON_DISABLE
+#ifdef LED_CON_INVERT
+ gpio_clear(LED_CON_GPIO_PORT, LED_CON_GPIO_PIN);
+ } else {
+ gpio_set(LED_CON_GPIO_PORT, LED_CON_GPIO_PIN);
+#else
gpio_set(LED_CON_GPIO_PORT, LED_CON_GPIO_PIN);
} else {
gpio_clear(LED_CON_GPIO_PORT, LED_CON_GPIO_PIN);
+#endif
}
+#else
+ (void) bit;
+#endif
}
static __inline void LED_RUNNING_OUT (uint32_t bit) {
+#ifndef LED_RUN_DISABLE
if ((bit & 0x1) ^ LED_OPEN_DRAIN) {
gpio_set(LED_RUN_GPIO_PORT, LED_RUN_GPIO_PIN);
} else {
gpio_clear(LED_RUN_GPIO_PORT, LED_RUN_GPIO_PIN);
}
+#else
+ (void) bit;
+#endif
}
static __inline void LED_ACTIVITY_OUT (uint32_t bit) {
+#ifndef LED_ACT_DISABLE
if ((bit & 0x1) ^ LED_OPEN_DRAIN) {
gpio_set(LED_ACT_GPIO_PORT, LED_ACT_GPIO_PIN);
} else {
gpio_clear(LED_ACT_GPIO_PORT, LED_ACT_GPIO_PIN);
}
+#else
+ (void) bit;
+#endif
}
static __inline void DAP_SETUP (void) {
diff --git a/src/stm32f103/daplink_f103c6/DAP/CMSIS_DAP_config.h b/src/stm32f103/daplink_f103c6/DAP/CMSIS_DAP_config.h
new file mode 100644
index 0000000..a04e24d
--- /dev/null
+++ b/src/stm32f103/daplink_f103c6/DAP/CMSIS_DAP_config.h
@@ -0,0 +1,180 @@
+/*
+ * Copyright (c) 2013-2017 ARM Limited. All rights reserved.
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ *
+ * Licensed under the Apache License, Version 2.0 (the License); you may
+ * not use this file except in compliance with the License.
+ * You may obtain a copy of the License at
+ *
+ * www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an AS IS BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ *
+ * ----------------------------------------------------------------------
+ *
+ * $Date: 1. December 2017
+ * $Revision: V2.0.0
+ *
+ * Project: CMSIS-DAP Configuration
+ * Title: DAP_config.h CMSIS-DAP Configuration File (Template)
+ *
+ *---------------------------------------------------------------------------*/
+
+#ifndef __DAP_CONFIG_H__
+#define __DAP_CONFIG_H__
+
+
+//**************************************************************************************************
+/**
+\defgroup DAP_Config_Debug_gr CMSIS-DAP Debug Unit Information
+\ingroup DAP_ConfigIO_gr
+@{
+Provides definitions about the hardware and configuration of the Debug Unit.
+
+This information includes:
+ - Definition of Cortex-M processor parameters used in CMSIS-DAP Debug Unit.
+ - Debug Unit Identification strings (Vendor, Product, Serial Number).
+ - Debug Unit communication packet size.
+ - Debug Access Port supported modes and settings (JTAG/SWD and SWO).
+ - Optional information about a connected Target Device (for Evaluation Boards).
+*/
+
+#include "config.h"
+
+// Board configuration options
+
+/// Processor Clock of the Cortex-M MCU used in the Debug Unit.
+/// This value is used to calculate the SWD/JTAG clock speed.
+#define CPU_CLOCK 72000000U ///< Specifies the CPU Clock in Hz.
+
+/// Number of processor cycles for I/O Port write operations.
+/// This value is used to calculate the SWD/JTAG clock speed that is generated with I/O
+/// Port write operations in the Debug Unit by a Cortex-M MCU. Most Cortex-M processors
+/// require 2 processor cycles for a I/O Port Write operation. If the Debug Unit uses
+/// a Cortex-M0+ processor with high-speed peripheral I/O only 1 processor cycle might be
+/// required.
+#define IO_PORT_WRITE_CYCLES 2U ///< I/O Cycles: 2=default, 1=Cortex-M0+ fast I/0.
+
+/// Indicate that Serial Wire Debug (SWD) communication mode is available at the Debug Access Port.
+/// This information is returned by the command \ref DAP_Info as part of Capabilities.
+#define DAP_SWD 1 ///< SWD Mode: 1 = available, 0 = not available.
+
+/// Indicate that JTAG communication mode is available at the Debug Port.
+/// This information is returned by the command \ref DAP_Info as part of Capabilities.
+#if defined(CONF_JTAG)
+#define DAP_JTAG 1 ///< JTAG Mode: 1 = available
+#else
+#define DAP_JTAG 0 ///< JTAG Mode: 0 = not available
+#endif
+
+/// Configure maximum number of JTAG devices on the scan chain connected to the Debug Access Port.
+/// This setting impacts the RAM requirements of the Debug Unit. Valid range is 1 .. 255.
+#define DAP_JTAG_DEV_CNT 8U ///< Maximum number of JTAG devices on scan chain
+
+/// Default communication mode on the Debug Access Port.
+/// Used for the command \ref DAP_Connect when Port Default mode is selected.
+#define DAP_DEFAULT_PORT 1U ///< Default JTAG/SWJ Port Mode: 1 = SWD, 2 = JTAG.
+
+/// Default communication speed on the Debug Access Port for SWD and JTAG mode.
+/// Used to initialize the default SWD/JTAG clock frequency.
+/// The command \ref DAP_SWJ_Clock can be used to overwrite this default setting.
+#define DAP_DEFAULT_SWJ_CLOCK 10000000U ///< Default SWD/JTAG clock frequency in Hz.
+
+/// Maximum Package Size for Command and Response data.
+/// This configuration settings is used to optimize the communication performance with the
+/// debugger and depends on the USB peripheral. Typical vales are 64 for Full-speed USB HID or WinUSB,
+/// 1024 for High-speed USB HID and 512 for High-speed USB WinUSB.
+#define DAP_PACKET_SIZE 64U ///< Specifies Packet Size in bytes.
+
+/// Maximum Package Buffers for Command and Response data.
+/// This configuration settings is used to optimize the communication performance with the
+/// debugger and depends on the USB peripheral. For devices with limited RAM or USB buffer the
+/// setting can be reduced (valid range is 1 .. 255).
+#define DAP_PACKET_COUNT 12U ///< Specifies number of packets buffered.
+
+#define DAP_PACKET_QUEUE_SIZE (DAP_PACKET_COUNT+8)
+
+/// Indicate that UART Serial Wire Output (SWO) trace is available.
+/// This information is returned by the command \ref DAP_Info as part of Capabilities.
+#define SWO_UART 0 ///< SWO UART: 1 = available, 0 = not available.
+
+/// Maximum SWO UART Baudrate.
+#define SWO_UART_MAX_BAUDRATE 10000000U ///< SWO UART Maximum Baudrate in Hz.
+
+/// Indicate that Manchester Serial Wire Output (SWO) trace is available.
+/// This information is returned by the command \ref DAP_Info as part of Capabilities.
+#define SWO_MANCHESTER 0 ///< SWO Manchester: 1 = available, 0 = not available.
+
+/// SWO Trace Buffer Size.
+#define SWO_BUFFER_SIZE 1024U ///< SWO Trace Buffer Size in bytes (must be 2^n).
+
+/// SWO Streaming Trace.
+#define SWO_STREAM 0 ///< SWO Streaming Trace: 1 = available, 0 = not available.
+
+/// Clock frequency of the Test Domain Timer. Timer value is returned with \ref TIMESTAMP_GET.
+#define TIMESTAMP_CLOCK 1000U ///< Timestamp clock in Hz (0 = timestamps not supported).
+
+/// Debug Unit is connected to fixed Target Device.
+/// The Debug Unit may be part of an evaluation board and always connected to a fixed
+/// known device. In this case a Device Vendor and Device Name string is stored which
+/// may be used by the debugger or IDE to configure device parameters.
+#define TARGET_DEVICE_FIXED 0 ///< Target Device: 1 = known, 0 = unknown;
+
+#if TARGET_DEVICE_FIXED
+#define TARGET_DEVICE_VENDOR "" ///< String indicating the Silicon Vendor
+#define TARGET_DEVICE_NAME "" ///< String indicating the Target Device
+#endif
+
+/** Get Vendor ID string.
+\param str Pointer to buffer to store the string.
+\return String length.
+*/
+static inline uint8_t DAP_GetVendorString (char *str) {
+ (void)str;
+ return (0U);
+}
+
+/** Get Product ID string.
+\param str Pointer to buffer to store the string.
+\return String length.
+*/
+static inline uint8_t DAP_GetProductString (char *str) {
+ (void)str;
+ return (0U);
+}
+
+/** Get Serial Number string.
+\param str Pointer to buffer to store the string.
+\return String length.
+*/
+static inline uint8_t DAP_GetSerNumString (char *str) {
+ (void)str;
+ return (0U);
+}
+
+///@}
+
+#define SWCLK_GPIO_PORT GPIOA
+#define SWCLK_GPIO_PIN GPIO4
+#define SWDIO_GPIO_PORT GPIOA
+#define SWDIO_GPIO_PIN GPIO2
+#define nRESET_GPIO_PORT GPIOA
+#define nRESET_GPIO_PIN GPIO6
+
+#define LED_CON_INVERT
+#define LED_CON_GPIO_PORT GPIOB
+#define LED_CON_GPIO_PIN GPIO8
+#define LED_RUN_DISABLE
+#define LED_RUN_GPIO_PORT GPIOB
+#define LED_RUN_GPIO_PIN GPIO8
+#define LED_ACT_GPIO_PORT GPIOB
+#define LED_ACT_GPIO_PIN GPIO12
+
+#define SWDIO_GPIO_PIN_NUM 2
+
+#endif /* __DAP_CONFIG_H__ */
diff --git a/src/stm32f103/daplink_f103c6/DFU b/src/stm32f103/daplink_f103c6/DFU
new file mode 120000
index 0000000..5cc14a8
--- /dev/null
+++ b/src/stm32f103/daplink_f103c6/DFU
@@ -0,0 +1 @@
+../bluepill/DFU
\ No newline at end of file
diff --git a/src/stm32f103/daplink_f103c6/USB/usb_setup.c b/src/stm32f103/daplink_f103c6/USB/usb_setup.c
new file mode 100644
index 0000000..7c4ed1f
--- /dev/null
+++ b/src/stm32f103/daplink_f103c6/USB/usb_setup.c
@@ -0,0 +1,37 @@
+/*
+ * Copyright (c) 2016, Devan Lai
+ *
+ * Permission to use, copy, modify, and/or distribute this software
+ * for any purpose with or without fee is hereby granted, provided
+ * that the above copyright notice and this permission notice
+ * appear in all copies.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL
+ * WARRANTIES WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED
+ * WARRANTIES OF MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE
+ * AUTHOR BE LIABLE FOR ANY SPECIAL, DIRECT, INDIRECT, OR
+ * CONSEQUENTIAL DAMAGES OR ANY DAMAGES WHATSOEVER RESULTING FROM
+ * LOSS OF USE, DATA OR PROFITS, WHETHER IN AN ACTION OF CONTRACT,
+ * NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF OR IN
+ * CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
+ */
+
+#include
+#include
+#include
+
+#include "USB/usb_setup.h"
+
+const usbd_driver* target_usb_init(void) {
+ rcc_periph_reset_pulse(RST_USB);
+
+ /* Force re-enumeration */
+ rcc_periph_clock_enable(RCC_GPIOA);
+ gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_10_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, GPIO12);
+ gpio_clear(GPIOA, GPIO12);
+ int i;
+ for (i = 0; i < 800000; i++)
+ __asm__("nop");
+ return &st_usbfs_v1_usb_driver;
+}
diff --git a/src/stm32f103/daplink_f103c6/config.h b/src/stm32f103/daplink_f103c6/config.h
new file mode 100644
index 0000000..5eac260
--- /dev/null
+++ b/src/stm32f103/daplink_f103c6/config.h
@@ -0,0 +1,62 @@
+/*
+ * Copyright (c) 2016, Devan Lai
+ *
+ * Permission to use, copy, modify, and/or distribute this software
+ * for any purpose with or without fee is hereby granted, provided
+ * that the above copyright notice and this permission notice
+ * appear in all copies.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL
+ * WARRANTIES WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED
+ * WARRANTIES OF MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE
+ * AUTHOR BE LIABLE FOR ANY SPECIAL, DIRECT, INDIRECT, OR
+ * CONSEQUENTIAL DAMAGES OR ANY DAMAGES WHATSOEVER RESULTING FROM
+ * LOSS OF USE, DATA OR PROFITS, WHETHER IN AN ACTION OF CONTRACT,
+ * NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF OR IN
+ * CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
+ */
+
+#ifndef CONFIG_H_INCLUDED
+#define CONFIG_H_INCLUDED
+
+#define PRODUCT_NAME "DAPLINK-F103C6"
+
+#define CAN_RX_AVAILABLE 0
+#define CAN_TX_AVAILABLE 0
+
+#define VCDC_AVAILABLE 0
+#define VCDC_TX_BUFFER_SIZE 128
+#define VCDC_RX_BUFFER_SIZE 128
+
+#define CDC_AVAILABLE 1
+#define DEFAULT_BAUDRATE 115200
+
+#define CONSOLE_USART USART1
+#define CONSOLE_TX_BUFFER_SIZE 128
+#define CONSOLE_RX_BUFFER_SIZE 1024
+
+#define CONSOLE_USART_GPIO_PORT GPIOA
+#define CONSOLE_USART_GPIO_TX GPIO9
+#define CONSOLE_USART_GPIO_RX GPIO10
+
+#define CONSOLE_USART_MODE USART_MODE_TX_RX
+
+#define CONSOLE_USART_CLOCK RCC_USART1
+
+#define CONSOLE_USART_IRQ_NAME usart1_isr
+#define CONSOLE_USART_NVIC_LINE NVIC_USART1_IRQ
+#define CONSOLE_RX_DMA_CONTROLLER DMA1
+#define CONSOLE_RX_DMA_CLOCK RCC_DMA1
+#define CONSOLE_RX_DMA_CHANNEL DMA_CHANNEL5
+
+#define TARGET_DFU_AVAILABLE 0
+
+/* Word size for usart_recv and usart_send */
+typedef uint16_t usart_word_t;
+
+/* Workaround for non-commonalized STM32F0 USART code */
+#define USART_RDR(usart_base) USART_DR(usart_base)
+
+#define LED_OPEN_DRAIN 0
+
+#endif
diff --git a/src/stm32f103/daplink_f103c6/target.c b/src/stm32f103/daplink_f103c6/target.c
new file mode 100644
index 0000000..f7044ed
--- /dev/null
+++ b/src/stm32f103/daplink_f103c6/target.c
@@ -0,0 +1,110 @@
+/*
+ * Copyright (c) 2016, Devan Lai
+ *
+ * Permission to use, copy, modify, and/or distribute this software
+ * for any purpose with or without fee is hereby granted, provided
+ * that the above copyright notice and this permission notice
+ * appear in all copies.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL
+ * WARRANTIES WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED
+ * WARRANTIES OF MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE
+ * AUTHOR BE LIABLE FOR ANY SPECIAL, DIRECT, INDIRECT, OR
+ * CONSEQUENTIAL DAMAGES OR ANY DAMAGES WHATSOEVER RESULTING FROM
+ * LOSS OF USE, DATA OR PROFITS, WHETHER IN AN ACTION OF CONTRACT,
+ * NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF OR IN
+ * CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
+ */
+
+#include
+#include
+
+#include "target.h"
+#include "config.h"
+#include "DAP/CMSIS_DAP_config.h"
+
+/* Reconfigure processor settings */
+void cpu_setup(void) {
+
+}
+
+/* Set STM32 to 72 MHz. */
+void clock_setup(void) {
+ // rcc_clock_setup_in_hse_8mhz_out_72mhz();
+ rcc_clock_setup_pll(&rcc_hse_configs[RCC_CLOCK_HSE8_72MHZ]);
+}
+
+void gpio_setup(void) {
+ /*
+ LED0, 1, 2 on PC13
+ TX, RX (MCU-side) on PA2, PA3
+ TGT_RST on PB0
+ TGT_SWDIO, TGT_SWCLK on PB14, PB13
+ TGT_SWO on PB11
+ */
+
+ /* Enable GPIOA, GPIOB and GPIOC clocks. */
+ rcc_periph_clock_enable(RCC_GPIOA);
+ rcc_periph_clock_enable(RCC_GPIOB);
+ rcc_periph_clock_enable(RCC_GPIOC);
+
+ /* Setup LEDs as open-drain outputs */
+ const uint8_t mode = GPIO_MODE_OUTPUT_10_MHZ;
+ const uint8_t conf = (LED_OPEN_DRAIN ? GPIO_CNF_OUTPUT_OPENDRAIN
+ : GPIO_CNF_OUTPUT_PUSHPULL);
+#ifndef LED_CON_DISABLE
+ gpio_set_mode(LED_CON_GPIO_PORT, mode, conf, LED_CON_GPIO_PIN);
+#endif
+#ifndef LED_RUN_DISABLE
+ gpio_set_mode(LED_RUN_GPIO_PORT, mode, conf, LED_RUN_GPIO_PIN);
+#endif
+#ifndef LED_ACT_DISABLE
+ gpio_set_mode(LED_ACT_GPIO_PORT, mode, conf, LED_ACT_GPIO_PIN);
+#endif
+}
+
+void target_console_init(void){
+ /* Enable UART clock */
+ rcc_periph_clock_enable(CONSOLE_USART_CLOCK);
+
+ /* Setup GPIO pins */
+ gpio_set_mode(CONSOLE_USART_GPIO_PORT, GPIO_MODE_OUTPUT_50_MHZ,
+ GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, CONSOLE_USART_GPIO_TX);
+ gpio_set_mode(CONSOLE_USART_GPIO_PORT, GPIO_MODE_INPUT,
+ GPIO_CNF_INPUT_FLOAT, CONSOLE_USART_GPIO_RX);
+}
+
+/*
+void led_bit(uint8_t position, bool state) {
+ uint32_t gpio = 0xFFFFFFFFU;
+ if (position == 0) {
+ gpio = GPIO13;
+ }
+
+ if (gpio != 0xFFFFFFFFU) {
+ if (state ^ LED_OPEN_DRAIN) {
+ gpio_set(GPIOC, gpio);
+ } else {
+ gpio_clear(GPIOC, gpio);
+ }
+ }
+}
+
+void led_num(uint8_t value) {
+ if ((value & 0x1) ^ LED_OPEN_DRAIN) {
+ gpio_set(LED_CON_GPIO_PORT, LED_CON_GPIO_PIN);
+ } else {
+ gpio_clear(LED_CON_GPIO_PORT, LED_CON_GPIO_PIN);
+ }
+ if (( (value>>1) & 0x1) ^ LED_OPEN_DRAIN) {
+ gpio_set(LED_RUN_GPIO_PORT, LED_RUN_GPIO_PIN);
+ } else {
+ gpio_clear(LED_RUN_GPIO_PORT, LED_RUN_GPIO_PIN);
+ }
+ if (( (value>>2) & 0x1) ^ LED_OPEN_DRAIN) {
+ gpio_set(LED_ACT_GPIO_PORT, LED_ACT_GPIO_PIN);
+ } else {
+ gpio_clear(LED_ACT_GPIO_PORT, LED_ACT_GPIO_PIN);
+ }
+}
+*/
diff --git a/src/stm32f103/stm32f103x6-dfuboot.ld b/src/stm32f103/stm32f103x6-dfuboot.ld
new file mode 100644
index 0000000..c8c549d
--- /dev/null
+++ b/src/stm32f103/stm32f103x6-dfuboot.ld
@@ -0,0 +1,30 @@
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * Copyright (C) 2015 Karl Palsson
+ *
+ * This library is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU Lesser General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This library 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 Lesser General Public License for more details.
+ *
+ * You should have received a copy of the GNU Lesser General Public License
+ * along with this library. If not, see .
+ */
+
+/* Linker script for STM32F103x8, 64k flash, 20k RAM. */
+
+/* Define memory regions. */
+MEMORY
+{
+ rom (rx) : ORIGIN = 0x08002000, LENGTH = 24K
+ ram (rwx) : ORIGIN = 0x20000000, LENGTH = 10K
+}
+
+/* Include the common ld script. */
+INCLUDE cortex-m-generic.ld
diff --git a/src/targets.mk b/src/targets.mk
index 54c03c9..cd37bea 100644
--- a/src/targets.mk
+++ b/src/targets.mk
@@ -109,6 +109,14 @@ ifeq ($(TARGET),STLINKV2-1-STBOOT)
DEFS += -DDFU_AVAILABLE=1
ARCH = STM32F1
endif
+ifeq ($(TARGET),DAPLINK_F103C6-DFUBOOT)
+ TARGET_COMMON_DIR := ./stm32f103
+ TARGET_SPEC_DIR := ./stm32f103/daplink_f103c6
+ LDSCRIPT ?= ./stm32f103/stm32f103x6-dfuboot.ld
+ DEFS += -DDFU_AVAILABLE=1
+ ARCH = STM32F1
+ DFU_VID_PID := 1209:db42
+endif
ifndef ARCH
$(error Unknown target $(TARGET))
endif