Skip to content

Commit

Permalink
Added PX4 IO V3
Browse files Browse the repository at this point in the history
  • Loading branch information
David Sidrane committed Oct 31, 2016
1 parent aa292c3 commit ac45014
Show file tree
Hide file tree
Showing 8 changed files with 705 additions and 1 deletion.
4 changes: 4 additions & 0 deletions Makefile
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,7 @@ TARGETS = \
px4fmuv4_bl \
px4fmuv4pro_bl \
px4io_bl \
px4iov3_bl \
tapv1_bl \

all: $(TARGETS)
Expand Down Expand Up @@ -97,6 +98,9 @@ crazyflie_bl: $(MAKEFILE_LIST) $(LIBOPENCM3)
px4io_bl: $(MAKEFILE_LIST) $(LIBOPENCM3)
make -f Makefile.f1 TARGET_HW=PX4_PIO_V1 LINKER_FILE=stm32f1.ld TARGET_FILE_NAME=$@

px4iov3_bl: $(MAKEFILE_LIST) $(LIBOPENCM3)
make -f Makefile.f3 TARGET_HW=PX4_PIO_V3 LINKER_FILE=stm32f3.ld TARGET_FILE_NAME=$@

tapv1_bl: $(MAKEFILE_LIST) $(LIBOPENCM3)
make -f Makefile.f4 TARGET_HW=TAP_V1 LINKER_FILE=stm32f4.ld TARGET_FILE_NAME=$@

Expand Down
38 changes: 38 additions & 0 deletions Makefile.f3
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
#
# PX4 bootloader build rules for STM32F3 targets.
#

OPENOCD ?= openocd

JTAGCONFIG ?= interface/olimex-jtag-tiny.cfg
#JTAGCONFIG ?= interface/jtagkey-tiny.cfg

# 5 seconds / 5000 ms default delay
PX4_BOOTLOADER_DELAY ?= 5000

SRCS = $(COMMON_SRCS) main_f3.c

FLAGS += -mthumb -mcpu=cortex-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 \
-DTARGET_HW_$(TARGET_HW) \
-DSTM32F3 \
-T$(LINKER_FILE) \
-L$(LIBOPENCM3)/lib \
-lopencm3_stm32f3 \
$(EXTRAFLAGS)

ELF = $(TARGET_FILE_NAME).elf
BINARY = $(TARGET_FILE_NAME).bin

all: $(ELF) $(BINARY)

$(ELF): $(SRCS) $(MAKEFILE_LIST)
$(CC) -o $@ $(SRCS) $(FLAGS)

$(BINARY): $(ELF)
$(OBJCOPY) -O binary $(ELF) $(BINARY)

#upload: all flash flash-bootloader
upload: all flash-bootloader

flash-bootloader:
$(OPENOCD) --search ../px4_bootloader -f $(JTAGCONFIG) -f stm32f3x.cfg -c init -c "reset halt" -c "flash write_image erase $(BINARY) 0x08000000" -c "reset run" -c shutdown
3 changes: 2 additions & 1 deletion cdcacm.c
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@
#include <libopencm3/usb/cdc.h>

#include "bl.h"

#if INTERFACE_USB != 0
#define USB_CDC_REQ_GET_LINE_CODING 0x21 // Not defined in libopencm3


Expand Down Expand Up @@ -379,3 +379,4 @@ usb_cout(uint8_t *buf, unsigned count)
}
}
}
#endif
47 changes: 47 additions & 0 deletions hw_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -419,6 +419,53 @@
# define BOARD_TYPE 10
# define FLASH_SECTOR_SIZE 0x400

/****************************************************************************
* TARGET_HW_PX4_PIO_V3
****************************************************************************/

#elif defined(TARGET_HW_PX4_PIO_V3)

# define APP_LOAD_ADDRESS 0x08001000
# define APP_SIZE_MAX 0x3f000
# define BOOTLOADER_DELAY 200
# define BOARD_PIO
# define INTERFACE_USB 0
# define INTERFACE_USART 1
# define USBDEVICESTRING ""
# define USBPRODUCTID -1

# define OSC_FREQ 24

# define BOARD_PIN_LED_ACTIVITY 0
# define BOARD_PIN_LED_BOOTLOADER GPIO13
# define BOARD_PORT_LEDS GPIOB
# define BOARD_CLOCK_LEDS_REGISTER RCC_AHBENR
# define BOARD_CLOCK_LEDS RCC_AHBENR_IOPBEN
# define BOARD_LED_ON gpio_clear
# define BOARD_LED_OFF gpio_set

# define BOARD_USART USART2
# define BOARD_USART_CLOCK_REGISTER RCC_APB1ENR
# define BOARD_USART_CLOCK_BIT RCC_APB1ENR_USART2EN

# define BOARD_PORT_USART GPIOA
# define BOARD_PORT_USART_AF GPIO_AF7
# define BOARD_PIN_TX GPIO2
# define BOARD_PIN_RX GPIO3
# define BOARD_USART_PIN_CLOCK_REGISTER RCC_AHBENR
# define BOARD_USART_PIN_CLOCK_BIT RCC_AHBENR_IOPAEN

# define BOARD_FORCE_BL_PIN GPIO5
# define BOARD_FORCE_BL_PORT GPIOB
# define BOARD_FORCE_BL_CLOCK_REGISTER RCC_AHBENR
# define BOARD_FORCE_BL_CLOCK_BIT RCC_AHBENR_IOPBEN
# define BOARD_FORCE_BL_PULL GPIO_PUPD_NONE // depend on external pull
# define BOARD_FORCE_BL_VALUE BOARD_FORCE_BL_PIN

# define BOARD_FLASH_SECTORS 60
# define BOARD_TYPE 13
# define FLASH_SECTOR_SIZE 0x800

/****************************************************************************
* TARGET_HW_PX4_AEROCORE_V1
****************************************************************************/
Expand Down
Loading

0 comments on commit ac45014

Please sign in to comment.