diff --git a/doc/QEMU.txt b/doc/QEMU.txt
new file mode 100644
index 0000000000..dc02f488a7
--- /dev/null
+++ b/doc/QEMU.txt
@@ -0,0 +1,35 @@
+Note: The following procedure has only been tested using a x86-64 Linux host. Your luck may vary with any other setup
+
+It is possible to do debugging and profiling using the STM32 QEMU fork here:
+https://github.com/DeviationTX/deviation/files/2743535/errors_master_gcc8.2.txt
+
+Build from scratch:
+ git submodule update --init dtc
+ ./configure --enable-debug --target-list="arm-softmmu" --disable-werror
+ make
+Using docker may be easier (but it is untested):
+ docker build . -t qemu_stm32
+
+You will need arm-none-eabi-gdb-py for profiling. This will require a more recent Embedded GCC (recommended GCC 8):
+https://developer.arm.com/open-source/gnu-toolchain/gnu-rm/downloads
+
+The image is built using:
+ cd src
+ make qemu
+The target is an STMF103RB (same as in devo7e). running on an Olimex P103 board. this is mostly irrelevant unless
+peripheral support is added in the future
+
+Once built, it can be started in qemu using:
+ qemu-system-arm -S -s -M stm32-p103 -kernel qemu.bin
+ or if you use the docker image (you're responsible for mounting your devo build area):
+ docker run --rm qemu_stm32 /usr/local/bin/qemu-system-arm -M stm32-p103 -kernel qemu
+
+And finally the profiler can be run via gdb:
+ arm-none-eabi-gdb-py
+ source ../utils/qemu.py
+
+The code to profile can be found in target/qemu/target_main.c
+The profiler will run only on the 'run_profile()' function. All other code in main() will run 1st.
+
+Be aware that the STM32 QEMU is not feature complete. It does not support SPI, and the Clock and Timer support is limited.
+Trying to run a full image is likely to be futile.
diff --git a/src/main.c b/src/main.c
index 48438e24bc..1af1b0f3a0 100644
--- a/src/main.c
+++ b/src/main.c
@@ -36,7 +36,7 @@ void TOUCH_Handler(); // temporarily in main()
void VIDEO_Update();
void PAGE_Test();
-#ifdef TEST
+#if defined (TEST) || defined (PROFILE)
#define main _main
#endif
diff --git a/src/target/qemu/.power.c.swp b/src/target/qemu/.power.c.swp
new file mode 100644
index 0000000000..820b489e80
Binary files /dev/null and b/src/target/qemu/.power.c.swp differ
diff --git a/src/target/qemu/Makefile.inc b/src/target/qemu/Makefile.inc
new file mode 100644
index 0000000000..b3af4d79e5
--- /dev/null
+++ b/src/target/qemu/Makefile.inc
@@ -0,0 +1,47 @@
+FILESYSTEMS := common base_fonts 320x240x16
+
+SCREENSIZE := 320x240x16
+FONTS = filesystem/$(FILESYSTEM)/media/15ascii.fon \
+ filesystem/$(FILESYSTEM)/media/23bold.fon
+
+ifndef BUILD_TARGET
+CROSS = arm-none-eabi-
+
+ALL = $(LIBOPENCM3) $(TARGET).bin
+
+NUM_MODELS ?= 10
+
+LINKFILE = $(SDIR)/target/$(TARGET)/$(TARGET).ld
+LIBOPENCM3 = $(SDIR)/libopencm3/lib/libopencm3_stm32f1.a
+
+SRC_C := $(wildcard $(SDIR)/target/$(TARGET)/*.c) \
+ $(wildcard $(SDIR)/target/common/stm32/*.c) \
+ $(wildcard $(SDIR)/target/common/filesystems/*.c) \
+ $(wildcard $(SDIR)/target/common/filesystems/devofs/*.c) \
+ $(wildcard $(SDIR)/target/common/filesystems/petit_fat/*.c) \
+ $(wildcard $(SDIR)/target/common/devo/msc2/*.c) \
+ $(wildcard $(SDIR)/target/common/devo/msc2/lib/*.c) \
+ $(wildcard $(SDIR)/target/common/devo/hid/*.c) \
+ $(wildcard $(SDIR)/target/common/devo/protocol/*.c) \
+ $(wildcard $(SDIR)/target/common/devo/uart.c)
+
+SRC_C := $(filter-out $(SDIR)/target/common/stm32/spi_flash.c, $(SRC_C))
+
+CFLAGS = -DPROFILE -D"assert_param(x)=" -DSTM32F10X_HD -DSTM32F1 -mcpu=cortex-m3 -mthumb -mfix-cortex-m3-ldrd -fdata-sections -ffunction-sections -I$(SDIR)/target/common/devo/msc2/lib -I$(SDIR)/target/common/devo/msc2 -I$(SDIR)/libopencm3/include -I$(SDIR)/target/common/filesystems -fno-builtin-printf -Os --specs=nano.specs
+MODULE_FLAGS = -fno-builtin
+
+LFLAGS = -nostartfiles -Wl,-gc-sections -Wl,-Map=$(TARGET).map,--cref -lc -lnosys -L$(SDIR) -Lobjs/$(TARGET)
+LFLAGS2 = -Wl,-T$(LINKFILE)
+
+
+else #BUILD_TARGET
+
+$(TARGET).bin: $(TARGET).elf
+ $(CP) -O binary $< $@
+ $(DUMP) -S $< > $(TARGET).list
+
+$(LIBOPENCM3):
+ +$(MAKE) -C $(SDIR)/libopencm3 TARGETS=stm32/f1 lib
+
+
+endif #BUILD_TARGET
diff --git a/src/target/qemu/backlight.c b/src/target/qemu/backlight.c
new file mode 100644
index 0000000000..f70dee8224
--- /dev/null
+++ b/src/target/qemu/backlight.c
@@ -0,0 +1,75 @@
+/*
+ This project 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.
+
+ Deviation 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 Deviation. If not, see .
+*/
+
+#include
+#include
+#include
+#include "common.h"
+
+// FIXME introduce constants for Timer (TIM4), compare (TIM_Oc4)
+// timer clock (RCC_APB1ENR_TIM4EN), Port (GPIOB), Pin (GPIO9)
+// Port clock RCC_APB2ENR_IOPBEN
+
+void BACKLIGHT_Init()
+{
+ // Pin PB9, Timer 4 channel 4
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
+ //Turn off backlight
+ gpio_set_mode(GPIOB, GPIO_MODE_INPUT,
+ GPIO_CNF_INPUT_FLOAT, GPIO9);
+
+ //Configure Backlight PWM
+ rcc_peripheral_enable_clock(&RCC_APB1ENR, RCC_APB1ENR_TIM4EN);
+ timer_set_mode(TIM4, TIM_CR1_CKD_CK_INT,
+ TIM_CR1_CMS_EDGE, TIM_CR1_DIR_UP);
+ timer_set_period(TIM4, 0x2CF);
+ timer_set_prescaler(TIM4, 0);
+ timer_generate_event(TIM4, TIM_EGR_UG);
+ //timer_set_repetition_counter(TIM3, 0);
+ timer_set_oc_mode(TIM4, TIM_OC4, TIM_OCM_PWM1);
+ timer_enable_oc_preload(TIM4, TIM_OC4);
+
+ timer_set_oc_polarity_high(TIM4, TIM_OC4);
+ timer_enable_oc_output(TIM4, TIM_OC4);
+
+ timer_enable_preload(TIM4);
+}
+
+void BACKLIGHT_Brightness(unsigned brightness)
+{
+ timer_disable_counter(TIM4);
+ if (brightness == 0) {
+ // Turn off Backlight
+ gpio_set_mode(GPIOB, GPIO_MODE_INPUT,
+ GPIO_CNF_INPUT_FLOAT, GPIO9);
+ } else if(brightness > 9) {
+ // Turn on Backlight full
+ gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, GPIO9);
+ gpio_set(GPIOB, GPIO9);
+ } else {
+ gpio_set_mode(GPIOB, GPIO_MODE_OUTPUT_50_MHZ,
+ GPIO_CNF_OUTPUT_ALTFN_PUSHPULL, GPIO9);
+ u32 duty_cycle = 720 * brightness / 10 ;
+ timer_set_oc_value(TIM4, TIM_OC4, duty_cycle);
+ timer_enable_counter(TIM4);
+ }
+}
+
+void LCD_Contrast(unsigned contrast)
+{
+ (void)contrast; // dummy method for devo8. Only valid in devo10 now
+}
+
diff --git a/src/target/qemu/capabilities.h b/src/target/qemu/capabilities.h
new file mode 100644
index 0000000000..3845916efb
--- /dev/null
+++ b/src/target/qemu/capabilities.h
@@ -0,0 +1,62 @@
+#ifdef CHANDEF
+ CHANDEF(AILERON)
+ CHANDEF(ELEVATOR)
+ CHANDEF(THROTTLE)
+ CHANDEF(RUDDER)
+ CHANDEF(AUX4)
+ CHANDEF(AUX5)
+ CHANDEF(AUX6)
+ CHANDEF(AUX7)
+ CHANDEF(SWA0)
+ CHANDEF(SWA1)
+ CHANDEF(SWB0)
+ CHANDEF(SWB1)
+ CHANDEF(SWC0)
+ CHANDEF(SWC1)
+ CHANDEF(SWC2)
+ CHANDEF(SWD0)
+ CHANDEF(SWD1)
+ CHANDEF(SWE0)
+ CHANDEF(SWE1)
+ CHANDEF(SWE2)
+ CHANDEF(SWF0)
+ CHANDEF(SWF1)
+ CHANDEF(SWG0)
+ CHANDEF(SWG1)
+ CHANDEF(SWG2)
+ CHANDEF(SWH0)
+ CHANDEF(SWH1)
+#endif
+
+#ifdef UNDEF_INP
+#define INP_RUD_DR0 INP_SWA0
+#define INP_RUD_DR1 INP_SWA1
+#define INP_ELE_DR0 INP_SWB0
+#define INP_ELE_DR1 INP_SWB1
+#define INP_AIL_DR0 INP_SWC0
+#define INP_AIL_DR1 INP_SWC1
+#define INP_FMOD0 INP_SWD0
+#define INP_MIX0 INP_SWE0
+#define INP_MIX1 INP_SWE1
+#define INP_MIX2 INP_SWE2
+#define INP_GEAR0 INP_SWF0
+#define INP_GEAR1 INP_SWF1
+#endif
+
+
+#ifdef BUTTONDEF
+ BUTTONDEF(TRIM_LV_NEG) /* LEFT-VERTICAL */
+ BUTTONDEF(TRIM_LV_POS)
+ BUTTONDEF(TRIM_RV_NEG) /* RIGHT-VERTICAL */
+ BUTTONDEF(TRIM_RV_POS)
+ BUTTONDEF(TRIM_LH_NEG) /* LEFT-HORIZONTAL */
+ BUTTONDEF(TRIM_LH_POS)
+ BUTTONDEF(TRIM_RH_NEG) /* RIGHT-HORIZONTAL */
+ BUTTONDEF(TRIM_RH_POS)
+ BUTTONDEF(LEFT)
+ BUTTONDEF(RIGHT)
+ BUTTONDEF(DOWN)
+ BUTTONDEF(UP)
+ BUTTONDEF(ENTER)
+ BUTTONDEF(EXIT)
+#endif
diff --git a/src/target/qemu/channels.c b/src/target/qemu/channels.c
new file mode 100644
index 0000000000..3ea0ef7f17
--- /dev/null
+++ b/src/target/qemu/channels.c
@@ -0,0 +1,124 @@
+/*
+ This project 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.
+
+ Deviation 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 Deviation. If not, see .
+*/
+#include
+#include
+#include "common.h"
+#include "mixer.h"
+#include "config/tx.h"
+#include "../common/devo/devo.h"
+
+//Order is MODE1: AIL, ELE, THR, RUD, LeftDial, Right Dial, Left Shoulder, Right Shoulder, Vdd, Voltage
+// PA0 PA1, PA2, PA3, PA5, PA6, PB0 PA4, PB1
+const u8 adc_chan_sel[NUM_ADC_CHANNELS] =
+ {0, 1, 2, 3, 5, 6, 8, 4, 16, 9};
+
+void CHAN_Init()
+{
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPCEN);
+ ADC_Init();
+
+ /* configure channels for analog */
+ gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_ANALOG, GPIO0);
+ gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_ANALOG, GPIO1);
+ gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_ANALOG, GPIO2);
+ gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_ANALOG, GPIO3);
+ gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_ANALOG, GPIO4);
+ gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_ANALOG, GPIO5);
+ gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_ANALOG, GPIO6);
+ /* Enable Voltage measurement */
+ gpio_set_mode(GPIOB, GPIO_MODE_INPUT, GPIO_CNF_INPUT_ANALOG, GPIO0);
+ gpio_set_mode(GPIOB, GPIO_MODE_INPUT, GPIO_CNF_INPUT_ANALOG, GPIO1);
+
+ /* configure switches for digital I/O */
+ gpio_set_mode(GPIOC, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN,
+ GPIO0 | GPIO1 | GPIO2 | GPIO3 | GPIO4 |
+ GPIO5 | GPIO6 | GPIO7 | GPIO8 | GPIO9);
+ gpio_set(GPIOC,
+ GPIO0 | GPIO1 | GPIO2 | GPIO3 | GPIO4 |
+ GPIO5 | GPIO6 | GPIO7 | GPIO8 | GPIO9);
+ gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, GPIO8);
+ gpio_set(GPIOA, GPIO8);
+}
+
+s32 CHAN_ReadRawInput(int channel)
+{
+ s32 value = 0;
+ switch(channel) {
+ case INP_AILERON: value = adc_array_raw[0]; break; // bug fix: right vertical
+ case INP_ELEVATOR: value = adc_array_raw[1]; break; // bug fix: right horizon
+ case INP_THROTTLE: value = adc_array_raw[2]; break; // bug fix: left horizon
+ case INP_RUDDER: value = adc_array_raw[3]; break; // bug fix: left vertical
+ case INP_AUX4: value = adc_array_raw[4]; break;
+ case INP_AUX5: value = adc_array_raw[5]; break;
+ case INP_AUX6: value = adc_array_raw[6]; break;
+ case INP_AUX7: value = adc_array_raw[7]; break;
+ case INP_SWA0: value = gpio_get(GPIOC, GPIO0); break;
+ case INP_SWA1: value = ! gpio_get(GPIOC, GPIO0); break;
+ case INP_SWB0: value = gpio_get(GPIOC, GPIO1); break;
+ case INP_SWB1: value = ! gpio_get(GPIOC, GPIO1); break;
+ case INP_SWC0: value = ! gpio_get(GPIOC, GPIO2); break;
+ case INP_SWC1: value = (gpio_get(GPIOC, GPIO2) && gpio_get(GPIOC, GPIO3)); break;
+ case INP_SWC2: value = ! gpio_get(GPIOC, GPIO3); break;
+ case INP_SWD0: value = gpio_get(GPIOC, GPIO6); break;
+ case INP_SWD1: value = ! gpio_get(GPIOC, GPIO6); break;
+ case INP_SWE0: value = ! gpio_get(GPIOC, GPIO4); break;
+ case INP_SWE1: value = (gpio_get(GPIOC, GPIO4) && gpio_get(GPIOC, GPIO5)); break;
+ case INP_SWE2: value = ! gpio_get(GPIOC, GPIO5); break;
+ case INP_SWF0: value = gpio_get(GPIOC, GPIO7); break;
+ case INP_SWF1: value = ! gpio_get(GPIOC, GPIO7); break;
+ case INP_SWG0: value = ! gpio_get(GPIOC, GPIO8); break;
+ case INP_SWG1: value = (gpio_get(GPIOC, GPIO8) && gpio_get(GPIOC, GPIO9)); break;
+ case INP_SWG2: value = ! gpio_get(GPIOC, GPIO9); break;
+ case INP_SWH0: value = gpio_get(GPIOA, GPIO8); break;
+ case INP_SWH1: value = ! gpio_get(GPIOA, GPIO8); break;
+ }
+ return value;
+}
+s32 CHAN_ReadInput(int channel)
+{
+ s32 value = CHAN_ReadRawInput(channel);
+ if(channel <= INP_HAS_CALIBRATION) {
+ s32 max = Transmitter.calibration[channel - 1].max;
+ s32 min = Transmitter.calibration[channel - 1].min;
+ s32 zero = Transmitter.calibration[channel - 1].zero;
+ if(! zero) {
+ //If this input doesn't have a zero, calculate from max/min
+ zero = ((u32)max + min) / 2;
+ }
+ // Derate min and max by 1% to ensure we can get all the way to 100%
+ max = (max - zero) * 99 / 100;
+ min = (min - zero) * 99 / 100;
+ if(value >= zero) {
+ value = (value - zero) * CHAN_MAX_VALUE / max;
+ } else {
+ value = (value - zero) * CHAN_MIN_VALUE / min;
+ }
+ //Bound output
+ if (value > CHAN_MAX_VALUE)
+ value = CHAN_MAX_VALUE;
+ if (value < CHAN_MIN_VALUE)
+ value = CHAN_MIN_VALUE;
+ } else {
+ value = value ? CHAN_MAX_VALUE : CHAN_MIN_VALUE;
+ }
+ if (channel == INP_AILERON || channel == INP_ELEVATOR ||
+ channel == INP_THROTTLE || channel == INP_RUDDER)
+ {
+ value = -value;
+ }
+ return value;
+}
diff --git a/src/target/qemu/lcd.c b/src/target/qemu/lcd.c
new file mode 100644
index 0000000000..3ba2f60699
--- /dev/null
+++ b/src/target/qemu/lcd.c
@@ -0,0 +1,55 @@
+/*
+ This project 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.
+
+ Deviation 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 Deviation. If not, see .
+*/
+#include
+#include
+#include
+#include "common.h"
+#include "lcd.h"
+
+u8 screen_flip;
+const struct lcdtype *disp_type;
+
+void lcd_cmd(uint8_t addr, uint8_t data)
+{
+}
+
+void lcd_set_pos(unsigned int x0, unsigned int y0)
+{
+}
+
+void LCD_DrawPixel(unsigned int color)
+{
+}
+
+void LCD_DrawPixelXY(unsigned int x, unsigned int y, unsigned int color)
+{
+}
+
+void LCD_DrawStart(unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1, enum DrawDir dir)
+{
+}
+
+void LCD_DrawStop(void)
+{
+}
+
+void LCD_Sleep()
+{
+}
+
+void LCD_Init()
+{
+}
+
diff --git a/src/target/qemu/lcd.h b/src/target/qemu/lcd.h
new file mode 100644
index 0000000000..48b990bbdf
--- /dev/null
+++ b/src/target/qemu/lcd.h
@@ -0,0 +1,23 @@
+#ifndef _DEVO8_LCD_H_
+#define _DEVO8_LCD_H_
+
+#include
+
+#define LCD_REG_ADDR ((uint32_t)FSMC_BANK1_BASE) /* Register Address */
+#define LCD_DATA_ADDR ((uint32_t)FSMC_BANK1_BASE + 0x20000) /* Data Address */
+
+#define LCD_REG *(volatile uint16_t *)(LCD_REG_ADDR)
+#define LCD_DATA *(volatile uint16_t *)(LCD_DATA_ADDR)
+
+struct lcdtype {
+ void (*set_pos)(unsigned int x0, unsigned int y0);
+ void (*draw_start)(unsigned int x0, unsigned int y0, unsigned int x1, unsigned int y1);
+ void (*sleep)();
+};
+extern const struct lcdtype *disp_type;
+extern uint8_t screen_flip;
+
+extern void lcd_cmd(uint8_t addr, uint8_t data);
+
+extern void ili9341_init();
+#endif
diff --git a/src/target/qemu/power.c b/src/target/qemu/power.c
new file mode 100644
index 0000000000..633246a6a5
--- /dev/null
+++ b/src/target/qemu/power.c
@@ -0,0 +1,62 @@
+#include
+#include
+#include
+#include "common.h"
+#include "../common/devo/devo.h"
+
+void PWR_Init(void)
+{
+ SCB_VTOR = VECTOR_TABLE_LOCATION;
+ SCB_SCR &= ~SCB_SCR_SLEEPONEXIT; //sleep immediate on WFI
+ rcc_clock_setup_in_hse_8mhz_out_72mhz();
+
+ /* Enable GPIOA and GPIOE so we can blink LEDs! */
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPEEN);
+
+ /* Disable SWD - SWDIO PA13 is used for Green LED */
+ AFIO_MAPR = (AFIO_MAPR & ~AFIO_MAPR_SWJ_MASK) | AFIO_MAPR_SWJ_CFG_JTAG_OFF_SW_OFF;
+
+ /* Green LED - pin PA13 */
+ gpio_set_mode(GPIOA, GPIO_MODE_OUTPUT_50_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, GPIO13);
+
+ /* Pin to ground - LED lit */
+ gpio_clear(GPIOA, GPIO13);
+
+ /* Red LED - pin PE1 */
+ gpio_set_mode(GPIOE, GPIO_MODE_OUTPUT_50_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, GPIO1);
+
+ /* Pin to Vcc - LED down */
+ gpio_set(GPIOE, GPIO1);
+}
+
+/* AT9 uses a hard power switch */
+int PWR_CheckPowerSwitch()
+{
+ return 0;
+}
+
+void PWR_Shutdown()
+{
+ printf("Shutdown\n");
+ BACKLIGHT_Brightness(0);
+ rcc_set_sysclk_source(RCC_CFGR_SW_SYSCLKSEL_HSICLK);
+ rcc_wait_for_osc_ready(HSI);
+ while(1) ;
+}
+
+void PWR_Sleep()
+{
+ //asm("wfi");
+}
+
+/* Return milivolts */
+unsigned PWR_ReadVoltage(void)
+{
+ u32 v = adc_array_raw[NUM_ADC_CHANNELS-1];
+ /* Multily the above by 1000 to get milivolts */
+ v = v * VOLTAGE_NUMERATOR / 100 + VOLTAGE_OFFSET;
+ return v;
+}
diff --git a/src/target/qemu/protospi.h b/src/target/qemu/protospi.h
new file mode 100644
index 0000000000..f92e30a4c1
--- /dev/null
+++ b/src/target/qemu/protospi.h
@@ -0,0 +1,17 @@
+#ifndef _SPIPROTO_H_
+#define _SPIPROTO_H_
+
+#include
+#include
+
+u8 PROTOSPI_read3wire();
+
+#define PROTOSPI_pin_set(io) gpio_set(io.port,io.pin)
+#define PROTOSPI_pin_clear(io) gpio_clear(io.port,io.pin)
+#define PROTOSPI_xfer(byte) spi_xfer(SPI2, byte)
+#define _NOP() asm volatile ("nop")
+
+#define _SPI_CYRF_RESET_PIN {GPIOB, GPIO11}
+#define _SPI_AVR_RESET_PIN {GPIO_BANK_JTCK_SWCLK, GPIO_JTCK_SWCLK}
+
+#endif // _SPIPROTO_H_
diff --git a/src/target/qemu/qemu.ld b/src/target/qemu/qemu.ld
new file mode 100644
index 0000000000..63f531912c
--- /dev/null
+++ b/src/target/qemu/qemu.ld
@@ -0,0 +1,10 @@
+MEMORY
+{
+ rom (rx) : ORIGIN = 0x08000000, LENGTH = 512K /* 12K is allocated to the bootloader, so only 500K is available */
+ ram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
+}
+_crc_offset = 0x1000; /* This is unneccessary but saves duplicating the ld file */
+/*
+ * INCLUDE ../target/common/devo/devo.ld
+ */
+INCLUDE target/common/devo/devo.ld
diff --git a/src/target/qemu/qemu_ports.h b/src/target/qemu/qemu_ports.h
new file mode 100644
index 0000000000..7263fb6c0c
--- /dev/null
+++ b/src/target/qemu/qemu_ports.h
@@ -0,0 +1,50 @@
+#ifndef _RADIOLINK_AT9_PORTS_H
+#define _RADIOLINK_AT9_PORTS_H
+
+#define FREQ_MHz 72
+
+#define SYSCLK_TIM 3
+
+#define _SPI_FLASH_PORT 2 //SPI2
+ #define _SPI_FLASH_CSN_PIN {GPIOB, GPIO12}
+ #define _SPI_FLASH_SCK_PIN {GPIOB, GPIO13}
+ #define _SPI_FLASH_MISO_PIN {GPIOB, GPIO14}
+ #define _SPI_FLASH_MOSI_PIN {GPIOB, GPIO15}
+
+#include "../../common/devo/ports.h"
+
+#if 0
+// _SPI_PROTO_PORT defined in ports.h
+
+#if 0 // defined in ports.h
+ #define _USART USART1
+ #define _USART_DR USART1_DR
+ #define _USART_DMA DMA1
+ #define _USART_DMA_CHANNEL DMA_CHANNEL4
+ #define _USART_DMA_ISR dma1_channel4_isr
+ #define _USART_NVIC_DMA_CHANNEL_IRQ NVIC_DMA1_CHANNEL4_IRQ
+ #define _USART_RCC_APB_ENR_IOP RCC_APB2ENR
+ #define _USART_RCC_APB_ENR_IOP_EN RCC_APB2ENR_IOPAEN
+ #define _USART_RCC_APB_ENR_USART RCC_APB2ENR
+ #define _USART_RCC_APB_ENR_USART_EN RCC_APB2ENR_USART1EN
+ #define _USART_GPIO GPIOA
+ #define _USART_GPIO_USART_TX GPIO_USART1_TX
+ #define _USART_GPIO_USART_RX GPIO_USART1_RX
+ #define _USART_ISR usart1_isr
+ #define _USART_NVIC_USART_IRQ NVIC_USART1_IRQ
+#endif
+
+#define ADC_OVERSAMPLE_WINDOW_COUNT 1
+ #define _ADC ADC1
+ #define _RCC_APB2ENR_ADCEN RCC_APB2ENR_ADC1EN
+ #define _RCC_APB2RSTR_ADCRST RCC_APB2RSTR_ADC1RST
+ #define _ADC_SMPR_SMP_XXDOT5CYC ADC_SMPR_SMP_239DOT5CYC
+ #define _DMA DMA1
+ #define _DMA_CHANNEL DMA_CHANNEL1
+ #define _RCC_AHBENR_DMAEN RCC_AHBENR_DMA1EN
+ #define _DMA_ISR dma1_channel1_isr
+ #define _DMA_IFCR_CGIF DMA_IFCR_CGIF1
+ #define _NVIC_DMA_CHANNEL_IRQ NVIC_DMA1_CHANNEL1_IRQ
+#endif
+
+#endif //_RADIOLINK_AT9_PORTS_H
diff --git a/src/target/qemu/qemu_stubs.c b/src/target/qemu/qemu_stubs.c
new file mode 100644
index 0000000000..6985ee34cd
--- /dev/null
+++ b/src/target/qemu/qemu_stubs.c
@@ -0,0 +1,108 @@
+/*
+ This project 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.
+
+ Deviation 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 Deviation. If not, see .
+*/
+#include
+#include
+#include
+#include
+
+#include "common.h"
+//void USB_Enable(unsigned type, unsigned use_interrupt) {
+// (void) type;
+// (void)use_interrupt;
+//}
+//void USB_Disable() {}
+void init_err_handler() {}
+
+void SOUND_Init() {}
+void SOUND_SetFrequency(unsigned frequency, unsigned volume) {
+ (void)frequency;
+ (void)volume;
+}
+void SOUND_Start(unsigned msec, u16(*next_note_cb)(), u8 vibrate) {
+ (void)msec;
+ (void)next_note_cb;
+ (void)vibrate;
+}
+void SOUND_StartWithoutVibrating(unsigned msec, u16(*next_note_cb)()) {
+ (void)msec;
+ (void)next_note_cb;
+}
+void SOUND_Stop() {}
+u32 SOUND_Callback() { return 0;}
+
+#if !defined HAS_4IN1_FLASH || !HAS_4IN1_FLASH
+void SPIFlash_Init() {}
+void SPI_FlashBlockWriteEnable(unsigned enable) {
+ (void)enable;
+}
+
+#define FS_ADDRESS (void *)0x08040000
+void SPIFlash_ReadBytes(u32 readAddress, u32 length, u8 * buffer) {
+ u8 *address = FS_ADDRESS + readAddress;
+ for(unsigned i=0;i.
+ */
+
+#include
+#include
+#include
+#include "common.h"
+//#include "../common/devo/devo.h"
+#include "config/tx.h"
+//#include "protocol/interface.h"
+//#include
+
+
+void SPI_ProtoInit()
+{
+// If we use SPI Switch board then SPI2 is shared between RF chips
+// and flash, so it is initialized in SPIFlash.
+//#if !defined HAS_4IN1_FLASH || !HAS_4IN1_FLASH
+#if _SPI_PROTO_PORT != _SPI_FLASH_PORT
+ #if _SPI_PROTO_PORT == 1
+ #define SPIx SPI1
+ #define SPIxEN RCC_APB2ENR_SPI1EN
+ #define APB_SPIxEN RCC_APB2ENR
+ #elif _SPI_PROTO_PORT == 2
+ #define SPIx SPI2
+ #define SPIxEN RCC_APB1ENR_SPI2EN
+ #define APB_SPIxEN RCC_APB1ENR
+ #endif
+ /* Enable SPIx */
+ rcc_peripheral_enable_clock(&APB_SPIxEN, SPIxEN);
+ /* Enable GPIOA */
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
+ /* Enable GPIOB */
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
+
+ PORT_mode_setup(PROTO_RST_PIN, GPIO_MODE_OUTPUT_50_MHZ, GPIO_CNF_OUTPUT_PUSHPULL);
+ PORT_mode_setup(PROTO_CSN_PIN, GPIO_MODE_OUTPUT_50_MHZ, GPIO_CNF_OUTPUT_PUSHPULL);
+ PORT_mode_setup(PROTO_SCK_PIN, GPIO_MODE_OUTPUT_50_MHZ, GPIO_CNF_OUTPUT_ALTFN_PUSHPULL);
+ PORT_mode_setup(PROTO_MOSI_PIN, GPIO_MODE_OUTPUT_50_MHZ, GPIO_CNF_OUTPUT_ALTFN_PUSHPULL);
+ PORT_mode_setup(PROTO_MISO_PIN, GPIO_MODE_INPUT, GPIO_CNF_INPUT_FLOAT);
+
+ PORT_pin_clear(PROTO_RST_PIN);
+ PORT_pin_set(PROTO_CSN_PIN);
+
+
+ /* Includes enable? */
+ spi_init_master(SPIx,
+ SPI_CR1_BAUDRATE_FPCLK_DIV_16,
+ SPI_CR1_CPOL_CLK_TO_0_WHEN_IDLE,
+ SPI_CR1_CPHA_CLK_TRANSITION_1,
+ SPI_CR1_DFF_8BIT,
+ SPI_CR1_MSBFIRST);
+ spi_enable_software_slave_management(SPIx);
+ spi_set_nss_high(SPIx);
+ spi_enable(SPIx);
+#endif
+}
+
+void MCU_InitModules()
+{
+}
+
+int MCU_SetPin(struct mcu_pin *port, const char *name) {
+// (void)port;
+ (void)name;
+ port->port = 1;
+ return 1;
+}
diff --git a/src/target/qemu/target_defs.h b/src/target/qemu/target_defs.h
new file mode 100644
index 0000000000..b5d7034149
--- /dev/null
+++ b/src/target/qemu/target_defs.h
@@ -0,0 +1,95 @@
+#ifndef _AT9_TARGET_DEFS_H_
+#define _AT9_TARGET_DEFS_H_
+
+#define TXID 0xA9
+#define VECTOR_TABLE_LOCATION 0x3000
+
+#define SPIFLASH_SECTOR_OFFSET 0x0000
+
+#if defined HAS_4IN1_FLASH && HAS_4IN1_FLASH
+ #define SPIFLASH_SECTORS 1024
+ #define SPIFLASH_TYPE IS25CQxxx
+#else
+ #define SPIFLASH_SECTORS 64
+ #define USE_PBM_IMAGE 1
+ #define USE_DEVOFS 1 //Must be before common_devo include
+#endif
+
+#define DISABLE_PWM 1 //FIXME
+#define NO_LANGUAGE_SUPPORT 1
+
+#ifndef FATSTRUCT_SIZE
+ #if defined USE_DEVOFS && USE_DEVOFS == 1
+ #include "enable_devofs.h"
+ #else
+ #include "enable_petit_fat.h"
+ #endif
+#endif
+
+#ifndef LCD_ForceUpdate
+static inline void LCD_ForceUpdate() {}
+#endif
+
+#define USE_4BUTTON_MODE 1
+#define HAS_STANDARD_GUI 0
+#define HAS_ADVANCED_GUI 1
+#define HAS_PERMANENT_TIMER 1
+#define HAS_TELEMETRY 1
+#define HAS_EXTENDED_TELEMETRY 1
+#define HAS_TOUCH 0
+#define HAS_RTC 0
+#define HAS_VIBRATINGMOTOR 1
+#define HAS_DATALOG 1
+#define HAS_LAYOUT_EDITOR 1
+#define HAS_SCANNER 0
+#define HAS_EXTRA_SWITCHES 0
+#define HAS_EXTRA_BUTTONS 0
+#define HAS_MULTIMOD_SUPPORT 0
+//#define HAS_4IN1_FLASH 1 // NB set in the Makefile.inc
+#define HAS_VIDEO 0
+#define HAS_EXTENDED_AUDIO 0
+#define HAS_AUDIO_UART5 0
+#define HAS_MUSIC_CONFIG 0
+#define HAS_HARD_POWER_OFF 1
+#define HAS_ROTARY_ENCODER 1
+
+#ifdef BUILDTYPE_DEV
+ #define DEBUG_WINDOW_SIZE 200
+#else
+ #define DEBUG_WINDOW_SIZE 0
+#endif
+
+#define MIN_BRIGHTNESS 0
+#define DEFAULT_BATTERY_ALARM 8000
+#define DEFAULT_BATTERY_CRITICAL 7500
+#define MAX_BATTERY_ALARM 12000
+#define MIN_BATTERY_ALARM 5500
+#define MAX_POWER_ALARM 60
+
+#define NUM_OUT_CHANNELS 16
+#define NUM_VIRT_CHANNELS 10
+
+#define NUM_TRIMS 10
+#define MAX_POINTS 13
+#define NUM_MIXERS ((NUM_OUT_CHANNELS + NUM_VIRT_CHANNELS) * 4)
+
+#define INP_HAS_CALIBRATION 8
+
+/* Compute voltage from y = 0.003672x + 0.0287 */
+#define VOLTAGE_NUMERATOR 367
+#define VOLTAGE_OFFSET 29
+#include "qemu_ports.h"
+
+
+/* Define button placement for chantest page*/
+/* these are supposed to more closely match real Tx button layout */
+/* negative value: box at the right side of the label */
+#define CHANTEST_BUTTON_PLACEMENT { \
+ {51, 120}, {51, 105}, {-229, 120}, {-229, 105}, \
+ {-106, 135}, {21, 135}, {-259, 135}, {174, 135}, \
+ {30, 71}, {30, 56}, {-250, 71}, {-250, 56}, \
+ {185, 220}, {185, 200}, \
+ }
+
+
+#endif //_AT9_TARGET_DEFS_H_
diff --git a/src/target/qemu/target_main.c b/src/target/qemu/target_main.c
new file mode 100644
index 0000000000..9662876a0d
--- /dev/null
+++ b/src/target/qemu/target_main.c
@@ -0,0 +1,51 @@
+#include
+#include
+#include
+#include
+#include "common.h"
+#include "mixer.h"
+#include "config/tx.h"
+#include "config/model.h"
+#include "../common/devo/devo.h"
+
+void run_profile();
+void init_profile();
+int main()
+{
+ SCB_VTOR = VECTOR_TABLE_LOCATION;
+ SCB_SCR &= ~SCB_SCR_SLEEPONEXIT; //sleep immediate on WFI
+ rcc_clock_setup_in_hse_8mhz_out_72mhz();
+ systick_set_clocksource(STK_CSR_CLKSOURCE_AHB_DIV8);
+ systick_set_reload(0x00FFFFFF);
+ systick_counter_enable();
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPCEN);
+ gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_50_MHZ,
+ GPIO_CNF_OUTPUT_PUSHPULL, GPIO12);
+ gpio_clear(GPIOC, GPIO12);
+ gpio_set(GPIOC, GPIO12);
+ gpio_clear(GPIOC, GPIO12);
+
+ init_profile();
+ run_profile();
+}
+
+void init_profile() {
+ for (int i = 0; i < INP_HAS_CALIBRATION; i++)
+ {
+ Transmitter.calibration[i].min = CHAN_MIN_VALUE;
+ Transmitter.calibration[i].max = CHAN_MAX_VALUE;
+ Transmitter.calibration[i].zero = 0;
+ }
+ memset(Model.mixers, 0, sizeof(Model.mixers));
+ for (unsigned i = 0; i < 1; i++) {
+ Model.mixers[i].src = 1;
+ Model.mixers[i].dest = (2 + i) % 5;
+ Model.mixers[i].scalar = 100;
+ Model.mixers[i].flags = MUX_REPLACE;
+ }
+ Model.num_channels = 12;
+}
+
+void __attribute__ ((noinline)) run_profile() {
+ MIXER_CalcChannels();
+}
diff --git a/src/target/qemu/tx_buttons.c b/src/target/qemu/tx_buttons.c
new file mode 100644
index 0000000000..720cfc2ea6
--- /dev/null
+++ b/src/target/qemu/tx_buttons.c
@@ -0,0 +1,113 @@
+/*
+ This project 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.
+
+ Deviation 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 Deviation. If not, see .
+*/
+#include
+#include
+#include
+#include
+
+#include "common.h"
+
+// To use interpretation of rapid rotary movement as long press
+// this timeout should be less than long press timeout, 100ms
+#define ROTARY_TIMEOUT 50
+
+static volatile int rotary = 0;
+static u32 last_rotary_clock = 0;
+
+void Initialize_ButtonMatrix()
+{
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPAEN);
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPBEN);
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPCEN);
+ rcc_peripheral_enable_clock(&RCC_APB2ENR, RCC_APB2ENR_IOPDEN);
+
+ /* Mode and End */
+ gpio_set_mode(GPIOA, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN, GPIO14 | GPIO15);
+ gpio_set(GPIOA, GPIO14 | GPIO15);
+ /* Trim */
+ gpio_set_mode(GPIOB, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN,
+ GPIO3 | GPIO4 | GPIO5 | GPIO6);
+ gpio_set(GPIOB, GPIO3 | GPIO4 | GPIO5 | GPIO6);
+ /*Rotary */
+ gpio_set_mode(GPIOC, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN,
+ GPIO13 | GPIO14 | GPIO15);
+ gpio_set(GPIOC, GPIO13 | GPIO14 | GPIO15);
+ /* Trim */
+ gpio_set_mode(GPIOD, GPIO_MODE_INPUT, GPIO_CNF_INPUT_PULL_UPDOWN,
+ GPIO2 | GPIO3 | GPIO12 | GPIO13);
+ gpio_set(GPIOD, GPIO2 | GPIO3 | GPIO12 | GPIO13);
+
+ nvic_enable_irq(NVIC_EXTI15_10_IRQ);
+ nvic_set_priority(NVIC_EXTI15_10_IRQ, 66); //Medium priority
+ exti_select_source(EXTI13 | EXTI14, GPIOC);
+ exti_set_trigger(EXTI13 | EXTI14, EXTI_TRIGGER_BOTH);
+ exti_enable_request(EXTI13 | EXTI14);
+}
+
+/* returns change in encoder state (-1,0,1) */
+int handle_rotary_encoder(unsigned val)
+{
+// static const s8 enc_states[] = {0,-1,1,0,1,0,0,-1,-1,0,0,1,0,1,-1,0};
+ static const s8 enc_states[] = {0,0,0,0,0,0,0,-1,0,0,0,1,0,0,0,0};
+ static unsigned old_AB = 0;
+ /**/
+ old_AB <<= 2; //remember previous state
+ old_AB |= val & 0x03; //add current state
+ return ( enc_states[( old_AB & 0x0f )]);
+}
+
+void exti15_10_isr()
+{
+ u32 button = gpio_port_read(GPIOC);
+ exti_reset_request(EXTI13 | EXTI14);
+ button = 0x03 & ((~button) >> 13);
+ int dir = handle_rotary_encoder(button);
+ if (button == 0) {
+ rotary = 0;
+ } else {
+ rotary = dir;
+ }
+}
+
+u32 ScanButtons()
+{
+ int last_rotary;
+ u32 result = 0;
+ result |= ! gpio_get(GPIOB, GPIO6) ? CHAN_ButtonMask(BUT_TRIM_LV_NEG) : 0;
+ result |= ! gpio_get(GPIOB, GPIO5) ? CHAN_ButtonMask(BUT_TRIM_LV_POS) : 0;
+ result |= ! gpio_get(GPIOD, GPIO3) ? CHAN_ButtonMask(BUT_TRIM_RV_NEG) : 0;
+ result |= ! gpio_get(GPIOD, GPIO2) ? CHAN_ButtonMask(BUT_TRIM_RV_POS) : 0;
+ result |= ! gpio_get(GPIOD, GPIO13) ? CHAN_ButtonMask(BUT_TRIM_LH_NEG) : 0;
+ result |= ! gpio_get(GPIOD, GPIO12) ? CHAN_ButtonMask(BUT_TRIM_LH_POS) : 0;
+ result |= ! gpio_get(GPIOB, GPIO4) ? CHAN_ButtonMask(BUT_TRIM_RH_NEG) : 0;
+ result |= ! gpio_get(GPIOB, GPIO3) ? CHAN_ButtonMask(BUT_TRIM_RH_POS) : 0;
+
+ result |= ! gpio_get(GPIOA, GPIO14) ? CHAN_ButtonMask(BUT_RIGHT) : 0; // MODE
+ result |= ! gpio_get(GPIOC, GPIO15) ? CHAN_ButtonMask(BUT_ENTER) : 0;
+ result |= ! gpio_get(GPIOA, GPIO15) ? CHAN_ButtonMask(BUT_EXIT) : 0;
+
+ last_rotary = rotary;
+ if (last_rotary) {
+ u32 rotary_clock = CLOCK_getms();
+ // To prevent rotary to generate button clicks too frequently we register
+ // an event in 'result' not more often than every ROTARY_TIMEOUT msec
+ if (rotary_clock > last_rotary_clock) {
+ result |= last_rotary > 0 ? CHAN_ButtonMask(BUT_DOWN) : CHAN_ButtonMask(BUT_UP);
+ last_rotary_clock = rotary_clock + ROTARY_TIMEOUT;
+ }
+ rotary = 0;
+ }
+ return result;
+}
diff --git a/src/target/qemu/tx_misc.c b/src/target/qemu/tx_misc.c
new file mode 100644
index 0000000000..afb62900a7
--- /dev/null
+++ b/src/target/qemu/tx_misc.c
@@ -0,0 +1,15 @@
+#include "common.h"
+#include "config/tx.h"
+
+void _usleep(u32 x)
+{
+ (void)x;
+ asm ("mov r1, #24;"
+ "mul r0, r0, r1;"
+ "b _delaycmp;"
+ "_delayloop:"
+ "subs r0, r0, #1;"
+ "_delaycmp:;"
+ "cmp r0, #0;"
+ " bne _delayloop;");
+}
diff --git a/utils/qemu.py b/utils/qemu.py
new file mode 100644
index 0000000000..23df920209
--- /dev/null
+++ b/utils/qemu.py
@@ -0,0 +1,89 @@
+# This script will profile the qemu.bin build and produce a calltrace log
+# It is meant to be loaded from within gdb via:
+# arm-none-eabi-gdb-py
+# source gdb
+# profile
+# An STM32 QEMU is needed (either docker or natively compiled): https://github.com/beckus/qemu_stm32
+# QEMU is started before running gdb via:
+# qemu-system-arm -S -s -M stm32-p103 -kernel qemu.bin
+
+import gdb
+
+compress = True
+
+class func:
+ def __init__(self, parent, pc, lr, name):
+ self.exclusive = 0
+ self.parent = parent
+ self.pc = pc
+ self.lr = lr
+ self.children = []
+ self.name = name
+ def newchild(self, pc, lr, name):
+ if compress:
+ for child in self.children:
+ if child.pc == pc:
+ child.lr = lr
+ return child
+ newfunc = func(self, pc, lr, name)
+ self.children.append(newfunc)
+ return newfunc
+
+def printstack(trace, depth=""):
+ inclusive = trace.exclusive
+ childstr = ""
+ for child in trace.children:
+ _str, incl = printstack(child, depth + " ")
+ childstr += _str
+ inclusive += incl
+ childstr = "{}{} 0x{:02x} (ex:{} inc:{})\n".format(depth, trace.name, trace.pc, trace.exclusive, inclusive) + childstr
+ if depth == "":
+ print childstr
+ else:
+ return childstr, inclusive
+
+topfunc = func(None, 0, 0, None)
+
+class Profile(gdb.Command):
+ def __init__(self):
+ # This registers our class as "simple_command"
+ super(Profile, self).__init__("profile", gdb.COMMAND_DATA)
+ gdb.execute("file qemu.elf")
+ gdb.execute("target remote localhost:1234")
+ gdb.execute("set pagination off")
+ self.trace = topfunc
+
+ def invoke(self, arg, from_tty):
+ # When we call "simple_command" from gdb, this is the method
+ # that will be called.
+ #gdb.execute("set logging file /dev/null")
+ #gdb.execute("set logging redirect on")
+ #gdb.execute("set logging on")
+ gdb.execute("b run_profile")
+ gdb.execute("c")
+ gdb.execute("disable")
+ stop_pc = gdb.newest_frame().older().pc()
+
+ last_lr = int(gdb.parse_and_eval('$lr'))-1
+ while True:
+ frame = gdb.newest_frame()
+ pc = frame.pc()
+ lr = int(gdb.parse_and_eval('$lr'))-1
+ if pc == self.trace.lr:
+ print "Returned from {:02x}".format(self.trace.pc)
+ self.trace = self.trace.parent
+ #return
+ elif lr != last_lr:
+ self.trace = self.trace.newchild(pc, lr, frame.name())
+ print "Called {}{:02x} (return: {:02x})".format(frame.name(), pc, lr)
+ #return
+ if pc == 0 or pc == stop_pc:
+ break;
+ self.trace.exclusive += 1
+ last_lr = lr
+ gdb.execute("si")
+ #gdb.execute("set logging off")
+ #gdb.execute("display")
+ printstack(topfunc)
+
+Profile()