mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-02-18 08:54:15 +01:00
OP-265 Flight reorganization of UAVObjects and Modules up a directory
git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2415 ebee16cc-31ac-478f-84a7-5cbb03baadba
This commit is contained in:
parent
982f2dd8af
commit
fc54159369
827
flight/CopterControl/Makefile
Normal file
827
flight/CopterControl/Makefile
Normal file
@ -0,0 +1,827 @@
|
||||
#####
|
||||
# Project: OpenPilot
|
||||
#
|
||||
#
|
||||
# Makefile for OpenPilot project build PiOS and the AP.
|
||||
#
|
||||
# The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2009.
|
||||
#
|
||||
#
|
||||
# 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, write to the Free Software Foundation, Inc.,
|
||||
# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
#####
|
||||
|
||||
|
||||
# Set developer code and compile options
|
||||
# Set to YES to compile for debugging
|
||||
DEBUG ?= YES
|
||||
|
||||
# Set to YES to use the Servo output pins for debugging via scope or logic analyser
|
||||
ENABLE_DEBUG_PINS ?= NO
|
||||
|
||||
# Set to Yes to enable the AUX UART which is mapped on the S1 (Tx) and S2 (Rx) servo outputs
|
||||
ENABLE_AUX_UART ?= NO
|
||||
|
||||
#
|
||||
USE_BOOTLOADER ?= NO
|
||||
|
||||
|
||||
# Set to YES when using Code Sourcery toolchain
|
||||
CODE_SOURCERY ?= YES
|
||||
|
||||
# Toolchain prefix (i.e arm-elf- -> arm-elf-gcc.exe)
|
||||
TCHAIN_PREFIX ?= arm-none-eabi-
|
||||
|
||||
# Remove command is different for Code Sourcery on Windows
|
||||
ifeq ($(CODE_SOURCERY), YES)
|
||||
REMOVE_CMD = cs-rm
|
||||
else
|
||||
REMOVE_CMD = rm
|
||||
endif
|
||||
|
||||
FLASH_TOOL = OPENOCD
|
||||
|
||||
# YES enables -mthumb option to flags for source-files listed
|
||||
# in SRC and CPPSRC
|
||||
USE_THUMB_MODE = YES
|
||||
|
||||
# List of modules to include
|
||||
MODULES = Actuator Telemetry GPS ManualControl Altitude AHRSComms Stabilization Guidance FirmwareIAP
|
||||
|
||||
#MODULES = Telemetry Example
|
||||
#MODULES = Telemetry MK/MKSerial
|
||||
#MODULES = Telemetry
|
||||
#MODULES += Osd/OsdEtStd
|
||||
|
||||
|
||||
# MCU name, submodel and board
|
||||
# - MCU used for compiler-option (-mcpu)
|
||||
# - MODEL used for linker-script name (-T) and passed as define
|
||||
# - BOARD just passed as define (optional)
|
||||
MCU = cortex-m3
|
||||
CHIP = STM32F103RET
|
||||
BOARD = STM3210E_OP
|
||||
MODEL = HD
|
||||
ifeq ($(USE_BOOTLOADER), YES)
|
||||
BOOT_MODEL = $(MODEL)_BL
|
||||
|
||||
else
|
||||
BOOT_MODEL = $(MODEL)_NB
|
||||
endif
|
||||
|
||||
# Directory for output files (lst, obj, dep, elf, sym, map, hex, bin etc.)
|
||||
OUTDIR = Build
|
||||
|
||||
# Target file name (without extension).
|
||||
TARGET = OpenPilot
|
||||
|
||||
# Paths
|
||||
OPSYSTEM = ./System
|
||||
OPSYSTEMINC = $(OPSYSTEM)/inc
|
||||
OPUAVTALK = ./UAVTalk
|
||||
OPUAVTALKINC = $(OPUAVTALK)/inc
|
||||
OPUAVOBJ = ./UAVObjects
|
||||
OPUAVOBJINC = $(OPUAVOBJ)/inc
|
||||
OPTESTS = ./Tests
|
||||
OPMODULEDIR = ./Modules
|
||||
FLIGHTLIB = ../Libraries
|
||||
FLIGHTLIBINC = ../Libraries/inc
|
||||
PIOS = ../PiOS
|
||||
PIOSINC = $(PIOS)/inc
|
||||
PIOSSTM32F10X = $(PIOS)/STM32F10x
|
||||
PIOSCOMMON = $(PIOS)/Common
|
||||
PIOSBOARDS = $(PIOS)/Boards
|
||||
APPLIBDIR = $(PIOSSTM32F10X)/Libraries
|
||||
STMLIBDIR = $(APPLIBDIR)
|
||||
STMSPDDIR = $(STMLIBDIR)/STM32F10x_StdPeriph_Driver
|
||||
STMUSBDIR = $(STMLIBDIR)/STM32_USB-FS-Device_Driver
|
||||
STMSPDSRCDIR = $(STMSPDDIR)/src
|
||||
STMSPDINCDIR = $(STMSPDDIR)/inc
|
||||
STMUSBSRCDIR = $(STMUSBDIR)/src
|
||||
STMUSBINCDIR = $(STMUSBDIR)/inc
|
||||
CMSISDIR = $(STMLIBDIR)/CMSIS/Core/CM3
|
||||
DOSFSDIR = $(APPLIBDIR)/dosfs
|
||||
MSDDIR = $(APPLIBDIR)/msd
|
||||
RTOSDIR = $(APPLIBDIR)/FreeRTOS
|
||||
RTOSSRCDIR = $(RTOSDIR)/Source
|
||||
RTOSINCDIR = $(RTOSSRCDIR)/include
|
||||
DOXYGENDIR = ../Doc/Doxygen
|
||||
AHRSBOOTLOADER = ../Bootloaders/AHRS/
|
||||
AHRSBOOTLOADERINC = $(AHRSBOOTLOADER)/inc
|
||||
PYMITE = $(FLIGHTLIB)/PyMite
|
||||
PYMITELIB = $(PYMITE)/lib
|
||||
PYMITEPLAT = $(PYMITE)/platform/openpilot
|
||||
PYMITETOOLS = $(PYMITE)/tools
|
||||
PYMITEVM = $(PYMITE)/vm
|
||||
PYMITEINC = $(PYMITEVM)
|
||||
PYMITEINC += $(PYMITEPLAT)
|
||||
PYMITEINC += $(OUTDIR)
|
||||
FLIGHTPLANLIB = $(OPMODULEDIR)/FlightPlan/lib
|
||||
FLIGHTPLANS = $(OPMODULEDIR)/FlightPlan/flightplans
|
||||
|
||||
# List C source files here. (C dependencies are automatically generated.)
|
||||
# use file-extension c for "c-only"-files
|
||||
|
||||
MODNAMES = $(notdir ${MODULES})
|
||||
|
||||
ifndef TESTAPP
|
||||
## MODULES
|
||||
SRC += ${foreach MOD, ${MODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}}
|
||||
SRC += ${OUTDIR}/InitMods.c
|
||||
## OPENPILOT CORE:
|
||||
SRC += ${OPMODULEDIR}/System/systemmod.c
|
||||
SRC += $(OPSYSTEM)/openpilot.c
|
||||
SRC += $(OPSYSTEM)/pios_board.c
|
||||
SRC += $(OPSYSTEM)/alarms.c
|
||||
SRC += $(OPSYSTEM)/taskmonitor.c
|
||||
SRC += $(OPUAVTALK)/uavtalk.c
|
||||
SRC += $(OPUAVOBJ)/uavobjectmanager.c
|
||||
SRC += $(OPUAVOBJ)/uavobjectsinit.c
|
||||
SRC += $(OPUAVOBJ)/eventdispatcher.c
|
||||
else
|
||||
## TESTCODE
|
||||
SRC += $(OPTESTS)/test_common.c
|
||||
SRC += $(OPTESTS)/$(TESTAPP).c
|
||||
endif
|
||||
|
||||
|
||||
|
||||
## UAVOBJECTS
|
||||
ifndef TESTAPP
|
||||
SRC += $(OPUAVOBJ)/objectpersistence.c
|
||||
SRC += $(OPUAVOBJ)/positionactual.c
|
||||
SRC += $(OPUAVOBJ)/gpsposition.c
|
||||
SRC += $(OPUAVOBJ)/gpstime.c
|
||||
SRC += $(OPUAVOBJ)/gpssatellites.c
|
||||
SRC += $(OPUAVOBJ)/gcstelemetrystats.c
|
||||
SRC += $(OPUAVOBJ)/flighttelemetrystats.c
|
||||
SRC += $(OPUAVOBJ)/systemstats.c
|
||||
SRC += $(OPUAVOBJ)/systemalarms.c
|
||||
SRC += $(OPUAVOBJ)/systemsettings.c
|
||||
SRC += $(OPUAVOBJ)/telemetrysettings.c
|
||||
SRC += $(OPUAVOBJ)/actuatorcommand.c
|
||||
SRC += $(OPUAVOBJ)/actuatordesired.c
|
||||
SRC += $(OPUAVOBJ)/actuatorsettings.c
|
||||
SRC += $(OPUAVOBJ)/manualcontrolcommand.c
|
||||
SRC += $(OPUAVOBJ)/manualcontrolsettings.c
|
||||
SRC += $(OPUAVOBJ)/attitudedesired.c
|
||||
SRC += $(OPUAVOBJ)/stabilizationsettings.c
|
||||
SRC += $(OPUAVOBJ)/ahrsstatus.c
|
||||
SRC += $(OPUAVOBJ)/i2cstats.c
|
||||
SRC += $(OPUAVOBJ)/baroaltitude.c
|
||||
SRC += $(OPUAVOBJ)/ahrscalibration.c
|
||||
SRC += $(OPUAVOBJ)/attitudeactual.c
|
||||
SRC += $(OPUAVOBJ)/ahrssettings.c
|
||||
SRC += $(OPUAVOBJ)/flightbatterystate.c
|
||||
SRC += $(OPUAVOBJ)/attituderaw.c
|
||||
SRC += $(OPUAVOBJ)/homelocation.c
|
||||
SRC += $(OPUAVOBJ)/mixersettings.c
|
||||
SRC += $(OPUAVOBJ)/mixerstatus.c
|
||||
SRC += $(OPUAVOBJ)/positiondesired.c
|
||||
SRC += $(OPUAVOBJ)/velocitydesired.c
|
||||
SRC += $(OPUAVOBJ)/velocityactual.c
|
||||
SRC += $(OPUAVOBJ)/guidancesettings.c
|
||||
SRC += $(OPUAVOBJ)/firmwareiapobj.c
|
||||
SRC += $(OPUAVOBJ)/ratedesired.c
|
||||
SRC += $(OPUAVOBJ)/pipxtrememodemsettings.c
|
||||
SRC += $(OPUAVOBJ)/pipxtrememodemstatus.c
|
||||
SRC += $(OPUAVOBJ)/batterysettings.c
|
||||
SRC += $(OPUAVOBJ)/flightplancontrol.c
|
||||
SRC += $(OPUAVOBJ)/flightplanstatus.c
|
||||
SRC += $(OPUAVOBJ)/flightplansettings.c
|
||||
SRC += $(OPUAVOBJ)/taskinfo.c
|
||||
SRC += $(OPUAVOBJ)/watchdogstatus.c
|
||||
endif
|
||||
|
||||
## PIOS Hardware (STM32F10x)
|
||||
SRC += $(PIOSSTM32F10X)/pios_sys.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_led.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_delay.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_usart.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_irq.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_adc.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_servo.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_i2c.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_spi.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_ppm.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_pwm.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_spektrum.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_debug.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_gpio.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_exti.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_wdg.c
|
||||
|
||||
|
||||
# PIOS USB related files (seperated to make code maintenance more easy)
|
||||
SRC += $(PIOSSTM32F10X)/pios_usb_hid.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_usb_hid_desc.c
|
||||
#SRC += $(PIOSSTM32F10X)/pios_usb_hid_endp.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_usb_hid_istr.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_usb_hid_prop.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_usb_hid_pwr.c
|
||||
|
||||
## PIOS Hardware (Common)
|
||||
SRC += $(PIOSCOMMON)/pios_sdcard.c
|
||||
SRC += $(PIOSCOMMON)/pios_com.c
|
||||
SRC += $(PIOSCOMMON)/pios_bmp085.c
|
||||
SRC += $(PIOSCOMMON)/pios_i2c_esc.c
|
||||
SRC += $(PIOSCOMMON)/pios_iap.c
|
||||
#SRC += $(PIOSCOMMON)/pios_opahrs.c
|
||||
#SRC += $(PIOSCOMMON)/pios_opahrs_proto.c
|
||||
SRC += $(PIOSCOMMON)/printf-stdarg.c
|
||||
SRC += $(FLIGHTLIB)/ahrs_spi_comm.c
|
||||
SRC += $(FLIGHTLIB)/ahrs_comm_objects.c
|
||||
## Libraries for flight calculations
|
||||
SRC += $(FLIGHTLIB)/fifo_buffer.c
|
||||
SRC += $(FLIGHTLIB)/WorldMagModel.c
|
||||
SRC += $(FLIGHTLIB)/CoordinateConversions.c
|
||||
|
||||
## CMSIS for STM32
|
||||
SRC += $(CMSISDIR)/core_cm3.c
|
||||
SRC += $(CMSISDIR)/system_stm32f10x.c
|
||||
|
||||
## Used parts of the STM-Library
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_adc.c
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_bkp.c
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_crc.c
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_dac.c
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_dma.c
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_exti.c
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_flash.c
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_gpio.c
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_i2c.c
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_pwr.c
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_rcc.c
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_rtc.c
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_spi.c
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_tim.c
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_usart.c
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_iwdg.c
|
||||
SRC += $(STMSPDSRCDIR)/stm32f10x_dbgmcu.c
|
||||
SRC += $(STMSPDSRCDIR)/misc.c
|
||||
|
||||
## STM32 USB Library
|
||||
SRC += $(STMUSBSRCDIR)/usb_core.c
|
||||
SRC += $(STMUSBSRCDIR)/usb_init.c
|
||||
SRC += $(STMUSBSRCDIR)/usb_int.c
|
||||
SRC += $(STMUSBSRCDIR)/usb_mem.c
|
||||
SRC += $(STMUSBSRCDIR)/usb_regs.c
|
||||
SRC += $(STMUSBSRCDIR)/usb_sil.c
|
||||
|
||||
## RTOS
|
||||
SRC += $(RTOSSRCDIR)/list.c
|
||||
SRC += $(RTOSSRCDIR)/queue.c
|
||||
SRC += $(RTOSSRCDIR)/tasks.c
|
||||
|
||||
## RTOS Portable
|
||||
SRC += $(RTOSSRCDIR)/portable/GCC/ARM_CM3/port.c
|
||||
SRC += $(RTOSSRCDIR)/portable/MemMang/heap_2.c
|
||||
|
||||
## Dosfs file system
|
||||
SRC += $(DOSFSDIR)/dosfs.c
|
||||
SRC += $(DOSFSDIR)/dfs_sdcard.c
|
||||
|
||||
## AHRS boot loader comms
|
||||
SRC += $(AHRSBOOTLOADER)/ahrs_spi_program_master.c
|
||||
SRC += $(AHRSBOOTLOADER)/ahrs_spi_program.c
|
||||
|
||||
## PyMite files
|
||||
#SRC += $(wildcard ${PYMITEVM}/*.c)
|
||||
#SRC += $(wildcard ${PYMITEPLAT}/*.c)
|
||||
#SRC += $(OUTDIR)/pmlib_img.c
|
||||
#SRC += $(OUTDIR)/pmlib_nat.c
|
||||
#SRC += $(OUTDIR)/pmlibusr_img.c
|
||||
#SRC += $(OUTDIR)/pmlibusr_nat.c
|
||||
|
||||
## Mass Storage Device
|
||||
#SRC += $(MSDDIR)/msd.c
|
||||
#SRC += $(MSDDIR)/msd_bot.c
|
||||
#SRC += $(MSDDIR)/msd_desc.c
|
||||
#SRC += $(MSDDIR)/msd_memory.c
|
||||
#SRC += $(MSDDIR)/msd_scsi.c
|
||||
#SRC += $(MSDDIR)/msd_scsi_data.c
|
||||
|
||||
# List C source files here which must be compiled in ARM-Mode (no -mthumb).
|
||||
# use file-extension c for "c-only"-files
|
||||
## just for testing, timer.c could be compiled in thumb-mode too
|
||||
SRCARM =
|
||||
|
||||
# List C++ source files here.
|
||||
# use file-extension .cpp for C++-files (not .C)
|
||||
CPPSRC =
|
||||
|
||||
# List C++ source files here which must be compiled in ARM-Mode.
|
||||
# use file-extension .cpp for C++-files (not .C)
|
||||
#CPPSRCARM = $(TARGET).cpp
|
||||
CPPSRCARM =
|
||||
|
||||
# List Assembler source files here.
|
||||
# Make them always end in a capital .S. Files ending in a lowercase .s
|
||||
# will not be considered source files but generated files (assembler
|
||||
# output from the compiler), and will be deleted upon "make clean"!
|
||||
# Even though the DOS/Win* filesystem matches both .s and .S the same,
|
||||
# it will preserve the spelling of the filenames, and gcc itself does
|
||||
# care about how the name is spelled on its command-line.
|
||||
ASRC = $(PIOSSTM32F10X)/startup_stm32f10x_$(MODEL)_OP.S
|
||||
|
||||
# List Assembler source files here which must be assembled in ARM-Mode..
|
||||
ASRCARM =
|
||||
|
||||
# List any extra directories to look for include files here.
|
||||
# Each directory must be seperated by a space.
|
||||
EXTRAINCDIRS = $(OPSYSTEM)
|
||||
EXTRAINCDIRS += $(OPSYSTEMINC)
|
||||
EXTRAINCDIRS += $(OPUAVTALK)
|
||||
EXTRAINCDIRS += $(OPUAVTALKINC)
|
||||
EXTRAINCDIRS += $(OPUAVOBJ)
|
||||
EXTRAINCDIRS += $(OPUAVOBJINC)
|
||||
EXTRAINCDIRS += $(PIOS)
|
||||
EXTRAINCDIRS += $(PIOSINC)
|
||||
EXTRAINCDIRS += $(FLIGHTLIBINC)
|
||||
EXTRAINCDIRS += $(PIOSSTM32F10X)
|
||||
EXTRAINCDIRS += $(PIOSCOMMON)
|
||||
EXTRAINCDIRS += $(PIOSBOARDS)
|
||||
EXTRAINCDIRS += $(STMSPDINCDIR)
|
||||
EXTRAINCDIRS += $(STMUSBINCDIR)
|
||||
EXTRAINCDIRS += $(CMSISDIR)
|
||||
EXTRAINCDIRS += $(DOSFSDIR)
|
||||
EXTRAINCDIRS += $(MSDDIR)
|
||||
EXTRAINCDIRS += $(RTOSINCDIR)
|
||||
EXTRAINCDIRS += $(APPLIBDIR)
|
||||
EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/ARM_CM3
|
||||
EXTRAINCDIRS += $(AHRSBOOTLOADERINC)
|
||||
EXTRAINCDIRS += $(PYMITEINC)
|
||||
|
||||
EXTRAINCDIRS += ${foreach MOD, ${MODULES}, Modules/${MOD}/inc} ${OPMODULEDIR}/System/inc
|
||||
|
||||
|
||||
# List any extra directories to look for library files here.
|
||||
# Also add directories where the linker should search for
|
||||
# includes from linker-script to the list
|
||||
# Each directory must be seperated by a space.
|
||||
EXTRA_LIBDIRS =
|
||||
|
||||
# Extra Libraries
|
||||
# Each library-name must be seperated by a space.
|
||||
# i.e. to link with libxyz.a, libabc.a and libefsl.a:
|
||||
# EXTRA_LIBS = xyz abc efsl
|
||||
# for newlib-lpc (file: libnewlibc-lpc.a):
|
||||
# EXTRA_LIBS = newlib-lpc
|
||||
EXTRA_LIBS =
|
||||
|
||||
# Path to Linker-Scripts
|
||||
LINKERSCRIPTPATH = $(PIOSSTM32F10X)
|
||||
|
||||
# Optimization level, can be [0, 1, 2, 3, s].
|
||||
# 0 = turn off optimization. s = optimize for size.
|
||||
# (Note: 3 is not always the best optimization level. See avr-libc FAQ.)
|
||||
|
||||
ifeq ($(DEBUG),YES)
|
||||
OPT = 0
|
||||
else
|
||||
OPT = s
|
||||
endif
|
||||
|
||||
# Output format. (can be ihex or binary or both)
|
||||
# binary to create a load-image in raw-binary format i.e. for SAM-BA,
|
||||
# ihex to create a load-image in Intel hex format
|
||||
#LOADFORMAT = ihex
|
||||
#LOADFORMAT = binary
|
||||
LOADFORMAT = both
|
||||
|
||||
# Debugging format.
|
||||
DEBUGF = dwarf-2
|
||||
|
||||
# Place project-specific -D (define) and/or
|
||||
# -U options for C here.
|
||||
CDEFS = -DSTM32F10X_$(MODEL)
|
||||
CDEFS += -DUSE_STDPERIPH_DRIVER
|
||||
CDEFS += -DUSE_$(BOARD)
|
||||
ifeq ($(ENABLE_DEBUG_PINS), YES)
|
||||
CDEFS += -DPIOS_ENABLE_DEBUG_PINS
|
||||
endif
|
||||
ifeq ($(ENABLE_AUX_UART), YES)
|
||||
CDEFS += -DPIOS_ENABLE_AUX_UART
|
||||
endif
|
||||
ifeq ($(USE_BOOTLOADER), YES)
|
||||
CDEFS += -DUSE_BOOTLOADER
|
||||
endif
|
||||
|
||||
|
||||
# Place project-specific -D and/or -U options for
|
||||
# Assembler with preprocessor here.
|
||||
#ADEFS = -DUSE_IRQ_ASM_WRAPPER
|
||||
ADEFS = -D__ASSEMBLY__
|
||||
|
||||
# Compiler flag to set the C Standard level.
|
||||
# c89 - "ANSI" C
|
||||
# gnu89 - c89 plus GCC extensions
|
||||
# c99 - ISO C99 standard (not yet fully implemented)
|
||||
# gnu99 - c99 plus GCC extensions
|
||||
CSTANDARD = -std=gnu99
|
||||
|
||||
#-----
|
||||
|
||||
# Compiler flags.
|
||||
|
||||
# -g*: generate debugging information
|
||||
# -O*: optimization level
|
||||
# -f...: tuning, see GCC manual and avr-libc documentation
|
||||
# -Wall...: warning level
|
||||
# -Wa,...: tell GCC to pass this to the assembler.
|
||||
# -adhlns...: create assembler listing
|
||||
#
|
||||
# Flags for C and C++ (arm-elf-gcc/arm-elf-g++)
|
||||
|
||||
ifeq ($(DEBUG),YES)
|
||||
CFLAGS = -g$(DEBUGF) -DDEBUG
|
||||
endif
|
||||
|
||||
CFLAGS += -O$(OPT)
|
||||
CFLAGS += -mcpu=$(MCU) -mthumb
|
||||
CFLAGS += $(CDEFS)
|
||||
CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I.
|
||||
|
||||
CFLAGS += -mapcs-frame
|
||||
CFLAGS += -fomit-frame-pointer
|
||||
ifeq ($(CODE_SOURCERY), YES)
|
||||
CFLAGS += -fpromote-loop-indices
|
||||
endif
|
||||
|
||||
CFLAGS += -Wall
|
||||
CFLAGS += -Werror
|
||||
CFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<))))
|
||||
# Compiler flags to generate dependency files:
|
||||
CFLAGS += -MD -MP -MF $(OUTDIR)/dep/$(@F).d
|
||||
|
||||
# flags only for C
|
||||
#CONLYFLAGS += -Wnested-externs
|
||||
CONLYFLAGS += $(CSTANDARD)
|
||||
|
||||
# Assembler flags.
|
||||
# -Wa,...: tell GCC to pass this to the assembler.
|
||||
# -ahlns: create listing
|
||||
ASFLAGS = -mcpu=$(MCU) -mthumb -I. -x assembler-with-cpp
|
||||
ASFLAGS += $(ADEFS)
|
||||
ASFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<))))
|
||||
ASFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS))
|
||||
|
||||
MATH_LIB = -lm
|
||||
|
||||
# Linker flags.
|
||||
# -Wl,...: tell GCC to pass this to linker.
|
||||
# -Map: create map file
|
||||
# --cref: add cross reference to map file
|
||||
LDFLAGS = -nostartfiles -Wl,-Map=$(OUTDIR)/$(TARGET).map,--cref,--gc-sections
|
||||
LDFLAGS += $(patsubst %,-L%,$(EXTRA_LIBDIRS))
|
||||
LDFLAGS += -lc
|
||||
LDFLAGS += $(patsubst %,-l%,$(EXTRA_LIBS))
|
||||
LDFLAGS += $(MATH_LIB)
|
||||
LDFLAGS += -lc -lgcc
|
||||
|
||||
# Set linker-script name depending on selected submodel name
|
||||
LDFLAGS +=-T$(LINKERSCRIPTPATH)/link_stm32f10x_$(BOOT_MODEL).ld
|
||||
|
||||
# ---------------------------------------------------------------------------
|
||||
# Options for OpenOCD flash-programming
|
||||
# see openocd.pdf/openocd.texi for further information
|
||||
#
|
||||
OOCD_LOADFILE+=$(OUTDIR)/$(TARGET).elf
|
||||
# if OpenOCD is in the $PATH just set OOCD_EXE=openocd
|
||||
OOCD_EXE=openocd
|
||||
# debug level
|
||||
OOCD_CL=-d0
|
||||
# interface and board/target settings (using the OOCD target-library here)
|
||||
UNAME := $(shell uname)
|
||||
ifeq ($(UNAME), Darwin)
|
||||
OOCD_CL+=-f ../Project/OpenOCD/floss-jtag.openpilot.osx.cfg -f ../Project/OpenOCD/stm32.cfg
|
||||
else
|
||||
OOCD_CL+=-f ../Project/OpenOCD/floss-jtag.openpilot.cfg -f ../Project/OpenOCD/stm32.cfg
|
||||
endif
|
||||
# initialize
|
||||
OOCD_CL+=-c init
|
||||
# show the targets
|
||||
OOCD_CL+=-c targets
|
||||
# commands to prepare flash-write
|
||||
OOCD_CL+= -c "reset halt"
|
||||
# flash erase
|
||||
OOCD_CL+=-c "stm32x mass_erase 0"
|
||||
# flash-write
|
||||
OOCD_CL+=-c "flash write_image $(OOCD_LOADFILE)"
|
||||
# Verify
|
||||
OOCD_CL+=-c "verify_image $(OOCD_LOADFILE)"
|
||||
# reset target
|
||||
OOCD_CL+=-c "reset run"
|
||||
# terminate OOCD after programming
|
||||
OOCD_CL+=-c shutdown
|
||||
# ---------------------------------------------------------------------------
|
||||
|
||||
|
||||
# Define programs and commands.
|
||||
CC = $(TCHAIN_PREFIX)gcc
|
||||
CPP = $(TCHAIN_PREFIX)g++
|
||||
AR = $(TCHAIN_PREFIX)ar
|
||||
OBJCOPY = $(TCHAIN_PREFIX)objcopy
|
||||
OBJDUMP = $(TCHAIN_PREFIX)objdump
|
||||
SIZE = $(TCHAIN_PREFIX)size
|
||||
NM = $(TCHAIN_PREFIX)nm
|
||||
REMOVE = $(REMOVE_CMD) -f
|
||||
PYTHON = python
|
||||
###SHELL = sh
|
||||
###COPY = cp
|
||||
|
||||
|
||||
|
||||
# Define Messages
|
||||
# English
|
||||
MSG_ERRORS_NONE = Errors: none
|
||||
MSG_BEGIN = ${quote}-------- begin (mode: $(RUN_MODE)) --------${quote}
|
||||
MSG_END = ${quote}-------- end --------${quote}
|
||||
MSG_MODINIT = ${quote}**** Generating ModInit.c${quote}
|
||||
MSG_SIZE_BEFORE = ${quote}Size before:${quote}
|
||||
MSG_SIZE_AFTER = ${quote}Size after build:${quote}
|
||||
MSG_LOAD_FILE = ${quote}Creating load file:${quote}
|
||||
MSG_EXTENDED_LISTING = ${quote}Creating Extended Listing/Disassembly:${quote}
|
||||
MSG_SYMBOL_TABLE = ${quote}Creating Symbol Table:${quote}
|
||||
MSG_LINKING = ${quote}**** Linking :${quote}
|
||||
MSG_COMPILING = ${quote}**** Compiling C :${quote}
|
||||
MSG_COMPILING_ARM = ${quote}**** Compiling C (ARM-only):${quote}
|
||||
MSG_COMPILINGCPP = ${quote}Compiling C++ :${quote}
|
||||
MSG_COMPILINGCPP_ARM = ${quote}Compiling C++ (ARM-only):${quote}
|
||||
MSG_ASSEMBLING = ${quote}**** Assembling:${quote}
|
||||
MSG_ASSEMBLING_ARM = ${quote}****Assembling (ARM-only):${quote}
|
||||
MSG_CLEANING = ${quote}Cleaning project:${quote}
|
||||
MSG_FORMATERROR = ${quote}Can not handle output-format${quote}
|
||||
MSG_ASMFROMC = ${quote}Creating asm-File from C-Source:${quote}
|
||||
MSG_ASMFROMC_ARM = ${quote}Creating asm-File from C-Source (ARM-only):${quote}
|
||||
MSG_PYMITEINIT = ${quote}**** Generating PyMite intermediate code${quote}
|
||||
|
||||
# List of all source files.
|
||||
ALLSRC = $(ASRCARM) $(ASRC) $(SRCARM) $(SRC) $(CPPSRCARM) $(CPPSRC)
|
||||
# List of all source files without directory and file-extension.
|
||||
ALLSRCBASE = $(notdir $(basename $(ALLSRC)))
|
||||
|
||||
# Define all object files.
|
||||
ALLOBJ = $(addprefix $(OUTDIR)/, $(addsuffix .o, $(ALLSRCBASE)))
|
||||
|
||||
# Define all listing files (used for make clean).
|
||||
LSTFILES = $(addprefix $(OUTDIR)/, $(addsuffix .lst, $(ALLSRCBASE)))
|
||||
# Define all depedency-files (used for make clean).
|
||||
DEPFILES = $(addprefix $(OUTDIR)/dep/, $(addsuffix .o.d, $(ALLSRCBASE)))
|
||||
|
||||
elf: $(OUTDIR)/$(TARGET).elf
|
||||
lss: $(OUTDIR)/$(TARGET).lss
|
||||
sym: $(OUTDIR)/$(TARGET).sym
|
||||
hex: $(OUTDIR)/$(TARGET).hex
|
||||
bin: $(OUTDIR)/$(TARGET).bin
|
||||
|
||||
# Default target.
|
||||
#all: begin gccversion sizebefore build sizeafter finished end
|
||||
all: begin gencode gccversion build sizeafter finished end
|
||||
|
||||
ifeq ($(LOADFORMAT),ihex)
|
||||
build: elf hex lss sym
|
||||
else
|
||||
ifeq ($(LOADFORMAT),binary)
|
||||
build: elf bin lss sym
|
||||
else
|
||||
ifeq ($(LOADFORMAT),both)
|
||||
build: elf hex bin lss sym
|
||||
else
|
||||
$(error "$(MSG_FORMATERROR) $(FORMAT)")
|
||||
endif
|
||||
endif
|
||||
endif
|
||||
|
||||
# Test if quotes are needed for the echo-command
|
||||
result = ${shell echo "test"}
|
||||
ifeq (${result}, test)
|
||||
quote = '
|
||||
else
|
||||
quote =
|
||||
endif
|
||||
|
||||
# Generate intermediate code
|
||||
gencode: ${OUTDIR}/InitMods.c #$(OUTDIR)/pmlib_img.c $(OUTDIR)/pmlib_nat.c $(OUTDIR)/pmlibusr_img.c $(OUTDIR)/pmlibusr_nat.c $(OUTDIR)/pmfeatures.h
|
||||
|
||||
# Generate code for module initialization
|
||||
${OUTDIR}/InitMods.c: Makefile
|
||||
@echo ${MSG_MODINIT}
|
||||
@echo ${quote}// Autogenerated file${quote} > ${OUTDIR}/InitMods.c
|
||||
@echo ${quote}${foreach MOD, ${MODNAMES}, extern unsigned int ${MOD}Initialize(void);}${quote} >> ${OUTDIR}/InitMods.c
|
||||
@echo ${quote}void InitModules() {${quote} >> ${OUTDIR}/InitMods.c
|
||||
@echo ${quote}${foreach MOD, ${MODNAMES}, ${MOD}Initialize();}${quote} >> ${OUTDIR}/InitMods.c
|
||||
@echo ${quote}}${quote} >> ${OUTDIR}/InitMods.c
|
||||
|
||||
# Generate code for PyMite
|
||||
#$(OUTDIR)/pmlib_img.c $(OUTDIR)/pmlib_nat.c $(OUTDIR)/pmlibusr_img.c $(OUTDIR)/pmlibusr_nat.c $(OUTDIR)/pmfeatures.h: $(wildcard $(PYMITELIB)/*.py) $(wildcard $(PYMITEPLAT)/*.py) $(wildcard $(FLIGHTPLANLIB)/*.py) $(wildcard $(FLIGHTPLANS)/*.py)
|
||||
# @echo ${MSG_PYMITEINIT}
|
||||
# @$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -s --memspace=flash -o $(OUTDIR)/pmlib_img.c --native-file=$(OUTDIR)/pmlib_nat.c $(PYMITELIB)/list.py $(PYMITELIB)/dict.py $(PYMITELIB)/__bi.py $(PYMITELIB)/sys.py $(PYMITELIB)/string.py $(wildcard $(FLIGHTPLANLIB)/*.py)
|
||||
# @$(PYTHON) $(PYMITETOOLS)/pmGenPmFeatures.py $(PYMITEPLAT)/pmfeatures.py > $(OUTDIR)/pmfeatures.h
|
||||
# @$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -u -o $(OUTDIR)/pmlibusr_img.c --native-file=$(OUTDIR)/pmlibusr_nat.c $(FLIGHTPLANS)/test.py
|
||||
|
||||
# Eye candy.
|
||||
begin:
|
||||
## @echo
|
||||
@echo $(MSG_BEGIN)
|
||||
|
||||
finished:
|
||||
## @echo $(MSG_ERRORS_NONE)
|
||||
|
||||
end:
|
||||
@echo $(MSG_END)
|
||||
## @echo
|
||||
|
||||
# Display sizes of sections.
|
||||
ELFSIZE = $(SIZE) -A $(OUTDIR)/$(TARGET).elf
|
||||
##ELFSIZE = $(SIZE) --format=Berkeley --common $(OUTDIR)/$(TARGET).elf
|
||||
sizebefore:
|
||||
# @if [ -f $(OUTDIR)/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_BEFORE); $(ELFSIZE); echo; fi
|
||||
|
||||
sizeafter:
|
||||
# @if [ -f $(OUTDIR)/$(TARGET).elf ]; then echo; echo $(MSG_SIZE_AFTER); $(ELFSIZE); echo; fi
|
||||
@echo $(MSG_SIZE_AFTER)
|
||||
$(ELFSIZE)
|
||||
|
||||
# Display compiler version information.
|
||||
gccversion :
|
||||
@$(CC) --version
|
||||
# @echo $(ALLOBJ)
|
||||
|
||||
# Program the device.
|
||||
ifeq ($(USE_BOOTLOADER), YES)
|
||||
# Program the device with OP Upload Tool".
|
||||
program: $(OUTDIR)/$(TARGET).bin
|
||||
@echo ${quote}Programming with OP Upload Tool${quote}
|
||||
../../ground/src/experimental/upload-build-desktop/debug/OPUploadTool -d 0 -p $(OUTDIR)/$(TARGET).bin
|
||||
else
|
||||
ifeq ($(FLASH_TOOL),OPENOCD)
|
||||
# Program the device with Dominic Rath's OPENOCD in "batch-mode", needs cfg and "reset-script".
|
||||
program: $(OUTDIR)/$(TARGET).elf
|
||||
@echo ${quote}Programming with OPENOCD${quote}
|
||||
$(OOCD_EXE) $(OOCD_CL)
|
||||
endif
|
||||
endif
|
||||
|
||||
# Create final output file (.hex) from ELF output file.
|
||||
%.hex: %.elf
|
||||
## @echo
|
||||
@echo $(MSG_LOAD_FILE) $@
|
||||
$(OBJCOPY) -O ihex $< $@
|
||||
|
||||
# Create final output file (.bin) from ELF output file.
|
||||
%.bin: %.elf
|
||||
## @echo
|
||||
@echo $(MSG_LOAD_FILE) $@
|
||||
$(OBJCOPY) -O binary $< $@
|
||||
|
||||
# Create extended listing file/disassambly from ELF output file.
|
||||
# using objdump testing: option -C
|
||||
%.lss: %.elf
|
||||
## @echo
|
||||
@echo $(MSG_EXTENDED_LISTING) $@
|
||||
$(OBJDUMP) -h -S -C -r $< > $@
|
||||
# $(OBJDUMP) -x -S $< > $@
|
||||
|
||||
# Create a symbol table from ELF output file.
|
||||
%.sym: %.elf
|
||||
## @echo
|
||||
@echo $(MSG_SYMBOL_TABLE) $@
|
||||
$(NM) -n $< > $@
|
||||
|
||||
# Link: create ELF output file from object files.
|
||||
.SECONDARY : $(TARGET).elf
|
||||
.PRECIOUS : $(ALLOBJ)
|
||||
%.elf: $(ALLOBJ)
|
||||
@echo $(MSG_LINKING) $@
|
||||
# use $(CC) for C-only projects or $(CPP) for C++-projects:
|
||||
$(CC) $(THUMB) $(CFLAGS) $(ALLOBJ) --output $@ $(LDFLAGS)
|
||||
# $(CPP) $(THUMB) $(CFLAGS) $(ALLOBJ) --output $@ $(LDFLAGS)
|
||||
|
||||
|
||||
# Assemble: create object files from assembler source files.
|
||||
define ASSEMBLE_TEMPLATE
|
||||
$(OUTDIR)/$(notdir $(basename $(1))).o : $(1)
|
||||
## @echo
|
||||
@echo $(MSG_ASSEMBLING) $$< to $$@
|
||||
$(CC) -c $(THUMB) $$(ASFLAGS) $$< -o $$@
|
||||
endef
|
||||
$(foreach src, $(ASRC), $(eval $(call ASSEMBLE_TEMPLATE, $(src))))
|
||||
|
||||
# Assemble: create object files from assembler source files. ARM-only
|
||||
define ASSEMBLE_ARM_TEMPLATE
|
||||
$(OUTDIR)/$(notdir $(basename $(1))).o : $(1)
|
||||
## @echo
|
||||
@echo $(MSG_ASSEMBLING_ARM) $$< to $$@
|
||||
$(CC) -c $$(ASFLAGS) $$< -o $$@
|
||||
endef
|
||||
$(foreach src, $(ASRCARM), $(eval $(call ASSEMBLE_ARM_TEMPLATE, $(src))))
|
||||
|
||||
|
||||
# Compile: create object files from C source files.
|
||||
define COMPILE_C_TEMPLATE
|
||||
$(OUTDIR)/$(notdir $(basename $(1))).o : $(1)
|
||||
## @echo
|
||||
@echo $(MSG_COMPILING) $$< to $$@
|
||||
$(CC) -c $(THUMB) $$(CFLAGS) $$(CONLYFLAGS) $$< -o $$@
|
||||
endef
|
||||
$(foreach src, $(SRC), $(eval $(call COMPILE_C_TEMPLATE, $(src))))
|
||||
|
||||
# Compile: create object files from C source files. ARM-only
|
||||
define COMPILE_C_ARM_TEMPLATE
|
||||
$(OUTDIR)/$(notdir $(basename $(1))).o : $(1)
|
||||
## @echo
|
||||
@echo $(MSG_COMPILING_ARM) $$< to $$@
|
||||
$(CC) -c $$(CFLAGS) $$(CONLYFLAGS) $$< -o $$@
|
||||
endef
|
||||
$(foreach src, $(SRCARM), $(eval $(call COMPILE_C_ARM_TEMPLATE, $(src))))
|
||||
|
||||
|
||||
# Compile: create object files from C++ source files.
|
||||
define COMPILE_CPP_TEMPLATE
|
||||
$(OUTDIR)/$(notdir $(basename $(1))).o : $(1)
|
||||
## @echo
|
||||
@echo $(MSG_COMPILINGCPP) $$< to $$@
|
||||
$(CC) -c $(THUMB) $$(CFLAGS) $$(CPPFLAGS) $$< -o $$@
|
||||
endef
|
||||
$(foreach src, $(CPPSRC), $(eval $(call COMPILE_CPP_TEMPLATE, $(src))))
|
||||
|
||||
# Compile: create object files from C++ source files. ARM-only
|
||||
define COMPILE_CPP_ARM_TEMPLATE
|
||||
$(OUTDIR)/$(notdir $(basename $(1))).o : $(1)
|
||||
## @echo
|
||||
@echo $(MSG_COMPILINGCPP_ARM) $$< to $$@
|
||||
$(CC) -c $$(CFLAGS) $$(CPPFLAGS) $$< -o $$@
|
||||
endef
|
||||
$(foreach src, $(CPPSRCARM), $(eval $(call COMPILE_CPP_ARM_TEMPLATE, $(src))))
|
||||
|
||||
|
||||
# Compile: create assembler files from C source files. ARM/Thumb
|
||||
$(SRC:.c=.s) : %.s : %.c
|
||||
@echo $(MSG_ASMFROMC) $< to $@
|
||||
$(CC) $(THUMB) -S $(CFLAGS) $(CONLYFLAGS) $< -o $@
|
||||
|
||||
# Compile: create assembler files from C source files. ARM only
|
||||
$(SRCARM:.c=.s) : %.s : %.c
|
||||
@echo $(MSG_ASMFROMC_ARM) $< to $@
|
||||
$(CC) -S $(CFLAGS) $(CONLYFLAGS) $< -o $@
|
||||
|
||||
# Generate Doxygen documents
|
||||
docs:
|
||||
doxygen $(DOXYGENDIR)/doxygen.cfg
|
||||
|
||||
# Target: clean project.
|
||||
clean: begin clean_list finished end
|
||||
|
||||
clean_list :
|
||||
## @echo
|
||||
@echo $(MSG_CLEANING)
|
||||
$(REMOVE) $(OUTDIR)/$(TARGET).map
|
||||
$(REMOVE) $(OUTDIR)/$(TARGET).elf
|
||||
$(REMOVE) $(OUTDIR)/$(TARGET).hex
|
||||
$(REMOVE) $(OUTDIR)/$(TARGET).bin
|
||||
$(REMOVE) $(OUTDIR)/$(TARGET).sym
|
||||
$(REMOVE) $(OUTDIR)/$(TARGET).lss
|
||||
$(REMOVE) $(wildcard $(OUTDIR)/*.c)
|
||||
$(REMOVE) $(wildcard $(OUTDIR)/*.h)
|
||||
$(REMOVE) $(ALLOBJ)
|
||||
$(REMOVE) $(LSTFILES)
|
||||
$(REMOVE) $(DEPFILES)
|
||||
$(REMOVE) $(SRC:.c=.s)
|
||||
$(REMOVE) $(SRCARM:.c=.s)
|
||||
$(REMOVE) $(CPPSRC:.cpp=.s)
|
||||
$(REMOVE) $(CPPSRCARM:.cpp=.s)
|
||||
|
||||
|
||||
# Create output files directory
|
||||
# all known MS Windows OS define the ComSpec environment variable
|
||||
ifdef ComSpec
|
||||
$(shell md $(OUTDIR) 2>NUL)
|
||||
else
|
||||
$(shell mkdir $(OUTDIR) 2>/dev/null)
|
||||
endif
|
||||
|
||||
# Include the dependency files.
|
||||
ifdef ComSpec
|
||||
-include $(shell md $(OUTDIR)\dep 2>NUL) $(wildcard $(OUTDIR)/dep/*)
|
||||
else
|
||||
-include $(shell mkdir $(OUTDIR) 2>/dev/null) $(shell mkdir $(OUTDIR)/dep 2>/dev/null) $(wildcard $(OUTDIR)/dep/*)
|
||||
endif
|
||||
|
||||
|
||||
|
||||
# Listing of phony targets.
|
||||
.PHONY : all begin finish end sizebefore sizeafter gccversion \
|
||||
build elf hex bin lss sym clean clean_list program gencode
|
||||
|
213
flight/CopterControl/System/alarms.c
Normal file
213
flight/CopterControl/System/alarms.c
Normal file
@ -0,0 +1,213 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotSystem OpenPilot System
|
||||
* @{
|
||||
* @addtogroup OpenPilotLibraries OpenPilot System Libraries
|
||||
* @brief OpenPilot System libraries are available to all OP modules.
|
||||
* @{
|
||||
* @file alarms.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Library for setting and clearing system alarms
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#include "openpilot.h"
|
||||
#include "alarms.h"
|
||||
|
||||
// Private constants
|
||||
|
||||
// Private types
|
||||
|
||||
// Private variables
|
||||
static xSemaphoreHandle lock;
|
||||
|
||||
// Private functions
|
||||
static int32_t hasSeverity(SystemAlarmsAlarmOptions severity);
|
||||
|
||||
/**
|
||||
* Initialize the alarms library
|
||||
*/
|
||||
int32_t AlarmsInitialize(void)
|
||||
{
|
||||
lock = xSemaphoreCreateRecursiveMutex();
|
||||
//do not change the default states of the alarms, let the init code generated by the uavobjectgenerator handle that
|
||||
//AlarmsClearAll();
|
||||
//AlarmsDefaultAll();
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Set an alarm
|
||||
* @param alarm The system alarm to be modified
|
||||
* @param severity The alarm severity
|
||||
* @return 0 if success, -1 if an error
|
||||
*/
|
||||
int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity)
|
||||
{
|
||||
SystemAlarmsData alarms;
|
||||
|
||||
// Check that this is a valid alarm
|
||||
if (alarm >= SYSTEMALARMS_ALARM_NUMELEM)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(lock, portMAX_DELAY);
|
||||
|
||||
// Read alarm and update its severity only if it was changed
|
||||
SystemAlarmsGet(&alarms);
|
||||
if ( alarms.Alarm[alarm] != severity )
|
||||
{
|
||||
alarms.Alarm[alarm] = severity;
|
||||
SystemAlarmsSet(&alarms);
|
||||
SystemAlarmsUpdated(); // force telemetry update since the alarm was changed
|
||||
}
|
||||
|
||||
// Release lock
|
||||
xSemaphoreGiveRecursive(lock);
|
||||
return 0;
|
||||
|
||||
}
|
||||
|
||||
/**
|
||||
* Get an alarm
|
||||
* @param alarm The system alarm to be read
|
||||
* @return Alarm severity
|
||||
*/
|
||||
SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm)
|
||||
{
|
||||
SystemAlarmsData alarms;
|
||||
|
||||
// Check that this is a valid alarm
|
||||
if (alarm >= SYSTEMALARMS_ALARM_NUMELEM)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
// Read alarm
|
||||
SystemAlarmsGet(&alarms);
|
||||
return alarms.Alarm[alarm];
|
||||
}
|
||||
|
||||
/**
|
||||
* Set an alarm to it's default value
|
||||
* @param alarm The system alarm to be modified
|
||||
* @return 0 if success, -1 if an error
|
||||
*/
|
||||
int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm)
|
||||
{
|
||||
return AlarmsSet(alarm, SYSTEMALARMS_ALARM_DEFAULT);
|
||||
}
|
||||
|
||||
/**
|
||||
* Default all alarms
|
||||
*/
|
||||
void AlarmsDefaultAll()
|
||||
{
|
||||
uint32_t n;
|
||||
for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n)
|
||||
{
|
||||
AlarmsDefault(n);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Clear an alarm
|
||||
* @param alarm The system alarm to be modified
|
||||
* @return 0 if success, -1 if an error
|
||||
*/
|
||||
int32_t AlarmsClear(SystemAlarmsAlarmElem alarm)
|
||||
{
|
||||
return AlarmsSet(alarm, SYSTEMALARMS_ALARM_OK);
|
||||
}
|
||||
|
||||
/**
|
||||
* Clear all alarms
|
||||
*/
|
||||
void AlarmsClearAll()
|
||||
{
|
||||
uint32_t n;
|
||||
for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n)
|
||||
{
|
||||
AlarmsClear(n);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Check if there are any alarms with the given or higher severity
|
||||
* @return 0 if no alarms are found, 1 if at least one alarm is found
|
||||
*/
|
||||
int32_t AlarmsHasWarnings()
|
||||
{
|
||||
return hasSeverity(SYSTEMALARMS_ALARM_WARNING);
|
||||
}
|
||||
|
||||
/**
|
||||
* Check if there are any alarms with error or higher severity
|
||||
* @return 0 if no alarms are found, 1 if at least one alarm is found
|
||||
*/
|
||||
int32_t AlarmsHasErrors()
|
||||
{
|
||||
return hasSeverity(SYSTEMALARMS_ALARM_ERROR);
|
||||
};
|
||||
|
||||
/**
|
||||
* Check if there are any alarms with critical or higher severity
|
||||
* @return 0 if no alarms are found, 1 if at least one alarm is found
|
||||
*/
|
||||
int32_t AlarmsHasCritical()
|
||||
{
|
||||
return hasSeverity(SYSTEMALARMS_ALARM_CRITICAL);
|
||||
};
|
||||
|
||||
/**
|
||||
* Check if there are any alarms with the given or higher severity
|
||||
* @return 0 if no alarms are found, 1 if at least one alarm is found
|
||||
*/
|
||||
static int32_t hasSeverity(SystemAlarmsAlarmOptions severity)
|
||||
{
|
||||
SystemAlarmsData alarms;
|
||||
uint32_t n;
|
||||
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(lock, portMAX_DELAY);
|
||||
|
||||
// Read alarms
|
||||
SystemAlarmsGet(&alarms);
|
||||
|
||||
// Go through alarms and check if any are of the given severity or higher
|
||||
for (n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n)
|
||||
{
|
||||
if ( alarms.Alarm[n] >= severity)
|
||||
{
|
||||
xSemaphoreGiveRecursive(lock);
|
||||
return 1;
|
||||
}
|
||||
}
|
||||
|
||||
// If this point is reached then no alarms found
|
||||
xSemaphoreGiveRecursive(lock);
|
||||
return 0;
|
||||
}
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
||||
|
@ -1,9 +1,12 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file eventdispatcher.h
|
||||
* @addtogroup OpenPilotSystem OpenPilot System
|
||||
* @{
|
||||
* @addtogroup OpenPilotLibraries OpenPilot System Libraries
|
||||
* @{
|
||||
* @file alarms.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Include files of the uavobjectlist library
|
||||
* @brief Include file of the alarm library
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
@ -22,26 +25,26 @@
|
||||
* with this program; if not, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
#ifndef ALARMS_H
|
||||
#define ALARMS_H
|
||||
|
||||
#ifndef EVENTDISPATCHER_H
|
||||
#define EVENTDISPATCHER_H
|
||||
#include "systemalarms.h"
|
||||
#define SYSTEMALARMS_ALARM_DEFAULT SYSTEMALARMS_ALARM_UNINITIALISED
|
||||
|
||||
int32_t AlarmsInitialize(void);
|
||||
int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity);
|
||||
SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm);
|
||||
int32_t AlarmsDefault(SystemAlarmsAlarmElem alarm);
|
||||
void AlarmsDefaultAll();
|
||||
int32_t AlarmsClear(SystemAlarmsAlarmElem alarm);
|
||||
void AlarmsClearAll();
|
||||
int32_t AlarmsHasWarnings();
|
||||
int32_t AlarmsHasErrors();
|
||||
int32_t AlarmsHasCritical();
|
||||
|
||||
#endif // ALARMS_H
|
||||
|
||||
// Public types
|
||||
/**
|
||||
* Event dispatcher statistics
|
||||
*/
|
||||
typedef struct {
|
||||
uint32_t eventErrors;
|
||||
} EventStats;
|
||||
|
||||
// Public functions
|
||||
int32_t EventDispatcherInitialize();
|
||||
void EventGetStats(EventStats* statsOut);
|
||||
void EventClearStats();
|
||||
int32_t EventCallbackDispatch(UAVObjEvent* ev, UAVObjEventCallback cb);
|
||||
int32_t EventPeriodicCallbackCreate(UAVObjEvent* ev, UAVObjEventCallback cb, int32_t periodMs);
|
||||
int32_t EventPeriodicCallbackUpdate(UAVObjEvent* ev, UAVObjEventCallback cb, int32_t periodMs);
|
||||
int32_t EventPeriodicQueueCreate(UAVObjEvent* ev, xQueueHandle queue, int32_t periodMs);
|
||||
int32_t EventPeriodicQueueUpdate(UAVObjEvent* ev, xQueueHandle queue, int32_t periodMs);
|
||||
|
||||
#endif // EVENTDISPATCHER_H
|
||||
* @}
|
||||
* @}
|
||||
*/
|
39
flight/CopterControl/System/inc/op_config.h
Normal file
39
flight/CopterControl/System/inc/op_config.h
Normal file
@ -0,0 +1,39 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotSystem OpenPilot System
|
||||
* @{
|
||||
* @addtogroup OpenPilotCore OpenPilot Core
|
||||
* @{
|
||||
*
|
||||
* @file op_config.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief OpenPilot configuration header.
|
||||
* Compile time config for OpenPilot Application
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
|
||||
#ifndef OP_CONFIG_H
|
||||
#define OP_CONFIG_H
|
||||
|
||||
#endif /* OP_CONFIG_H */
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
53
flight/CopterControl/System/inc/openpilot.h
Normal file
53
flight/CopterControl/System/inc/openpilot.h
Normal file
@ -0,0 +1,53 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotSystem OpenPilot System
|
||||
* @{
|
||||
* @addtogroup OpenPilotCore OpenPilot Core
|
||||
* @{
|
||||
* @file openpilot.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Main OpenPilot header.
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
|
||||
#ifndef OPENPILOT_H
|
||||
#define OPENPILOT_H
|
||||
|
||||
|
||||
/* PIOS Includes */
|
||||
#include <pios.h>
|
||||
|
||||
/* OpenPilot Libraries */
|
||||
#include "op_config.h"
|
||||
#include "utlist.h"
|
||||
#include "uavobjectmanager.h"
|
||||
#include "eventdispatcher.h"
|
||||
#include "alarms.h"
|
||||
#include "taskmonitor.h"
|
||||
#include "uavtalk.h"
|
||||
|
||||
/* Global Functions */
|
||||
void OpenPilotInit(void);
|
||||
|
||||
#endif /* OPENPILOT_H */
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
84
flight/CopterControl/System/inc/pios_board_posix.h
Normal file
84
flight/CopterControl/System/inc/pios_board_posix.h
Normal file
@ -0,0 +1,84 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file pios_board.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Defines board hardware for the OpenPilot Version 1.1 hardware.
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
|
||||
#ifndef PIOS_BOARD_H
|
||||
#define PIOS_BOARD_H
|
||||
|
||||
|
||||
|
||||
|
||||
//------------------------
|
||||
// PIOS_LED
|
||||
//------------------------
|
||||
//#define PIOS_LED_LED1_GPIO_PORT GPIOC
|
||||
//#define PIOS_LED_LED1_GPIO_PIN GPIO_Pin_12
|
||||
//#define PIOS_LED_LED1_GPIO_CLK RCC_APB2Periph_GPIOC
|
||||
//#define PIOS_LED_LED2_GPIO_PORT GPIOC
|
||||
//#define PIOS_LED_LED2_GPIO_PIN GPIO_Pin_13
|
||||
//#define PIOS_LED_LED2_GPIO_CLK RCC_APB2Periph_GPIOC
|
||||
#define PIOS_LED_NUM 2
|
||||
//#define PIOS_LED_PORTS { PIOS_LED_LED1_GPIO_PORT, PIOS_LED_LED2_GPIO_PORT }
|
||||
//#define PIOS_LED_PINS { PIOS_LED_LED1_GPIO_PIN, PIOS_LED_LED2_GPIO_PIN }
|
||||
//#define PIOS_LED_CLKS { PIOS_LED_LED1_GPIO_CLK, PIOS_LED_LED2_GPIO_CLK }
|
||||
|
||||
|
||||
//-------------------------
|
||||
// COM
|
||||
//
|
||||
// See also pios_board_posix.c
|
||||
//-------------------------
|
||||
//#define PIOS_USART_TX_BUFFER_SIZE 256
|
||||
#define PIOS_COM_BUFFER_SIZE 1024
|
||||
#define PIOS_UDP_RX_BUFFER_SIZE PIOS_COM_BUFFER_SIZE
|
||||
|
||||
#define PIOS_COM_TELEM_RF 0
|
||||
#define PIOS_COM_GPS 1
|
||||
#define PIOS_COM_TELEM_USB 2
|
||||
|
||||
#ifdef PIOS_ENABLE_AUX_UART
|
||||
#define PIOS_COM_AUX 3
|
||||
#define PIOS_COM_DEBUG PIOS_COM_AUX
|
||||
#endif
|
||||
|
||||
/**
|
||||
* glue macros for file IO
|
||||
* STM32 uses DOSFS for file IO
|
||||
*/
|
||||
#define PIOS_FOPEN_READ(filename,file) (file=fopen((char*)filename,"r"))==NULL
|
||||
|
||||
#define PIOS_FOPEN_WRITE(filename,file) (file=fopen((char*)filename,"w"))==NULL
|
||||
|
||||
#define PIOS_FREAD(file,bufferadr,length,resultadr) (*resultadr=fread((uint8_t*)bufferadr,1,length,*file)) != length
|
||||
|
||||
#define PIOS_FWRITE(file,bufferadr,length,resultadr) *resultadr=fwrite((uint8_t*)bufferadr,1,length,*file)
|
||||
|
||||
|
||||
|
||||
#define PIOS_FCLOSE(file) fclose(file)
|
||||
|
||||
#define PIOS_FUNLINK(file) unlink((char*)filename)
|
||||
|
||||
#endif /* PIOS_BOARD_H */
|
82
flight/CopterControl/System/inc/pios_config.h
Normal file
82
flight/CopterControl/System/inc/pios_config.h
Normal file
@ -0,0 +1,82 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotSystem OpenPilot System
|
||||
* @{
|
||||
* @addtogroup OpenPilotCore OpenPilot Core
|
||||
* @{
|
||||
*
|
||||
* @file pios_config.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief PiOS configuration header.
|
||||
* Central compile time config for the project.
|
||||
* In particular, pios_config.h is where you define which PiOS libraries
|
||||
* and features are included in the firmware.
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
|
||||
#ifndef PIOS_CONFIG_H
|
||||
#define PIOS_CONFIG_H
|
||||
|
||||
|
||||
/* Enable/Disable PiOS Modules */
|
||||
#define PIOS_INCLUDE_ADC
|
||||
#define PIOS_INCLUDE_DELAY
|
||||
#define PIOS_INCLUDE_I2C
|
||||
#define PIOS_INCLUDE_IRQ
|
||||
#define PIOS_INCLUDE_LED
|
||||
//#define PIOS_INCLUDE_SPEKTRUM
|
||||
//#define PIOS_INCLUDE_PPM
|
||||
#define PIOS_INCLUDE_PWM
|
||||
#define PIOS_INCLUDE_SERVO
|
||||
#define PIOS_INCLUDE_SPI
|
||||
#define PIOS_INCLUDE_SYS
|
||||
#define PIOS_INCLUDE_USART
|
||||
#define PIOS_INCLUDE_USB_HID
|
||||
#define PIOS_INCLUDE_BMP085
|
||||
#define PIOS_INCLUDE_OPAHRS
|
||||
#define PIOS_INCLUDE_COM
|
||||
#define PIOS_INCLUDE_SDCARD
|
||||
#define PIOS_INCLUDE_SETTINGS
|
||||
#define PIOS_INCLUDE_FREERTOS
|
||||
#define PIOS_INCLUDE_GPIO
|
||||
#define PIOS_INCLUDE_EXTI
|
||||
#define PIOS_INCLUDE_WDG
|
||||
#define PIOS_INCLUDE_I2C_ESC
|
||||
|
||||
/* Defaults for Logging */
|
||||
#define LOG_FILENAME "PIOS.LOG"
|
||||
#define STARTUP_LOG_ENABLED 1
|
||||
|
||||
/* COM Module */
|
||||
#define GPS_BAUDRATE 19200
|
||||
#define TELEM_BAUDRATE 19200
|
||||
#define AUXUART_ENABLED 0
|
||||
#define AUXUART_BAUDRATE 19200
|
||||
|
||||
/* Servos */
|
||||
#define SERVOS_POSITION_MIN 800
|
||||
#define SERVOS_POSITION_MAX 2200
|
||||
|
||||
|
||||
#endif /* PIOS_CONFIG_H */
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
58
flight/CopterControl/System/inc/pios_config_posix.h
Normal file
58
flight/CopterControl/System/inc/pios_config_posix.h
Normal file
@ -0,0 +1,58 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file pios_config.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief PiOS configuration header.
|
||||
* Central compile time config for the project.
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
|
||||
#ifndef PIOS_CONFIG_POSIX_H
|
||||
#define PIOS_CONFIG_POSIX_H
|
||||
|
||||
|
||||
/* Enable/Disable PiOS Modules */
|
||||
#define PIOS_INCLUDE_SYS
|
||||
#define PIOS_INCLUDE_DELAY
|
||||
#define PIOS_INCLUDE_LED
|
||||
#define PIOS_INCLUDE_SDCARD
|
||||
#define PIOS_INCLUDE_FREERTOS
|
||||
#define PIOS_INCLUDE_COM
|
||||
#define PIOS_INCLUDE_UDP
|
||||
#define PIOS_INCLUDE_SERVO
|
||||
|
||||
|
||||
/* Defaults for Logging */
|
||||
#define LOG_FILENAME "PIOS.LOG"
|
||||
#define STARTUP_LOG_ENABLED 1
|
||||
|
||||
/* COM Module */
|
||||
#define GPS_BAUDRATE 19200
|
||||
#define TELEM_BAUDRATE 19200
|
||||
#define AUXUART_ENABLED 0
|
||||
#define AUXUART_BAUDRATE 19200
|
||||
|
||||
/* Servos */
|
||||
#define SERVOS_POSITION_MIN 800
|
||||
#define SERVOS_POSITION_MAX 2200
|
||||
|
||||
|
||||
#endif /* PIOS_CONFIG_POSIX_H */
|
42
flight/CopterControl/System/inc/taskmonitor.h
Normal file
42
flight/CopterControl/System/inc/taskmonitor.h
Normal file
@ -0,0 +1,42 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotSystem OpenPilot System
|
||||
* @{
|
||||
* @addtogroup OpenPilotLibraries OpenPilot System Libraries
|
||||
* @{
|
||||
* @file taskmonitor.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Include file of the task monitoring library
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
#ifndef TASKMONITOR_H
|
||||
#define TASKMONITOR_H
|
||||
|
||||
#include "taskinfo.h"
|
||||
|
||||
int32_t TaskMonitorInitialize(void);
|
||||
int32_t TaskMonitorAdd(TaskInfoRunningElem task, xTaskHandle handle);
|
||||
void TaskMonitorUpdateAll(void);
|
||||
|
||||
#endif // TASKMONITOR_H
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
343
flight/CopterControl/System/openpilot.c
Normal file
343
flight/CopterControl/System/openpilot.c
Normal file
@ -0,0 +1,343 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotSystem OpenPilot System
|
||||
* @brief These files are the core system files of OpenPilot.
|
||||
* They are the ground layer just above PiOS. In practice, OpenPilot actually starts
|
||||
* in the main() function of openpilot.c
|
||||
* @{
|
||||
* @addtogroup OpenPilotCore OpenPilot Core
|
||||
* @brief This is where the OP firmware starts. Those files also define the compile-time
|
||||
* options of the firmware.
|
||||
* @{
|
||||
* @file openpilot.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Sets up and runs main OpenPilot tasks.
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
|
||||
/* OpenPilot Includes */
|
||||
#include "openpilot.h"
|
||||
#include "uavobjectsinit.h"
|
||||
#include "systemmod.h"
|
||||
|
||||
/* Task Priorities */
|
||||
#define PRIORITY_TASK_HOOKS (tskIDLE_PRIORITY + 3)
|
||||
|
||||
/* Global Variables */
|
||||
|
||||
/* Local Variables */
|
||||
#define INCLUDE_TEST_TASKS 0
|
||||
#if INCLUDE_TEST_TASKS
|
||||
static uint8_t sdcard_available;
|
||||
#endif
|
||||
FILEINFO File;
|
||||
char Buffer[1024];
|
||||
uint32_t Cache;
|
||||
|
||||
/* Function Prototypes */
|
||||
#if INCLUDE_TEST_TASKS
|
||||
static void TaskTick(void *pvParameters);
|
||||
static void TaskTesting(void *pvParameters);
|
||||
static void TaskHIDTest(void *pvParameters);
|
||||
static void TaskServos(void *pvParameters);
|
||||
static void TaskSDCard(void *pvParameters);
|
||||
#endif
|
||||
int32_t CONSOLE_Parse(uint8_t port, char c);
|
||||
void OP_ADC_NotifyChange(uint32_t pin, uint32_t pin_value);
|
||||
|
||||
/* Prototype of generated InitModules() function */
|
||||
extern void InitModules(void);
|
||||
|
||||
/* Prototype of PIOS_Board_Init() function */
|
||||
extern void PIOS_Board_Init(void);
|
||||
|
||||
/**
|
||||
* OpenPilot Main function:
|
||||
*
|
||||
* Initialize PiOS<BR>
|
||||
* Create the "System" task (SystemModInitializein Modules/System/systemmod.c) <BR>
|
||||
* Start FreeRTOS Scheduler (vTaskStartScheduler)<BR>
|
||||
* If something goes wrong, blink LED1 and LED2 every 100ms
|
||||
*
|
||||
*/
|
||||
int main()
|
||||
{
|
||||
/* NOTE: Do NOT modify the following start-up sequence */
|
||||
/* Any new initialization functions should be added in OpenPilotInit() */
|
||||
|
||||
/* Brings up System using CMSIS functions, enables the LEDs. */
|
||||
PIOS_SYS_Init();
|
||||
|
||||
/* Initialize the system thread */
|
||||
SystemModInitialize();
|
||||
|
||||
/* Start the FreeRTOS scheduler */
|
||||
vTaskStartScheduler();
|
||||
|
||||
/* If all is well we will never reach here as the scheduler will now be running. */
|
||||
/* If we do get here, it will most likely be because we ran out of heap space. */
|
||||
PIOS_LED_Off(LED1);
|
||||
PIOS_LED_Off(LED2);
|
||||
for(;;) {
|
||||
PIOS_LED_Toggle(LED1);
|
||||
PIOS_LED_Toggle(LED2);
|
||||
PIOS_DELAY_WaitmS(100);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialize the hardware, libraries and modules (called by the System thread in systemmod.c)
|
||||
*/
|
||||
void OpenPilotInit()
|
||||
{
|
||||
|
||||
/* Architecture dependant Hardware and
|
||||
* core subsystem initialisation
|
||||
* (see pios_board.c for your arch)
|
||||
* */
|
||||
|
||||
PIOS_Board_Init();
|
||||
|
||||
/* Initialize modules */
|
||||
InitModules();
|
||||
|
||||
/* Create test tasks */
|
||||
//xTaskCreate(TaskTesting, (signed portCHAR *)"Testing", configMINIMAL_STACK_SIZE , NULL, 4, NULL);
|
||||
//xTaskCreate(TaskHIDTest, (signed portCHAR *)"HIDTest", configMINIMAL_STACK_SIZE , NULL, 3, NULL);
|
||||
//xTaskCreate(TaskServos, (signed portCHAR *)"Servos", configMINIMAL_STACK_SIZE , NULL, 3, NULL);
|
||||
//xTaskCreate(TaskSDCard, (signed portCHAR *)"SDCard", configMINIMAL_STACK_SIZE, NULL, (tskIDLE_PRIORITY + 2), NULL);
|
||||
}
|
||||
|
||||
#if INCLUDE_TEST_TASKS
|
||||
static void TaskTesting(void *pvParameters)
|
||||
{
|
||||
portTickType xDelay = 250 / portTICK_RATE_MS;
|
||||
portTickType xTimeout = 10 / portTICK_RATE_MS;
|
||||
|
||||
//PIOS_BMP085_Init();
|
||||
|
||||
for(;;)
|
||||
{
|
||||
/* This blocks the task until the BMP085 EOC */
|
||||
/*
|
||||
PIOS_BMP085_StartADC(TemperatureConv);
|
||||
xSemaphoreTake(PIOS_BMP085_EOC, xTimeout);
|
||||
PIOS_BMP085_ReadADC();
|
||||
PIOS_COM_SendFormattedStringNonBlocking(COM_DEBUG_USART, "%u\r", PIOS_BMP085_GetTemperature());
|
||||
|
||||
PIOS_BMP085_StartADC(PressureConv);
|
||||
xSemaphoreTake(PIOS_BMP085_EOC, xTimeout);
|
||||
PIOS_BMP085_ReadADC();
|
||||
PIOS_COM_SendFormattedStringNonBlocking(COM_DEBUG_USART, "%u\r", PIOS_BMP085_GetPressure());
|
||||
*/
|
||||
|
||||
#if defined(PIOS_INCLUDE_SPEKTRUM)
|
||||
PIOS_COM_SendFormattedStringNonBlocking(COM_DEBUG_USART, "%u,%u,%u,%u,%u,%u,%u,%u\r", PIOS_SPEKTRUM_Get(0), PIOS_SPEKTRUM_Get(1), PIOS_SPEKTRUM_Get(2), PIOS_SPEKTRUM_Get(3), PIOS_SPEKTRUM_Get(4), PIOS_SPEKTRUM_Get(5), PIOS_SPEKTRUM_Get(6), PIOS_SPEKTRUM_Get(7));
|
||||
#endif
|
||||
#if defined(PIOS_INCLUDE_PWM)
|
||||
PIOS_COM_SendFormattedStringNonBlocking(COM_DEBUG_USART, "%u,%u,%u,%u,%u,%u,%u,%u uS\r", PIOS_PWM_Get(0), PIOS_PWM_Get(1), PIOS_PWM_Get(2), PIOS_PWM_Get(3), PIOS_PWM_Get(4), PIOS_PWM_Get(5), PIOS_PWM_Get(6), PIOS_PWM_Get(7));
|
||||
#endif
|
||||
#if defined(PIOS_INCLUDE_PPM)
|
||||
PIOS_COM_SendFormattedStringNonBlocking(COM_DEBUG_USART, "%u,%u,%u,%u,%u,%u,%u,%u uS\r", PIOS_PPM_Get(0), PIOS_PPM_Get(1), PIOS_PPM_Get(2), PIOS_PPM_Get(3), PIOS_PPM_Get(4), PIOS_PPM_Get(5), PIOS_PPM_Get(6), PIOS_PPM_Get(7));
|
||||
#endif
|
||||
|
||||
/* This blocks the task until there is something on the buffer */
|
||||
/*xSemaphoreTake(PIOS_USART1_Buffer, portMAX_DELAY);
|
||||
int32_t len = PIOS_COM_ReceiveBufferUsed(COM_USART1);
|
||||
for(int32_t i = 0; i < len; i++) {
|
||||
PIOS_COM_SendFormattedString(COM_DEBUG_USART, ">%c\r", PIOS_COM_ReceiveBuffer(COM_USART1));
|
||||
}*/
|
||||
|
||||
//int32_t state = PIOS_USB_CableConnected();
|
||||
//PIOS_COM_SendFormattedStringNonBlocking(COM_DEBUG_USART, "State: %d\r", state);
|
||||
|
||||
//PIOS_I2C_Transfer(I2C_Write_WithoutStop, 0x57, (uint8_t *)50, 1);
|
||||
|
||||
/* Test ADC pins */
|
||||
//temp = ((1.43 - ((Vsense / 4096) * 3.3)) / 4.3) + 25;
|
||||
//uint32_t vsense = PIOS_ADC_PinGet(0);
|
||||
//uint32_t Temp = (1.42 - vsense * 3.3 / 4096) * 1000 / 4.35 + 25;
|
||||
//PIOS_COM_SendFormattedString(COM_DEBUG_USART, "Temp: %d, CS_I: %d, CS_V: %d, 5v: %d\r", PIOS_ADC_PinGet(0), PIOS_ADC_PinGet(1), PIOS_ADC_PinGet(2), PIOS_ADC_PinGet(3));
|
||||
//PIOS_COM_SendFormattedString(COM_DEBUG_USART, "AUX1: %d, AUX2: %d, AUX3: %d\r", PIOS_ADC_PinGet(4), PIOS_ADC_PinGet(5), PIOS_ADC_PinGet(6));
|
||||
|
||||
vTaskDelay(xDelay);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#if INCLUDE_TEST_TASKS
|
||||
static void TaskHIDTest(void *pvParameters)
|
||||
{
|
||||
uint8_t byte;
|
||||
uint8_t line_buffer[128];
|
||||
uint16_t line_ix = 0;
|
||||
|
||||
for(;;)
|
||||
{
|
||||
/* HID Loopback Test */
|
||||
#if 0
|
||||
if(PIOS_COM_ReceiveBufferUsed(COM_USB_HID) != 0) {
|
||||
byte = PIOS_COM_ReceiveBuffer(COM_USB_HID);
|
||||
if(byte == '\r' || byte == '\n' || byte == 0) {
|
||||
PIOS_COM_SendFormattedString(COM_USB_HID, "RX: %s\r", line_buffer);
|
||||
PIOS_COM_SendFormattedString(COM_DEBUG_USART, "RX: %s\r", line_buffer);
|
||||
line_ix = 0;
|
||||
} else if(line_ix < sizeof(line_buffer)) {
|
||||
line_buffer[line_ix++] = byte;
|
||||
line_buffer[line_ix] = 0;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/* HID Loopback Test */
|
||||
if(PIOS_COM_ReceiveBufferUsed(COM_USART2) != 0) {
|
||||
byte = PIOS_COM_ReceiveBuffer(COM_USART2);
|
||||
#if 0
|
||||
if(byte == '\r' || byte == '\n' || byte == 0) {
|
||||
PIOS_COM_SendFormattedString(COM_DEBUG_USART, "RX: %s\r", line_buffer);
|
||||
line_ix = 0;
|
||||
} else if(line_ix < sizeof(line_buffer)) {
|
||||
line_buffer[line_ix++] = byte;
|
||||
line_buffer[line_ix] = 0;
|
||||
}
|
||||
#endif
|
||||
PIOS_COM_SendChar(COM_DEBUG_USART, (char)byte);
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#if INCLUDE_TEST_TASKS
|
||||
static void TaskServos(void *pvParameters)
|
||||
{
|
||||
/* For testing servo outputs */
|
||||
portTickType xDelay;
|
||||
|
||||
/* Used to test servos, cycles all servos from one side to the other */
|
||||
for(;;) {
|
||||
/*xDelay = 250 / portTICK_RATE_MS;
|
||||
PIOS_Servo_Set(0, 2000);
|
||||
vTaskDelay(xDelay);
|
||||
PIOS_Servo_Set(1, 2000);
|
||||
vTaskDelay(xDelay);
|
||||
PIOS_Servo_Set(2, 2000);
|
||||
vTaskDelay(xDelay);
|
||||
PIOS_Servo_Set(3, 2000);
|
||||
vTaskDelay(xDelay);
|
||||
PIOS_Servo_Set(4, 2000);
|
||||
vTaskDelay(xDelay);
|
||||
PIOS_Servo_Set(5, 2000);
|
||||
vTaskDelay(xDelay);
|
||||
PIOS_Servo_Set(6, 2000);
|
||||
vTaskDelay(xDelay);
|
||||
PIOS_Servo_Set(7, 2000);
|
||||
vTaskDelay(xDelay);
|
||||
|
||||
PIOS_Servo_Set(7, 1000);
|
||||
vTaskDelay(xDelay);
|
||||
PIOS_Servo_Set(6, 1000);
|
||||
vTaskDelay(xDelay);
|
||||
PIOS_Servo_Set(5, 1000);
|
||||
vTaskDelay(xDelay);
|
||||
PIOS_Servo_Set(4, 1000);
|
||||
vTaskDelay(xDelay);
|
||||
PIOS_Servo_Set(3, 1000);
|
||||
vTaskDelay(xDelay);
|
||||
PIOS_Servo_Set(2, 1000);
|
||||
vTaskDelay(xDelay);
|
||||
PIOS_Servo_Set(1, 1000);
|
||||
vTaskDelay(xDelay);
|
||||
PIOS_Servo_Set(0, 1000);
|
||||
vTaskDelay(xDelay);*/
|
||||
|
||||
xDelay = 1 / portTICK_RATE_MS;
|
||||
for(int i = 1000; i < 2000; i++) {
|
||||
PIOS_Servo_Set(0, i);
|
||||
PIOS_Servo_Set(1, i);
|
||||
PIOS_Servo_Set(2, i);
|
||||
PIOS_Servo_Set(3, i);
|
||||
PIOS_Servo_Set(4, i);
|
||||
PIOS_Servo_Set(5, i);
|
||||
PIOS_Servo_Set(6, i);
|
||||
PIOS_Servo_Set(7, i);
|
||||
vTaskDelay(xDelay);
|
||||
}
|
||||
for(int i = 2000; i > 1000; i--) {
|
||||
PIOS_Servo_Set(0, i);
|
||||
PIOS_Servo_Set(1, i);
|
||||
PIOS_Servo_Set(2, i);
|
||||
PIOS_Servo_Set(3, i);
|
||||
PIOS_Servo_Set(4, i);
|
||||
PIOS_Servo_Set(5, i);
|
||||
PIOS_Servo_Set(6, i);
|
||||
PIOS_Servo_Set(7, i);
|
||||
vTaskDelay(xDelay);
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#if INCLUDE_TEST_TASKS
|
||||
static void TaskSDCard(void *pvParameters)
|
||||
{
|
||||
uint16_t second_delay_ctr = 0;
|
||||
portTickType xLastExecutionTime;
|
||||
|
||||
/* Initialise the xLastExecutionTime variable on task entry */
|
||||
xLastExecutionTime = xTaskGetTickCount();
|
||||
|
||||
for(;;) {
|
||||
vTaskDelayUntil(&xLastExecutionTime, 1 / portTICK_RATE_MS);
|
||||
|
||||
/* Each second: */
|
||||
/* Check if SD card is available */
|
||||
/* High-speed access if SD card was previously available */
|
||||
if(++second_delay_ctr >= 1000) {
|
||||
second_delay_ctr = 0;
|
||||
|
||||
uint8_t prev_sdcard_available = sdcard_available;
|
||||
sdcard_available = PIOS_SDCARD_CheckAvailable(prev_sdcard_available);
|
||||
|
||||
if(sdcard_available && !prev_sdcard_available) {
|
||||
/* SD Card has been connected! */
|
||||
/* Switch to mass storage device */
|
||||
MSD_Init(0);
|
||||
} else if(!sdcard_available && prev_sdcard_available) {
|
||||
/* Re-init USB for HID */
|
||||
PIOS_USB_Init(1);
|
||||
/* SD Card disconnected! */
|
||||
}
|
||||
}
|
||||
|
||||
/* Each millisecond: */
|
||||
/* Handle USB access if device is available */
|
||||
if(sdcard_available) {
|
||||
MSD_Periodic_mS();
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
||||
|
679
flight/CopterControl/System/pios_board.c
Normal file
679
flight/CopterControl/System/pios_board.c
Normal file
@ -0,0 +1,679 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotSystem OpenPilot System
|
||||
* @{
|
||||
* @addtogroup OpenPilotCore OpenPilot Core
|
||||
* @{
|
||||
*
|
||||
* @file pios_board.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Defines board specific static initializers for hardware for the OpenPilot board.
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#include <pios.h>
|
||||
#include <pios_spi_priv.h>
|
||||
#include <pios_usart_priv.h>
|
||||
#include <pios_com_priv.h>
|
||||
#include <pios_i2c_priv.h>
|
||||
#include <openpilot.h>
|
||||
#include <uavobjectsinit.h>
|
||||
|
||||
/**
|
||||
* PIOS_Board_Init()
|
||||
* initializes all the core subsystems on this specific hardware
|
||||
* called from System/openpilot.c
|
||||
*/
|
||||
void PIOS_Board_Init(void) {
|
||||
|
||||
/* Delay system */
|
||||
PIOS_DELAY_Init();
|
||||
|
||||
/* SPI Init */
|
||||
PIOS_SPI_Init();
|
||||
|
||||
/* Enable and mount the SDCard */
|
||||
PIOS_SDCARD_Init();
|
||||
PIOS_SDCARD_MountFS(0);
|
||||
#if defined(PIOS_INCLUDE_SPEKTRUM)
|
||||
/* SPEKTRUM init must come before comms */
|
||||
PIOS_SPEKTRUM_Init();
|
||||
#endif
|
||||
/* Initialize UAVObject libraries */
|
||||
EventDispatcherInitialize();
|
||||
UAVObjInitialize();
|
||||
UAVObjectsInitializeAll();
|
||||
|
||||
/* Initialize the alarms library */
|
||||
AlarmsInitialize();
|
||||
|
||||
/* Initialize the task monitor library */
|
||||
TaskMonitorInitialize();
|
||||
|
||||
/* Initialize the PiOS library */
|
||||
PIOS_COM_Init();
|
||||
PIOS_Servo_Init();
|
||||
PIOS_ADC_Init();
|
||||
PIOS_GPIO_Init();
|
||||
|
||||
#if defined(PIOS_INCLUDE_PWM)
|
||||
PIOS_PWM_Init();
|
||||
#endif
|
||||
#if defined(PIOS_INCLUDE_PPM)
|
||||
PIOS_PPM_Init();
|
||||
#endif
|
||||
#if defined(PIOS_INCLUDE_USB_HID)
|
||||
PIOS_USB_HID_Init(0);
|
||||
#endif
|
||||
PIOS_I2C_Init();
|
||||
PIOS_IAP_Init();
|
||||
PIOS_WDG_Init();
|
||||
}
|
||||
|
||||
/* MicroSD Interface
|
||||
*
|
||||
* NOTE: Leave this declared as const data so that it ends up in the
|
||||
* .rodata section (ie. Flash) rather than in the .bss section (RAM).
|
||||
*/
|
||||
void PIOS_SPI_sdcard_irq_handler(void);
|
||||
void DMA1_Channel2_IRQHandler() __attribute__ ((alias ("PIOS_SPI_sdcard_irq_handler")));
|
||||
void DMA1_Channel3_IRQHandler() __attribute__ ((alias ("PIOS_SPI_sdcard_irq_handler")));
|
||||
const struct pios_spi_cfg pios_spi_sdcard_cfg = {
|
||||
.regs = SPI1,
|
||||
.init = {
|
||||
.SPI_Mode = SPI_Mode_Master,
|
||||
.SPI_Direction = SPI_Direction_2Lines_FullDuplex,
|
||||
.SPI_DataSize = SPI_DataSize_8b,
|
||||
.SPI_NSS = SPI_NSS_Soft,
|
||||
.SPI_FirstBit = SPI_FirstBit_MSB,
|
||||
.SPI_CRCPolynomial = 7,
|
||||
.SPI_CPOL = SPI_CPOL_High,
|
||||
.SPI_CPHA = SPI_CPHA_2Edge,
|
||||
.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_256, /* Maximum divider (ie. slowest clock rate) */
|
||||
},
|
||||
.dma = {
|
||||
.ahb_clk = RCC_AHBPeriph_DMA1,
|
||||
|
||||
.irq = {
|
||||
.handler = PIOS_SPI_sdcard_irq_handler,
|
||||
.flags = (DMA1_FLAG_TC2 | DMA1_FLAG_TE2 | DMA1_FLAG_HT2 | DMA1_FLAG_GL2),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA1_Channel2_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
|
||||
.rx = {
|
||||
.channel = DMA1_Channel2,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR),
|
||||
.DMA_DIR = DMA_DIR_PeripheralSRC,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_Medium,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.channel = DMA1_Channel3,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR),
|
||||
.DMA_DIR = DMA_DIR_PeripheralDST,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_Medium,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
},
|
||||
.ssel = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_4,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
},
|
||||
},
|
||||
.sclk = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_5,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
.miso = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_6,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IPU,
|
||||
},
|
||||
},
|
||||
.mosi = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_7,
|
||||
.GPIO_Speed = GPIO_Speed_50MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
/* AHRS Interface
|
||||
*
|
||||
* NOTE: Leave this declared as const data so that it ends up in the
|
||||
* .rodata section (ie. Flash) rather than in the .bss section (RAM).
|
||||
*/
|
||||
void PIOS_SPI_ahrs_irq_handler(void);
|
||||
void DMA1_Channel4_IRQHandler() __attribute__ ((alias ("PIOS_SPI_ahrs_irq_handler")));
|
||||
void DMA1_Channel5_IRQHandler() __attribute__ ((alias ("PIOS_SPI_ahrs_irq_handler")));
|
||||
const struct pios_spi_cfg pios_spi_ahrs_cfg = {
|
||||
.regs = SPI2,
|
||||
.init = {
|
||||
.SPI_Mode = SPI_Mode_Master,
|
||||
.SPI_Direction = SPI_Direction_2Lines_FullDuplex,
|
||||
.SPI_DataSize = SPI_DataSize_8b,
|
||||
.SPI_NSS = SPI_NSS_Soft,
|
||||
.SPI_FirstBit = SPI_FirstBit_MSB,
|
||||
.SPI_CRCPolynomial = 7,
|
||||
.SPI_CPOL = SPI_CPOL_High,
|
||||
.SPI_CPHA = SPI_CPHA_2Edge,
|
||||
.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_16,
|
||||
},
|
||||
.use_crc = TRUE,
|
||||
.dma = {
|
||||
.ahb_clk = RCC_AHBPeriph_DMA1,
|
||||
|
||||
.irq = {
|
||||
.handler = PIOS_SPI_ahrs_irq_handler,
|
||||
.flags = (DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 | DMA1_FLAG_GL4),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA1_Channel4_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
|
||||
.rx = {
|
||||
.channel = DMA1_Channel4,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI2->DR),
|
||||
.DMA_DIR = DMA_DIR_PeripheralSRC,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_High,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.channel = DMA1_Channel5,
|
||||
.init = {
|
||||
.DMA_PeripheralBaseAddr = (uint32_t)&(SPI2->DR),
|
||||
.DMA_DIR = DMA_DIR_PeripheralDST,
|
||||
.DMA_PeripheralInc = DMA_PeripheralInc_Disable,
|
||||
.DMA_MemoryInc = DMA_MemoryInc_Enable,
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_High,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
},
|
||||
.ssel = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_12,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
},
|
||||
},
|
||||
.sclk = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_13,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
.miso = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_14,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
|
||||
},
|
||||
},
|
||||
.mosi = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_15,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
/*
|
||||
* Board specific number of devices.
|
||||
*/
|
||||
struct pios_spi_dev pios_spi_devs[] = {
|
||||
{
|
||||
.cfg = &pios_spi_sdcard_cfg,
|
||||
},
|
||||
{
|
||||
.cfg = &pios_spi_ahrs_cfg,
|
||||
},
|
||||
};
|
||||
|
||||
uint8_t pios_spi_num_devices = NELEMENTS(pios_spi_devs);
|
||||
|
||||
void PIOS_SPI_sdcard_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_SPI_IRQ_Handler(PIOS_SDCARD_SPI);
|
||||
}
|
||||
|
||||
void PIOS_SPI_ahrs_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_SPI_IRQ_Handler(PIOS_OPAHRS_SPI);
|
||||
}
|
||||
|
||||
/*
|
||||
* Telemetry USART
|
||||
*/
|
||||
void PIOS_USART_telem_irq_handler(void);
|
||||
void USART2_IRQHandler() __attribute__ ((alias ("PIOS_USART_telem_irq_handler")));
|
||||
const struct pios_usart_cfg pios_usart_telem_cfg = {
|
||||
.regs = USART2,
|
||||
.init = {
|
||||
#if defined (PIOS_COM_TELEM_BAUDRATE)
|
||||
.USART_BaudRate = PIOS_COM_TELEM_BAUDRATE,
|
||||
#else
|
||||
.USART_BaudRate = 57600,
|
||||
#endif
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.handler = PIOS_USART_telem_irq_handler,
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART2_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_3,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IPU,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_2,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
/*
|
||||
* GPS USART
|
||||
*/
|
||||
void PIOS_USART_gps_irq_handler(void);
|
||||
void USART3_IRQHandler() __attribute__ ((alias ("PIOS_USART_gps_irq_handler")));
|
||||
const struct pios_usart_cfg pios_usart_gps_cfg = {
|
||||
.regs = USART3,
|
||||
.remap = GPIO_PartialRemap_USART3,
|
||||
.init = {
|
||||
#if defined (PIOS_COM_GPS_BAUDRATE)
|
||||
.USART_BaudRate = PIOS_COM_GPS_BAUDRATE,
|
||||
#else
|
||||
.USART_BaudRate = 57600,
|
||||
#endif
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.handler = PIOS_USART_gps_irq_handler,
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART3_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IPU,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOC,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
#ifdef PIOS_COM_AUX
|
||||
/*
|
||||
* AUX USART
|
||||
*/
|
||||
void PIOS_USART_aux_irq_handler(void);
|
||||
void USART1_IRQHandler() __attribute__ ((alias ("PIOS_USART_aux_irq_handler")));
|
||||
const struct pios_usart_cfg pios_usart_aux_cfg = {
|
||||
.regs = USART1,
|
||||
.init = {
|
||||
#if defined (PIOS_COM_AUX_BAUDRATE)
|
||||
.USART_BaudRate = PIOS_COM_AUX_BAUDRATE,
|
||||
#else
|
||||
.USART_BaudRate = 57600,
|
||||
#endif
|
||||
.USART_BaudRate = 57600,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.handler = PIOS_USART_aux_irq_handler,
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART1_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.remap = GPIO_Remap_USART1,
|
||||
.rx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_7,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IPU,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_6,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
};
|
||||
#endif
|
||||
|
||||
#ifdef PIOS_COM_SPEKTRUM
|
||||
/*
|
||||
* SPEKTRUM USART
|
||||
*/
|
||||
void PIOS_USART_spektrum_irq_handler(void);
|
||||
void USART1_IRQHandler() __attribute__ ((alias ("PIOS_USART_spektrum_irq_handler")));
|
||||
const struct pios_usart_cfg pios_usart_spektrum_cfg = {
|
||||
.regs = USART1,
|
||||
.init = {
|
||||
#if defined (PIOS_COM_SPEKTRUM_BAUDRATE)
|
||||
.USART_BaudRate = PIOS_COM_SPEKTRUM_BAUDRATE,
|
||||
#else
|
||||
.USART_BaudRate = 115200,
|
||||
#endif
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx,
|
||||
},
|
||||
.irq = {
|
||||
.handler = PIOS_USART_spektrum_irq_handler,
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART1_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IPU,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_9,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IN_FLOATING,
|
||||
},
|
||||
},
|
||||
};
|
||||
#endif
|
||||
|
||||
/*
|
||||
* Board specific number of devices.
|
||||
*/
|
||||
struct pios_usart_dev pios_usart_devs[] = {
|
||||
#define PIOS_USART_TELEM 0
|
||||
{
|
||||
.cfg = &pios_usart_telem_cfg,
|
||||
},
|
||||
#define PIOS_USART_GPS 1
|
||||
{
|
||||
.cfg = &pios_usart_gps_cfg,
|
||||
},
|
||||
#ifdef PIOS_COM_AUX
|
||||
#define PIOS_USART_AUX 2
|
||||
{
|
||||
.cfg = &pios_usart_aux_cfg,
|
||||
},
|
||||
#endif
|
||||
#ifdef PIOS_COM_SPEKTRUM
|
||||
#define PIOS_USART_AUX 2
|
||||
{
|
||||
.cfg = &pios_usart_spektrum_cfg,
|
||||
},
|
||||
#endif
|
||||
};
|
||||
|
||||
uint8_t pios_usart_num_devices = NELEMENTS(pios_usart_devs);
|
||||
|
||||
void PIOS_USART_telem_irq_handler(void)
|
||||
{
|
||||
PIOS_USART_IRQ_Handler(PIOS_USART_TELEM);
|
||||
}
|
||||
|
||||
void PIOS_USART_gps_irq_handler(void)
|
||||
{
|
||||
PIOS_USART_IRQ_Handler(PIOS_USART_GPS);
|
||||
}
|
||||
|
||||
#ifdef PIOS_COM_AUX
|
||||
void PIOS_USART_aux_irq_handler(void)
|
||||
{
|
||||
PIOS_USART_IRQ_Handler(PIOS_USART_AUX);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef PIOS_COM_SPEKTRUM
|
||||
void PIOS_USART_spektrum_irq_handler(void)
|
||||
{
|
||||
SPEKTRUM_IRQHandler();
|
||||
}
|
||||
#endif
|
||||
|
||||
/*
|
||||
* COM devices
|
||||
*/
|
||||
|
||||
/*
|
||||
* Board specific number of devices.
|
||||
*/
|
||||
extern const struct pios_com_driver pios_usart_com_driver;
|
||||
extern const struct pios_com_driver pios_usb_com_driver;
|
||||
|
||||
struct pios_com_dev pios_com_devs[] = {
|
||||
{
|
||||
.id = PIOS_USART_TELEM,
|
||||
.driver = &pios_usart_com_driver,
|
||||
},
|
||||
{
|
||||
.id = PIOS_USART_GPS,
|
||||
.driver = &pios_usart_com_driver,
|
||||
},
|
||||
#if defined(PIOS_INCLUDE_USB_HID)
|
||||
{
|
||||
.id = 0,
|
||||
.driver = &pios_usb_com_driver,
|
||||
},
|
||||
#endif
|
||||
#ifdef PIOS_COM_AUX
|
||||
{
|
||||
.id = PIOS_USART_AUX,
|
||||
.driver = &pios_usart_com_driver,
|
||||
},
|
||||
#endif
|
||||
#ifdef PIOS_COM_SPEKTRUM
|
||||
{
|
||||
.id = PIOS_USART_AUX,
|
||||
.driver = &pios_usart_com_driver,
|
||||
},
|
||||
#endif
|
||||
};
|
||||
|
||||
const uint8_t pios_com_num_devices = NELEMENTS(pios_com_devs);
|
||||
|
||||
/*
|
||||
* I2C Adapters
|
||||
*/
|
||||
|
||||
void PIOS_I2C_main_adapter_ev_irq_handler(void);
|
||||
void PIOS_I2C_main_adapter_er_irq_handler(void);
|
||||
void I2C2_EV_IRQHandler() __attribute__ ((alias ("PIOS_I2C_main_adapter_ev_irq_handler")));
|
||||
void I2C2_ER_IRQHandler() __attribute__ ((alias ("PIOS_I2C_main_adapter_er_irq_handler")));
|
||||
|
||||
const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = {
|
||||
.regs = I2C2,
|
||||
.init = {
|
||||
.I2C_Mode = I2C_Mode_I2C,
|
||||
.I2C_OwnAddress1 = 0,
|
||||
.I2C_Ack = I2C_Ack_Enable,
|
||||
.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit,
|
||||
.I2C_DutyCycle = I2C_DutyCycle_2,
|
||||
.I2C_ClockSpeed = 400000, /* bits/s */
|
||||
},
|
||||
.transfer_timeout_ms = 50,
|
||||
.scl = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_OD,
|
||||
},
|
||||
},
|
||||
.sda = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Speed = GPIO_Speed_10MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_OD,
|
||||
},
|
||||
},
|
||||
.event = {
|
||||
.handler = PIOS_I2C_main_adapter_ev_irq_handler,
|
||||
.flags = 0, /* FIXME: check this */
|
||||
.init = {
|
||||
.NVIC_IRQChannel = I2C2_EV_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.error = {
|
||||
.handler = PIOS_I2C_main_adapter_er_irq_handler,
|
||||
.flags = 0, /* FIXME: check this */
|
||||
.init = {
|
||||
.NVIC_IRQChannel = I2C2_ER_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
/*
|
||||
* Board specific number of devices.
|
||||
*/
|
||||
struct pios_i2c_adapter pios_i2c_adapters[] = {
|
||||
{
|
||||
.cfg = &pios_i2c_main_adapter_cfg,
|
||||
},
|
||||
};
|
||||
|
||||
uint8_t pios_i2c_num_adapters = NELEMENTS(pios_i2c_adapters);
|
||||
|
||||
void PIOS_I2C_main_adapter_ev_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_I2C_EV_IRQ_Handler(PIOS_I2C_MAIN_ADAPTER);
|
||||
}
|
||||
|
||||
void PIOS_I2C_main_adapter_er_irq_handler(void)
|
||||
{
|
||||
/* Call into the generic code to handle the IRQ for this specific device */
|
||||
PIOS_I2C_ER_IRQ_Handler(PIOS_I2C_MAIN_ADAPTER);
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
143
flight/CopterControl/System/pios_board_posix.c
Normal file
143
flight/CopterControl/System/pios_board_posix.c
Normal file
@ -0,0 +1,143 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file pios_board.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Defines board specific static initializers for hardware for the OpenPilot board.
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
#include <pios.h>
|
||||
#include <pios_udp_priv.h>
|
||||
#include <pios_com_priv.h>
|
||||
#include <openpilot.h>
|
||||
#include <uavobjectsinit.h>
|
||||
|
||||
/**
|
||||
* PIOS_Board_Init()
|
||||
* initializes all the core systems on this specific hardware
|
||||
* called from System/openpilot.c
|
||||
*/
|
||||
void PIOS_Board_Init(void) {
|
||||
|
||||
/* Delay system */
|
||||
PIOS_DELAY_Init();
|
||||
|
||||
/* Initialize UAVObject libraries */
|
||||
EventDispatcherInitialize();
|
||||
UAVObjInitialize();
|
||||
UAVObjectsInitializeAll();
|
||||
|
||||
/* Initialize the alarms library */
|
||||
AlarmsInitialize();
|
||||
|
||||
/* Initialize the task monitor library */
|
||||
TaskMonitorInitialize();
|
||||
|
||||
/* Initialize the PiOS library */
|
||||
PIOS_COM_Init();
|
||||
|
||||
}
|
||||
|
||||
|
||||
const struct pios_udp_cfg pios_udp0_cfg = {
|
||||
.ip = "0.0.0.0",
|
||||
.port = 9000,
|
||||
};
|
||||
const struct pios_udp_cfg pios_udp1_cfg = {
|
||||
.ip = "0.0.0.0",
|
||||
.port = 9001,
|
||||
};
|
||||
const struct pios_udp_cfg pios_udp2_cfg = {
|
||||
.ip = "0.0.0.0",
|
||||
.port = 9002,
|
||||
};
|
||||
|
||||
#ifdef PIOS_COM_AUX
|
||||
/*
|
||||
* AUX USART
|
||||
*/
|
||||
const struct pios_udp_cfg pios_udp3_cfg = {
|
||||
.ip = "0.0.0.0",
|
||||
.port = 9003,
|
||||
};
|
||||
#endif
|
||||
|
||||
/*
|
||||
* Board specific number of devices.
|
||||
*/
|
||||
struct pios_udp_dev pios_udp_devs[] = {
|
||||
#define PIOS_UDP_TELEM 0
|
||||
{
|
||||
.cfg = &pios_udp0_cfg,
|
||||
},
|
||||
#define PIOS_UDP_GPS 1
|
||||
{
|
||||
.cfg = &pios_udp1_cfg,
|
||||
},
|
||||
#define PIOS_UDP_LOCAL 2
|
||||
{
|
||||
.cfg = &pios_udp2_cfg,
|
||||
},
|
||||
#ifdef PIOS_COM_AUX
|
||||
#define PIOS_UDP_AUX 3
|
||||
{
|
||||
.cfg = &pios_udp3_cfg,
|
||||
},
|
||||
#endif
|
||||
};
|
||||
|
||||
uint8_t pios_udp_num_devices = NELEMENTS(pios_udp_devs);
|
||||
|
||||
/*
|
||||
* COM devices
|
||||
*/
|
||||
|
||||
/*
|
||||
* Board specific number of devices.
|
||||
*/
|
||||
extern const struct pios_com_driver pios_serial_com_driver;
|
||||
extern const struct pios_com_driver pios_udp_com_driver;
|
||||
|
||||
struct pios_com_dev pios_com_devs[] = {
|
||||
{
|
||||
.id = PIOS_UDP_TELEM,
|
||||
.driver = &pios_udp_com_driver,
|
||||
},
|
||||
{
|
||||
.id = PIOS_UDP_GPS,
|
||||
.driver = &pios_udp_com_driver,
|
||||
},
|
||||
{
|
||||
.id = PIOS_UDP_LOCAL,
|
||||
.driver = &pios_udp_com_driver,
|
||||
},
|
||||
#ifdef PIOS_COM_AUX
|
||||
{
|
||||
.id = PIOS_UDP_AUX,
|
||||
.driver = &pios_udp_com_driver,
|
||||
},
|
||||
#endif
|
||||
};
|
||||
|
||||
const uint8_t pios_com_num_devices = NELEMENTS(pios_com_devs);
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
104
flight/CopterControl/System/taskmonitor.c
Normal file
104
flight/CopterControl/System/taskmonitor.c
Normal file
@ -0,0 +1,104 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotSystem OpenPilot System
|
||||
* @{
|
||||
* @addtogroup OpenPilotLibraries OpenPilot System Libraries
|
||||
* @{
|
||||
* @file taskmonitor.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Task monitoring library
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
#include "openpilot.h"
|
||||
//#include "taskmonitor.h"
|
||||
|
||||
// Private constants
|
||||
|
||||
// Private types
|
||||
|
||||
// Private variables
|
||||
static xSemaphoreHandle lock;
|
||||
static xTaskHandle handles[TASKINFO_RUNNING_NUMELEM];
|
||||
|
||||
// Private functions
|
||||
|
||||
/**
|
||||
* Initialize library
|
||||
*/
|
||||
int32_t TaskMonitorInitialize(void)
|
||||
{
|
||||
lock = xSemaphoreCreateRecursiveMutex();
|
||||
memset(handles, 0, sizeof(xTaskHandle)*TASKINFO_RUNNING_NUMELEM);
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Register a task handle with the library
|
||||
*/
|
||||
int32_t TaskMonitorAdd(TaskInfoRunningElem task, xTaskHandle handle)
|
||||
{
|
||||
if (task < TASKINFO_RUNNING_NUMELEM)
|
||||
{
|
||||
xSemaphoreTakeRecursive(lock, portMAX_DELAY);
|
||||
handles[task] = handle;
|
||||
xSemaphoreGiveRecursive(lock);
|
||||
return 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Update the status of all tasks
|
||||
*/
|
||||
void TaskMonitorUpdateAll(void)
|
||||
{
|
||||
TaskInfoData data;
|
||||
int n;
|
||||
|
||||
// Lock
|
||||
xSemaphoreTakeRecursive(lock, portMAX_DELAY);
|
||||
|
||||
// Update all task information
|
||||
for (n = 0; n < TASKINFO_RUNNING_NUMELEM; ++n)
|
||||
{
|
||||
if (handles[n] != 0)
|
||||
{
|
||||
data.Running[n] = TASKINFO_RUNNING_TRUE;
|
||||
#if defined(ARCH_POSIX) || defined(ARCH_WIN32)
|
||||
data.StackRemaining[n] = 10000;
|
||||
#else
|
||||
data.StackRemaining[n] = uxTaskGetStackHighWaterMark(handles[n]) * 4;
|
||||
#endif
|
||||
}
|
||||
else
|
||||
{
|
||||
data.Running[n] = TASKINFO_RUNNING_FALSE;
|
||||
data.StackRemaining[n] = 0;
|
||||
}
|
||||
}
|
||||
|
||||
// Update object
|
||||
TaskInfoSet(&data);
|
||||
|
||||
// Done
|
||||
xSemaphoreGiveRecursive(lock);
|
||||
}
|
@ -89,14 +89,14 @@ TARGET = OpenPilot
|
||||
# Paths
|
||||
OPSYSTEM = ./System
|
||||
OPSYSTEMINC = $(OPSYSTEM)/inc
|
||||
OPUAVTALK = ./UAVTalk
|
||||
OPUAVTALK = ../UAVTalk
|
||||
OPUAVTALKINC = $(OPUAVTALK)/inc
|
||||
OPUAVOBJ = ./UAVObjects
|
||||
OPUAVOBJ = ../UAVObjects
|
||||
OPUAVOBJINC = $(OPUAVOBJ)/inc
|
||||
OPTESTS = ./Tests
|
||||
OPMODULEDIR = ./Modules
|
||||
OPMODULEDIR = ../Modules
|
||||
FLIGHTLIB = ../Libraries
|
||||
FLIGHTLIBINC = ../Libraries/inc
|
||||
FLIGHTLIBINC = $(FLIGHTLIB)/inc
|
||||
PIOS = ../PiOS
|
||||
PIOSINC = $(PIOS)/inc
|
||||
PIOSSTM32F10X = $(PIOS)/STM32F10x
|
||||
@ -364,7 +364,7 @@ EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/ARM_CM3
|
||||
EXTRAINCDIRS += $(AHRSBOOTLOADERINC)
|
||||
EXTRAINCDIRS += $(PYMITEINC)
|
||||
|
||||
EXTRAINCDIRS += ${foreach MOD, ${MODULES}, Modules/${MOD}/inc} ${OPMODULEDIR}/System/inc
|
||||
EXTRAINCDIRS += ${foreach MOD, ${MODULES}, $(OPMODULEDIR)/${MOD}/inc} ${OPMODULEDIR}/System/inc
|
||||
|
||||
|
||||
# List any extra directories to look for library files here.
|
||||
|
419
flight/PiOS/Boards/STM3210E_CC_Rev1.h
Normal file
419
flight/PiOS/Boards/STM3210E_CC_Rev1.h
Normal file
@ -0,0 +1,419 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotSystem OpenPilot System
|
||||
* @{
|
||||
* @addtogroup OpenPilotCore OpenPilot Core
|
||||
* @{
|
||||
* @file pios_board.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief Defines board hardware for the OpenPilot Version 1.1 hardware.
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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, write to the Free Software Foundation, Inc.,
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
|
||||
|
||||
#ifndef STM3210E_OP_H_
|
||||
#define STM3210E_OP_H_
|
||||
|
||||
|
||||
|
||||
//------------------------
|
||||
// Timers and Channels Used
|
||||
//------------------------
|
||||
/*
|
||||
Timer | Channel 1 | Channel 2 | Channel 3 | Channel 4
|
||||
------+-----------+-----------+-----------+----------
|
||||
TIM1 | RC In 3 | RC In 6 | RC In 5 |
|
||||
TIM2 | --------------- PIOS_DELAY -----------------
|
||||
TIM3 | RC In 7 | RC In 8 | RC In 1 | RC In 2
|
||||
TIM4 | Servo 1 | Servo 2 | Servo 3 | Servo 4
|
||||
TIM5 | RC In 4 | | |
|
||||
TIM6 | ----------- PIOS_PWM (Supervisor) ----------
|
||||
TIM7 | | | |
|
||||
TIM8 | Servo 5 | Servo 6 | Servo 7 | Servo 8
|
||||
------+-----------+-----------+-----------+----------
|
||||
*/
|
||||
|
||||
//------------------------
|
||||
// DMA Channels Used
|
||||
//------------------------
|
||||
/* Channel 1 - ADC */
|
||||
/* Channel 2 - SPI1 RX */
|
||||
/* Channel 3 - SPI1 TX */
|
||||
/* Channel 4 - SPI2 RX */
|
||||
/* Channel 5 - SPI2 TX */
|
||||
/* Channel 6 - */
|
||||
/* Channel 7 - */
|
||||
/* Channel 8 - */
|
||||
/* Channel 9 - */
|
||||
/* Channel 10 - */
|
||||
/* Channel 11 - */
|
||||
/* Channel 12 - */
|
||||
|
||||
//------------------------
|
||||
// BOOTLOADER_SETTINGS
|
||||
//------------------------
|
||||
|
||||
#define FUNC_ID 1
|
||||
#define HW_VERSION 01
|
||||
#define BOOTLOADER_VERSION 0
|
||||
#define MEM_SIZE 524288 //512K
|
||||
#define SIZE_OF_DESCRIPTION (uint8_t) 100
|
||||
#define START_OF_USER_CODE (uint32_t)0x08005000//REMEMBER SET ALSO IN link_stm32f10x_HD_BL.ld
|
||||
#define SIZE_OF_CODE (uint32_t) (MEM_SIZE-(START_OF_USER_CODE-0x08000000)-SIZE_OF_DESCRIPTION)
|
||||
|
||||
#ifdef STM32F10X_HD
|
||||
#define HW_TYPE 0 //0=high_density 1=medium_density;
|
||||
#elif STM32F10X_MD
|
||||
#define HW_TYPE 1 //0=high_density 1=medium_density;
|
||||
#endif
|
||||
#define BOARD_READABLE TRUE
|
||||
#define BOARD_WRITABLA TRUE
|
||||
#define MAX_DEL_RETRYS 3
|
||||
|
||||
//------------------------
|
||||
// WATCHDOG_SETTINGS
|
||||
//------------------------
|
||||
#define PIOS_WATCHDOG_TIMEOUT 250
|
||||
#define PIOS_WDG_REGISTER BKP_DR4
|
||||
#define PIOS_WDG_ACTUATOR 0x0001
|
||||
#define PIOS_WDG_STABILIZATION 0x0002
|
||||
#define PIOS_WDG_AHRS 0x0004
|
||||
#define PIOS_WDG_MANUAL 0x0008
|
||||
|
||||
//------------------------
|
||||
// PIOS_LED
|
||||
//------------------------
|
||||
#define PIOS_LED_LED1_GPIO_PORT GPIOC
|
||||
#define PIOS_LED_LED1_GPIO_PIN GPIO_Pin_12
|
||||
#define PIOS_LED_LED1_GPIO_CLK RCC_APB2Periph_GPIOC
|
||||
#define PIOS_LED_LED2_GPIO_PORT GPIOC
|
||||
#define PIOS_LED_LED2_GPIO_PIN GPIO_Pin_13
|
||||
#define PIOS_LED_LED2_GPIO_CLK RCC_APB2Periph_GPIOC
|
||||
#define PIOS_LED_NUM 2
|
||||
#define PIOS_LED_PORTS { PIOS_LED_LED1_GPIO_PORT, PIOS_LED_LED2_GPIO_PORT }
|
||||
#define PIOS_LED_PINS { PIOS_LED_LED1_GPIO_PIN, PIOS_LED_LED2_GPIO_PIN }
|
||||
#define PIOS_LED_CLKS { PIOS_LED_LED1_GPIO_CLK, PIOS_LED_LED2_GPIO_CLK }
|
||||
|
||||
//------------------------
|
||||
// PIOS_I2C
|
||||
// See also pios_board.c
|
||||
//------------------------
|
||||
#define PIOS_I2C_MAIN_ADAPTER 0
|
||||
|
||||
//------------------------
|
||||
// PIOS_BMP085
|
||||
//------------------------
|
||||
#define PIOS_BMP085_EOC_GPIO_PORT GPIOC
|
||||
#define PIOS_BMP085_EOC_GPIO_PIN GPIO_Pin_15
|
||||
#define PIOS_BMP085_EOC_PORT_SOURCE GPIO_PortSourceGPIOC
|
||||
#define PIOS_BMP085_EOC_PIN_SOURCE GPIO_PinSource15
|
||||
#define PIOS_BMP085_EOC_CLK RCC_APB2Periph_GPIOC
|
||||
#define PIOS_BMP085_EOC_EXTI_LINE EXTI_Line15
|
||||
#define PIOS_BMP085_EOC_IRQn EXTI15_10_IRQn
|
||||
#define PIOS_BMP085_EOC_PRIO PIOS_IRQ_PRIO_LOW
|
||||
//#define PIOS_BMP085_OVERSAMPLING 2
|
||||
#define PIOS_BMP085_OVERSAMPLING 3
|
||||
|
||||
//-------------------------
|
||||
// USART
|
||||
//
|
||||
// See also pios_board.c
|
||||
//-------------------------
|
||||
#define PIOS_USART_RX_BUFFER_SIZE 1024
|
||||
#define PIOS_USART_TX_BUFFER_SIZE 256
|
||||
|
||||
#define PIOS_COM_TELEM_BAUDRATE 57600
|
||||
#define PIOS_COM_GPS_BAUDRATE 57600
|
||||
|
||||
#ifdef PIOS_NO_GPS
|
||||
#define PIOS_COM_TELEM_RF 0
|
||||
#define PIOS_COM_TELEM_USB 1
|
||||
#else
|
||||
#define PIOS_COM_TELEM_RF 0
|
||||
#define PIOS_COM_GPS 1
|
||||
#define PIOS_COM_TELEM_USB 2
|
||||
#endif
|
||||
|
||||
#ifdef PIOS_ENABLE_AUX_UART
|
||||
#define PIOS_COM_AUX_BAUDRATE 57600
|
||||
#define PIOS_COM_AUX 3
|
||||
#define PIOS_COM_DEBUG PIOS_COM_AUX
|
||||
#endif
|
||||
|
||||
#ifdef PIOS_INCLUDE_SPEKTRUM
|
||||
#define PIOS_COM_SPEKTRUM_BAUDRATE 115200
|
||||
#define PIOS_COM_SPEKTRUM 3
|
||||
#endif
|
||||
|
||||
//-------------------------
|
||||
// SPI
|
||||
//
|
||||
// See also pios_board.c
|
||||
//-------------------------
|
||||
#define PIOS_SDCARD_SPI 0
|
||||
#define PIOS_OPAHRS_SPI 1
|
||||
|
||||
//-------------------------
|
||||
// Delay Timer
|
||||
//-------------------------
|
||||
#define PIOS_DELAY_TIMER TIM2
|
||||
#define PIOS_DELAY_TIMER_RCC_FUNC RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE)
|
||||
|
||||
//-------------------------
|
||||
// System Settings
|
||||
//-------------------------
|
||||
#define PIOS_MASTER_CLOCK 72000000
|
||||
#define PIOS_PERIPHERAL_CLOCK (PIOS_MASTER_CLOCK / 2)
|
||||
#if defined(USE_BOOTLOADER)
|
||||
#define PIOS_NVIC_VECTTAB_FLASH (START_OF_USER_CODE)
|
||||
#else
|
||||
#define PIOS_NVIC_VECTTAB_FLASH ((uint32_t)0x08000000)
|
||||
#endif
|
||||
|
||||
//-------------------------
|
||||
// Interrupt Priorities
|
||||
//-------------------------
|
||||
#define PIOS_IRQ_PRIO_LOW 12 // lower than RTOS
|
||||
#define PIOS_IRQ_PRIO_MID 8 // higher than RTOS
|
||||
#define PIOS_IRQ_PRIO_HIGH 5 // for SPI, ADC, I2C etc...
|
||||
#define PIOS_IRQ_PRIO_HIGHEST 4 // for USART etc...
|
||||
|
||||
//-------------------------
|
||||
// Receiver PWM inputs
|
||||
//-------------------------
|
||||
#define PIOS_PWM_CH1_GPIO_PORT GPIOA
|
||||
#define PIOS_PWM_CH1_PIN GPIO_Pin_9
|
||||
#define PIOS_PWM_CH1_TIM_PORT TIM1
|
||||
#define PIOS_PWM_CH1_CH TIM_Channel_2
|
||||
#define PIOS_PWM_CH1_CCR TIM_IT_CC2
|
||||
#define PIOS_PWM_CH2_GPIO_PORT GPIOA
|
||||
#define PIOS_PWM_CH2_PIN GPIO_Pin_10
|
||||
#define PIOS_PWM_CH2_TIM_PORT TIM1
|
||||
#define PIOS_PWM_CH2_CH TIM_Channel_3
|
||||
#define PIOS_PWM_CH2_CCR TIM_IT_CC3
|
||||
#define PIOS_PWM_CH3_GPIO_PORT GPIOA
|
||||
#define PIOS_PWM_CH3_PIN GPIO_Pin_0
|
||||
#define PIOS_PWM_CH3_TIM_PORT TIM5
|
||||
#define PIOS_PWM_CH3_CH TIM_Channel_1
|
||||
#define PIOS_PWM_CH3_CCR TIM_IT_CC1
|
||||
#define PIOS_PWM_CH4_GPIO_PORT GPIOA
|
||||
#define PIOS_PWM_CH4_PIN GPIO_Pin_8
|
||||
#define PIOS_PWM_CH4_TIM_PORT TIM1
|
||||
#define PIOS_PWM_CH4_CH TIM_Channel_1
|
||||
#define PIOS_PWM_CH4_CCR TIM_IT_CC1
|
||||
#define PIOS_PWM_CH5_GPIO_PORT GPIOB
|
||||
#define PIOS_PWM_CH5_PIN GPIO_Pin_1
|
||||
#define PIOS_PWM_CH5_TIM_PORT TIM3
|
||||
#define PIOS_PWM_CH5_CH TIM_Channel_4
|
||||
#define PIOS_PWM_CH5_CCR TIM_IT_CC4
|
||||
#define PIOS_PWM_CH6_GPIO_PORT GPIOB
|
||||
#define PIOS_PWM_CH6_PIN GPIO_Pin_0
|
||||
#define PIOS_PWM_CH6_TIM_PORT TIM3
|
||||
#define PIOS_PWM_CH6_CH TIM_Channel_3
|
||||
#define PIOS_PWM_CH6_CCR TIM_IT_CC3
|
||||
#define PIOS_PWM_CH7_GPIO_PORT GPIOB
|
||||
#define PIOS_PWM_CH7_PIN GPIO_Pin_4
|
||||
#define PIOS_PWM_CH7_TIM_PORT TIM3
|
||||
#define PIOS_PWM_CH7_CH TIM_Channel_1
|
||||
#define PIOS_PWM_CH7_CCR TIM_IT_CC1
|
||||
#define PIOS_PWM_CH8_GPIO_PORT GPIOB
|
||||
#define PIOS_PWM_CH8_PIN GPIO_Pin_5
|
||||
#define PIOS_PWM_CH8_TIM_PORT TIM3
|
||||
#define PIOS_PWM_CH8_CH TIM_Channel_2
|
||||
#define PIOS_PWM_CH8_CCR TIM_IT_CC2
|
||||
#define PIOS_PWM_GPIO_PORTS { PIOS_PWM_CH1_GPIO_PORT, PIOS_PWM_CH2_GPIO_PORT, PIOS_PWM_CH3_GPIO_PORT, PIOS_PWM_CH4_GPIO_PORT, PIOS_PWM_CH5_GPIO_PORT, PIOS_PWM_CH6_GPIO_PORT, PIOS_PWM_CH7_GPIO_PORT, PIOS_PWM_CH8_GPIO_PORT }
|
||||
#define PIOS_PWM_GPIO_PINS { PIOS_PWM_CH1_PIN, PIOS_PWM_CH2_PIN, PIOS_PWM_CH3_PIN, PIOS_PWM_CH4_PIN, PIOS_PWM_CH5_PIN, PIOS_PWM_CH6_PIN, PIOS_PWM_CH7_PIN, PIOS_PWM_CH8_PIN }
|
||||
#define PIOS_PWM_TIM_PORTS { PIOS_PWM_CH1_TIM_PORT, PIOS_PWM_CH2_TIM_PORT, PIOS_PWM_CH3_TIM_PORT, PIOS_PWM_CH4_TIM_PORT, PIOS_PWM_CH5_TIM_PORT, PIOS_PWM_CH6_TIM_PORT, PIOS_PWM_CH7_TIM_PORT, PIOS_PWM_CH8_TIM_PORT }
|
||||
#define PIOS_PWM_TIM_CHANNELS { PIOS_PWM_CH1_CH, PIOS_PWM_CH2_CH, PIOS_PWM_CH3_CH, PIOS_PWM_CH4_CH, PIOS_PWM_CH5_CH, PIOS_PWM_CH6_CH, PIOS_PWM_CH7_CH, PIOS_PWM_CH8_CH }
|
||||
#define PIOS_PWM_TIM_CCRS { PIOS_PWM_CH1_CCR, PIOS_PWM_CH2_CCR, PIOS_PWM_CH3_CCR, PIOS_PWM_CH4_CCR, PIOS_PWM_CH5_CCR, PIOS_PWM_CH6_CCR, PIOS_PWM_CH7_CCR, PIOS_PWM_CH8_CCR }
|
||||
#define PIOS_PWM_TIMS { TIM1, TIM3, TIM5 }
|
||||
#define PIOS_PWM_TIM_IRQS { TIM1_CC_IRQn, TIM3_IRQn, TIM5_IRQn }
|
||||
#define PIOS_PWM_NUM_INPUTS 8
|
||||
#define PIOS_PWM_NUM_TIMS 3
|
||||
#define PIOS_PWM_SUPV_ENABLED 1
|
||||
#define PIOS_PWM_SUPV_TIMER TIM6
|
||||
#define PIOS_PWM_SUPV_TIMER_RCC_FUNC RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM6, ENABLE)
|
||||
#define PIOS_PWM_SUPV_HZ 25
|
||||
#define PIOS_PWM_SUPV_IRQ_CHANNEL TIM6_IRQn
|
||||
#define PIOS_PWM_SUPV_IRQ_FUNC void TIM6_IRQHandler(void)
|
||||
|
||||
//-------------------------
|
||||
// Receiver PPM input
|
||||
//-------------------------
|
||||
#define PIOS_PPM_GPIO_PORT PIOS_PWM_CH1_GPIO_PORT
|
||||
#define PIOS_PPM_GPIO_PIN PIOS_PWM_CH1_PIN
|
||||
#define PIOS_PPM_TIM_PORT PIOS_PWM_CH1_TIM_PORT
|
||||
#define PIOS_PPM_TIM_CHANNEL PIOS_PWM_CH1_CH
|
||||
#define PIOS_PPM_TIM_CCR PIOS_PWM_CH1_CCR
|
||||
#define PIOS_PPM_TIM TIM1
|
||||
#define PIOS_PPM_TIM_IRQ TIM1_CC_IRQn
|
||||
#define PIOS_PPM_NUM_INPUTS 8 //Could be more if needed
|
||||
#define PIOS_PPM_SUPV_ENABLED 1
|
||||
#define PIOS_PPM_SUPV_TIMER TIM6
|
||||
#define PIOS_PPM_SUPV_TIMER_RCC_FUNC RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM6, ENABLE)
|
||||
#define PIOS_PPM_SUPV_HZ 25
|
||||
#define PIOS_PPM_SUPV_IRQ_CHANNEL TIM6_IRQn
|
||||
#define PIOS_PPM_SUPV_IRQ_FUNC void TIM6_IRQHandler(void)
|
||||
|
||||
//-------------------------
|
||||
// SPEKTRUM input
|
||||
//-------------------------
|
||||
#define PIOS_SPEKTRUM_SUPV_ENABLED 1
|
||||
#define PIOS_SPEKTRUM_SUPV_TIMER TIM6
|
||||
#define PIOS_SPEKTRUM_SUPV_TIMER_RCC_FUNC RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM6, ENABLE)
|
||||
#define PIOS_SPEKTRUM_SUPV_HZ 60 // 1/22ms
|
||||
#define PIOS_SPEKTRUM_SUPV_IRQ_CHANNEL TIM6_IRQn
|
||||
#define PIOS_SPEKTRUM_SUPV_IRQ_FUNC void TIM6_IRQHandler(void)
|
||||
|
||||
//-------------------------
|
||||
// Servo outputs
|
||||
//-------------------------
|
||||
#define PIOS_SERVO_GPIO_PORT_1TO4 GPIOB
|
||||
#define PIOS_SERVO_GPIO_PIN_1 GPIO_Pin_6
|
||||
#define PIOS_SERVO_GPIO_PIN_2 GPIO_Pin_7
|
||||
#define PIOS_SERVO_GPIO_PIN_3 GPIO_Pin_8
|
||||
#define PIOS_SERVO_GPIO_PIN_4 GPIO_Pin_9
|
||||
#define PIOS_SERVO_GPIO_PORT_5TO8 GPIOC
|
||||
#define PIOS_SERVO_GPIO_PIN_5 GPIO_Pin_6
|
||||
#define PIOS_SERVO_GPIO_PIN_6 GPIO_Pin_7
|
||||
#define PIOS_SERVO_GPIO_PIN_7 GPIO_Pin_8
|
||||
#define PIOS_SERVO_GPIO_PIN_8 GPIO_Pin_9
|
||||
#define PIOS_SERVO_NUM_OUTPUTS 8
|
||||
#define PIOS_SERVO_NUM_TIMERS PIOS_SERVO_NUM_OUTPUTS
|
||||
#define PIOS_SERVO_UPDATE_HZ 50
|
||||
#define PIOS_SERVOS_INITIAL_POSITION 0 /* dont want to start motors, have no pulse till settings loaded */
|
||||
|
||||
//-------------------------
|
||||
// ADC
|
||||
// PIOS_ADC_PinGet(0) = Temperature Sensor (On-board)
|
||||
// PIOS_ADC_PinGet(1) = Power Sensor (Current)
|
||||
// PIOS_ADC_PinGet(2) = Power Sensor (Voltage)
|
||||
// PIOS_ADC_PinGet(3) = On-board 5v Rail Sensor
|
||||
// PIOS_ADC_PinGet(4) = Auxiliary Input 1
|
||||
// PIOS_ADC_PinGet(5) = Auxiliary Input 2
|
||||
// PIOS_ADC_PinGet(6) = Auxiliary Input 3
|
||||
//-------------------------
|
||||
//#define PIOS_ADC_OVERSAMPLING_RATE 1
|
||||
#define PIOS_ADC_USE_TEMP_SENSOR 1
|
||||
#define PIOS_ADC_TEMP_SENSOR_ADC ADC1
|
||||
#define PIOS_ADC_TEMP_SENSOR_ADC_CHANNEL 1
|
||||
#define PIOS_ADC_PIN1_GPIO_PORT GPIOA // PA1 (Power Sense - Voltage)
|
||||
#define PIOS_ADC_PIN1_GPIO_PIN GPIO_Pin_1 // ADC123_IN1
|
||||
#define PIOS_ADC_PIN1_GPIO_CHANNEL ADC_Channel_1
|
||||
#define PIOS_ADC_PIN1_ADC ADC1
|
||||
#define PIOS_ADC_PIN1_ADC_NUMBER 2
|
||||
#define PIOS_ADC_PIN2_GPIO_PORT GPIOC // PC3 (Power Sense - Current)
|
||||
#define PIOS_ADC_PIN2_GPIO_PIN GPIO_Pin_3 // ADC123_IN13
|
||||
#define PIOS_ADC_PIN2_GPIO_CHANNEL ADC_Channel_13
|
||||
#define PIOS_ADC_PIN2_ADC ADC2
|
||||
#define PIOS_ADC_PIN2_ADC_NUMBER 1
|
||||
#define PIOS_ADC_PIN3_GPIO_PORT GPIOC // PC5 (Onboard 5v Sensor) PC5
|
||||
#define PIOS_ADC_PIN3_GPIO_PIN GPIO_Pin_5 // ADC12_IN15
|
||||
#define PIOS_ADC_PIN3_GPIO_CHANNEL ADC_Channel_15
|
||||
#define PIOS_ADC_PIN3_ADC ADC2
|
||||
#define PIOS_ADC_PIN3_ADC_NUMBER 2
|
||||
#define PIOS_ADC_PIN4_GPIO_PORT GPIOC // PC0 (AUX 1)
|
||||
#define PIOS_ADC_PIN4_GPIO_PIN GPIO_Pin_0 // ADC123_IN10
|
||||
#define PIOS_ADC_PIN4_GPIO_CHANNEL ADC_Channel_10
|
||||
#define PIOS_ADC_PIN4_ADC ADC1
|
||||
#define PIOS_ADC_PIN4_ADC_NUMBER 3
|
||||
#define PIOS_ADC_PIN5_GPIO_PORT GPIOC // PC1 (AUX 2)
|
||||
#define PIOS_ADC_PIN5_GPIO_PIN GPIO_Pin_1 // ADC123_IN11
|
||||
#define PIOS_ADC_PIN5_GPIO_CHANNEL ADC_Channel_11
|
||||
#define PIOS_ADC_PIN5_ADC ADC2
|
||||
#define PIOS_ADC_PIN5_ADC_NUMBER 3
|
||||
#define PIOS_ADC_PIN6_GPIO_PORT GPIOC // PC2 (AUX 3)
|
||||
#define PIOS_ADC_PIN6_GPIO_PIN GPIO_Pin_2 // ADC123_IN12
|
||||
#define PIOS_ADC_PIN6_GPIO_CHANNEL ADC_Channel_12
|
||||
#define PIOS_ADC_PIN6_ADC ADC1
|
||||
#define PIOS_ADC_PIN6_ADC_NUMBER 4
|
||||
#define PIOS_ADC_NUM_PINS 6
|
||||
#define PIOS_ADC_PORTS { PIOS_ADC_PIN1_GPIO_PORT, PIOS_ADC_PIN2_GPIO_PORT, PIOS_ADC_PIN3_GPIO_PORT, PIOS_ADC_PIN4_GPIO_PORT, PIOS_ADC_PIN5_GPIO_PORT, PIOS_ADC_PIN6_GPIO_PORT }
|
||||
#define PIOS_ADC_PINS { PIOS_ADC_PIN1_GPIO_PIN, PIOS_ADC_PIN2_GPIO_PIN, PIOS_ADC_PIN3_GPIO_PIN, PIOS_ADC_PIN4_GPIO_PIN, PIOS_ADC_PIN5_GPIO_PIN, PIOS_ADC_PIN6_GPIO_PIN }
|
||||
#define PIOS_ADC_CHANNELS { PIOS_ADC_PIN1_GPIO_CHANNEL, PIOS_ADC_PIN2_GPIO_CHANNEL, PIOS_ADC_PIN3_GPIO_CHANNEL, PIOS_ADC_PIN4_GPIO_CHANNEL, PIOS_ADC_PIN5_GPIO_CHANNEL, PIOS_ADC_PIN6_GPIO_CHANNEL }
|
||||
#define PIOS_ADC_MAPPING { PIOS_ADC_PIN1_ADC, PIOS_ADC_PIN2_ADC, PIOS_ADC_PIN3_ADC, PIOS_ADC_PIN4_ADC, PIOS_ADC_PIN5_ADC, PIOS_ADC_PIN6_ADC }
|
||||
#define PIOS_ADC_CHANNEL_MAPPING { PIOS_ADC_PIN1_ADC_NUMBER, PIOS_ADC_PIN2_ADC_NUMBER, PIOS_ADC_PIN3_ADC_NUMBER, PIOS_ADC_PIN4_ADC_NUMBER, PIOS_ADC_PIN5_ADC_NUMBER, PIOS_ADC_PIN6_ADC_NUMBER }
|
||||
#define PIOS_ADC_NUM_CHANNELS (PIOS_ADC_NUM_PINS + PIOS_ADC_USE_TEMP_SENSOR)
|
||||
#define PIOS_ADC_NUM_ADC_CHANNELS 2
|
||||
#define PIOS_ADC_USE_ADC2 1
|
||||
#define PIOS_ADC_CLOCK_FUNCTION RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1 | RCC_APB2Periph_ADC2, ENABLE)
|
||||
#define PIOS_ADC_ADCCLK RCC_PCLK2_Div8
|
||||
/* RCC_PCLK2_Div2: ADC clock = PCLK2/2 */
|
||||
/* RCC_PCLK2_Div4: ADC clock = PCLK2/4 */
|
||||
/* RCC_PCLK2_Div6: ADC clock = PCLK2/6 */
|
||||
/* RCC_PCLK2_Div8: ADC clock = PCLK2/8 */
|
||||
#define PIOS_ADC_SAMPLE_TIME ADC_SampleTime_239Cycles5
|
||||
/* Sample time: */
|
||||
/* With an ADCCLK = 14 MHz and a sampling time of 293.5 cycles: */
|
||||
/* Tconv = 239.5 + 12.5 = 252 cycles = 18?s */
|
||||
/* (1 / (ADCCLK / CYCLES)) = Sample Time (?S) */
|
||||
#define PIOS_ADC_IRQ_PRIO PIOS_IRQ_PRIO_LOW
|
||||
|
||||
//-------------------------
|
||||
// GPIO
|
||||
//-------------------------
|
||||
#define PIOS_GPIO_1_PORT GPIOC
|
||||
#define PIOS_GPIO_1_PIN GPIO_Pin_0
|
||||
#define PIOS_GPIO_1_GPIO_CLK RCC_APB2Periph_GPIOC
|
||||
#define PIOS_GPIO_2_PORT GPIOC
|
||||
#define PIOS_GPIO_2_PIN GPIO_Pin_1
|
||||
#define PIOS_GPIO_2_GPIO_CLK RCC_APB2Periph_GPIOC
|
||||
#define PIOS_GPIO_3_PORT GPIOC
|
||||
#define PIOS_GPIO_3_PIN GPIO_Pin_2
|
||||
#define PIOS_GPIO_3_GPIO_CLK RCC_APB2Periph_GPIOC
|
||||
#define PIOS_GPIO_4_PORT GPIOD
|
||||
#define PIOS_GPIO_4_PIN GPIO_Pin_2
|
||||
#define PIOS_GPIO_4_GPIO_CLK RCC_APB2Periph_GPIOD
|
||||
#define PIOS_GPIO_PORTS { PIOS_GPIO_1_PORT, PIOS_GPIO_2_PORT, PIOS_GPIO_3_PORT, PIOS_GPIO_4_PORT }
|
||||
#define PIOS_GPIO_PINS { PIOS_GPIO_1_PIN, PIOS_GPIO_2_PIN, PIOS_GPIO_3_PIN, PIOS_GPIO_4_PIN }
|
||||
#define PIOS_GPIO_CLKS { PIOS_GPIO_1_GPIO_CLK, PIOS_GPIO_2_GPIO_CLK, PIOS_GPIO_3_GPIO_CLK, PIOS_GPIO_4_GPIO_CLK }
|
||||
#define PIOS_GPIO_NUM 4
|
||||
|
||||
//-------------------------
|
||||
// USB
|
||||
//-------------------------
|
||||
#define PIOS_USB_ENABLED 1
|
||||
#define PIOS_USB_DETECT_GPIO_PORT GPIOC
|
||||
#define PIOS_USB_DETECT_GPIO_PIN GPIO_Pin_4
|
||||
#define PIOS_USB_DETECT_EXTI_LINE EXTI_Line4
|
||||
#define PIOS_IRQ_USB_PRIORITY PIOS_IRQ_PRIO_MID
|
||||
|
||||
/**
|
||||
* glue macros for file IO
|
||||
* STM32 uses DOSFS for file IO
|
||||
*/
|
||||
#define PIOS_FOPEN_READ(filename,file) DFS_OpenFile(&PIOS_SDCARD_VolInfo, (uint8_t *)filename, DFS_READ, PIOS_SDCARD_Sector, &file) != DFS_OK
|
||||
|
||||
#define PIOS_FOPEN_WRITE(filename,file) DFS_OpenFile(&PIOS_SDCARD_VolInfo, (uint8_t *)filename, DFS_WRITE, PIOS_SDCARD_Sector, &file) != DFS_OK
|
||||
|
||||
#define PIOS_FREAD(file,bufferadr,length,resultadr) DFS_ReadFile(file, PIOS_SDCARD_Sector, (uint8_t*)bufferadr, resultadr, length) != DFS_OK
|
||||
|
||||
#define PIOS_FWRITE(file,bufferadr,length,resultadr) DFS_WriteFile(file, PIOS_SDCARD_Sector, (uint8_t*)bufferadr, resultadr, length)
|
||||
|
||||
#define PIOS_FCLOSE(file) DFS_Close(&file)
|
||||
|
||||
#define PIOS_FUNLINK(filename) DFS_UnlinkFile(&PIOS_SDCARD_VolInfo, (uint8_t *)filename, PIOS_SDCARD_Sector)
|
||||
|
||||
|
||||
|
||||
#endif /* STM3210E_OP_H_ */
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
Loading…
x
Reference in New Issue
Block a user