aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--src/include/gdb_if.h2
-rw-r--r--src/main.c2
-rw-r--r--src/platforms/dev2/Makefile.inc3
-rw-r--r--src/platforms/dev2/jtagtap.c79
-rw-r--r--src/platforms/dev2/platform.c171
-rw-r--r--src/platforms/dev2/platform.h95
-rw-r--r--src/platforms/dev2/swdptap.c171
-rw-r--r--src/platforms/libftdi/Makefile.inc2
8 files changed, 522 insertions, 3 deletions
diff --git a/src/include/gdb_if.h b/src/include/gdb_if.h
index 3307454..4d2f5ea 100644
--- a/src/include/gdb_if.h
+++ b/src/include/gdb_if.h
@@ -21,7 +21,7 @@
#ifndef __GDB_IF_H
#define __GDB_IF_H
-#if !defined(LIBFTDI)
+#if !defined(HOST)
#include <libopencm3/usb/usbd.h>
void gdb_usb_out_cb(usbd_device *dev, uint8_t ep);
#endif
diff --git a/src/main.c b/src/main.c
index 4921aed..aed3e80 100644
--- a/src/main.c
+++ b/src/main.c
@@ -36,7 +36,7 @@
int
main(int argc, char **argv)
{
-#if defined(LIBFTDI)
+#if defined(HOST)
assert(platform_init(argc, argv) == 0);
#else
(void) argc;
diff --git a/src/platforms/dev2/Makefile.inc b/src/platforms/dev2/Makefile.inc
new file mode 100644
index 0000000..ce45067
--- /dev/null
+++ b/src/platforms/dev2/Makefile.inc
@@ -0,0 +1,3 @@
+CFLAGS += -DHOST
+
+vpath gdb_if.c platforms/libftdi
diff --git a/src/platforms/dev2/jtagtap.c b/src/platforms/dev2/jtagtap.c
new file mode 100644
index 0000000..30cf9f8
--- /dev/null
+++ b/src/platforms/dev2/jtagtap.c
@@ -0,0 +1,79 @@
+/*
+ * This file is part of the Black Magic Debug project.
+ *
+ * Copyright (C) 2011 Black Sphere Technologies Ltd.
+ * Written by Gareth McMullin <gareth@blacksphere.co.nz>
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ */
+
+/* This file implements the low-level JTAG TAP interface. */
+
+#include <stdio.h>
+
+#include "general.h"
+
+#include "jtagtap.h"
+#include "platform.h"
+
+int jtagtap_init(void)
+{
+ /* Make sure TMS is still output (shared with SWDIO). */
+ uint8_t cmd[] = { DEV2_OP_DIR_OUT, TMS_PIN };
+ platform_buffer_write (cmd, sizeof (cmd));
+
+ /* Go to JTAG mode for SWJ-DP */
+ for(int i = 0; i <= 50; i++) jtagtap_next(1, 0); /* Reset SW-DP */
+ jtagtap_tms_seq(0xE73C, 16); /* SWD to JTAG sequence */
+ jtagtap_soft_reset();
+
+ return 0;
+}
+
+void jtagtap_reset(void)
+{
+ jtagtap_soft_reset();
+}
+
+void jtagtap_srst(void)
+{
+}
+
+inline uint8_t jtagtap_next(uint8_t dTMS, uint8_t dTDO)
+{
+ uint8_t cmd[] = {
+ DEV2_OP_OUT_CHANGE, TMS_PIN | TDI_PIN,
+ (dTMS ? TMS_PIN : 0) | (dTDO ? TDI_PIN : 0),
+ DEV2_OP_OUT_SET, TCK_PIN,
+ DEV2_OP_IN,
+ DEV2_OP_OUT_RESET, TCK_PIN,
+ };
+ platform_buffer_write (cmd, sizeof (cmd));
+ uint8_t rep[1];
+ platform_buffer_read (rep, sizeof (rep));
+ int ret = rep[0] & TDO_PIN;
+
+ DEBUG("jtagtap_next(TMS = %d, TDO = %d) = %d\n", dTMS, dTDO, ret);
+
+ return ret != 0;
+}
+
+
+
+#define PROVIDE_GENERIC_JTAGTAP_TMS_SEQ
+#define PROVIDE_GENERIC_JTAGTAP_TDI_TDO_SEQ
+#define PROVIDE_GENERIC_JTAGTAP_TDI_SEQ
+
+#include "jtagtap_generic.c"
+
diff --git a/src/platforms/dev2/platform.c b/src/platforms/dev2/platform.c
new file mode 100644
index 0000000..3d5929b
--- /dev/null
+++ b/src/platforms/dev2/platform.c
@@ -0,0 +1,171 @@
+/*
+ * This file is part of the Black Magic Debug project.
+ *
+ * Copyright (C) 2011 Black Sphere Technologies Ltd.
+ * Written by Gareth McMullin <gareth@blacksphere.co.nz>
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ */
+#include "platform.h"
+#include "gdb_if.h"
+#include "jtag_scan.h"
+
+#include <stdlib.h>
+#include <stdarg.h>
+#include <string.h>
+#include <assert.h>
+#include <termios.h>
+#include <unistd.h>
+#include <errno.h>
+#include <sys/types.h>
+#include <sys/stat.h>
+#include <fcntl.h>
+
+static int serial_fd = -1;
+static int debug;
+
+#define BUF_SIZE 4096
+static uint8_t outbuf[BUF_SIZE];
+static uint16_t bufptr = 0;
+
+int serial_open(const char *name)
+{
+ int fd;
+ /* Open. */
+ fd = open(name, O_RDWR | O_NOCTTY);
+ if (fd == -1)
+ return -1;
+ /* Setup raw. */
+ struct termios tc;
+ if(tcgetattr(fd, &tc) == -1) {
+ close(fd);
+ return -1;
+ }
+ tc.c_iflag &= ~(IGNPAR | PARMRK | ISTRIP | IGNBRK | BRKINT | IGNCR |
+ ICRNL | INLCR | IXON | IXOFF | IXANY | IMAXBEL);
+ tc.c_oflag &= ~(OPOST);
+ tc.c_cflag &= ~(HUPCL | CSTOPB | PARENB | PARODD | CSIZE);
+ tc.c_cflag |= CS8 | CLOCAL | CREAD;
+ tc.c_lflag &= ~(ICANON | ECHO | ISIG | IEXTEN | NOFLSH | TOSTOP);
+ tc.c_cc[VTIME] = 0;
+ tc.c_cc[VMIN] = 1;
+ tcflush(fd, TCIFLUSH);
+ if(tcsetattr(fd, TCSANOW, &tc) == -1) {
+ close(fd);
+ return -1;
+ }
+ return fd;
+}
+
+int platform_init(int argc, char **argv)
+{
+ int c;
+ char *serial = NULL;
+
+ while((c = getopt(argc, argv, "ds:")) != -1) {
+ switch(c) {
+ case 'd':
+ debug = 1;
+ break;
+ case 's':
+ serial = optarg;
+ break;
+ }
+ }
+ if(optind != argc) {
+ fprintf(stderr, "too many arguments\n");
+ abort();
+ }
+
+ serial_fd = serial_open(serial);
+ if(serial_fd == -1) {
+ fprintf(stderr, "unable to open serial device: %s\n",
+ strerror(errno));
+ abort();
+ }
+
+ uint8_t init_str[] = {
+ DEV2_OP_RESET_SYNC, DEV2_OP_RESET_SYNC, DEV2_OP_RESET_SYNC,
+ DEV2_OP_RESET_SYNC, DEV2_OP_RESET_SYNC, DEV2_OP_RESET_SYNC,
+ DEV2_OP_RESET_SYNC, DEV2_OP_RESET_SYNC, DEV2_OP_RESET_SYNC,
+ DEV2_OP_RESET_SYNC, DEV2_OP_RESET_SYNC, DEV2_OP_RESET_SYNC,
+ DEV2_OP_SETUP, 8, 0, 0, 0, 0,
+ DEV2_OP_DIR, TMS_PIN | TCK_PIN | TDI_PIN
+ };
+ platform_buffer_write (init_str, sizeof (init_str));
+
+ assert(gdb_if_init() == 0);
+
+ jtag_scan(NULL);
+
+ return 0;
+}
+
+void platform_buffer_flush(void)
+{
+ if(bufptr) {
+ assert(write(serial_fd, outbuf, bufptr) == bufptr);
+ bufptr = 0;
+ }
+}
+
+int platform_buffer_write(const uint8_t *data, int size)
+{
+ if((bufptr + size) / BUF_SIZE > 0) platform_buffer_flush();
+ memcpy(outbuf + bufptr, data, size);
+ bufptr += size;
+ return size;
+}
+
+int platform_buffer_read(uint8_t *data, int size)
+{
+ int index = 0;
+ platform_buffer_flush();
+ while((index += read(serial_fd, data + index, size - index)) != size);
+ return size;
+}
+
+#ifdef WIN32
+#warning "This vasprintf() is dubious!"
+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))
+ *strp = realloc(*strp, size <<= 1);
+
+ return ret;
+}
+#endif
+
+const char *platform_target_voltage(void)
+{
+ return "not supported";
+}
+
+void platform_delay(uint32_t delay)
+{
+ usleep(delay * 100000);
+}
+
+void platform_debug(const char *fmt, ...)
+{
+ if(debug) {
+ va_list ap;
+ va_start(ap, fmt);
+ vprintf(fmt, ap);
+ va_end(ap);
+ }
+}
diff --git a/src/platforms/dev2/platform.h b/src/platforms/dev2/platform.h
new file mode 100644
index 0000000..c35c839
--- /dev/null
+++ b/src/platforms/dev2/platform.h
@@ -0,0 +1,95 @@
+/*
+ * This file is part of the Black Magic Debug project.
+ *
+ * Copyright (C) 2011 Black Sphere Technologies Ltd.
+ * Written by Gareth McMullin <gareth@blacksphere.co.nz>
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ */
+
+#ifndef __PLATFORM_H
+#define __PLATFORM_H
+
+#include <stdint.h>
+#include <stdio.h>
+
+#ifndef WIN32
+# include <alloca.h>
+#else
+# define alloca __builtin_alloca
+#endif
+
+/* All communications are big endian. */
+
+/* Reset communication and set all pins as input. */
+#define DEV2_OP_RESET_SYNC 0xa5
+/* Set port width (1 byte argument) and period (4 bytes, in ns unit).
+ * Port width will determine the size of a port argument (1 byte for 8, 2
+ * bytes for 16...). Period is the pause between two output changes, 0 means
+ * as fast as possible. */
+#define DEV2_OP_SETUP 0xaa
+
+/* Set complete port direction, 1 is output. */
+#define DEV2_OP_DIR 0xb0
+/* Set direction as output for selected pins. */
+#define DEV2_OP_DIR_OUT 0xb1
+/* Set direction as input for selected pins. */
+#define DEV2_OP_DIR_IN 0xb2
+/* Set complete output port value. */
+#define DEV2_OP_OUT 0xb4
+/* Set pins in output port. */
+#define DEV2_OP_OUT_SET 0xb5
+/* Reset pins in output port. */
+#define DEV2_OP_OUT_RESET 0xb6
+/* Toggle pins in output port. */
+#define DEV2_OP_OUT_TOGGLE 0xb7
+/* Change pins (mask as first argument, value as second argument). */
+#define DEV2_OP_OUT_CHANGE 0xb8
+/* Request port input. */
+#define DEV2_OP_IN 0xb9
+
+
+/* Pins definition. */
+#define TDI_PIN 0x80
+#define TMS_PIN 0x01
+#define TCK_PIN 0x02
+#define TDO_PIN 0x40
+#define SWDIO_PIN TMS_PIN
+#define SWCLK_PIN TCK_PIN
+#undef TRST_PIN
+#undef SRST_PIN
+
+#define SET_RUN_STATE(state)
+#define SET_IDLE_STATE(state)
+#define SET_ERROR_STATE(state)
+
+#define PLATFORM_FATAL_ERROR(error) abort()
+#define PLATFORM_SET_FATAL_ERROR_RECOVERY()
+
+#define DEBUG(...) platform_debug(__VA_ARGS__)
+
+#define morse(x, y) do { if (x) fprintf(stderr,"%s\n", x); } while (0)
+#define morse_msg 0
+
+int platform_init(int argc, char **argv);
+const char *platform_target_voltage(void);
+void platform_delay(uint32_t delay);
+
+void platform_buffer_flush(void);
+int platform_buffer_write(const uint8_t *data, int size);
+int platform_buffer_read(uint8_t *data, int size);
+void platform_debug(const char *fmt, ...);
+
+#endif
+
diff --git a/src/platforms/dev2/swdptap.c b/src/platforms/dev2/swdptap.c
new file mode 100644
index 0000000..50f9bbb
--- /dev/null
+++ b/src/platforms/dev2/swdptap.c
@@ -0,0 +1,171 @@
+/*
+ * This file is part of the Black Magic Debug project.
+ *
+ * Copyright (C) 2011 Black Sphere Technologies Ltd.
+ * Written by Gareth McMullin <gareth@blacksphere.co.nz>
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program. If not, see <http://www.gnu.org/licenses/>.
+ */
+
+/* This file implements the low-level SW-DP interface. */
+
+#include <stdio.h>
+
+#include "general.h"
+
+#include "swdptap.h"
+
+#include "gdb_packet.h"
+
+static void swdptap_turnaround(uint8_t dir)
+{
+ static uint8_t olddir = 0;
+
+ DEBUG("%s", dir ? "\n-> ":"\n<- ");
+
+ /* Don't turnaround if direction not changing */
+ if(dir == olddir) return;
+ olddir = dir;
+
+ uint8_t cmd[6];
+ int i = 0;
+
+ if(dir) {
+ cmd[i++] = DEV2_OP_DIR_IN;
+ cmd[i++] = SWDIO_PIN;
+ }
+ cmd[i++] = DEV2_OP_OUT_SET;
+ cmd[i++] = SWCLK_PIN;
+ cmd[i++] = DEV2_OP_OUT_RESET;
+ cmd[i++] = SWCLK_PIN;
+ if(!dir)
+ {
+ cmd[i++] = DEV2_OP_DIR_OUT;
+ cmd[i++] = SWDIO_PIN;
+ }
+ platform_buffer_write(cmd, i);
+}
+
+static uint8_t swdptap_bit_in(void)
+{
+ uint8_t cmd[] = {
+ DEV2_OP_IN,
+ DEV2_OP_OUT_SET, SWCLK_PIN,
+ DEV2_OP_OUT_RESET, SWCLK_PIN,
+ };
+ platform_buffer_write (cmd, sizeof (cmd));
+ uint8_t rep[1];
+ platform_buffer_read (rep, sizeof (rep));
+ int ret = rep[0] & SWDIO_PIN;
+
+ DEBUG("%d", ret?1:0);
+
+ return ret != 0;
+}
+
+static void swdptap_bit_out(uint8_t val)
+{
+ DEBUG("%d", val);
+
+ uint8_t cmd[] = {
+ DEV2_OP_OUT_CHANGE, SWDIO_PIN, (val ? SWDIO_PIN : 0),
+ DEV2_OP_OUT_SET, SWCLK_PIN,
+ DEV2_OP_OUT_RESET, SWCLK_PIN,
+ };
+ platform_buffer_write (cmd, sizeof (cmd));
+}
+
+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_reset();
+ swdptap_seq_out(0, 16);
+
+ return 0;
+}
+
+
+void swdptap_reset(void)
+{
+ swdptap_turnaround(0);
+ /* 50 clocks with TMS high */
+ for(int i = 0; i < 50; i++) swdptap_bit_out(1);
+}
+
+
+uint32_t swdptap_seq_in(int ticks)
+{
+ uint32_t index = 1;
+ uint32_t ret = 0;
+
+ swdptap_turnaround(1);
+
+ while(ticks--) {
+ if(swdptap_bit_in()) ret |= index;
+ index <<= 1;
+ }
+
+ return ret;
+}
+
+
+uint8_t swdptap_seq_in_parity(uint32_t *ret, int ticks)
+{
+ uint32_t index = 1;
+ uint8_t parity = 0;
+ *ret = 0;
+
+ swdptap_turnaround(1);
+
+ while(ticks--) {
+ if(swdptap_bit_in()) {
+ *ret |= index;
+ parity ^= 1;
+ }
+ index <<= 1;
+ }
+ if(swdptap_bit_in()) parity ^= 1;
+
+ return parity;
+}
+
+
+void swdptap_seq_out(uint32_t MS, int ticks)
+{
+ swdptap_turnaround(0);
+
+ while(ticks--) {
+ swdptap_bit_out(MS & 1);
+ MS >>= 1;
+ }
+}
+
+
+void swdptap_seq_out_parity(uint32_t MS, int ticks)
+{
+ uint8_t parity = 0;
+
+ swdptap_turnaround(0);
+
+ while(ticks--) {
+ swdptap_bit_out(MS & 1);
+ parity ^= MS;
+ MS >>= 1;
+ }
+ swdptap_bit_out(parity & 1);
+}
+
diff --git a/src/platforms/libftdi/Makefile.inc b/src/platforms/libftdi/Makefile.inc
index fa6292b..7be436a 100644
--- a/src/platforms/libftdi/Makefile.inc
+++ b/src/platforms/libftdi/Makefile.inc
@@ -1,2 +1,2 @@
-CFLAGS += -DLIBFTDI
+CFLAGS += -DHOST
LDFLAGS += -lftdi -lusb