forked from Archive/PX4-Autopilot
Pull v2 pieces up to build with the merge
This commit is contained in:
parent
43f1843cc7
commit
b4029dd824
|
@ -0,0 +1,12 @@
|
|||
{
|
||||
"board_id": 10,
|
||||
"magic": "PX4FWv2",
|
||||
"description": "Firmware for the PX4IOv2 board",
|
||||
"image": "",
|
||||
"build_time": 0,
|
||||
"summary": "PX4IOv2",
|
||||
"version": "2.0",
|
||||
"image_size": 0,
|
||||
"git_identity": "",
|
||||
"board_revision": 0
|
||||
}
|
87
Makefile
87
Makefile
|
@ -100,7 +100,7 @@ all: $(STAGED_FIRMWARES)
|
|||
# is taken care of.
|
||||
#
|
||||
$(STAGED_FIRMWARES): $(IMAGE_DIR)%.px4: $(BUILD_DIR)%.build/firmware.px4
|
||||
@echo %% Copying $@
|
||||
@$(ECHO) %% Copying $@
|
||||
$(Q) $(COPY) $< $@
|
||||
$(Q) $(COPY) $(patsubst %.px4,%.bin,$<) $(patsubst %.px4,%.bin,$@)
|
||||
|
||||
|
@ -111,9 +111,9 @@ $(STAGED_FIRMWARES): $(IMAGE_DIR)%.px4: $(BUILD_DIR)%.build/firmware.px4
|
|||
$(BUILD_DIR)%.build/firmware.px4: config = $(patsubst $(BUILD_DIR)%.build/firmware.px4,%,$@)
|
||||
$(BUILD_DIR)%.build/firmware.px4: work_dir = $(BUILD_DIR)$(config).build/
|
||||
$(FIRMWARES): $(BUILD_DIR)%.build/firmware.px4:
|
||||
@echo %%%%
|
||||
@echo %%%% Building $(config) in $(work_dir)
|
||||
@echo %%%%
|
||||
@$(ECHO) %%%%
|
||||
@$(ECHO) %%%% Building $(config) in $(work_dir)
|
||||
@$(ECHO) %%%%
|
||||
$(Q) mkdir -p $(work_dir)
|
||||
$(Q) make -r -C $(work_dir) \
|
||||
-f $(PX4_MK_DIR)firmware.mk \
|
||||
|
@ -132,8 +132,6 @@ $(FIRMWARES): $(BUILD_DIR)%.build/firmware.px4:
|
|||
# XXX Should support fetching/unpacking from a separate directory to permit
|
||||
# downloads of the prebuilt archives as well...
|
||||
#
|
||||
# XXX PX4IO configuration name is bad - NuttX configs should probably all be "px4"
|
||||
#
|
||||
NUTTX_ARCHIVES = $(foreach board,$(BOARDS),$(ARCHIVE_DIR)$(board).export)
|
||||
.PHONY: archives
|
||||
archives: $(NUTTX_ARCHIVES)
|
||||
|
@ -146,16 +144,22 @@ endif
|
|||
|
||||
$(ARCHIVE_DIR)%.export: board = $(notdir $(basename $@))
|
||||
$(ARCHIVE_DIR)%.export: configuration = nsh
|
||||
$(NUTTX_ARCHIVES): $(ARCHIVE_DIR)%.export: $(NUTTX_SRC) $(NUTTX_APPS)
|
||||
@echo %% Configuring NuttX for $(board)
|
||||
$(NUTTX_ARCHIVES): $(ARCHIVE_DIR)%.export: $(NUTTX_SRC)
|
||||
@$(ECHO) %% Configuring NuttX for $(board)
|
||||
$(Q) (cd $(NUTTX_SRC) && $(RMDIR) nuttx-export)
|
||||
$(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) distclean
|
||||
$(Q) (cd $(NUTTX_SRC)/configs && ln -sf $(PX4_BASE)/nuttx-configs/* .)
|
||||
$(Q) (cd $(NUTTX_SRC)tools && ./configure.sh $(board)/$(configuration))
|
||||
@echo %% Exporting NuttX for $(board)
|
||||
@$(ECHO) %% Exporting NuttX for $(board)
|
||||
$(Q) make -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) export
|
||||
$(Q) mkdir -p $(dir $@)
|
||||
$(Q) $(COPY) $(NUTTX_SRC)nuttx-export.zip $@
|
||||
|
||||
$(NUTTX_SRC):
|
||||
@$(ECHO) ""
|
||||
@$(ECHO) "NuttX sources missing - clone https://github.com/PX4/NuttX.git and try again."
|
||||
@$(ECHO) ""
|
||||
|
||||
#
|
||||
# Cleanup targets. 'clean' should remove all built products and force
|
||||
# a complete re-compilation, 'distclean' should remove everything
|
||||
|
@ -170,46 +174,47 @@ clean:
|
|||
distclean: clean
|
||||
$(Q) $(REMOVE) $(ARCHIVE_DIR)*.export
|
||||
$(Q) make -C $(NUTTX_SRC) -r $(MQUIET) distclean
|
||||
$(Q) (cd $(NUTTX_SRC)/configs && find . -type l -depth 1 -delete)
|
||||
|
||||
#
|
||||
# Print some help text
|
||||
#
|
||||
.PHONY: help
|
||||
help:
|
||||
@echo ""
|
||||
@echo " PX4 firmware builder"
|
||||
@echo " ===================="
|
||||
@echo ""
|
||||
@echo " Available targets:"
|
||||
@echo " ------------------"
|
||||
@echo ""
|
||||
@echo " archives"
|
||||
@echo " Build the NuttX RTOS archives that are used by the firmware build."
|
||||
@echo ""
|
||||
@echo " all"
|
||||
@echo " Build all firmware configs: $(CONFIGS)"
|
||||
@echo " A limited set of configs can be built with CONFIGS=<list-of-configs>"
|
||||
@echo ""
|
||||
@$(ECHO) ""
|
||||
@$(ECHO) " PX4 firmware builder"
|
||||
@$(ECHO) " ===================="
|
||||
@$(ECHO) ""
|
||||
@$(ECHO) " Available targets:"
|
||||
@$(ECHO) " ------------------"
|
||||
@$(ECHO) ""
|
||||
@$(ECHO) " archives"
|
||||
@$(ECHO) " Build the NuttX RTOS archives that are used by the firmware build."
|
||||
@$(ECHO) ""
|
||||
@$(ECHO) " all"
|
||||
@$(ECHO) " Build all firmware configs: $(CONFIGS)"
|
||||
@$(ECHO) " A limited set of configs can be built with CONFIGS=<list-of-configs>"
|
||||
@$(ECHO) ""
|
||||
@for config in $(CONFIGS); do \
|
||||
echo " $$config"; \
|
||||
echo " Build just the $$config firmware configuration."; \
|
||||
echo ""; \
|
||||
done
|
||||
@echo " clean"
|
||||
@echo " Remove all firmware build pieces."
|
||||
@echo ""
|
||||
@echo " distclean"
|
||||
@echo " Remove all compilation products, including NuttX RTOS archives."
|
||||
@echo ""
|
||||
@echo " upload"
|
||||
@echo " When exactly one config is being built, add this target to upload the"
|
||||
@echo " firmware to the board when the build is complete. Not supported for"
|
||||
@echo " all configurations."
|
||||
@echo ""
|
||||
@echo " Common options:"
|
||||
@echo " ---------------"
|
||||
@echo ""
|
||||
@echo " V=1"
|
||||
@echo " If V is set, more verbose output is printed during the build. This can"
|
||||
@echo " help when diagnosing issues with the build or toolchain."
|
||||
@echo ""
|
||||
@$(ECHO) " clean"
|
||||
@$(ECHO) " Remove all firmware build pieces."
|
||||
@$(ECHO) ""
|
||||
@$(ECHO) " distclean"
|
||||
@$(ECHO) " Remove all compilation products, including NuttX RTOS archives."
|
||||
@$(ECHO) ""
|
||||
@$(ECHO) " upload"
|
||||
@$(ECHO) " When exactly one config is being built, add this target to upload the"
|
||||
@$(ECHO) " firmware to the board when the build is complete. Not supported for"
|
||||
@$(ECHO) " all configurations."
|
||||
@$(ECHO) ""
|
||||
@$(ECHO) " Common options:"
|
||||
@$(ECHO) " ---------------"
|
||||
@$(ECHO) ""
|
||||
@$(ECHO) " V=1"
|
||||
@$(ECHO) " If V is set, more verbose output is printed during the build. This can"
|
||||
@$(ECHO) " help when diagnosing issues with the build or toolchain."
|
||||
@$(ECHO) ""
|
||||
|
|
|
@ -12,19 +12,14 @@ ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_test
|
|||
#
|
||||
MODULES += drivers/device
|
||||
MODULES += drivers/stm32
|
||||
MODULES += drivers/px4io
|
||||
MODULES += drivers/boards/px4fmuv2
|
||||
MODULES += systemcmds/perf
|
||||
MODULES += systemcmds/reboot
|
||||
|
||||
# needed because things use it for logging
|
||||
MODULES += modules/mavlink
|
||||
|
||||
#
|
||||
# Library modules
|
||||
#
|
||||
MODULES += modules/systemlib
|
||||
MODULES += modules/systemlib/mixer
|
||||
MODULES += modules/uORB
|
||||
|
||||
#
|
|
@ -45,7 +45,6 @@ export PX4_INCLUDE_DIR = $(abspath $(PX4_BASE)/src/include)/
|
|||
export PX4_MODULE_SRC = $(abspath $(PX4_BASE)/src)/
|
||||
export PX4_MK_DIR = $(abspath $(PX4_BASE)/makefiles)/
|
||||
export NUTTX_SRC = $(abspath $(PX4_BASE)/NuttX/nuttx)/
|
||||
export NUTTX_APP_SRC = $(abspath $(PX4_BASE)/NuttX/apps)/
|
||||
export MAVLINK_SRC = $(abspath $(PX4_BASE)/mavlink)/
|
||||
export ROMFS_SRC = $(abspath $(PX4_BASE)/ROMFS)/
|
||||
export IMAGE_DIR = $(abspath $(PX4_BASE)/Images)/
|
||||
|
|
|
@ -27,7 +27,7 @@ all: upload-$(METHOD)-$(BOARD)
|
|||
upload-serial-px4fmu-v1: $(BUNDLE) $(UPLOADER)
|
||||
$(Q) $(PYTHON) -u $(UPLOADER) --port $(SERIAL_PORTS) $(BUNDLE)
|
||||
|
||||
upload-serial-px4fmuv2: $(BUNDLE) $(UPLOADER)
|
||||
upload-serial-px4fmu-v2: $(BUNDLE) $(UPLOADER)
|
||||
$(Q) $(PYTHON) -u $(UPLOADER) --port $(SERIAL_PORTS) $(BUNDLE)
|
||||
|
||||
#
|
||||
|
|
|
@ -3,5 +3,5 @@
|
|||
# see misc/tools/kconfig-language.txt.
|
||||
#
|
||||
|
||||
if ARCH_BOARD_PX4FMUV2
|
||||
if ARCH_BOARD_PX4FMU_V2
|
||||
endif
|
|
@ -46,6 +46,8 @@
|
|||
# include <stdint.h>
|
||||
#endif
|
||||
|
||||
#include <stm32.h>
|
||||
|
||||
/************************************************************************************
|
||||
* Definitions
|
||||
************************************************************************************/
|
||||
|
@ -194,10 +196,8 @@
|
|||
|
||||
/* High-resolution timer
|
||||
*/
|
||||
#ifdef CONFIG_HRT_TIMER
|
||||
# define HRT_TIMER 8 /* use timer8 for the HRT */
|
||||
# define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */
|
||||
#endif
|
||||
#define HRT_TIMER 8 /* use timer8 for the HRT */
|
||||
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */
|
||||
|
||||
/* Alternate function pin selections ************************************************/
|
||||
|
|
@ -0,0 +1,3 @@
|
|||
include ${TOPDIR}/.config
|
||||
|
||||
include $(TOPDIR)/configs/px4fmu-v2/common/Make.defs
|
File diff suppressed because it is too large
Load Diff
|
@ -75,8 +75,8 @@ CONFIG_ARCH_ARM=y
|
|||
CONFIG_ARCH_CORTEXM4=y
|
||||
CONFIG_ARCH_CHIP="stm32"
|
||||
CONFIG_ARCH_CHIP_STM32F427V=y
|
||||
CONFIG_ARCH_BOARD="px4fmuv2"
|
||||
CONFIG_ARCH_BOARD_PX4FMUV2=y
|
||||
CONFIG_ARCH_BOARD="px4fmu-v2"
|
||||
CONFIG_ARCH_BOARD_PX4FMU_V2=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=16717
|
||||
CONFIG_DRAM_SIZE=0x00040000
|
||||
CONFIG_DRAM_START=0x20000000
|
||||
|
@ -297,22 +297,6 @@ CONFIG_USART6_RXDMA=y
|
|||
CONFIG_UART7_RXDMA=n
|
||||
CONFIG_UART8_RXDMA=n
|
||||
|
||||
#
|
||||
# PX4FMU specific driver settings
|
||||
#
|
||||
# CONFIG_HRT_TIMER
|
||||
# Enables the high-resolution timer. The board definition must
|
||||
# set HRT_TIMER and HRT_TIMER_CHANNEL to the timer and capture/
|
||||
# compare channels to be used.
|
||||
# CONFIG_HRT_PPM
|
||||
# Enables R/C PPM input using the HRT. The board definition must
|
||||
# set HRT_PPM_CHANNEL to the timer capture/compare channel to be
|
||||
# used, and define GPIO_PPM_IN to configure the appropriate timer
|
||||
# GPIO.
|
||||
#
|
||||
CONFIG_HRT_TIMER=y
|
||||
CONFIG_HRT_PPM=n
|
||||
|
||||
#
|
||||
# STM32F40xxx specific SPI device driver settings
|
||||
#
|
|
@ -45,11 +45,8 @@
|
|||
#include <nuttx/config.h>
|
||||
#ifndef __ASSEMBLY__
|
||||
# include <stdint.h>
|
||||
# include <stdbool.h>
|
||||
#endif
|
||||
#include <stm32_rcc.h>
|
||||
#include <stm32_sdio.h>
|
||||
#include <stm32_internal.h>
|
||||
#include <stm32.h>
|
||||
|
||||
/************************************************************************************
|
||||
* Definitions
|
||||
|
@ -118,10 +115,8 @@
|
|||
/*
|
||||
* High-resolution timer
|
||||
*/
|
||||
#ifdef CONFIG_HRT_TIMER
|
||||
# define HRT_TIMER 1 /* use timer1 for the HRT */
|
||||
# define HRT_TIMER_CHANNEL 2 /* use capture/compare channel 2 */
|
||||
#endif
|
||||
#define HRT_TIMER 1 /* use timer1 for the HRT */
|
||||
#define HRT_TIMER_CHANNEL 2 /* use capture/compare channel 2 */
|
||||
|
||||
/*
|
||||
* PPM
|
||||
|
@ -130,10 +125,8 @@
|
|||
*
|
||||
* Pin is PA8, timer 1, channel 1
|
||||
*/
|
||||
#if defined(CONFIG_HRT_TIMER) && defined (CONFIG_HRT_PPM)
|
||||
# define HRT_PPM_CHANNEL 1 /* use capture/compare channel 1 */
|
||||
# define GPIO_PPM_IN GPIO_TIM1_CH1IN
|
||||
#endif
|
||||
#define HRT_PPM_CHANNEL 1 /* use capture/compare channel 1 */
|
||||
#define GPIO_PPM_IN GPIO_TIM1_CH1IN
|
||||
|
||||
/* LED definitions ******************************************************************/
|
||||
/* PX4 has two LEDs that we will encode as: */
|
|
@ -0,0 +1,3 @@
|
|||
include ${TOPDIR}/.config
|
||||
|
||||
include $(TOPDIR)/configs/px4io-v2/common/Make.defs
|
|
@ -74,8 +74,8 @@ CONFIG_ARCH_ARM=y
|
|||
CONFIG_ARCH_CORTEXM3=y
|
||||
CONFIG_ARCH_CHIP="stm32"
|
||||
CONFIG_ARCH_CHIP_STM32F100C8=y
|
||||
CONFIG_ARCH_BOARD="px4iov2"
|
||||
CONFIG_ARCH_BOARD_PX4IOV2=y
|
||||
CONFIG_ARCH_BOARD="px4io-v2"
|
||||
CONFIG_ARCH_BOARD_PX4IO_V2=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=2000
|
||||
CONFIG_DRAM_SIZE=0x00002000
|
||||
CONFIG_DRAM_START=0x20000000
|
||||
|
@ -195,28 +195,6 @@ SERIAL_HAVE_CONSOLE_DMA=y
|
|||
CONFIG_USART2_RXDMA=n
|
||||
CONFIG_USART3_RXDMA=y
|
||||
|
||||
#
|
||||
# PX4IO specific driver settings
|
||||
#
|
||||
# CONFIG_HRT_TIMER
|
||||
# Enables the high-resolution timer. The board definition must
|
||||
# set HRT_TIMER and HRT_TIMER_CHANNEL to the timer and capture/
|
||||
# compare channels to be used.
|
||||
# CONFIG_HRT_PPM
|
||||
# Enables R/C PPM input using the HRT. The board definition must
|
||||
# set HRT_PPM_CHANNEL to the timer capture/compare channel to be
|
||||
# used, and define GPIO_PPM_IN to configure the appropriate timer
|
||||
# GPIO.
|
||||
# CONFIG_PWM_SERVO
|
||||
# Enables the PWM servo driver. The driver configuration must be
|
||||
# supplied by the board support at initialisation time.
|
||||
# Note that USART2 must be disabled on the PX4 board for this to
|
||||
# be available.
|
||||
#
|
||||
#
|
||||
CONFIG_HRT_TIMER=y
|
||||
CONFIG_HRT_PPM=y
|
||||
|
||||
#
|
||||
# General build options
|
||||
#
|
|
@ -75,7 +75,7 @@ CONFIG_ARCH_CORTEXM3=y
|
|||
CONFIG_ARCH_CHIP=stm32
|
||||
CONFIG_ARCH_CHIP_STM32F100C8=y
|
||||
CONFIG_ARCH_BOARD=px4iov2
|
||||
CONFIG_ARCH_BOARD_PX4IOV2=y
|
||||
CONFIG_ARCH_BOARD_PX4IO_V2=y
|
||||
CONFIG_BOARD_LOOPSPERMSEC=24000
|
||||
CONFIG_DRAM_SIZE=0x00002000
|
||||
CONFIG_DRAM_START=0x20000000
|
||||
|
@ -187,29 +187,6 @@ CONFIG_USART1_2STOP=0
|
|||
CONFIG_USART2_2STOP=0
|
||||
CONFIG_USART3_2STOP=0
|
||||
|
||||
#
|
||||
# PX4IO specific driver settings
|
||||
#
|
||||
# CONFIG_HRT_TIMER
|
||||
# Enables the high-resolution timer. The board definition must
|
||||
# set HRT_TIMER and HRT_TIMER_CHANNEL to the timer and capture/
|
||||
# compare channels to be used.
|
||||
# CONFIG_HRT_PPM
|
||||
# Enables R/C PPM input using the HRT. The board definition must
|
||||
# set HRT_PPM_CHANNEL to the timer capture/compare channel to be
|
||||
# used, and define GPIO_PPM_IN to configure the appropriate timer
|
||||
# GPIO.
|
||||
# CONFIG_PWM_SERVO
|
||||
# Enables the PWM servo driver. The driver configuration must be
|
||||
# supplied by the board support at initialisation time.
|
||||
# Note that USART2 must be disabled on the PX4 board for this to
|
||||
# be available.
|
||||
#
|
||||
#
|
||||
CONFIG_HRT_TIMER=y
|
||||
CONFIG_HRT_PPM=y
|
||||
CONFIG_PWM_SERVO=y
|
||||
|
||||
#
|
||||
# General build options
|
||||
#
|
|
@ -1,3 +0,0 @@
|
|||
include ${TOPDIR}/.config
|
||||
|
||||
include $(TOPDIR)/configs/px4fmuv2/common/Make.defs
|
|
@ -1,3 +0,0 @@
|
|||
include ${TOPDIR}/.config
|
||||
|
||||
include $(TOPDIR)/configs/px4io/common/Make.defs
|
|
@ -59,9 +59,9 @@
|
|||
#include <nuttx/mmcsd.h>
|
||||
#include <nuttx/analog/adc.h>
|
||||
|
||||
#include "stm32_internal.h"
|
||||
#include <stm32.h>
|
||||
#include "px4fmu_internal.h"
|
||||
#include "stm32_uart.h"
|
||||
#include <stm32_uart.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
|
|
|
@ -50,7 +50,7 @@
|
|||
__BEGIN_DECLS
|
||||
|
||||
/* these headers are not C++ safe */
|
||||
#include <stm32_internal.h>
|
||||
#include <stm32.h>
|
||||
|
||||
|
||||
/****************************************************************************************************
|
||||
|
|
|
@ -46,7 +46,7 @@
|
|||
#include <arch/board/board.h>
|
||||
#include <drivers/drv_pwm_output.h>
|
||||
|
||||
#include <stm32_internal.h>
|
||||
#include <stm32.h>
|
||||
#include <stm32_gpio.h>
|
||||
#include <stm32_tim.h>
|
||||
|
||||
|
|
|
@ -50,9 +50,9 @@
|
|||
#include <nuttx/spi.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "up_arch.h"
|
||||
#include "chip.h"
|
||||
#include "stm32_internal.h"
|
||||
#include <up_arch.h>
|
||||
#include <chip.h>
|
||||
#include <stm32.h>
|
||||
#include "px4fmu_internal.h"
|
||||
|
||||
/************************************************************************************
|
||||
|
|
|
@ -51,8 +51,8 @@
|
|||
#include <nuttx/usb/usbdev.h>
|
||||
#include <nuttx/usb/usbdev_trace.h>
|
||||
|
||||
#include "up_arch.h"
|
||||
#include "stm32_internal.h"
|
||||
#include <up_arch.h>
|
||||
#include <stm32.h>
|
||||
#include "px4fmu_internal.h"
|
||||
|
||||
/************************************************************************************
|
||||
|
|
|
@ -54,7 +54,7 @@
|
|||
|
||||
#include <nuttx/arch.h>
|
||||
|
||||
#include "stm32_internal.h"
|
||||
#include <stm32.h>
|
||||
#include "px4iov2_internal.h"
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
|
|
@ -48,7 +48,7 @@
|
|||
#include <stdint.h>
|
||||
|
||||
/* these headers are not C++ safe */
|
||||
#include <stm32_internal.h>
|
||||
#include <stm32.h>
|
||||
|
||||
|
||||
/******************************************************************************
|
||||
|
|
|
@ -46,7 +46,7 @@
|
|||
#include <arch/board/board.h>
|
||||
#include <drivers/drv_pwm_output.h>
|
||||
|
||||
#include <stm32_internal.h>
|
||||
#include <stm32.h>
|
||||
#include <stm32_gpio.h>
|
||||
#include <stm32_tim.h>
|
||||
|
||||
|
|
|
@ -42,7 +42,7 @@
|
|||
|
||||
#include <sys/ioctl.h>
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_PX4FMU
|
||||
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
|
||||
/*
|
||||
* PX4FMU GPIO numbers.
|
||||
*
|
||||
|
@ -67,7 +67,7 @@
|
|||
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_PX4FMUV2
|
||||
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
|
||||
/*
|
||||
* PX4FMUv2 GPIO numbers.
|
||||
*
|
||||
|
@ -93,36 +93,14 @@
|
|||
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_PX4IO
|
||||
/*
|
||||
* PX4IO GPIO numbers.
|
||||
*
|
||||
* XXX note that these are here for reference/future use; currently
|
||||
* there is no good way to wire these up without a common STM32 GPIO
|
||||
* driver, which isn't implemented yet.
|
||||
*/
|
||||
/* outputs */
|
||||
# define GPIO_ACC1_POWER (1<<0) /**< accessory power 1 */
|
||||
# define GPIO_ACC2_POWER (1<<1) /**< accessory power 2 */
|
||||
# define GPIO_SERVO_POWER (1<<2) /**< servo power */
|
||||
# define GPIO_RELAY1 (1<<3) /**< relay 1 */
|
||||
# define GPIO_RELAY2 (1<<4) /**< relay 2 */
|
||||
# define GPIO_LED_BLUE (1<<5) /**< blue LED */
|
||||
# define GPIO_LED_AMBER (1<<6) /**< amber/red LED */
|
||||
# define GPIO_LED_SAFETY (1<<7) /**< safety LED */
|
||||
|
||||
/* inputs */
|
||||
# define GPIO_ACC_OVERCURRENT (1<<8) /**< accessory 1/2 overcurrent detect */
|
||||
# define GPIO_SERVO_OVERCURRENT (1<<9) /**< servo overcurrent detect */
|
||||
# define GPIO_SAFETY_BUTTON (1<<10) /**< safety button pressed */
|
||||
|
||||
/**
|
||||
* Default GPIO device - other devices may also support this protocol if
|
||||
* they also export GPIO-like things. This is always the GPIOs on the
|
||||
* main board.
|
||||
*/
|
||||
# define GPIO_DEVICE_PATH "/dev/px4io"
|
||||
#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
|
||||
/* no GPIO driver on the PX4IOv1 board */
|
||||
# define GPIO_DEVICE_PATH "/nonexistent"
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_PX4IO_V2
|
||||
/* no GPIO driver on the PX4IOv2 board */
|
||||
# define GPIO_DEVICE_PATH "/nonexistent"
|
||||
#endif
|
||||
|
||||
#ifndef GPIO_DEVICE_PATH
|
||||
|
|
|
@ -59,10 +59,10 @@
|
|||
#include <drivers/drv_gpio.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU)
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
|
||||
# include <drivers/boards/px4fmu/px4fmu_internal.h>
|
||||
# define FMU_HAVE_PPM
|
||||
#elif defined(CONFIG_ARCH_BOARD_PX4FMUV2)
|
||||
#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
|
||||
# include <drivers/boards/px4fmuv2/px4fmu_internal.h>
|
||||
# undef FMU_HAVE_PPM
|
||||
#else
|
||||
|
@ -158,7 +158,7 @@ private:
|
|||
};
|
||||
|
||||
const PX4FMU::GPIOConfig PX4FMU::_gpio_tab[] = {
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU)
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
|
||||
{GPIO_GPIO0_INPUT, GPIO_GPIO0_OUTPUT, 0},
|
||||
{GPIO_GPIO1_INPUT, GPIO_GPIO1_OUTPUT, 0},
|
||||
{GPIO_GPIO2_INPUT, GPIO_GPIO2_OUTPUT, GPIO_USART2_CTS_1},
|
||||
|
@ -168,7 +168,7 @@ const PX4FMU::GPIOConfig PX4FMU::_gpio_tab[] = {
|
|||
{GPIO_GPIO6_INPUT, GPIO_GPIO6_OUTPUT, GPIO_CAN2_TX_2},
|
||||
{GPIO_GPIO7_INPUT, GPIO_GPIO7_OUTPUT, GPIO_CAN2_RX_2},
|
||||
#endif
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMUV2)
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
|
||||
{GPIO_GPIO0_INPUT, GPIO_GPIO0_OUTPUT, 0},
|
||||
{GPIO_GPIO1_INPUT, GPIO_GPIO1_OUTPUT, 0},
|
||||
{GPIO_GPIO2_INPUT, GPIO_GPIO2_OUTPUT, 0},
|
||||
|
@ -873,7 +873,7 @@ PX4FMU::gpio_reset(void)
|
|||
}
|
||||
}
|
||||
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU)
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
|
||||
/* if we have a GPIO direction control, set it to zero (input) */
|
||||
stm32_gpiowrite(GPIO_GPIO_DIR, 0);
|
||||
stm32_configgpio(GPIO_GPIO_DIR);
|
||||
|
@ -883,7 +883,7 @@ PX4FMU::gpio_reset(void)
|
|||
void
|
||||
PX4FMU::gpio_set_function(uint32_t gpios, int function)
|
||||
{
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU)
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
|
||||
/*
|
||||
* GPIOs 0 and 1 must have the same direction as they are buffered
|
||||
* by a shared 2-port driver. Any attempt to set either sets both.
|
||||
|
@ -918,7 +918,7 @@ PX4FMU::gpio_set_function(uint32_t gpios, int function)
|
|||
}
|
||||
}
|
||||
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU)
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
|
||||
/* flip buffer to input mode if required */
|
||||
if ((GPIO_SET_INPUT == function) && (gpios & 3))
|
||||
stm32_gpiowrite(GPIO_GPIO_DIR, 0);
|
||||
|
@ -1024,17 +1024,17 @@ fmu_new_mode(PortMode new_mode)
|
|||
break;
|
||||
|
||||
case PORT_FULL_PWM:
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU)
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
|
||||
/* select 4-pin PWM mode */
|
||||
servo_mode = PX4FMU::MODE_4PWM;
|
||||
#endif
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMUV2)
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
|
||||
servo_mode = PX4FMU::MODE_6PWM;
|
||||
#endif
|
||||
break;
|
||||
|
||||
/* mixed modes supported on v1 board only */
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU)
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
|
||||
case PORT_FULL_SERIAL:
|
||||
/* set all multi-GPIOs to serial mode */
|
||||
gpio_bits = GPIO_MULTI_1 | GPIO_MULTI_2 | GPIO_MULTI_3 | GPIO_MULTI_4;
|
||||
|
@ -1116,7 +1116,7 @@ test(void)
|
|||
|
||||
if (ioctl(fd, PWM_SERVO_SET(3), 1600) < 0) err(1, "servo 4 set failed");
|
||||
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMUV2)
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
|
||||
if (ioctl(fd, PWM_SERVO_SET(4), 1800) < 0) err(1, "servo 5 set failed");
|
||||
|
||||
if (ioctl(fd, PWM_SERVO_SET(5), 2000) < 0) err(1, "servo 6 set failed");
|
||||
|
@ -1183,7 +1183,7 @@ fmu_main(int argc, char *argv[])
|
|||
} else if (!strcmp(verb, "mode_pwm")) {
|
||||
new_mode = PORT_FULL_PWM;
|
||||
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU)
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
|
||||
} else if (!strcmp(verb, "mode_serial")) {
|
||||
new_mode = PORT_FULL_SERIAL;
|
||||
|
||||
|
@ -1217,9 +1217,9 @@ fmu_main(int argc, char *argv[])
|
|||
fake(argc - 1, argv + 1);
|
||||
|
||||
fprintf(stderr, "FMU: unrecognised command, try:\n");
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU)
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
|
||||
fprintf(stderr, " mode_gpio, mode_serial, mode_pwm, mode_gpio_serial, mode_pwm_serial, mode_pwm_gpio\n");
|
||||
#elif defined(CONFIG_ARCH_BOARD_PX4FMUV2)
|
||||
#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
|
||||
fprintf(stderr, " mode_gpio, mode_pwm\n");
|
||||
#endif
|
||||
exit(1);
|
||||
|
|
|
@ -56,7 +56,6 @@
|
|||
#include <chip.h>
|
||||
#include <up_internal.h>
|
||||
#include <up_arch.h>
|
||||
#include <stm32_internal.h>
|
||||
|
||||
#include <debug.h>
|
||||
|
||||
|
|
|
@ -1604,9 +1604,9 @@ start(int argc, char *argv[])
|
|||
|
||||
PX4IO_interface *interface;
|
||||
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMUV2)
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
|
||||
interface = io_serial_interface();
|
||||
#elif defined(CONFIG_ARCH_BOARD_PX4FMU)
|
||||
#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
|
||||
interface = io_i2c_interface(PX4_I2C_BUS_ONBOARD, PX4_I2C_OBDEV_PX4IO);
|
||||
#else
|
||||
# error Unknown board - cannot select interface.
|
||||
|
@ -1741,9 +1741,9 @@ if_test(unsigned mode)
|
|||
{
|
||||
PX4IO_interface *interface;
|
||||
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMUV2)
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2)
|
||||
interface = io_serial_interface();
|
||||
#elif defined(CONFIG_ARCH_BOARD_PX4FMU)
|
||||
#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V1)
|
||||
interface = io_i2c_interface(PX4_I2C_BUS_ONBOARD, PX4_I2C_OBDEV_PX4IO);
|
||||
#else
|
||||
# error Unknown board - cannot select interface.
|
||||
|
|
|
@ -56,10 +56,10 @@
|
|||
|
||||
#include "uploader.h"
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_PX4FMUV2
|
||||
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V2
|
||||
#include <drivers/boards/px4fmuv2/px4fmu_internal.h>
|
||||
#endif
|
||||
#ifdef CONFIG_ARCH_BOARD_PX4FMU
|
||||
#ifdef CONFIG_ARCH_BOARD_PX4FMU_V1
|
||||
#include <drivers/boards/px4fmu/px4fmu_internal.h>
|
||||
#endif
|
||||
|
||||
|
|
|
@ -70,7 +70,7 @@
|
|||
#include "stm32_gpio.h"
|
||||
#include "stm32_tim.h"
|
||||
|
||||
#ifdef CONFIG_HRT_TIMER
|
||||
#ifdef HRT_TIMER
|
||||
|
||||
/* HRT configuration */
|
||||
#if HRT_TIMER == 1
|
||||
|
@ -275,7 +275,7 @@ static void hrt_call_invoke(void);
|
|||
/*
|
||||
* Specific registers and bits used by PPM sub-functions
|
||||
*/
|
||||
#ifdef CONFIG_HRT_PPM
|
||||
#ifdef HRT_PPM_CHANNEL
|
||||
/*
|
||||
* If the timer hardware doesn't support GTIM_CCER_CCxNP, then we will work around it.
|
||||
*
|
||||
|
@ -377,7 +377,7 @@ static void hrt_ppm_decode(uint32_t status);
|
|||
# define CCMR1_PPM 0
|
||||
# define CCMR2_PPM 0
|
||||
# define CCER_PPM 0
|
||||
#endif /* CONFIG_HRT_PPM */
|
||||
#endif /* HRT_PPM_CHANNEL */
|
||||
|
||||
/*
|
||||
* Initialise the timer we are going to use.
|
||||
|
@ -907,4 +907,4 @@ hrt_latency_update(void)
|
|||
}
|
||||
|
||||
|
||||
#endif /* CONFIG_HRT_TIMER */
|
||||
#endif /* HRT_TIMER */
|
||||
|
|
|
@ -117,10 +117,6 @@
|
|||
|
||||
#include <systemlib/err.h>
|
||||
|
||||
#ifndef CONFIG_HRT_TIMER
|
||||
# error This driver requires CONFIG_HRT_TIMER
|
||||
#endif
|
||||
|
||||
/* Tone alarm configuration */
|
||||
#if TONE_ALARM_TIMER == 2
|
||||
# define TONE_ALARM_BASE STM32_TIM2_BASE
|
||||
|
|
|
@ -15,10 +15,10 @@ SRCS = adc.c \
|
|||
../systemlib/mixer/mixer_multirotor.cpp \
|
||||
../systemlib/mixer/mixer_simple.cpp \
|
||||
|
||||
ifeq ($(BOARD),px4io)
|
||||
ifeq ($(BOARD),px4io-v1)
|
||||
SRCS += i2c.c
|
||||
endif
|
||||
ifeq ($(BOARD),px4iov2)
|
||||
ifeq ($(BOARD),px4io-v2)
|
||||
SRCS += serial.c \
|
||||
../systemlib/hx_stream.c
|
||||
endif
|
||||
|
|
|
@ -42,10 +42,10 @@
|
|||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_PX4IO
|
||||
#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
|
||||
# include <drivers/boards/px4io/px4io_internal.h>
|
||||
#endif
|
||||
#ifdef CONFIG_ARCH_BOARD_PX4IOV2
|
||||
#ifdef CONFIG_ARCH_BOARD_PX4IO_V2
|
||||
# include <drivers/boards/px4iov2/px4iov2_internal.h>
|
||||
#endif
|
||||
|
||||
|
@ -129,18 +129,7 @@ extern struct sys_state_s system_state;
|
|||
#define LED_AMBER(_s) stm32_gpiowrite(GPIO_LED2, !(_s))
|
||||
#define LED_SAFETY(_s) stm32_gpiowrite(GPIO_LED3, !(_s))
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_PX4IOV2
|
||||
|
||||
# define PX4IO_RELAY_CHANNELS 0
|
||||
# define POWER_SPEKTRUM(_s) stm32_gpiowrite(GPIO_SPEKTRUM_PWR_EN, (_s))
|
||||
|
||||
# define VDD_SERVO_FAULT (!stm32_gpioread(GPIO_SERVO_FAULT_DETECT))
|
||||
|
||||
# define PX4IO_ADC_CHANNEL_COUNT 2
|
||||
# define ADC_VSERVO 4
|
||||
# define ADC_RSSI 5
|
||||
|
||||
#else /* CONFIG_ARCH_BOARD_PX4IOV1 */
|
||||
#ifdef CONFIG_ARCH_BOARD_PX4IO_V1
|
||||
|
||||
# define PX4IO_RELAY_CHANNELS 4
|
||||
# define POWER_SERVO(_s) stm32_gpiowrite(GPIO_SERVO_PWR_EN, (_s))
|
||||
|
@ -158,6 +147,19 @@ extern struct sys_state_s system_state;
|
|||
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_ARCH_BOARD_PX4IO_V2
|
||||
|
||||
# define PX4IO_RELAY_CHANNELS 0
|
||||
# define POWER_SPEKTRUM(_s) stm32_gpiowrite(GPIO_SPEKTRUM_PWR_EN, (_s))
|
||||
|
||||
# define VDD_SERVO_FAULT (!stm32_gpioread(GPIO_SERVO_FAULT_DETECT))
|
||||
|
||||
# define PX4IO_ADC_CHANNEL_COUNT 2
|
||||
# define ADC_VSERVO 4
|
||||
# define ADC_RSSI 5
|
||||
|
||||
#endif
|
||||
|
||||
#define BUTTON_SAFETY stm32_gpioread(GPIO_BTN_SAFETY)
|
||||
|
||||
/*
|
||||
|
|
|
@ -59,7 +59,7 @@ static void pwm_configure_rates(uint16_t map, uint16_t defaultrate, uint16_t alt
|
|||
*/
|
||||
static const uint16_t r_page_config[] = {
|
||||
[PX4IO_P_CONFIG_PROTOCOL_VERSION] = PX4IO_PROTOCOL_VERSION,
|
||||
#ifdef CONFIG_ARCH_BOARD_PX4IOV2
|
||||
#ifdef CONFIG_ARCH_BOARD_PX4IO_V2
|
||||
[PX4IO_P_CONFIG_HARDWARE_VERSION] = 2,
|
||||
#else
|
||||
[PX4IO_P_CONFIG_HARDWARE_VERSION] = 1,
|
||||
|
|
|
@ -50,7 +50,7 @@
|
|||
#include <chip.h>
|
||||
#include <up_internal.h>
|
||||
#include <up_arch.h>
|
||||
#include <stm32_internal.h>
|
||||
#include <stm32.h>
|
||||
#include <systemlib/perf_counter.h>
|
||||
|
||||
//#define DEBUG
|
||||
|
|
Loading…
Reference in New Issue