Merge branch 'next' into camera_stabilization
Conflicts: flight/CopterControl/Makefile flight/CopterControl/System/coptercontrol.c flight/Modules/Actuator/actuator.c flight/Modules/GPS/GPS.c flight/Modules/ManualControl/manualcontrol.c flight/Modules/Stabilization/stabilization.c flight/Modules/System/systemmod.c shared/uavobjectdefinition/manualcontrolsettings.xml shared/uavobjectdefinition/stabilizationdesired.xml
@ -27,6 +27,10 @@ N: Pedro Assuncao
|
||||
E: pedro (dot) agda (plus) openpilot (at) gmail (dot) com
|
||||
D: Initial GCS Settings Gadget work
|
||||
|
||||
N: Werner Backes
|
||||
E: werner (at) bit-1 (dot) de
|
||||
D: Port of CopterControl to PS3 Move Controller (MoveCopter)
|
||||
|
||||
N: Jose Barros
|
||||
E: josembarros (at) hotmail (dot) com
|
||||
D: Next-Gen OP Map Lib, Y-Modem Library, Uploader Plugin
|
||||
|
21
HISTORY.txt
Normal file
@ -0,0 +1,21 @@
|
||||
Short summary of changes. For a complete list see the git log.
|
||||
|
||||
2011-07-17
|
||||
Updated module initialization from Mathieu which separates the initialization
|
||||
from the task startup. Also implements a method to reclaim unused ram from
|
||||
initialization and end of memory for the FreeRTOS heap.
|
||||
|
||||
2011-07-12
|
||||
Improvements to the stabilization code. Included a LPF on the gyros to smooth
|
||||
out noise in high vibration environments. Also two new modes: axis-lock and
|
||||
weak leveling. Axis-lock will try and hold an axis at a fixed position and
|
||||
reject any disturbances. This is like heading-hold on a heli for the tail but
|
||||
can be useful for other axes. Weak leveling is rate mode with a weak
|
||||
correction to self level the craft - good for easier rate mode flying.
|
||||
|
||||
2011-07-07
|
||||
Dynamic hardware configuration from Stac. The input type is now
|
||||
selected from ManualControlSettings.InputMode and the aircraft must be rebooted
|
||||
after changing this. Also for CopterControl the HwSettings object must
|
||||
indicate which modules are connected to which ports. PPM currently not
|
||||
working.
|
@ -117,11 +117,45 @@ C: Sami Korhonen (Sambas)
|
||||
D: May 2011
|
||||
V: http://vimeo.com/24258192
|
||||
|
||||
M: First CopterControl flip on a Flybarless Heli
|
||||
M: First Y6 CopterControl flight
|
||||
C: Michel Pet
|
||||
D: June 2011
|
||||
V: http://www.youtube.com/watch?v=QsE2MQELPZY
|
||||
|
||||
M: First MoveCopter flight
|
||||
C: Werner Backes
|
||||
D: July 2011
|
||||
V: http://vimeo.com/25983655
|
||||
|
||||
M: First Y4 CopterControl flight
|
||||
C: Mat Wellington
|
||||
D: July 2011
|
||||
V: http://www.youtube.com/watch?v=TxZ4MDGIj1o
|
||||
|
||||
M: First V-Tail4 CopterControl flight
|
||||
C: Mat Wellington
|
||||
D: July 2011
|
||||
V: http://www.youtube.com/watch?v=YE4Fd9vdg1I
|
||||
|
||||
M: First Altitude Hold using Sonar
|
||||
C:
|
||||
D:
|
||||
V:
|
||||
|
||||
M: First CopterControl Navigation on RC Ground Vechicle
|
||||
C:
|
||||
D:
|
||||
V:
|
||||
|
||||
M: First CopterControl Navigation on RC Water Vechicle
|
||||
C:
|
||||
D:
|
||||
V:
|
||||
|
||||
M: First CopterControl flip on a Flybarless Heli
|
||||
C:
|
||||
D:
|
||||
V:
|
||||
|
||||
|
||||
An incomplete list of some future Milestones is below:
|
||||
@ -131,8 +165,7 @@ An incomplete list of some future Milestones is below:
|
||||
* First successful flight using the GCS only and no RC TX
|
||||
* First use of Magic Waypoint
|
||||
* First Flybarless Helicopter flight with OpenPilot
|
||||
* First flight with CopterControl
|
||||
* First fixed wing navigation flight
|
||||
* First fixed wing navigation flight
|
||||
* First Multirotor navigation flight
|
||||
* First Helicopter navigation flight
|
||||
* First over 1km navigation flight
|
||||
|
75
Makefile
@ -71,6 +71,7 @@ help:
|
||||
@echo " qt_sdk_install - Install the QT v4.6.2 tools"
|
||||
@echo " arm_sdk_install - Install the Code Sourcery ARM gcc toolchain"
|
||||
@echo " openocd_install - Install the OpenOCD JTAG daemon"
|
||||
@echo " stm32flash_install - Install the stm32flash tool for unbricking boards"
|
||||
@echo
|
||||
@echo " [Big Hammer]"
|
||||
@echo " all - Generate UAVObjects, build openpilot firmware and gcs"
|
||||
@ -92,21 +93,25 @@ help:
|
||||
@echo " <board> - Build firmware for <board>"
|
||||
@echo " supported boards are ($(ALL_BOARDS))"
|
||||
@echo " fw_<board> - Build firmware for <board>"
|
||||
@echo " supported boards are ($(FW_TARGETS))"
|
||||
@echo " supported boards are ($(FW_BOARDS))"
|
||||
@echo " fw_<board>_clean - Remove firmware for <board>"
|
||||
@echo " fw_<board>_program - Use OpenOCD + JTAG to write firmware to <board>"
|
||||
@echo
|
||||
@echo " [Bootloader]"
|
||||
@echo " bl_<board> - Build bootloader for <board>"
|
||||
@echo " supported boards are ($(BL_TARGETS))"
|
||||
@echo " supported boards are ($(BL_BOARDS))"
|
||||
@echo " bl_<board>_clean - Remove bootloader for <board>"
|
||||
@echo " bl_<board>_program - Use OpenOCD + JTAG to write bootloader to <board>"
|
||||
@echo
|
||||
@echo " [Bootloader Updater]"
|
||||
@echo " bu_<board> - Build bootloader updater for <board>"
|
||||
@echo " supported boards are ($(BU_TARGETS))"
|
||||
@echo " supported boards are ($(BU_BOARDS))"
|
||||
@echo " bu_<board>_clean - Remove bootloader updater for <board>"
|
||||
@echo
|
||||
@echo " [Unbrick a board]"
|
||||
@echo " unbrick_<board> - Use the STM32's built in boot ROM to write a bootloader to <board>"
|
||||
@echo " supported boards are ($(BL_BOARDS))"
|
||||
@echo
|
||||
@echo " [Simulation]"
|
||||
@echo " sim_posix - Build OpenPilot simulation firmware for"
|
||||
@echo " a POSIX compatible system (Linux, Mac OS X, ...)"
|
||||
@ -175,10 +180,10 @@ qt_sdk_clean:
|
||||
$(V1) [ ! -d "$(QT_SDK_DIR)" ] || $(RM) -rf $(QT_SDK_DIR)
|
||||
|
||||
# Set up ARM (STM32) SDK
|
||||
ARM_SDK_DIR := $(TOOLS_DIR)/arm-2009q3
|
||||
ARM_SDK_DIR := $(TOOLS_DIR)/arm-2011.03
|
||||
|
||||
.PHONY: arm_sdk_install
|
||||
arm_sdk_install: ARM_SDK_URL := http://www.codesourcery.com/sgpp/lite/arm/portal/package5353/public/arm-none-eabi/arm-2009q3-68-arm-none-eabi-i686-pc-linux-gnu.tar.bz2
|
||||
arm_sdk_install: ARM_SDK_URL := http://www.codesourcery.com/sgpp/lite/arm/portal/package8734/public/arm-none-eabi/arm-2011.03-42-arm-none-eabi-i686-pc-linux-gnu.tar.bz2
|
||||
arm_sdk_install: ARM_SDK_FILE := $(notdir $(ARM_SDK_URL))
|
||||
# order-only prereq on directory existance:
|
||||
arm_sdk_install: | $(DL_DIR) $(TOOLS_DIR)
|
||||
@ -226,6 +231,25 @@ openocd_install: openocd_clean
|
||||
openocd_clean:
|
||||
$(V1) [ ! -d "$(OPENOCD_DIR)" ] || $(RM) -r "$(OPENOCD_DIR)"
|
||||
|
||||
STM32FLASH_DIR := $(TOOLS_DIR)/stm32flash
|
||||
|
||||
.PHONY: stm32flash_install
|
||||
stm32flash_install: STM32FLASH_URL := http://stm32flash.googlecode.com/svn/trunk
|
||||
stm32flash_install: STM32FLASH_REV := 52
|
||||
stm32flash_install: stm32flash_clean
|
||||
# download the source
|
||||
$(V0) @echo " DOWNLOAD $(STM32FLASH_URL) @ r$(STM32FLASH_REV)"
|
||||
$(V1) svn export -q -r "$(STM32FLASH_REV)" "$(STM32FLASH_URL)" "$(STM32FLASH_DIR)"
|
||||
|
||||
# build
|
||||
$(V0) @echo " BUILD $(STM32FLASH_DIR)"
|
||||
$(V1) $(MAKE) --silent -C $(STM32FLASH_DIR) all
|
||||
|
||||
.PHONY: stm32flash_clean
|
||||
stm32flash_clean:
|
||||
$(V0) @echo " CLEAN $(STM32FLASH_DIR)"
|
||||
$(V1) [ ! -d "$(STM32FLASH_DIR)" ] || $(RM) -r "$(STM32FLASH_DIR)"
|
||||
|
||||
##############################
|
||||
#
|
||||
# Set up paths to tools
|
||||
@ -277,7 +301,7 @@ openpilotgcs: uavobjects_gcs
|
||||
|
||||
.PHONY: openpilotgcs_clean
|
||||
openpilotgcs_clean:
|
||||
$(V0) @echo " CLEAN $@"
|
||||
$(V0) @echo " CLEAN $@"
|
||||
$(V1) [ ! -d "$(BUILD_DIR)/ground/openpilotgcs" ] || $(RM) -r "$(BUILD_DIR)/ground/openpilotgcs"
|
||||
|
||||
.PHONY: uavobjgenerator
|
||||
@ -307,7 +331,7 @@ uavobjects_test: $(UAVOBJ_OUT_DIR) uavobjgenerator
|
||||
$(V1) $(UAVOBJGENERATOR) -v -none $(UAVOBJ_XML_DIR) $(ROOT_DIR)
|
||||
|
||||
uavobjects_clean:
|
||||
$(V0) @echo " CLEAN $@"
|
||||
$(V0) @echo " CLEAN $@"
|
||||
$(V1) [ ! -d "$(UAVOBJ_OUT_DIR)" ] || $(RM) -r "$(UAVOBJ_OUT_DIR)"
|
||||
|
||||
##############################
|
||||
@ -335,7 +359,7 @@ fw_$(1)_%: uavobjects_flight
|
||||
.PHONY: $(1)_clean
|
||||
$(1)_clean: fw_$(1)_clean
|
||||
fw_$(1)_clean:
|
||||
$(V0) @echo " CLEAN $$@"
|
||||
$(V0) @echo " CLEAN $$@"
|
||||
$(V1) $(RM) -fr $(BUILD_DIR)/fw_$(1)
|
||||
endef
|
||||
|
||||
@ -355,9 +379,23 @@ bl_$(1)_%:
|
||||
REMOVE_CMD="$(RM)" OOCD_EXE="$(OPENOCD)" \
|
||||
$$*
|
||||
|
||||
.PHONY: unbrick_$(1)
|
||||
unbrick_$(1): bl_$(1)_hex
|
||||
$(if $(filter-out undefined,$(origin UNBRICK_TTY)),
|
||||
$(V0) @echo " UNBRICK $(1) via $$(UNBRICK_TTY)"
|
||||
$(V1) $(STM32FLASH_DIR)/stm32flash \
|
||||
-w $(BUILD_DIR)/bl_$(1)/bl_$(1).hex \
|
||||
-g 0x0 \
|
||||
$$(UNBRICK_TTY)
|
||||
,
|
||||
$(V0) @echo
|
||||
$(V0) @echo "ERROR: You must specify UNBRICK_TTY=<serial-device> to use for unbricking."
|
||||
$(V0) @echo " eg. $$(MAKE) $$@ UNBRICK_TTY=/dev/ttyUSB0"
|
||||
)
|
||||
|
||||
.PHONY: bl_$(1)_clean
|
||||
bl_$(1)_clean:
|
||||
$(V0) @echo " CLEAN $$@"
|
||||
$(V0) @echo " CLEAN $$@"
|
||||
$(V1) $(RM) -fr $(BUILD_DIR)/bl_$(1)
|
||||
endef
|
||||
|
||||
@ -377,7 +415,7 @@ bu_$(1)_%: bl_$(1)_bino
|
||||
|
||||
.PHONY: bu_$(1)_clean
|
||||
bu_$(1)_clean:
|
||||
$(V0) @echo " CLEAN $$@"
|
||||
$(V0) @echo " CLEAN $$@"
|
||||
$(V1) $(RM) -fr $(BUILD_DIR)/bu_$(1)
|
||||
endef
|
||||
|
||||
@ -403,14 +441,20 @@ pipxtreme_friendly := PipXtreme
|
||||
ins_friendly := INS
|
||||
ahrs_friendly := AHRS
|
||||
|
||||
FW_TARGETS := $(addprefix fw_, $(ALL_BOARDS))
|
||||
BL_TARGETS := $(addprefix bl_, $(ALL_BOARDS))
|
||||
BU_TARGETS := $(addprefix bu_, $(ALL_BOARDS))
|
||||
# Start out assuming that we'll build fw, bl and bu for all boards
|
||||
FW_BOARDS := $(ALL_BOARDS)
|
||||
BL_BOARDS := $(ALL_BOARDS)
|
||||
BU_BOARDS := $(ALL_BOARDS)
|
||||
|
||||
# FIXME: The INS build doesn't have a bootloader or bootloader
|
||||
# updater yet so we need to filter them out to prevent errors.
|
||||
BL_TARGETS := $(filter-out bl_ins, $(BL_TARGETS))
|
||||
BU_TARGETS := $(filter-out bu_ins, $(BU_TARGETS))
|
||||
BL_BOARDS := $(filter-out ins, $(ALL_BOARDS))
|
||||
BU_BOARDS := $(filter-out ins, $(ALL_BOARDS))
|
||||
|
||||
# Generate the targets for whatever boards are left in each list
|
||||
FW_TARGETS := $(addprefix fw_, $(FW_BOARDS))
|
||||
BL_TARGETS := $(addprefix bl_, $(BL_BOARDS))
|
||||
BU_TARGETS := $(addprefix bu_, $(BU_BOARDS))
|
||||
|
||||
.PHONY: all_fw all_fw_clean
|
||||
all_fw: $(addsuffix _opfw, $(FW_TARGETS))
|
||||
@ -428,6 +472,7 @@ all_bu_clean: $(addsuffix _clean, $(BU_TARGETS))
|
||||
all_flight: all_fw all_bl all_bu
|
||||
all_flight_clean: all_fw_clean all_bl_clean all_bu_clean
|
||||
|
||||
# Expand the groups of targets for each board
|
||||
$(foreach board, $(ALL_BOARDS), $(eval $(call BOARD_PHONY_TEMPLATE,$(board))))
|
||||
|
||||
# Expand the bootloader updater rules
|
||||
|
BIN
artwork/3D Model/multi/joes_cnc/CC.PNG
Normal file
After Width: | Height: | Size: 96 KiB |
BIN
artwork/3D Model/multi/joes_cnc/J14-QT_+.3DS
Normal file
BIN
artwork/3D Model/multi/joes_cnc/J14-QT_+.jpg
Normal file
After Width: | Height: | Size: 125 KiB |
BIN
artwork/3D Model/multi/joes_cnc/J14-QT_X.3DS
Normal file
BIN
artwork/3D Model/multi/joes_cnc/J14-QT_X.jpg
Normal file
After Width: | Height: | Size: 132 KiB |
BIN
artwork/3D Model/multi/joes_cnc/J14-Q_+.3DS
Normal file
BIN
artwork/3D Model/multi/joes_cnc/J14-Q_+.jpg
Normal file
After Width: | Height: | Size: 84 KiB |
BIN
artwork/3D Model/multi/joes_cnc/J14-Q_X.3DS
Normal file
BIN
artwork/3D Model/multi/joes_cnc/J14-Q_X.jpg
Normal file
After Width: | Height: | Size: 84 KiB |
BIN
artwork/3D Model/multi/joes_cnc/TEXTURE.PNG
Normal file
After Width: | Height: | Size: 1.1 KiB |
1329
artwork/Dials/deluxe/lineardial-horizontal.svg
Normal file
@ -0,0 +1,1329 @@
|
||||
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||
<!-- Created with Inkscape (http://www.inkscape.org/) -->
|
||||
|
||||
<svg
|
||||
xmlns:dc="http://purl.org/dc/elements/1.1/"
|
||||
xmlns:cc="http://creativecommons.org/ns#"
|
||||
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
|
||||
xmlns:svg="http://www.w3.org/2000/svg"
|
||||
xmlns="http://www.w3.org/2000/svg"
|
||||
xmlns:xlink="http://www.w3.org/1999/xlink"
|
||||
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
|
||||
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
|
||||
width="280.76797"
|
||||
height="70.597504"
|
||||
id="svg10068"
|
||||
version="1.1"
|
||||
inkscape:version="0.48.1 "
|
||||
sodipodi:docname="lineardial-horizontal.svg"
|
||||
inkscape:export-filename="H:\Documents\Hobbies\W433\My Gauges\vbat-001.png"
|
||||
inkscape:export-xdpi="103.61"
|
||||
inkscape:export-ydpi="103.61"
|
||||
style="display:inline">
|
||||
<defs
|
||||
id="defs10070">
|
||||
<linearGradient
|
||||
id="linearGradient4439">
|
||||
<stop
|
||||
style="stop-color:#1a1a1a;stop-opacity:1"
|
||||
offset="0"
|
||||
id="stop4441" />
|
||||
<stop
|
||||
id="stop4443"
|
||||
offset="0.19742694"
|
||||
style="stop-color:#808080;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#000000;stop-opacity:1"
|
||||
offset="1"
|
||||
id="stop4445" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient4413">
|
||||
<stop
|
||||
id="stop4415"
|
||||
offset="0"
|
||||
style="stop-color:#1a1a1a;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#4d4d4d;stop-opacity:1"
|
||||
offset="0.19742694"
|
||||
id="stop4417" />
|
||||
<stop
|
||||
id="stop4419"
|
||||
offset="1"
|
||||
style="stop-color:#000000;stop-opacity:1" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient4387">
|
||||
<stop
|
||||
id="stop4389"
|
||||
offset="0"
|
||||
style="stop-color:#4d4d4d;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#000000;stop-opacity:1"
|
||||
offset="0.60976541"
|
||||
id="stop4391" />
|
||||
<stop
|
||||
id="stop4393"
|
||||
offset="1"
|
||||
style="stop-color:#4d4d4d;stop-opacity:1" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient4361">
|
||||
<stop
|
||||
style="stop-color:#4d4d4d;stop-opacity:1"
|
||||
offset="0"
|
||||
id="stop4363" />
|
||||
<stop
|
||||
id="stop4365"
|
||||
offset="0.60976541"
|
||||
style="stop-color:#000000;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#4d4d4d;stop-opacity:1"
|
||||
offset="1"
|
||||
id="stop4367" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient4317">
|
||||
<stop
|
||||
id="stop4319"
|
||||
offset="0"
|
||||
style="stop-color:#4d4d4d;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#000000;stop-opacity:1"
|
||||
offset="0.60976541"
|
||||
id="stop4321" />
|
||||
<stop
|
||||
id="stop4323"
|
||||
offset="1"
|
||||
style="stop-color:#b3b3b3;stop-opacity:1" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient4265">
|
||||
<stop
|
||||
style="stop-color:#333333;stop-opacity:1"
|
||||
offset="0"
|
||||
id="stop4267" />
|
||||
<stop
|
||||
id="stop4269"
|
||||
offset="0.60976541"
|
||||
style="stop-color:#000000;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#333333;stop-opacity:1"
|
||||
offset="1"
|
||||
id="stop4271" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient4239">
|
||||
<stop
|
||||
id="stop4241"
|
||||
offset="0"
|
||||
style="stop-color:#000000;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#808080;stop-opacity:1"
|
||||
offset="0.60976541"
|
||||
id="stop4243" />
|
||||
<stop
|
||||
id="stop4245"
|
||||
offset="1"
|
||||
style="stop-color:#000000;stop-opacity:1" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient4215">
|
||||
<stop
|
||||
style="stop-color:#1a1a1a;stop-opacity:1"
|
||||
offset="0"
|
||||
id="stop4217" />
|
||||
<stop
|
||||
id="stop4219"
|
||||
offset="0.3051295"
|
||||
style="stop-color:#808080;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#000000;stop-opacity:1"
|
||||
offset="1"
|
||||
id="stop4221" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient4193">
|
||||
<stop
|
||||
id="stop4195"
|
||||
offset="0"
|
||||
style="stop-color:#1a1a1a;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#999999;stop-opacity:1"
|
||||
offset="0.3051295"
|
||||
id="stop4197" />
|
||||
<stop
|
||||
id="stop4199"
|
||||
offset="1"
|
||||
style="stop-color:#000000;stop-opacity:1" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient4171">
|
||||
<stop
|
||||
style="stop-color:#1a1a1a;stop-opacity:1"
|
||||
offset="0"
|
||||
id="stop4173" />
|
||||
<stop
|
||||
id="stop4175"
|
||||
offset="0.3051295"
|
||||
style="stop-color:#666666;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#1a1a1a;stop-opacity:1"
|
||||
offset="1"
|
||||
id="stop4177" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient4121">
|
||||
<stop
|
||||
id="stop4123"
|
||||
offset="0"
|
||||
style="stop-color:#1a1a1a;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#666666;stop-opacity:1"
|
||||
offset="0.2984421"
|
||||
id="stop4125" />
|
||||
<stop
|
||||
id="stop4127"
|
||||
offset="1"
|
||||
style="stop-color:#1a1a1a;stop-opacity:1" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient4085">
|
||||
<stop
|
||||
style="stop-color:#1a1a1a;stop-opacity:1"
|
||||
offset="0"
|
||||
id="stop4087" />
|
||||
<stop
|
||||
id="stop4089"
|
||||
offset="0.2984421"
|
||||
style="stop-color:#999999;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#1a1a1a;stop-opacity:1"
|
||||
offset="1"
|
||||
id="stop4091" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient4063">
|
||||
<stop
|
||||
id="stop4065"
|
||||
offset="0"
|
||||
style="stop-color:#1a1a1a;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#b3b3b3;stop-opacity:1"
|
||||
offset="0.39999998"
|
||||
id="stop4067" />
|
||||
<stop
|
||||
id="stop4069"
|
||||
offset="1"
|
||||
style="stop-color:#1a1a1a;stop-opacity:1" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient4027">
|
||||
<stop
|
||||
style="stop-color:#000000;stop-opacity:1"
|
||||
offset="0"
|
||||
id="stop4029" />
|
||||
<stop
|
||||
id="stop4031"
|
||||
offset="0.31880337"
|
||||
style="stop-color:#b3b3b3;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#000000;stop-opacity:1"
|
||||
offset="1"
|
||||
id="stop4033" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient3903">
|
||||
<stop
|
||||
id="stop3905"
|
||||
offset="0"
|
||||
style="stop-color:#000000;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#ffffff;stop-opacity:1"
|
||||
offset="0.3220683"
|
||||
id="stop3907" />
|
||||
<stop
|
||||
id="stop3909"
|
||||
offset="1"
|
||||
style="stop-color:#000000;stop-opacity:1" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient5375">
|
||||
<stop
|
||||
style="stop-color:#00000c;stop-opacity:1"
|
||||
offset="0"
|
||||
id="stop5377" />
|
||||
<stop
|
||||
id="stop5383"
|
||||
offset="0.34210527"
|
||||
style="stop-color:#0044d8;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#00000c;stop-opacity:1"
|
||||
offset="1"
|
||||
id="stop5379" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient5367">
|
||||
<stop
|
||||
style="stop-color:#000020;stop-opacity:1"
|
||||
offset="0"
|
||||
id="stop5369" />
|
||||
<stop
|
||||
id="stop5371"
|
||||
offset="1"
|
||||
style="stop-color:#000018;stop-opacity:1" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient5359">
|
||||
<stop
|
||||
style="stop-color:#00002c;stop-opacity:1"
|
||||
offset="0"
|
||||
id="stop5361" />
|
||||
<stop
|
||||
id="stop5363"
|
||||
offset="0.32456139"
|
||||
style="stop-color:#00ffff;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#00c8fc;stop-opacity:1"
|
||||
offset="1"
|
||||
id="stop5365" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient5346">
|
||||
<stop
|
||||
id="stop5348"
|
||||
offset="0"
|
||||
style="stop-color:#1a1a1a;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#666666;stop-opacity:1"
|
||||
offset="0.37595931"
|
||||
id="stop5350" />
|
||||
<stop
|
||||
id="stop5352"
|
||||
offset="1"
|
||||
style="stop-color:#1a1a1a;stop-opacity:1" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient5326">
|
||||
<stop
|
||||
style="stop-color:#000000;stop-opacity:1"
|
||||
offset="0"
|
||||
id="stop5328" />
|
||||
<stop
|
||||
id="stop5330"
|
||||
offset="0.35277387"
|
||||
style="stop-color:#4d4d4d;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#000000;stop-opacity:1"
|
||||
offset="1"
|
||||
id="stop5332" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient5306">
|
||||
<stop
|
||||
id="stop5308"
|
||||
offset="0"
|
||||
style="stop-color:#000000;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#808080;stop-opacity:1"
|
||||
offset="0.35277387"
|
||||
id="stop5310" />
|
||||
<stop
|
||||
id="stop5312"
|
||||
offset="1"
|
||||
style="stop-color:#000000;stop-opacity:1" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient5271">
|
||||
<stop
|
||||
id="stop5273"
|
||||
offset="0"
|
||||
style="stop-color:#000080;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#00ffff;stop-opacity:1"
|
||||
offset="0.32456139"
|
||||
id="stop5275" />
|
||||
<stop
|
||||
id="stop5277"
|
||||
offset="1"
|
||||
style="stop-color:#000080;stop-opacity:1" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient5248">
|
||||
<stop
|
||||
style="stop-color:#000080;stop-opacity:1"
|
||||
offset="0"
|
||||
id="stop5250" />
|
||||
<stop
|
||||
id="stop5256"
|
||||
offset="0.32456139"
|
||||
style="stop-color:#00ffff;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#000080;stop-opacity:1"
|
||||
offset="1"
|
||||
id="stop5252" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient5236">
|
||||
<stop
|
||||
style="stop-color:#000000;stop-opacity:1;"
|
||||
offset="0"
|
||||
id="stop5238" />
|
||||
<stop
|
||||
id="stop5244"
|
||||
offset="0.5"
|
||||
style="stop-color:#000000;stop-opacity:0.49803922;" />
|
||||
<stop
|
||||
style="stop-color:#000000;stop-opacity:0;"
|
||||
offset="1"
|
||||
id="stop5240" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient5219">
|
||||
<stop
|
||||
style="stop-color:#000000;stop-opacity:1"
|
||||
offset="0"
|
||||
id="stop5221" />
|
||||
<stop
|
||||
id="stop5223"
|
||||
offset="0.35277387"
|
||||
style="stop-color:#b3b3b3;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#1a1a1a;stop-opacity:1"
|
||||
offset="1"
|
||||
id="stop5225" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient5151">
|
||||
<stop
|
||||
id="stop5153"
|
||||
offset="0"
|
||||
style="stop-color:#000000;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#b3b3b3;stop-opacity:1"
|
||||
offset="0.38512576"
|
||||
id="stop5155" />
|
||||
<stop
|
||||
id="stop5157"
|
||||
offset="1"
|
||||
style="stop-color:#000000;stop-opacity:1" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient5129">
|
||||
<stop
|
||||
style="stop-color:#1a1a1a;stop-opacity:1"
|
||||
offset="0"
|
||||
id="stop5131" />
|
||||
<stop
|
||||
id="stop5137"
|
||||
offset="0.38512576"
|
||||
style="stop-color:#cccccc;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#4d4d4d;stop-opacity:1"
|
||||
offset="1"
|
||||
id="stop5133" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient5116">
|
||||
<stop
|
||||
style="stop-color:#000000;stop-opacity:1"
|
||||
offset="0"
|
||||
id="stop5118" />
|
||||
<stop
|
||||
id="stop5124"
|
||||
offset="0.35911319"
|
||||
style="stop-color:#dcaf28;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#000000;stop-opacity:1"
|
||||
offset="1"
|
||||
id="stop5120" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient5106">
|
||||
<stop
|
||||
style="stop-color:#000000;stop-opacity:1"
|
||||
offset="0"
|
||||
id="stop5108" />
|
||||
<stop
|
||||
id="stop5114"
|
||||
offset="0.36023793"
|
||||
style="stop-color:#00a000;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#000000;stop-opacity:1"
|
||||
offset="1"
|
||||
id="stop5110" />
|
||||
</linearGradient>
|
||||
<linearGradient
|
||||
id="linearGradient5096">
|
||||
<stop
|
||||
style="stop-color:#100000;stop-opacity:1"
|
||||
offset="0"
|
||||
id="stop5098" />
|
||||
<stop
|
||||
id="stop5104"
|
||||
offset="0.36453304"
|
||||
style="stop-color:#aa0000;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#0c0000;stop-opacity:1"
|
||||
offset="1"
|
||||
id="stop5100" />
|
||||
</linearGradient>
|
||||
<marker
|
||||
inkscape:stockid="Arrow2Sstart"
|
||||
orient="auto"
|
||||
refY="0"
|
||||
refX="0"
|
||||
id="Arrow2Sstart"
|
||||
style="overflow:visible">
|
||||
<path
|
||||
id="path4640"
|
||||
style="font-size:12px;fill-rule:evenodd;stroke-width:0.625;stroke-linejoin:round"
|
||||
d="M 8.7185878,4.0337352 -2.2072895,0.01601326 8.7185884,-4.0017078 c -1.7454984,2.3720609 -1.7354408,5.6174519 -6e-7,8.035443 z"
|
||||
transform="matrix(0.3,0,0,0.3,-0.69,0)"
|
||||
inkscape:connector-curvature="0" />
|
||||
</marker>
|
||||
<inkscape:perspective
|
||||
sodipodi:type="inkscape:persp3d"
|
||||
inkscape:vp_x="0 : 526.18109 : 1"
|
||||
inkscape:vp_y="0 : 1000 : 0"
|
||||
inkscape:vp_z="744.09448 : 526.18109 : 1"
|
||||
inkscape:persp3d-origin="372.04724 : 350.78739 : 1"
|
||||
id="perspective10076" />
|
||||
<inkscape:perspective
|
||||
id="perspective9987"
|
||||
inkscape:persp3d-origin="0.5 : 0.33333333 : 1"
|
||||
inkscape:vp_z="1 : 0.5 : 1"
|
||||
inkscape:vp_y="0 : 1000 : 0"
|
||||
inkscape:vp_x="0 : 0.5 : 1"
|
||||
sodipodi:type="inkscape:persp3d" />
|
||||
<inkscape:perspective
|
||||
id="perspective10250"
|
||||
inkscape:persp3d-origin="0.5 : 0.33333333 : 1"
|
||||
inkscape:vp_z="1 : 0.5 : 1"
|
||||
inkscape:vp_y="0 : 1000 : 0"
|
||||
inkscape:vp_x="0 : 0.5 : 1"
|
||||
sodipodi:type="inkscape:persp3d" />
|
||||
<inkscape:perspective
|
||||
id="perspective10279"
|
||||
inkscape:persp3d-origin="0.5 : 0.33333333 : 1"
|
||||
inkscape:vp_z="1 : 0.5 : 1"
|
||||
inkscape:vp_y="0 : 1000 : 0"
|
||||
inkscape:vp_x="0 : 0.5 : 1"
|
||||
sodipodi:type="inkscape:persp3d" />
|
||||
<inkscape:perspective
|
||||
id="perspective10517"
|
||||
inkscape:persp3d-origin="0.5 : 0.33333333 : 1"
|
||||
inkscape:vp_z="1 : 0.5 : 1"
|
||||
inkscape:vp_y="0 : 1000 : 0"
|
||||
inkscape:vp_x="0 : 0.5 : 1"
|
||||
sodipodi:type="inkscape:persp3d" />
|
||||
<inkscape:perspective
|
||||
id="perspective11202"
|
||||
inkscape:persp3d-origin="0.5 : 0.33333333 : 1"
|
||||
inkscape:vp_z="1 : 0.5 : 1"
|
||||
inkscape:vp_y="0 : 1000 : 0"
|
||||
inkscape:vp_x="0 : 0.5 : 1"
|
||||
sodipodi:type="inkscape:persp3d" />
|
||||
<inkscape:perspective
|
||||
id="perspective3720"
|
||||
inkscape:persp3d-origin="0.5 : 0.33333333 : 1"
|
||||
inkscape:vp_z="1 : 0.5 : 1"
|
||||
inkscape:vp_y="0 : 1000 : 0"
|
||||
inkscape:vp_x="0 : 0.5 : 1"
|
||||
sodipodi:type="inkscape:persp3d" />
|
||||
<inkscape:perspective
|
||||
id="perspective3735"
|
||||
inkscape:persp3d-origin="0.5 : 0.33333333 : 1"
|
||||
inkscape:vp_z="1 : 0.5 : 1"
|
||||
inkscape:vp_y="0 : 1000 : 0"
|
||||
inkscape:vp_x="0 : 0.5 : 1"
|
||||
sodipodi:type="inkscape:persp3d" />
|
||||
<inkscape:perspective
|
||||
id="perspective3757"
|
||||
inkscape:persp3d-origin="0.5 : 0.33333333 : 1"
|
||||
inkscape:vp_z="1 : 0.5 : 1"
|
||||
inkscape:vp_y="0 : 1000 : 0"
|
||||
inkscape:vp_x="0 : 0.5 : 1"
|
||||
sodipodi:type="inkscape:persp3d" />
|
||||
<inkscape:perspective
|
||||
id="perspective3828"
|
||||
inkscape:persp3d-origin="0.5 : 0.33333333 : 1"
|
||||
inkscape:vp_z="1 : 0.5 : 1"
|
||||
inkscape:vp_y="0 : 1000 : 0"
|
||||
inkscape:vp_x="0 : 0.5 : 1"
|
||||
sodipodi:type="inkscape:persp3d" />
|
||||
<inkscape:perspective
|
||||
id="perspective3889"
|
||||
inkscape:persp3d-origin="0.5 : 0.33333333 : 1"
|
||||
inkscape:vp_z="1 : 0.5 : 1"
|
||||
inkscape:vp_y="0 : 1000 : 0"
|
||||
inkscape:vp_x="0 : 0.5 : 1"
|
||||
sodipodi:type="inkscape:persp3d" />
|
||||
<inkscape:perspective
|
||||
id="perspective3925"
|
||||
inkscape:persp3d-origin="0.5 : 0.33333333 : 1"
|
||||
inkscape:vp_z="1 : 0.5 : 1"
|
||||
inkscape:vp_y="0 : 1000 : 0"
|
||||
inkscape:vp_x="0 : 0.5 : 1"
|
||||
sodipodi:type="inkscape:persp3d" />
|
||||
<inkscape:perspective
|
||||
id="perspective3968"
|
||||
inkscape:persp3d-origin="0.5 : 0.33333333 : 1"
|
||||
inkscape:vp_z="1 : 0.5 : 1"
|
||||
inkscape:vp_y="0 : 1000 : 0"
|
||||
inkscape:vp_x="0 : 0.5 : 1"
|
||||
sodipodi:type="inkscape:persp3d" />
|
||||
<inkscape:perspective
|
||||
id="perspective3982"
|
||||
inkscape:persp3d-origin="0.5 : 0.33333333 : 1"
|
||||
inkscape:vp_z="1 : 0.5 : 1"
|
||||
inkscape:vp_y="0 : 1000 : 0"
|
||||
inkscape:vp_x="0 : 0.5 : 1"
|
||||
sodipodi:type="inkscape:persp3d" />
|
||||
<inkscape:perspective
|
||||
id="perspective4682"
|
||||
inkscape:persp3d-origin="0.5 : 0.33333333 : 1"
|
||||
inkscape:vp_z="1 : 0.5 : 1"
|
||||
inkscape:vp_y="0 : 1000 : 0"
|
||||
inkscape:vp_x="0 : 0.5 : 1"
|
||||
sodipodi:type="inkscape:persp3d" />
|
||||
<inkscape:perspective
|
||||
id="perspective3347"
|
||||
inkscape:persp3d-origin="0.5 : 0.33333333 : 1"
|
||||
inkscape:vp_z="1 : 0.5 : 1"
|
||||
inkscape:vp_y="0 : 1000 : 0"
|
||||
inkscape:vp_x="0 : 0.5 : 1"
|
||||
sodipodi:type="inkscape:persp3d" />
|
||||
<inkscape:perspective
|
||||
id="perspective5659"
|
||||
inkscape:persp3d-origin="0.5 : 0.33333333 : 1"
|
||||
inkscape:vp_z="1 : 0.5 : 1"
|
||||
inkscape:vp_y="0 : 1000 : 0"
|
||||
inkscape:vp_x="0 : 0.5 : 1"
|
||||
sodipodi:type="inkscape:persp3d" />
|
||||
<inkscape:perspective
|
||||
id="perspective5719"
|
||||
inkscape:persp3d-origin="0.5 : 0.33333333 : 1"
|
||||
inkscape:vp_z="1 : 0.5 : 1"
|
||||
inkscape:vp_y="0 : 1000 : 0"
|
||||
inkscape:vp_x="0 : 0.5 : 1"
|
||||
sodipodi:type="inkscape:persp3d" />
|
||||
<inkscape:perspective
|
||||
id="perspective5810"
|
||||
inkscape:persp3d-origin="0.5 : 0.33333333 : 1"
|
||||
inkscape:vp_z="1 : 0.5 : 1"
|
||||
inkscape:vp_y="0 : 1000 : 0"
|
||||
inkscape:vp_x="0 : 0.5 : 1"
|
||||
sodipodi:type="inkscape:persp3d" />
|
||||
<inkscape:perspective
|
||||
id="perspective3546"
|
||||
inkscape:persp3d-origin="0.5 : 0.33333333 : 1"
|
||||
inkscape:vp_z="1 : 0.5 : 1"
|
||||
inkscape:vp_y="0 : 1000 : 0"
|
||||
inkscape:vp_x="0 : 0.5 : 1"
|
||||
sodipodi:type="inkscape:persp3d" />
|
||||
<inkscape:perspective
|
||||
id="perspective4328"
|
||||
inkscape:persp3d-origin="0.5 : 0.33333333 : 1"
|
||||
inkscape:vp_z="1 : 0.5 : 1"
|
||||
inkscape:vp_y="0 : 1000 : 0"
|
||||
inkscape:vp_x="0 : 0.5 : 1"
|
||||
sodipodi:type="inkscape:persp3d" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient8928"
|
||||
id="linearGradient5318"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="matrix(2.2532936,0,0,2.206809,446.89077,-285.33499)"
|
||||
x1="-29.837337"
|
||||
y1="285.0596"
|
||||
x2="-29.837337"
|
||||
y2="342.60553" />
|
||||
<linearGradient
|
||||
id="linearGradient8928">
|
||||
<stop
|
||||
style="stop-color:#ffffff;stop-opacity:0.89156628;"
|
||||
offset="0"
|
||||
id="stop8930" />
|
||||
<stop
|
||||
style="stop-color:#ffffff;stop-opacity:0;"
|
||||
offset="1"
|
||||
id="stop8932" />
|
||||
</linearGradient>
|
||||
<inkscape:perspective
|
||||
id="perspective4367"
|
||||
inkscape:persp3d-origin="0.5 : 0.33333333 : 1"
|
||||
inkscape:vp_z="1 : 0.5 : 1"
|
||||
inkscape:vp_y="0 : 1000 : 0"
|
||||
inkscape:vp_x="0 : 0.5 : 1"
|
||||
sodipodi:type="inkscape:persp3d" />
|
||||
<inkscape:perspective
|
||||
id="perspective4402"
|
||||
inkscape:persp3d-origin="0.5 : 0.33333333 : 1"
|
||||
inkscape:vp_z="1 : 0.5 : 1"
|
||||
inkscape:vp_y="0 : 1000 : 0"
|
||||
inkscape:vp_x="0 : 0.5 : 1"
|
||||
sodipodi:type="inkscape:persp3d" />
|
||||
<inkscape:perspective
|
||||
id="perspective2940"
|
||||
inkscape:persp3d-origin="0.5 : 0.33333333 : 1"
|
||||
inkscape:vp_z="1 : 0.5 : 1"
|
||||
inkscape:vp_y="0 : 1000 : 0"
|
||||
inkscape:vp_x="0 : 0.5 : 1"
|
||||
sodipodi:type="inkscape:persp3d" />
|
||||
<inkscape:perspective
|
||||
id="perspective2864"
|
||||
inkscape:persp3d-origin="0.5 : 0.33333333 : 1"
|
||||
inkscape:vp_z="1 : 0.5 : 1"
|
||||
inkscape:vp_y="0 : 1000 : 0"
|
||||
inkscape:vp_x="0 : 0.5 : 1"
|
||||
sodipodi:type="inkscape:persp3d" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5096"
|
||||
id="linearGradient5102"
|
||||
x1="117.41457"
|
||||
y1="168.83261"
|
||||
x2="87.074203"
|
||||
y2="168.83261"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="matrix(0,0.99999995,-0.99999975,0,-11.23354,-270.8763)" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5106"
|
||||
id="linearGradient5112"
|
||||
x1="117.57944"
|
||||
y1="173.46591"
|
||||
x2="86.644958"
|
||||
y2="173.46591"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="matrix(0,0.99999997,-1,0,-11.23354,-270.8763)" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5116"
|
||||
id="linearGradient5122"
|
||||
x1="117.77806"
|
||||
y1="168.82289"
|
||||
x2="86.547356"
|
||||
y2="168.82289"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="matrix(0,1,-1,0,-11.23354,-270.8763)" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5129"
|
||||
id="linearGradient5135"
|
||||
x1="-246.82069"
|
||||
y1="353.9455"
|
||||
x2="-246.82069"
|
||||
y2="408.26157"
|
||||
gradientUnits="userSpaceOnUse" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5129"
|
||||
id="linearGradient5144"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="-246.82069"
|
||||
y1="353.9455"
|
||||
x2="-246.82069"
|
||||
y2="408.26157" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5151"
|
||||
id="linearGradient5149"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="-246.82069"
|
||||
y1="353.9455"
|
||||
x2="-246.82069"
|
||||
y2="408.26157" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5151"
|
||||
id="linearGradient5164"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="-246.82069"
|
||||
y1="353.9455"
|
||||
x2="-246.82069"
|
||||
y2="408.26157" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5151"
|
||||
id="linearGradient5169"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="-246.82069"
|
||||
y1="353.9455"
|
||||
x2="-246.82069"
|
||||
y2="408.26157" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5151"
|
||||
id="linearGradient5176"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="-246.82069"
|
||||
y1="353.9455"
|
||||
x2="-246.82069"
|
||||
y2="408.26157" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5151"
|
||||
id="linearGradient5181"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="-246.82069"
|
||||
y1="353.9455"
|
||||
x2="-246.82069"
|
||||
y2="408.26157" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5151"
|
||||
id="linearGradient5188"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="-246.82069"
|
||||
y1="353.9455"
|
||||
x2="-246.82069"
|
||||
y2="408.26157" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5151"
|
||||
id="linearGradient5193"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="-246.82069"
|
||||
y1="353.9455"
|
||||
x2="-246.82069"
|
||||
y2="408.26157" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5151"
|
||||
id="linearGradient5200"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="-246.82069"
|
||||
y1="353.9455"
|
||||
x2="-246.82069"
|
||||
y2="408.26157" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5151"
|
||||
id="linearGradient5205"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="-246.82069"
|
||||
y1="353.9455"
|
||||
x2="-246.82069"
|
||||
y2="408.26157" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5151"
|
||||
id="linearGradient5212"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="-246.82069"
|
||||
y1="353.9455"
|
||||
x2="-246.82069"
|
||||
y2="408.26157" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5219"
|
||||
id="linearGradient5217"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="-246.82069"
|
||||
y1="353.9455"
|
||||
x2="-247.44464"
|
||||
y2="412.00528" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5236"
|
||||
id="linearGradient5242"
|
||||
x1="3.7395172"
|
||||
y1="59.899364"
|
||||
x2="42.432911"
|
||||
y2="59.899364"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="translate(129.62194,-129.52019)" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5248"
|
||||
id="linearGradient5254"
|
||||
x1="-172.83463"
|
||||
y1="74.562233"
|
||||
x2="-137.26938"
|
||||
y2="74.562233"
|
||||
gradientUnits="userSpaceOnUse" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5271"
|
||||
id="linearGradient5285"
|
||||
x1="-172.83463"
|
||||
y1="74.562233"
|
||||
x2="-137.26938"
|
||||
y2="74.562233"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="matrix(1,0,0,0.58333333,-2.7039997e-8,32.705471)" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5219"
|
||||
id="linearGradient5287"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="-246.82069"
|
||||
y1="353.9455"
|
||||
x2="-247.44464"
|
||||
y2="412.00528" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5219"
|
||||
id="linearGradient5292"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="-246.82069"
|
||||
y1="353.9455"
|
||||
x2="-247.44464"
|
||||
y2="412.00528" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5219"
|
||||
id="linearGradient5299"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="-246.82069"
|
||||
y1="353.9455"
|
||||
x2="-247.44464"
|
||||
y2="412.00528" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5306"
|
||||
id="linearGradient5304"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="-246.82069"
|
||||
y1="353.9455"
|
||||
x2="-247.44464"
|
||||
y2="412.00528" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5306"
|
||||
id="linearGradient5319"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="-246.82069"
|
||||
y1="353.9455"
|
||||
x2="-247.44464"
|
||||
y2="412.00528" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5326"
|
||||
id="linearGradient5324"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="-246.82069"
|
||||
y1="353.9455"
|
||||
x2="-247.44464"
|
||||
y2="412.00528" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5326"
|
||||
id="linearGradient5339"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="-246.82069"
|
||||
y1="353.9455"
|
||||
x2="-247.44464"
|
||||
y2="412.00528" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient5375"
|
||||
id="linearGradient5381"
|
||||
x1="-172.83463"
|
||||
y1="74.562233"
|
||||
x2="-137.26938"
|
||||
y2="74.562233"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="translate(128.37404,-129.52019)" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient3903"
|
||||
id="linearGradient3899"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="matrix(0,-0.99999988,1.7142859,0,35.373449,-317.43383)"
|
||||
x1="-150.75359"
|
||||
y1="68.860146"
|
||||
x2="-150.75359"
|
||||
y2="87.776077" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient4317"
|
||||
id="linearGradient4337"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="-384.0242"
|
||||
y1="-558.1579"
|
||||
x2="-384.0242"
|
||||
y2="-510.8558" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient4215"
|
||||
id="linearGradient4340"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="matrix(0,0.99999998,-0.99999991,0,-11.233538,-270.87634)"
|
||||
x1="-235.30438"
|
||||
y1="369.2117"
|
||||
x2="-299.45587"
|
||||
y2="369.2117" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient4215"
|
||||
id="linearGradient4349"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="matrix(0,0.99999998,-0.99999991,0,-11.233538,-270.87634)"
|
||||
x1="-235.30438"
|
||||
y1="369.2117"
|
||||
x2="-299.45587"
|
||||
y2="369.2117" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient4317"
|
||||
id="linearGradient4351"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="-384.0242"
|
||||
y1="-558.1579"
|
||||
x2="-384.0242"
|
||||
y2="-510.8558" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient4361"
|
||||
id="linearGradient4355"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="-384.0242"
|
||||
y1="-558.1579"
|
||||
x2="-383.71014"
|
||||
y2="-510.8558" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient4215"
|
||||
id="linearGradient4358"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="matrix(0,0.99999998,-0.99999991,0,-11.233538,-270.87634)"
|
||||
x1="-235.30438"
|
||||
y1="369.2117"
|
||||
x2="-299.45587"
|
||||
y2="369.2117" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient4215"
|
||||
id="linearGradient4375"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="matrix(0,0.99999998,-0.99999991,0,-11.233538,-270.87634)"
|
||||
x1="-235.30438"
|
||||
y1="369.2117"
|
||||
x2="-299.45587"
|
||||
y2="369.2117" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient4361"
|
||||
id="linearGradient4377"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="-384.0242"
|
||||
y1="-558.1579"
|
||||
x2="-383.71014"
|
||||
y2="-510.8558" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient4387"
|
||||
id="linearGradient4381"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="-383.39609"
|
||||
y1="-561.92657"
|
||||
x2="-383.71014"
|
||||
y2="-510.8558" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient4215"
|
||||
id="linearGradient4384"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="matrix(0,0.99999998,-0.99999991,0,-11.233538,-270.87634)"
|
||||
x1="-235.30438"
|
||||
y1="369.2117"
|
||||
x2="-299.45587"
|
||||
y2="369.2117" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient4215"
|
||||
id="linearGradient4401"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="matrix(0,0.99999998,-0.99999991,0,-11.233536,-270.87635)"
|
||||
x1="-235.30438"
|
||||
y1="369.2117"
|
||||
x2="-299.45587"
|
||||
y2="369.2117" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient4387"
|
||||
id="linearGradient4403"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
x1="-383.39609"
|
||||
y1="-561.92657"
|
||||
x2="-383.71014"
|
||||
y2="-510.8558"
|
||||
gradientTransform="translate(2.3925782e-6,-1.3232422e-5)" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient4387"
|
||||
id="linearGradient4407"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="translate(2.3925782e-6,-1.3232422e-5)"
|
||||
x1="-383.39609"
|
||||
y1="-561.92657"
|
||||
x2="-383.71014"
|
||||
y2="-510.8558" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient4413"
|
||||
id="linearGradient4410"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="matrix(0,0.99999998,-0.99999991,0,-11.233536,-270.87635)"
|
||||
x1="-235.30438"
|
||||
y1="369.2117"
|
||||
x2="-299.45587"
|
||||
y2="369.2117" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient4413"
|
||||
id="linearGradient4427"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="matrix(0,0.99999998,-0.99999991,0,-11.233536,-270.87635)"
|
||||
x1="-235.30438"
|
||||
y1="369.2117"
|
||||
x2="-299.45587"
|
||||
y2="369.2117" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient4387"
|
||||
id="linearGradient4429"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="translate(2.3925782e-6,-1.3232422e-5)"
|
||||
x1="-383.39609"
|
||||
y1="-561.92657"
|
||||
x2="-383.71014"
|
||||
y2="-510.8558" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient4387"
|
||||
id="linearGradient4433"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="translate(2.3925782e-6,-1.3232422e-5)"
|
||||
x1="-383.39609"
|
||||
y1="-561.92657"
|
||||
x2="-383.71014"
|
||||
y2="-510.8558" />
|
||||
<linearGradient
|
||||
inkscape:collect="always"
|
||||
xlink:href="#linearGradient4439"
|
||||
id="linearGradient4436"
|
||||
gradientUnits="userSpaceOnUse"
|
||||
gradientTransform="matrix(0,0.99999998,-0.99999991,0,-11.233536,-270.87635)"
|
||||
x1="-235.30438"
|
||||
y1="369.2117"
|
||||
x2="-299.45587"
|
||||
y2="369.2117" />
|
||||
</defs>
|
||||
<sodipodi:namedview
|
||||
id="base"
|
||||
pagecolor="#ffffff"
|
||||
bordercolor="#666666"
|
||||
borderopacity="1.0"
|
||||
inkscape:pageopacity="0.0"
|
||||
inkscape:pageshadow="2"
|
||||
inkscape:zoom="3.1841238"
|
||||
inkscape:cx="140.38399"
|
||||
inkscape:cy="35.455778"
|
||||
inkscape:document-units="px"
|
||||
inkscape:current-layer="layer5"
|
||||
showgrid="false"
|
||||
inkscape:window-width="1366"
|
||||
inkscape:window-height="706"
|
||||
inkscape:window-x="-8"
|
||||
inkscape:window-y="-8"
|
||||
inkscape:window-maximized="1"
|
||||
inkscape:object-paths="true"
|
||||
showguides="true"
|
||||
inkscape:guide-bbox="true"
|
||||
inkscape:snap-to-guides="false"
|
||||
inkscape:snap-grids="false"
|
||||
inkscape:snap-global="false"
|
||||
fit-margin-top="0"
|
||||
fit-margin-left="0"
|
||||
fit-margin-right="0"
|
||||
fit-margin-bottom="0" />
|
||||
<metadata
|
||||
id="metadata10073">
|
||||
<rdf:RDF>
|
||||
<cc:Work
|
||||
rdf:about="">
|
||||
<dc:format>image/svg+xml</dc:format>
|
||||
<dc:type
|
||||
rdf:resource="http://purl.org/dc/dcmitype/StillImage" />
|
||||
<dc:title></dc:title>
|
||||
<dc:creator>
|
||||
<cc:Agent>
|
||||
<dc:title>Edouard Lafargue</dc:title>
|
||||
</cc:Agent>
|
||||
</dc:creator>
|
||||
</cc:Work>
|
||||
</rdf:RDF>
|
||||
</metadata>
|
||||
<g
|
||||
style="display:inline"
|
||||
inkscape:label="Dark background"
|
||||
id="g2932"
|
||||
inkscape:groupmode="layer"
|
||||
transform="translate(-368.2988,-507.08981)"
|
||||
sodipodi:insensitive="true">
|
||||
<g
|
||||
id="background"
|
||||
inkscape:label="#g4447">
|
||||
<rect
|
||||
inkscape:export-ydpi="88.809998"
|
||||
inkscape:export-xdpi="88.809998"
|
||||
inkscape:export-filename="H:\Documents\Hobbies\W433\g9905.png"
|
||||
ry="4.5346842"
|
||||
y="-577.68732"
|
||||
x="-616.67365"
|
||||
height="61.448738"
|
||||
width="226.5451"
|
||||
id="rect3145"
|
||||
style="fill:none;stroke:none"
|
||||
transform="scale(-1,-1)" />
|
||||
<rect
|
||||
transform="scale(-1,-1)"
|
||||
style="fill:url(#linearGradient4436);fill-opacity:1;stroke:none"
|
||||
id="rect2936"
|
||||
width="280.76797"
|
||||
height="53.465179"
|
||||
x="-649.06677"
|
||||
y="-560.55499"
|
||||
ry="3.9455285"
|
||||
inkscape:export-filename="H:\Documents\Hobbies\W433\g9905.png"
|
||||
inkscape:export-xdpi="88.809998"
|
||||
inkscape:export-ydpi="88.809998" />
|
||||
<rect
|
||||
transform="scale(-1,-1)"
|
||||
inkscape:label="#rect4388"
|
||||
inkscape:export-ydpi="88.809998"
|
||||
inkscape:export-xdpi="88.809998"
|
||||
inkscape:export-filename="H:\Documents\Hobbies\W433\g9905.png"
|
||||
ry="2.9134333"
|
||||
y="-554.10626"
|
||||
x="-642.96082"
|
||||
height="39.479435"
|
||||
width="267.02957"
|
||||
id="bargraph-outer"
|
||||
style="fill:url(#linearGradient4433);fill-opacity:1;stroke:none" />
|
||||
<rect
|
||||
transform="scale(-1,-1)"
|
||||
style="fill:#000000;fill-opacity:1;stroke:none"
|
||||
id="bargraph"
|
||||
width="262.18338"
|
||||
height="32.956219"
|
||||
x="-640.57104"
|
||||
y="-550.64001"
|
||||
ry="2.432044"
|
||||
inkscape:export-filename="H:\Documents\Hobbies\W433\g9905.png"
|
||||
inkscape:export-xdpi="88.809998"
|
||||
inkscape:export-ydpi="88.809998"
|
||||
inkscape:label="#rect4388" />
|
||||
</g>
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer5"
|
||||
inkscape:label="Green Zone"
|
||||
style="display:inline"
|
||||
transform="translate(-140.85549,-141.35611)"
|
||||
sodipodi:insensitive="true">
|
||||
<rect
|
||||
inkscape:label="#rect5741"
|
||||
style="fill:url(#linearGradient5112);fill-opacity:1;stroke:none;display:inline"
|
||||
id="green"
|
||||
width="260.53882"
|
||||
height="32.20755"
|
||||
x="-411.77084"
|
||||
y="-184.00433"
|
||||
ry="2.3767958"
|
||||
inkscape:export-filename="H:\Documents\Hobbies\W433\g9905.png"
|
||||
inkscape:export-xdpi="88.809998"
|
||||
inkscape:export-ydpi="88.809998"
|
||||
transform="scale(-1,-1)" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer4"
|
||||
inkscape:label="Yellow Zone"
|
||||
style="display:none"
|
||||
transform="translate(-140.85549,-141.35611)"
|
||||
sodipodi:insensitive="true">
|
||||
<rect
|
||||
inkscape:export-ydpi="88.809998"
|
||||
inkscape:export-xdpi="88.809998"
|
||||
inkscape:export-filename="H:\Documents\Hobbies\W433\g9905.png"
|
||||
ry="2.4231479"
|
||||
y="-184.63248"
|
||||
x="-411.45679"
|
||||
height="32.835663"
|
||||
width="260.53882"
|
||||
id="yellow"
|
||||
style="fill:url(#linearGradient5122);fill-opacity:1;stroke:none;display:inline"
|
||||
inkscape:label="#rect5741"
|
||||
transform="scale(-1,-1)" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer3"
|
||||
inkscape:label="Red zone"
|
||||
style="display:none"
|
||||
transform="translate(-140.85549,-141.35611)"
|
||||
sodipodi:insensitive="true">
|
||||
<rect
|
||||
inkscape:label="#rect5741"
|
||||
style="fill:url(#linearGradient5102);fill-opacity:1;stroke:none;display:inline"
|
||||
id="red"
|
||||
width="260.23901"
|
||||
height="32.519711"
|
||||
x="-411.38739"
|
||||
y="-184.35484"
|
||||
ry="2.399832"
|
||||
inkscape:export-filename="H:\Documents\Hobbies\W433\g9905.png"
|
||||
inkscape:export-xdpi="88.809998"
|
||||
inkscape:export-ydpi="88.809998"
|
||||
transform="scale(-1,-1)" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer6"
|
||||
inkscape:label="Indicator"
|
||||
style="display:inline"
|
||||
transform="translate(-140.85549,-141.35611)"
|
||||
sodipodi:insensitive="true">
|
||||
<rect
|
||||
style="fill:url(#linearGradient3899);fill-opacity:1;stroke:#000000;stroke-width:0.2964696;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="needle"
|
||||
width="32.035065"
|
||||
height="6.0045304"
|
||||
x="152.63882"
|
||||
y="-157.12926"
|
||||
inkscape:label="#rect5246"
|
||||
transform="matrix(0,1,-1,0,0,0)" />
|
||||
</g>
|
||||
<g
|
||||
inkscape:groupmode="layer"
|
||||
id="layer1"
|
||||
inkscape:label="Text"
|
||||
style="display:inline"
|
||||
transform="translate(-140.85549,-141.35611)"
|
||||
sodipodi:insensitive="true">
|
||||
<rect
|
||||
style="fill:#ffffff;fill-opacity:1;stroke:none"
|
||||
id="field"
|
||||
width="50.321022"
|
||||
height="13.236827"
|
||||
x="-201.80493"
|
||||
y="-209.93616"
|
||||
inkscape:label="#rect2878"
|
||||
transform="scale(-1,-1)" />
|
||||
<rect
|
||||
inkscape:label="#rect2878"
|
||||
y="-209.5061"
|
||||
x="-405.05276"
|
||||
height="13.236827"
|
||||
width="51.71294"
|
||||
id="value"
|
||||
style="fill:#ffffff;fill-opacity:1;stroke:none"
|
||||
transform="scale(-1,-1)" />
|
||||
</g>
|
||||
</svg>
|
After Width: | Height: | Size: 39 KiB |
@ -30,7 +30,7 @@
|
||||
style="stop-color:#000000;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#ffffff;stop-opacity:1"
|
||||
offset="0.32793573"
|
||||
offset="0.39386007"
|
||||
id="stop3907" />
|
||||
<stop
|
||||
id="stop3909"
|
||||
@ -222,7 +222,7 @@
|
||||
<stop
|
||||
id="stop5124"
|
||||
offset="0.37640449"
|
||||
style="stop-color:#ffff00;stop-opacity:1" />
|
||||
style="stop-color:#dcaf28;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#000000;stop-opacity:1"
|
||||
offset="1"
|
||||
@ -236,8 +236,8 @@
|
||||
id="stop5108" />
|
||||
<stop
|
||||
id="stop5114"
|
||||
offset="0.33917606"
|
||||
style="stop-color:#00ff00;stop-opacity:1" />
|
||||
offset="0.38184431"
|
||||
style="stop-color:#00a000;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#000000;stop-opacity:1"
|
||||
offset="1"
|
||||
@ -252,7 +252,7 @@
|
||||
<stop
|
||||
id="stop5104"
|
||||
offset="0.39717463"
|
||||
style="stop-color:#ff2a2a;stop-opacity:1" />
|
||||
style="stop-color:#aa0000;stop-opacity:1" />
|
||||
<stop
|
||||
style="stop-color:#0c0000;stop-opacity:1"
|
||||
offset="1"
|
||||
@ -740,9 +740,9 @@
|
||||
borderopacity="1.0"
|
||||
inkscape:pageopacity="0.0"
|
||||
inkscape:pageshadow="2"
|
||||
inkscape:zoom="7.9373969"
|
||||
inkscape:cx="10.296503"
|
||||
inkscape:cy="298.23206"
|
||||
inkscape:zoom="1.9843492"
|
||||
inkscape:cx="13.888309"
|
||||
inkscape:cy="302.67927"
|
||||
inkscape:document-units="px"
|
||||
inkscape:current-layer="layer6"
|
||||
showgrid="false"
|
||||
@ -849,7 +849,7 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer4"
|
||||
inkscape:label="Yellow Zone"
|
||||
style="display:inline"
|
||||
style="display:none"
|
||||
transform="translate(-129.62194,129.52019)"
|
||||
sodipodi:insensitive="true">
|
||||
<rect
|
||||
@ -891,11 +891,10 @@
|
||||
inkscape:groupmode="layer"
|
||||
id="layer6"
|
||||
inkscape:label="Indicator"
|
||||
style="display:none"
|
||||
transform="translate(-129.62194,129.52019)"
|
||||
sodipodi:insensitive="true">
|
||||
style="display:inline"
|
||||
transform="translate(-129.62194,129.52019)">
|
||||
<rect
|
||||
style="fill:url(#linearGradient3899);fill-opacity:1;stroke:#000000;stroke-width:0.30000001;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
style="fill:url(#linearGradient3899);fill-opacity:1;stroke:#000000;stroke-width:0.30000000999999998;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none"
|
||||
id="needle"
|
||||
width="33.162418"
|
||||
height="5.9393759"
|
||||
|
Before Width: | Height: | Size: 28 KiB After Width: | Height: | Size: 28 KiB |
35
artwork/GCS Icons/dialog-warning.svg
Normal file
@ -0,0 +1,35 @@
|
||||
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||
<!-- Created with Inkscape (http://www.inkscape.org/) -->
|
||||
<svg id="svg3247" xmlns="http://www.w3.org/2000/svg" height="48" width="48" version="1.0" xmlns:xlink="http://www.w3.org/1999/xlink">
|
||||
<defs id="defs3249">
|
||||
<linearGradient id="linearGradient2411" y2="5.4676" gradientUnits="userSpaceOnUse" x2="63.397" gradientTransform="matrix(2.1154 0 0 2.1153 -107.58 32.427)" y1="-12.489" x1="63.397">
|
||||
<stop id="stop4875" style="stop-color:#fff" offset="0"/>
|
||||
<stop id="stop4877" style="stop-color:#fff;stop-opacity:0" offset="1"/>
|
||||
</linearGradient>
|
||||
<linearGradient id="linearGradient2416" y2="3.0816" gradientUnits="userSpaceOnUse" x2="18.379" gradientTransform="matrix(.95844 0 0 .95844 .99752 1.9975)" y1="44.98" x1="18.379">
|
||||
<stop id="stop2492" style="stop-color:#791235" offset="0"/>
|
||||
<stop id="stop2494" style="stop-color:#dd3b27" offset="1"/>
|
||||
</linearGradient>
|
||||
<radialGradient id="radialGradient2414" gradientUnits="userSpaceOnUse" cy="3.99" cx="23.896" gradientTransform="matrix(0 2.2875 -3.0194 0 36.047 -50.63)" r="20.397">
|
||||
<stop id="stop3244" style="stop-color:#f8b17e" offset="0"/>
|
||||
<stop id="stop3246" style="stop-color:#e35d4f" offset=".26238"/>
|
||||
<stop id="stop3248" style="stop-color:#c6262e" offset=".66094"/>
|
||||
<stop id="stop3250" style="stop-color:#690b54" offset="1"/>
|
||||
</radialGradient>
|
||||
<radialGradient id="radialGradient2419" gradientUnits="userSpaceOnUse" cy="4.625" cx="62.625" gradientTransform="matrix(2.1647 0 0 .75294 -111.56 36.518)" r="10.625">
|
||||
<stop id="stop8840" offset="0"/>
|
||||
<stop id="stop8842" style="stop-opacity:0" offset="1"/>
|
||||
</radialGradient>
|
||||
</defs>
|
||||
<g id="layer1">
|
||||
<g id="g3275">
|
||||
<path id="path8836" style="opacity:.3;fill-rule:evenodd;fill:url(#radialGradient2419)" d="m47 40c0 4.418-10.297 8-23 8s-23-3.582-23-8 10.297-8 23-8 23 3.582 23 8z"/>
|
||||
<path id="path2555" style="stroke-linejoin:round;stroke:url(#linearGradient2416);stroke-linecap:round;stroke-width:1.0037;fill:url(#radialGradient2414)" d="m24 5.5018c-10.758 0-19.498 8.7402-19.498 19.498-0.0002 10.758 8.74 19.498 19.498 19.498s19.498-8.74 19.498-19.498-8.74-19.498-19.498-19.498z"/>
|
||||
<path id="path8655" style="opacity:.4;stroke:url(#linearGradient2411);fill:none" d="m42.5 24.999c0 10.218-8.283 18.501-18.5 18.501s-18.5-8.283-18.5-18.501c0-10.217 8.283-18.499 18.5-18.499s18.5 8.282 18.5 18.499z"/>
|
||||
</g>
|
||||
<g id="g3243" transform="translate(51.075 .56862)">
|
||||
<path id="path3295" style="opacity:.2" d="m-29.451 12.554c0.563 5.5 1.208 10.961 1.687 16.482h1.53c0.397-5.302 1.038-10.571 1.501-15.867 0.236-1.254-0.408-2.742-1.732-3.047-1.308-0.3824-2.77 0.565-2.944 1.918-0.029 0.17-0.042 0.342-0.042 0.514zm-0.167 22.359c-0.059 1.637 1.742 2.92 3.28 2.401 1.489-0.38 2.274-2.252 1.51-3.583-0.683-1.375-2.687-1.829-3.84-0.776-0.582 0.479-0.968 1.194-0.95 1.958z"/>
|
||||
<path id="text2315" style="fill:#fff" d="m-29.451 13.555c0.563 5.499 1.208 10.96 1.687 16.481h1.53c0.397-5.301 1.038-10.571 1.501-15.866 0.236-1.254-0.408-2.743-1.732-3.048-1.308-0.382-2.77 0.565-2.944 1.918-0.029 0.17-0.042 0.342-0.042 0.515zm-0.167 22.358c-0.059 1.637 1.742 2.921 3.28 2.402 1.489-0.381 2.274-2.253 1.51-3.584-0.683-1.375-2.687-1.828-3.84-0.776-0.582 0.479-0.968 1.194-0.95 1.958z"/>
|
||||
</g>
|
||||
</g>
|
||||
</svg>
|
After Width: | Height: | Size: 3.2 KiB |
@ -54,7 +54,7 @@ static const struct pios_spi_cfg pios_spi_op_cfg = {
|
||||
.ahb_clk = RCC_AHBPeriph_DMA1,
|
||||
|
||||
.irq = {
|
||||
.handler = PIOS_SPI_op_irq_handler,
|
||||
.handler = NULL,
|
||||
.flags =
|
||||
(DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 |
|
||||
DMA1_FLAG_GL4),
|
||||
@ -153,11 +153,11 @@ void PIOS_SPI_op_irq_handler(void)
|
||||
extern void PIOS_ADC_handler(void);
|
||||
void DMA1_Channel1_IRQHandler() __attribute__ ((alias("PIOS_ADC_handler")));
|
||||
// Remap the ADC DMA handler to this one
|
||||
const struct pios_adc_cfg pios_adc_cfg = {
|
||||
static const struct pios_adc_cfg pios_adc_cfg = {
|
||||
.dma = {
|
||||
.ahb_clk = RCC_AHBPeriph_DMA1,
|
||||
.irq = {
|
||||
.handler = PIOS_ADC_DMA_Handler,
|
||||
.handler = NULL,
|
||||
.flags = (DMA1_FLAG_TC1 | DMA1_FLAG_TE1 | DMA1_FLAG_HT1 | DMA1_FLAG_GL1),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA1_Channel1_IRQn,
|
||||
@ -205,17 +205,10 @@ void PIOS_ADC_handler() {
|
||||
/*
|
||||
* AUX USART
|
||||
*/
|
||||
void PIOS_USART_aux_irq_handler(void);
|
||||
void USART3_IRQHandler()
|
||||
__attribute__ ((alias("PIOS_USART_aux_irq_handler")));
|
||||
const struct pios_usart_cfg pios_usart_aux_cfg = {
|
||||
static const struct pios_usart_cfg pios_usart_aux_cfg = {
|
||||
.regs = USART3,
|
||||
.init = {
|
||||
#if defined (PIOS_USART_BAUDRATE)
|
||||
.USART_BaudRate = PIOS_USART_BAUDRATE,
|
||||
#else
|
||||
.USART_BaudRate = 57600,
|
||||
#endif
|
||||
.USART_BaudRate = 230400,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
@ -224,7 +217,7 @@ const struct pios_usart_cfg pios_usart_aux_cfg = {
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.handler = PIOS_USART_aux_irq_handler,
|
||||
.handler = NULL,
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART3_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
@ -250,12 +243,6 @@ const struct pios_usart_cfg pios_usart_aux_cfg = {
|
||||
},
|
||||
};
|
||||
|
||||
static uint32_t pios_usart_aux_id;
|
||||
void PIOS_USART_aux_irq_handler(void)
|
||||
{
|
||||
PIOS_USART_IRQ_Handler(pios_usart_aux_id);
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_USART */
|
||||
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
@ -279,7 +266,7 @@ void I2C1_EV_IRQHandler()
|
||||
void I2C1_ER_IRQHandler()
|
||||
__attribute__ ((alias("PIOS_I2C_main_adapter_er_irq_handler")));
|
||||
|
||||
const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = {
|
||||
static const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = {
|
||||
.regs = I2C1,
|
||||
.init = {
|
||||
.I2C_Mode = I2C_Mode_I2C,
|
||||
@ -307,7 +294,7 @@ const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = {
|
||||
},
|
||||
},
|
||||
.event = {
|
||||
.handler = PIOS_I2C_main_adapter_ev_irq_handler,
|
||||
.handler = NULL,
|
||||
.flags = 0, /* FIXME: check this */
|
||||
.init = {
|
||||
.NVIC_IRQChannel = I2C1_EV_IRQn,
|
||||
@ -317,7 +304,7 @@ const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = {
|
||||
},
|
||||
},
|
||||
.error = {
|
||||
.handler = PIOS_I2C_main_adapter_er_irq_handler,
|
||||
.handler = NULL,
|
||||
.flags = 0, /* FIXME: check this */
|
||||
.init = {
|
||||
.NVIC_IRQChannel = I2C1_ER_IRQn,
|
||||
@ -388,6 +375,7 @@ void PIOS_Board_Init(void) {
|
||||
/* Communication system */
|
||||
#if !defined(PIOS_ENABLE_DEBUG_PINS)
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
uint32_t pios_usart_aux_id;
|
||||
if (PIOS_USART_Init(&pios_usart_aux_id, &pios_usart_aux_cfg)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
|
@ -55,7 +55,7 @@ static const struct pios_spi_cfg
|
||||
.ahb_clk = RCC_AHBPeriph_DMA1,
|
||||
|
||||
.irq = {
|
||||
.handler = PIOS_SPI_op_irq_handler,
|
||||
.handler = NULL,
|
||||
.flags = (DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 | DMA1_FLAG_GL4),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA1_Channel4_IRQn,
|
||||
|
@ -60,7 +60,7 @@ const struct pios_spi_cfg
|
||||
.ahb_clk = RCC_AHBPeriph_DMA1,
|
||||
|
||||
.irq = {
|
||||
.handler = PIOS_SPI_ahrs_irq_handler,
|
||||
.handler = NULL,
|
||||
.flags = (DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 | DMA1_FLAG_GL4),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA1_Channel4_IRQn,
|
||||
@ -143,9 +143,9 @@ void PIOS_SPI_ahrs_irq_handler(void) {
|
||||
/*
|
||||
* 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 = {
|
||||
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
|
||||
@ -157,7 +157,7 @@ const struct pios_usart_cfg pios_usart_telem_cfg = { .regs = USART2, .init = {
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
}, .irq = {
|
||||
.handler = PIOS_USART_telem_irq_handler,
|
||||
.handler = NULL,
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART2_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
@ -180,11 +180,6 @@ const struct pios_usart_cfg pios_usart_telem_cfg = { .regs = USART2, .init = {
|
||||
},
|
||||
}, };
|
||||
|
||||
static uint32_t pios_usart_telem_rf_id;
|
||||
void PIOS_USART_telem_irq_handler(void) {
|
||||
PIOS_USART_IRQ_Handler(pios_usart_telem_rf_id);
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_USART */
|
||||
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
@ -218,6 +213,7 @@ void PIOS_Board_Init(void) {
|
||||
|
||||
/* Initialize the PiOS library */
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
uint32_t pios_usart_telem_rf_id;
|
||||
if (PIOS_USART_Init(&pios_usart_telem_rf_id, &pios_usart_telem_cfg)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
|
@ -48,7 +48,7 @@ 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_SPEKTRUM ?= NO
|
||||
USE_GPS ?= NO
|
||||
|
||||
USE_I2C ?= NO
|
||||
|
||||
@ -118,12 +118,9 @@ OPUAVSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight
|
||||
# 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)/coptercontrol.c
|
||||
@ -169,6 +166,7 @@ SRC += $(OPUAVSYNTHDIR)/mixersettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/firmwareiapobj.c
|
||||
SRC += $(OPUAVSYNTHDIR)/attitudesettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/camerastabsettings.c
|
||||
SRC += $(OPUAVSYNTHDIR)/hwsettings.c
|
||||
|
||||
ifeq ($(DIAGNOISTCS),YES)
|
||||
SRC += $(OPUAVSYNTHDIR)/taskinfo.c
|
||||
@ -195,6 +193,7 @@ SRC += $(PIOSSTM32F10X)/pios_spi.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_ppm.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_pwm.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_spektrum.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_sbus.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_debug.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_gpio.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_exti.c
|
||||
@ -217,6 +216,7 @@ SRC += $(PIOSCOMMON)/pios_com.c
|
||||
SRC += $(PIOSCOMMON)/pios_i2c_esc.c
|
||||
SRC += $(PIOSCOMMON)/pios_iap.c
|
||||
SRC += $(PIOSCOMMON)/pios_bl_helper.c
|
||||
SRC += $(PIOSCOMMON)/pios_rcvr.c
|
||||
SRC += $(PIOSCOMMON)/printf-stdarg.c
|
||||
## Libraries for flight calculations
|
||||
SRC += $(FLIGHTLIB)/fifo_buffer.c
|
||||
@ -389,15 +389,15 @@ endif
|
||||
ifeq ($(ERASE_FLASH), YES)
|
||||
CDEFS += -DERASE_FLASH
|
||||
endif
|
||||
ifeq ($(USE_SPEKTRUM), YES)
|
||||
CDEFS += -DUSE_SPEKTRUM
|
||||
|
||||
ifneq ($(USE_GPS), NO)
|
||||
CDEFS += -DUSE_GPS
|
||||
endif
|
||||
|
||||
ifeq ($(USE_I2C), YES)
|
||||
CDEFS += -DUSE_I2C
|
||||
endif
|
||||
|
||||
|
||||
# Place project-specific -D and/or -U options for
|
||||
# Assembler with preprocessor here.
|
||||
#ADEFS = -DUSE_IRQ_ASM_WRAPPER
|
||||
@ -501,7 +501,7 @@ LSTFILES = $(addprefix $(OUTDIR)/, $(addsuffix .lst, $(ALLSRCBASE)))
|
||||
DEPFILES = $(addprefix $(OUTDIR)/dep/, $(addsuffix .o.d, $(ALLSRCBASE)))
|
||||
|
||||
# Default target.
|
||||
all: gencode build
|
||||
all: build
|
||||
|
||||
ifeq ($(LOADFORMAT),ihex)
|
||||
build: elf hex lss sym
|
||||
@ -517,18 +517,6 @@ endif
|
||||
endif
|
||||
endif
|
||||
|
||||
# Generate intermediate code for objects
|
||||
gencode: ${OUTDIR}/InitMods.c
|
||||
|
||||
# Generate code for module initialization
|
||||
${OUTDIR}/InitMods.c: Makefile
|
||||
@echo $(MSG_MODINIT) $(call toprel, $@)
|
||||
@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) $(call toprel, $@)
|
||||
@ -635,4 +623,4 @@ else
|
||||
endif
|
||||
|
||||
# Listing of phony targets.
|
||||
.PHONY : all build clean clean_list gencode install
|
||||
.PHONY : all build clean clean_list install
|
||||
|
@ -42,18 +42,16 @@
|
||||
|
||||
/* Global Variables */
|
||||
|
||||
/* Prototype of generated InitModules() function */
|
||||
extern void InitModules(void);
|
||||
|
||||
/* Prototype of PIOS_Board_Init() function */
|
||||
extern void PIOS_Board_Init(void);
|
||||
extern void Stack_Change(void);
|
||||
|
||||
/**
|
||||
* OpenPilot Main function:
|
||||
*
|
||||
* Initialize PiOS<BR>
|
||||
* Create the "System" task (SystemModInitializein Modules/System/systemmod.c) <BR>
|
||||
* Start FreeRTOS Scheduler (vTaskStartScheduler)<BR>
|
||||
* Start FreeRTOS Scheduler (vTaskStartScheduler) (Now handled by caller)
|
||||
* If something goes wrong, blink LED1 and LED2 every 100ms
|
||||
*
|
||||
*/
|
||||
@ -65,43 +63,32 @@ int main()
|
||||
/* 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. */
|
||||
|
||||
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();
|
||||
|
||||
#ifdef ERASE_FLASH
|
||||
PIOS_Flash_W25X_EraseChip();
|
||||
while(TRUE){
|
||||
PIOS_LED_Toggle(LED1);
|
||||
PIOS_DELAY_WaitmS(50);
|
||||
};
|
||||
#endif
|
||||
|
||||
/* Initialize modules */
|
||||
InitModules();
|
||||
}
|
||||
MODULE_INITIALISE_ALL
|
||||
|
||||
/* swap the stack to use the IRQ stack */
|
||||
Stack_Change();
|
||||
|
||||
/* Start the FreeRTOS scheduler which should never returns.*/
|
||||
vTaskStartScheduler();
|
||||
|
||||
/* If all is well we will never reach here as the scheduler will now be running. */
|
||||
|
||||
/* Do some indication to user that something bad just happened */
|
||||
PIOS_LED_Off(LED1); \
|
||||
for(;;) { \
|
||||
PIOS_LED_Toggle(LED1); \
|
||||
PIOS_DELAY_WaitmS(100); \
|
||||
};
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @}
|
||||
|
@ -9,7 +9,7 @@
|
||||
* application requirements.
|
||||
*
|
||||
* THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE
|
||||
* FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE.
|
||||
* FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE.
|
||||
*
|
||||
* See http://www.freertos.org/a00110.html.
|
||||
*----------------------------------------------------------*/
|
||||
@ -29,8 +29,8 @@
|
||||
#define configCPU_CLOCK_HZ ( ( unsigned long ) 72000000 )
|
||||
#define configTICK_RATE_HZ ( ( portTickType ) 1000 )
|
||||
#define configMAX_PRIORITIES ( ( unsigned portBASE_TYPE ) 5 )
|
||||
#define configMINIMAL_STACK_SIZE ( ( unsigned short ) 128 )
|
||||
#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 14 * 1024 ) )
|
||||
#define configMINIMAL_STACK_SIZE ( ( unsigned short ) 48 )
|
||||
#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 54 * 256) )
|
||||
#define configMAX_TASK_NAME_LEN ( 16 )
|
||||
#define configUSE_TRACE_FACILITY 0
|
||||
#define configUSE_16_BIT_TICKS 0
|
||||
@ -70,6 +70,10 @@ configKERNEL_INTERRUPT_PRIORITY setting. Here 15 corresponds to the lowest
|
||||
NVIC value of 255. */
|
||||
#define configLIBRARY_KERNEL_INTERRUPT_PRIORITY 15
|
||||
|
||||
#if !defined(ARCH_POSIX) && !defined(ARCH_WIN32)
|
||||
#define CHECK_IRQ_STACK
|
||||
#endif
|
||||
|
||||
/* Enable run time stats collection */
|
||||
#if defined(DIAGNOSTICS)
|
||||
#define configCHECK_FOR_STACK_OVERFLOW 2
|
||||
@ -86,6 +90,7 @@ do {\
|
||||
#define configCHECK_FOR_STACK_OVERFLOW 1
|
||||
#endif
|
||||
|
||||
|
||||
/**
|
||||
* @}
|
||||
*/
|
||||
|
@ -1,107 +1,110 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @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
|
||||
#if defined(USE_I2C)
|
||||
#define PIOS_INCLUDE_I2C
|
||||
#define PIOS_INCLUDE_I2C_ESC
|
||||
#endif
|
||||
#define PIOS_INCLUDE_IRQ
|
||||
#define PIOS_INCLUDE_LED
|
||||
|
||||
#if defined(USE_SPEKTRUM)
|
||||
#define PIOS_INCLUDE_SPEKTRUM
|
||||
#else
|
||||
#define PIOS_INCLUDE_GPS
|
||||
//#define PIOS_INCLUDE_PPM
|
||||
#define PIOS_INCLUDE_PWM
|
||||
#endif
|
||||
|
||||
|
||||
#define PIOS_INCLUDE_SERVO
|
||||
#define PIOS_INCLUDE_SPI
|
||||
#define PIOS_INCLUDE_SYS
|
||||
#define PIOS_INCLUDE_USART
|
||||
#define PIOS_INCLUDE_USB_HID
|
||||
#define PIOS_INCLUDE_COM
|
||||
#define PIOS_INCLUDE_SETTINGS
|
||||
#define PIOS_INCLUDE_FREERTOS
|
||||
#define PIOS_INCLUDE_GPIO
|
||||
#define PIOS_INCLUDE_EXTI
|
||||
#define PIOS_INCLUDE_RTC
|
||||
#define PIOS_INCLUDE_WDG
|
||||
#define PIOS_INCLUDE_BL_HELPER
|
||||
|
||||
#define PIOS_INCLUDE_ADXL345
|
||||
#define PIOS_INCLUDE_FLASH
|
||||
|
||||
/* A really shitty setting saving implementation */
|
||||
#define PIOS_INCLUDE_FLASH_SECTOR_SETTINGS
|
||||
|
||||
/* 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
|
||||
|
||||
/* Alarm Thresholds */
|
||||
#define HEAP_LIMIT_WARNING 220
|
||||
#define HEAP_LIMIT_CRITICAL 150
|
||||
#define CPULOAD_LIMIT_WARNING 80
|
||||
#define CPULOAD_LIMIT_CRITICAL 95
|
||||
|
||||
/* Task stack sizes */
|
||||
#define PIOS_ACTUATOR_STACK_SIZE 1020
|
||||
#define PIOS_MANUAL_STACK_SIZE 724
|
||||
#define PIOS_SYSTEM_STACK_SIZE 560
|
||||
#define PIOS_STABILIZATION_STACK_SIZE 524
|
||||
#define PIOS_TELEM_STACK_SIZE 500
|
||||
|
||||
#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD 1995998
|
||||
//#define PIOS_QUATERNION_STABILIZATION
|
||||
|
||||
#endif /* PIOS_CONFIG_H */
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
||||
/**
|
||||
******************************************************************************
|
||||
* @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
|
||||
#if defined(USE_I2C)
|
||||
#define PIOS_INCLUDE_I2C
|
||||
#define PIOS_INCLUDE_I2C_ESC
|
||||
#endif
|
||||
#define PIOS_INCLUDE_IRQ
|
||||
#define PIOS_INCLUDE_LED
|
||||
|
||||
#define PIOS_INCLUDE_RCVR
|
||||
|
||||
/* Supported receiver interfaces */
|
||||
#define PIOS_INCLUDE_SPEKTRUM
|
||||
#define PIOS_INCLUDE_SBUS
|
||||
//#define PIOS_INCLUDE_PPM
|
||||
#define PIOS_INCLUDE_PWM
|
||||
|
||||
/* Supported USART-based PIOS modules */
|
||||
#define PIOS_INCLUDE_TELEMETRY_RF
|
||||
//#define PIOS_INCLUDE_GPS
|
||||
|
||||
#define PIOS_INCLUDE_SERVO
|
||||
#define PIOS_INCLUDE_SPI
|
||||
#define PIOS_INCLUDE_SYS
|
||||
#define PIOS_INCLUDE_USART
|
||||
#define PIOS_INCLUDE_USB_HID
|
||||
#define PIOS_INCLUDE_COM
|
||||
#define PIOS_INCLUDE_SETTINGS
|
||||
#define PIOS_INCLUDE_FREERTOS
|
||||
#define PIOS_INCLUDE_GPIO
|
||||
#define PIOS_INCLUDE_EXTI
|
||||
#define PIOS_INCLUDE_RTC
|
||||
#define PIOS_INCLUDE_WDG
|
||||
#define PIOS_INCLUDE_BL_HELPER
|
||||
|
||||
#define PIOS_INCLUDE_ADXL345
|
||||
#define PIOS_INCLUDE_FLASH
|
||||
|
||||
/* A really shitty setting saving implementation */
|
||||
#define PIOS_INCLUDE_FLASH_SECTOR_SETTINGS
|
||||
|
||||
/* 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
|
||||
|
||||
/* Alarm Thresholds */
|
||||
#define HEAP_LIMIT_WARNING 220
|
||||
#define HEAP_LIMIT_CRITICAL 40
|
||||
#define IRQSTACK_LIMIT_WARNING 100
|
||||
#define IRQSTACK_LIMIT_CRITICAL 60
|
||||
#define CPULOAD_LIMIT_WARNING 85
|
||||
#define CPULOAD_LIMIT_CRITICAL 95
|
||||
|
||||
/* Task stack sizes */
|
||||
#define PIOS_ACTUATOR_STACK_SIZE 1020
|
||||
#define PIOS_MANUAL_STACK_SIZE 724
|
||||
#define PIOS_SYSTEM_STACK_SIZE 460
|
||||
#define PIOS_STABILIZATION_STACK_SIZE 524
|
||||
#define PIOS_TELEM_STACK_SIZE 500
|
||||
#define PIOS_EVENTDISPATCHER_STACK_SIZE 96
|
||||
#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD 1995998
|
||||
//#define PIOS_QUATERNION_STABILIZATION
|
||||
|
||||
#endif /* PIOS_CONFIG_H */
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
||||
|
@ -30,10 +30,11 @@
|
||||
#include <pios.h>
|
||||
#include <openpilot.h>
|
||||
#include <uavobjectsinit.h>
|
||||
#include <hwsettings.h>
|
||||
#include <manualcontrolsettings.h>
|
||||
|
||||
#if defined(PIOS_INCLUDE_SPI)
|
||||
|
||||
|
||||
#include <pios_spi_priv.h>
|
||||
|
||||
/* Flash/Accel Interface
|
||||
@ -44,7 +45,7 @@
|
||||
void PIOS_SPI_flash_accel_irq_handler(void);
|
||||
void DMA1_Channel4_IRQHandler() __attribute__ ((alias ("PIOS_SPI_flash_accel_irq_handler")));
|
||||
void DMA1_Channel5_IRQHandler() __attribute__ ((alias ("PIOS_SPI_flash_accel_irq_handler")));
|
||||
const struct pios_spi_cfg pios_spi_flash_accel_cfg = {
|
||||
static const struct pios_spi_cfg pios_spi_flash_accel_cfg = {
|
||||
.regs = SPI2,
|
||||
.init = {
|
||||
.SPI_Mode = SPI_Mode_Master,
|
||||
@ -62,7 +63,7 @@ const struct pios_spi_cfg pios_spi_flash_accel_cfg = {
|
||||
.ahb_clk = RCC_AHBPeriph_DMA1,
|
||||
|
||||
.irq = {
|
||||
.handler = PIOS_SPI_flash_accel_irq_handler,
|
||||
.handler = NULL,
|
||||
.flags = (DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 | DMA1_FLAG_GL4),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA1_Channel4_IRQn,
|
||||
@ -151,11 +152,11 @@ void PIOS_SPI_flash_accel_irq_handler(void)
|
||||
extern void PIOS_ADC_handler(void);
|
||||
void DMA1_Channel1_IRQHandler() __attribute__ ((alias("PIOS_ADC_handler")));
|
||||
// Remap the ADC DMA handler to this one
|
||||
const struct pios_adc_cfg pios_adc_cfg = {
|
||||
static const struct pios_adc_cfg pios_adc_cfg = {
|
||||
.dma = {
|
||||
.ahb_clk = RCC_AHBPeriph_DMA1,
|
||||
.irq = {
|
||||
.handler = PIOS_ADC_DMA_Handler,
|
||||
.handler = NULL,
|
||||
.flags = (DMA1_FLAG_TC1 | DMA1_FLAG_TE1 | DMA1_FLAG_HT1 | DMA1_FLAG_GL1),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA1_Channel1_IRQn,
|
||||
@ -200,19 +201,14 @@ void PIOS_ADC_handler() {
|
||||
|
||||
#include "pios_usart_priv.h"
|
||||
|
||||
#if defined(PIOS_INCLUDE_TELEMETRY_RF)
|
||||
/*
|
||||
* Telemetry USART
|
||||
*/
|
||||
void PIOS_USART_telem_irq_handler(void);
|
||||
void USART1_IRQHandler() __attribute__ ((alias ("PIOS_USART_telem_irq_handler")));
|
||||
const struct pios_usart_cfg pios_usart_telem_cfg = {
|
||||
static const struct pios_usart_cfg pios_usart_telem_main_cfg = {
|
||||
.regs = USART1,
|
||||
.init = {
|
||||
#if defined (PIOS_COM_TELEM_BAUDRATE)
|
||||
.USART_BaudRate = PIOS_COM_TELEM_BAUDRATE,
|
||||
#else
|
||||
.USART_BaudRate = 57600,
|
||||
#endif
|
||||
.USART_BaudRate = 57600,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
@ -220,7 +216,7 @@ const struct pios_usart_cfg pios_usart_telem_cfg = {
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.handler = PIOS_USART_telem_irq_handler,
|
||||
.handler = NULL,
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART1_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
@ -246,20 +242,10 @@ const struct pios_usart_cfg pios_usart_telem_cfg = {
|
||||
},
|
||||
};
|
||||
|
||||
#if defined(PIOS_INCLUDE_GPS)
|
||||
/*
|
||||
* 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,
|
||||
static const struct pios_usart_cfg pios_usart_telem_flexi_cfg = {
|
||||
.regs = USART3,
|
||||
.init = {
|
||||
#if defined (PIOS_COM_GPS_BAUDRATE)
|
||||
.USART_BaudRate = PIOS_COM_GPS_BAUDRATE,
|
||||
#else
|
||||
.USART_BaudRate = 57600,
|
||||
#endif
|
||||
.USART_BaudRate = 57600,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
@ -267,7 +253,7 @@ const struct pios_usart_cfg pios_usart_gps_cfg = {
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.handler = PIOS_USART_gps_irq_handler,
|
||||
.handler = NULL,
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART3_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
@ -292,22 +278,97 @@ const struct pios_usart_cfg pios_usart_gps_cfg = {
|
||||
},
|
||||
},
|
||||
};
|
||||
#endif
|
||||
#endif /* PIOS_INCLUDE_TELEMETRY_RF */
|
||||
|
||||
#if defined(PIOS_INCLUDE_GPS)
|
||||
/*
|
||||
* GPS USART
|
||||
*/
|
||||
static const struct pios_usart_cfg pios_usart_gps_main_cfg = {
|
||||
.regs = USART1,
|
||||
.init = {
|
||||
.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 = NULL,
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART1_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.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_AF_PP,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_gps_flexi_cfg = {
|
||||
.regs = USART3,
|
||||
.init = {
|
||||
.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 = NULL,
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART3_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.rx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_IPU,
|
||||
},
|
||||
},
|
||||
.tx = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_AF_PP,
|
||||
},
|
||||
},
|
||||
};
|
||||
#endif /* PIOS_INCLUDE_GPS */
|
||||
|
||||
#if defined(PIOS_INCLUDE_SPEKTRUM)
|
||||
/*
|
||||
* SPEKTRUM USART
|
||||
*/
|
||||
void PIOS_USART_spektrum_irq_handler(void);
|
||||
void USART3_IRQHandler() __attribute__ ((alias ("PIOS_USART_spektrum_irq_handler")));
|
||||
const struct pios_usart_cfg pios_usart_spektrum_cfg = {
|
||||
.regs = USART3,
|
||||
#include <pios_spektrum_priv.h>
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_spektrum_main_cfg = {
|
||||
.regs = USART1,
|
||||
.init = {
|
||||
#if defined (PIOS_COM_SPEKTRUM_BAUDRATE)
|
||||
.USART_BaudRate = PIOS_COM_SPEKTRUM_BAUDRATE,
|
||||
#else
|
||||
.USART_BaudRate = 115200,
|
||||
#endif
|
||||
.USART_BaudRate = 115200,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
@ -315,7 +376,56 @@ const struct pios_usart_cfg pios_usart_spektrum_cfg = {
|
||||
.USART_Mode = USART_Mode_Rx,
|
||||
},
|
||||
.irq = {
|
||||
.handler = PIOS_USART_spektrum_irq_handler,
|
||||
.handler = PIOS_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,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
static const struct pios_spektrum_cfg pios_spektrum_main_cfg = {
|
||||
.bind = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
},
|
||||
},
|
||||
.remap = 0,
|
||||
};
|
||||
|
||||
static const struct pios_usart_cfg pios_usart_spektrum_flexi_cfg = {
|
||||
.regs = USART3,
|
||||
.init = {
|
||||
.USART_BaudRate = 115200,
|
||||
.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_SPEKTRUM_irq_handler,
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART3_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
@ -341,63 +451,81 @@ const struct pios_usart_cfg pios_usart_spektrum_cfg = {
|
||||
},
|
||||
};
|
||||
|
||||
static uint32_t pios_usart_spektrum_id;
|
||||
void PIOS_USART_spektrum_irq_handler(void)
|
||||
{
|
||||
SPEKTRUM_IRQHandler(pios_usart_spektrum_id);
|
||||
}
|
||||
|
||||
#include <pios_spektrum_priv.h>
|
||||
void RTC_IRQHandler();
|
||||
void RTC_IRQHandler() __attribute__ ((alias ("PIOS_SUPV_irq_handler")));
|
||||
const struct pios_spektrum_cfg pios_spektrum_cfg = {
|
||||
.pios_usart_spektrum_cfg = &pios_usart_spektrum_cfg,
|
||||
.gpio_init = { //used for bind feature
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
.remap = 0,
|
||||
.irq = {
|
||||
.handler = RTC_IRQHandler,
|
||||
.init = {
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
static const struct pios_spektrum_cfg pios_spektrum_flexi_cfg = {
|
||||
.bind = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_11,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
},
|
||||
},
|
||||
.port = GPIOB,
|
||||
.pin = GPIO_Pin_11,
|
||||
.remap = 0,
|
||||
};
|
||||
|
||||
void PIOS_SUPV_irq_handler() {
|
||||
if (RTC_GetITStatus(RTC_IT_SEC))
|
||||
{
|
||||
/* Call the right handler */
|
||||
PIOS_SPEKTRUM_irq_handler(pios_usart_spektrum_id);
|
||||
|
||||
/* Wait until last write operation on RTC registers has finished */
|
||||
RTC_WaitForLastTask();
|
||||
/* Clear the RTC Second interrupt */
|
||||
RTC_ClearITPendingBit(RTC_IT_SEC);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_SPEKTRUM */
|
||||
|
||||
static uint32_t pios_usart_telem_rf_id;
|
||||
void PIOS_USART_telem_irq_handler(void)
|
||||
{
|
||||
PIOS_USART_IRQ_Handler(pios_usart_telem_rf_id);
|
||||
}
|
||||
#if defined(PIOS_INCLUDE_SBUS)
|
||||
/*
|
||||
* SBUS USART
|
||||
*/
|
||||
#include <pios_sbus_priv.h>
|
||||
|
||||
#if defined(PIOS_INCLUDE_GPS)
|
||||
static uint32_t pios_usart_gps_id;
|
||||
void PIOS_USART_gps_irq_handler(void)
|
||||
{
|
||||
PIOS_USART_IRQ_Handler(pios_usart_gps_id);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_GPS */
|
||||
static const struct pios_usart_cfg pios_usart_sbus_main_cfg = {
|
||||
.regs = USART1,
|
||||
.init = {
|
||||
.USART_BaudRate = 100000,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_Even,
|
||||
.USART_StopBits = USART_StopBits_2,
|
||||
.USART_HardwareFlowControl = USART_HardwareFlowControl_None,
|
||||
.USART_Mode = USART_Mode_Rx,
|
||||
},
|
||||
.irq = {
|
||||
.handler = PIOS_SBUS_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 /* PIOS_INCLUDE_USART */
|
||||
static const struct pios_sbus_cfg pios_sbus_cfg = {
|
||||
/* Inverter configuration */
|
||||
.inv = {
|
||||
.gpio = GPIOB,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_2,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
},
|
||||
.gpio_clk_func = RCC_APB2PeriphClockCmd,
|
||||
.gpio_clk_periph = RCC_APB2Periph_GPIOB,
|
||||
.gpio_inv_enable = Bit_SET,
|
||||
};
|
||||
|
||||
#endif /* PIOS_INCLUDE_SBUS */
|
||||
|
||||
#endif /* PIOS_INCLUDE_USART */
|
||||
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
|
||||
@ -405,11 +533,40 @@ void PIOS_USART_gps_irq_handler(void)
|
||||
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
|
||||
#if defined(PIOS_INCLUDE_RTC)
|
||||
/*
|
||||
* Realtime Clock (RTC)
|
||||
*/
|
||||
#include <pios_rtc_priv.h>
|
||||
|
||||
void PIOS_RTC_IRQ_Handler (void);
|
||||
void RTC_IRQHandler() __attribute__ ((alias ("PIOS_RTC_IRQ_Handler")));
|
||||
static const struct pios_rtc_cfg pios_rtc_main_cfg = {
|
||||
.clksrc = RCC_RTCCLKSource_HSE_Div128,
|
||||
.prescaler = 100,
|
||||
.irq = {
|
||||
.handler = NULL,
|
||||
.init = {
|
||||
.NVIC_IRQChannel = RTC_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
void PIOS_RTC_IRQ_Handler (void)
|
||||
{
|
||||
PIOS_RTC_irq_handler ();
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
/*
|
||||
* Servo outputs
|
||||
*/
|
||||
#include <pios_servo_priv.h>
|
||||
const struct pios_servo_channel pios_servo_channels[] = {
|
||||
static const struct pios_servo_channel pios_servo_channels[] = {
|
||||
{
|
||||
.timer = TIM4,
|
||||
.port = GPIOB,
|
||||
@ -475,13 +632,65 @@ const struct pios_servo_cfg pios_servo_cfg = {
|
||||
.num_channels = NELEMENTS(pios_servo_channels),
|
||||
};
|
||||
|
||||
#if defined(PIOS_INCLUDE_PWM) && defined(PIOS_INCLUDE_PPM)
|
||||
#error Cannot define both PIOS_INCLUDE_PWM and PIOS_INCLUDE_PPM at the same time (yet)
|
||||
#endif
|
||||
|
||||
/*
|
||||
* PPM Inputs
|
||||
*/
|
||||
#if defined(PIOS_INCLUDE_PPM)
|
||||
#include <pios_ppm_priv.h>
|
||||
|
||||
void TIM4_IRQHandler();
|
||||
void TIM4_IRQHandler() __attribute__ ((alias ("PIOS_TIM4_irq_handler")));
|
||||
const struct pios_ppm_cfg pios_ppm_cfg = {
|
||||
.tim_base_init = {
|
||||
.TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1, /* For 1 uS accuracy */
|
||||
.TIM_ClockDivision = TIM_CKD_DIV1,
|
||||
.TIM_CounterMode = TIM_CounterMode_Up,
|
||||
.TIM_Period = 0xFFFF, /* shared timer, make sure init correctly in outputs */
|
||||
.TIM_RepetitionCounter = 0x0000,
|
||||
},
|
||||
.tim_ic_init = {
|
||||
.TIM_Channel = TIM_Channel_1,
|
||||
.TIM_ICPolarity = TIM_ICPolarity_Rising,
|
||||
.TIM_ICSelection = TIM_ICSelection_DirectTI,
|
||||
.TIM_ICPrescaler = TIM_ICPSC_DIV1,
|
||||
.TIM_ICFilter = 0x0,
|
||||
},
|
||||
.gpio_init = {
|
||||
.GPIO_Pin = GPIO_Pin_6,
|
||||
.GPIO_Mode = GPIO_Mode_IPD,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
.remap = 0,
|
||||
.irq = {
|
||||
.handler = TIM4_IRQHandler,
|
||||
.init = {
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
.timer = TIM4,
|
||||
.port = GPIOB,
|
||||
.ccr = TIM_IT_CC1,
|
||||
};
|
||||
|
||||
void PIOS_TIM4_irq_handler()
|
||||
{
|
||||
PIOS_PPM_irq_handler();
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_PPM */
|
||||
|
||||
/*
|
||||
* PWM Inputs
|
||||
*/
|
||||
#if defined(PIOS_INCLUDE_PWM)
|
||||
#include <pios_pwm_priv.h>
|
||||
const struct pios_pwm_channel pios_pwm_channels[] = {
|
||||
|
||||
static const struct pios_pwm_channel pios_pwm_channels[] = {
|
||||
{
|
||||
.timer = TIM4,
|
||||
.port = GPIOB,
|
||||
@ -552,7 +761,7 @@ const struct pios_pwm_cfg pios_pwm_cfg = {
|
||||
},
|
||||
.remap = 0,
|
||||
.irq = {
|
||||
.handler = TIM2_IRQHandler,
|
||||
.handler = NULL,
|
||||
.init = {
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
@ -589,7 +798,7 @@ 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 = {
|
||||
static const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = {
|
||||
.regs = I2C2,
|
||||
.init = {
|
||||
.I2C_Mode = I2C_Mode_I2C,
|
||||
@ -617,7 +826,7 @@ const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = {
|
||||
},
|
||||
},
|
||||
.event = {
|
||||
.handler = PIOS_I2C_main_adapter_ev_irq_handler,
|
||||
.handler = NULL,
|
||||
.flags = 0, /* FIXME: check this */
|
||||
.init = {
|
||||
.NVIC_IRQChannel = I2C2_EV_IRQn,
|
||||
@ -627,7 +836,7 @@ const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = {
|
||||
},
|
||||
},
|
||||
.error = {
|
||||
.handler = PIOS_I2C_main_adapter_er_irq_handler,
|
||||
.handler = NULL,
|
||||
.flags = 0, /* FIXME: check this */
|
||||
.init = {
|
||||
.NVIC_IRQChannel = I2C2_ER_IRQn,
|
||||
@ -653,12 +862,18 @@ void PIOS_I2C_main_adapter_er_irq_handler(void)
|
||||
|
||||
#endif /* PIOS_INCLUDE_I2C */
|
||||
|
||||
#if defined(PIOS_INCLUDE_RCVR)
|
||||
#include "pios_rcvr_priv.h"
|
||||
|
||||
struct pios_rcvr_channel_map pios_rcvr_channel_to_id_map[PIOS_RCVR_MAX_CHANNELS];
|
||||
uint32_t pios_rcvr_max_channel;
|
||||
#endif /* PIOS_INCLUDE_RCVR */
|
||||
|
||||
extern const struct pios_com_driver pios_usb_com_driver;
|
||||
|
||||
uint32_t pios_com_telem_rf_id;
|
||||
uint32_t pios_com_telem_usb_id;
|
||||
uint32_t pios_com_gps_id;
|
||||
uint32_t pios_com_spektrum_id;
|
||||
|
||||
/**
|
||||
* PIOS_Board_Init()
|
||||
@ -668,56 +883,227 @@ uint32_t pios_com_spektrum_id;
|
||||
void PIOS_Board_Init(void) {
|
||||
|
||||
/* Delay system */
|
||||
PIOS_DELAY_Init();
|
||||
|
||||
PIOS_DELAY_Init();
|
||||
|
||||
/* Set up the SPI interface to the serial flash */
|
||||
if (PIOS_SPI_Init(&pios_spi_flash_accel_id, &pios_spi_flash_accel_cfg)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
PIOS_Flash_W25X_Init(pios_spi_flash_accel_id);
|
||||
PIOS_ADXL345_Attach(pios_spi_flash_accel_id);
|
||||
|
||||
|
||||
PIOS_FLASHFS_Init();
|
||||
|
||||
#if defined(PIOS_INCLUDE_SPEKTRUM)
|
||||
/* SPEKTRUM init must come before comms */
|
||||
PIOS_SPEKTRUM_Init();
|
||||
|
||||
if (PIOS_USART_Init(&pios_usart_spektrum_id, &pios_usart_spektrum_cfg)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
if (PIOS_COM_Init(&pios_com_spektrum_id, &pios_usart_com_driver, pios_usart_spektrum_id)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
#endif
|
||||
/* Initialize UAVObject libraries */
|
||||
EventDispatcherInitialize();
|
||||
UAVObjInitialize();
|
||||
|
||||
#if defined(PIOS_INCLUDE_RTC)
|
||||
/* Initialize the real-time clock and its associated tick */
|
||||
PIOS_RTC_Init(&pios_rtc_main_cfg);
|
||||
#endif
|
||||
|
||||
/* Initialize the alarms library */
|
||||
AlarmsInitialize();
|
||||
|
||||
/* Initialize the task monitor library */
|
||||
TaskMonitorInitialize();
|
||||
|
||||
/* Initialize the PiOS library */
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
if (PIOS_USART_Init(&pios_usart_telem_rf_id, &pios_usart_telem_cfg)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_usart_com_driver, pios_usart_telem_rf_id)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
/* Configure the main IO port */
|
||||
uint8_t hwsettings_cc_mainport;
|
||||
HwSettingsCC_MainPortGet(&hwsettings_cc_mainport);
|
||||
|
||||
switch (hwsettings_cc_mainport) {
|
||||
case HWSETTINGS_CC_MAINPORT_DISABLED:
|
||||
break;
|
||||
case HWSETTINGS_CC_MAINPORT_TELEMETRY:
|
||||
#if defined(PIOS_INCLUDE_TELEMETRY_RF)
|
||||
{
|
||||
uint32_t pios_usart_telem_rf_id;
|
||||
if (PIOS_USART_Init(&pios_usart_telem_rf_id, &pios_usart_telem_main_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_usart_com_driver, pios_usart_telem_rf_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_TELEMETRY_RF */
|
||||
break;
|
||||
case HWSETTINGS_CC_MAINPORT_SBUS:
|
||||
#if defined(PIOS_INCLUDE_SBUS)
|
||||
{
|
||||
PIOS_SBUS_Init(&pios_sbus_cfg);
|
||||
|
||||
uint32_t pios_usart_sbus_id;
|
||||
if (PIOS_USART_Init(&pios_usart_sbus_id, &pios_usart_sbus_main_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_SBUS */
|
||||
break;
|
||||
case HWSETTINGS_CC_MAINPORT_GPS:
|
||||
#if defined(PIOS_INCLUDE_GPS)
|
||||
if (PIOS_USART_Init(&pios_usart_gps_id, &pios_usart_gps_cfg)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
if (PIOS_COM_Init(&pios_com_gps_id, &pios_usart_com_driver, pios_usart_gps_id)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
{
|
||||
uint32_t pios_usart_gps_id;
|
||||
if (PIOS_USART_Init(&pios_usart_gps_id, &pios_usart_gps_main_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
if (PIOS_COM_Init(&pios_com_gps_id, &pios_usart_com_driver, pios_usart_gps_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_GPS */
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
break;
|
||||
case HWSETTINGS_CC_MAINPORT_SPEKTRUM:
|
||||
#if defined(PIOS_INCLUDE_SPEKTRUM)
|
||||
{
|
||||
/* SPEKTRUM init must come before usart init since it may use Rx pin for bind */
|
||||
PIOS_SPEKTRUM_Init(&pios_spektrum_main_cfg, false);
|
||||
|
||||
uint32_t pios_usart_spektrum_id;
|
||||
if (PIOS_USART_Init(&pios_usart_spektrum_id, &pios_usart_spektrum_main_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_SPEKTRUM */
|
||||
break;
|
||||
case HWSETTINGS_CC_MAINPORT_COMAUX:
|
||||
break;
|
||||
}
|
||||
|
||||
/* Configure the flexi port */
|
||||
uint8_t hwsettings_cc_flexiport;
|
||||
HwSettingsCC_FlexiPortGet(&hwsettings_cc_flexiport);
|
||||
|
||||
switch (hwsettings_cc_flexiport) {
|
||||
case HWSETTINGS_CC_FLEXIPORT_DISABLED:
|
||||
break;
|
||||
case HWSETTINGS_CC_FLEXIPORT_TELEMETRY:
|
||||
#if defined(PIOS_INCLUDE_TELEMETRY_RF)
|
||||
{
|
||||
uint32_t pios_usart_telem_rf_id;
|
||||
if (PIOS_USART_Init(&pios_usart_telem_rf_id, &pios_usart_telem_flexi_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_usart_com_driver, pios_usart_telem_rf_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_TELEMETRY_RF */
|
||||
break;
|
||||
case HWSETTINGS_CC_FLEXIPORT_GPS:
|
||||
#if defined(PIOS_INCLUDE_GPS)
|
||||
{
|
||||
uint32_t pios_usart_gps_id;
|
||||
if (PIOS_USART_Init(&pios_usart_gps_id, &pios_usart_gps_flexi_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
if (PIOS_COM_Init(&pios_com_gps_id, &pios_usart_com_driver, pios_usart_gps_id)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_GPS */
|
||||
break;
|
||||
case HWSETTINGS_CC_FLEXIPORT_SPEKTRUM:
|
||||
#if defined(PIOS_INCLUDE_SPEKTRUM)
|
||||
{
|
||||
/* SPEKTRUM init must come before usart init since it may use Rx pin for bind */
|
||||
PIOS_SPEKTRUM_Init(&pios_spektrum_flexi_cfg, false);
|
||||
|
||||
uint32_t pios_usart_spektrum_id;
|
||||
if (PIOS_USART_Init(&pios_usart_spektrum_id, &pios_usart_spektrum_flexi_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_SPEKTRUM */
|
||||
break;
|
||||
case HWSETTINGS_CC_FLEXIPORT_COMAUX:
|
||||
break;
|
||||
case HWSETTINGS_CC_FLEXIPORT_I2C:
|
||||
#if defined(PIOS_INCLUDE_I2C)
|
||||
{
|
||||
if (PIOS_I2C_Init(&pios_i2c_main_adapter_id, &pios_i2c_main_adapter_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_I2C */
|
||||
break;
|
||||
}
|
||||
|
||||
/* Configure the selected receiver */
|
||||
uint8_t manualcontrolsettings_inputmode;
|
||||
ManualControlSettingsInputModeGet(&manualcontrolsettings_inputmode);
|
||||
|
||||
switch (manualcontrolsettings_inputmode) {
|
||||
case MANUALCONTROLSETTINGS_INPUTMODE_PWM:
|
||||
#if defined(PIOS_INCLUDE_PWM)
|
||||
PIOS_PWM_Init();
|
||||
uint32_t pios_pwm_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_pwm_rcvr_id, &pios_pwm_rcvr_driver, 0)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
for (uint8_t i = 0;
|
||||
i < PIOS_PWM_NUM_INPUTS && pios_rcvr_max_channel < NELEMENTS(pios_rcvr_channel_to_id_map);
|
||||
i++) {
|
||||
pios_rcvr_channel_to_id_map[pios_rcvr_max_channel].id = pios_pwm_rcvr_id;
|
||||
pios_rcvr_channel_to_id_map[pios_rcvr_max_channel].channel = i;
|
||||
pios_rcvr_max_channel++;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_PWM */
|
||||
break;
|
||||
case MANUALCONTROLSETTINGS_INPUTMODE_PPM:
|
||||
#if defined(PIOS_INCLUDE_PPM)
|
||||
PIOS_PPM_Init();
|
||||
uint32_t pios_ppm_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, 0)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
for (uint8_t i = 0;
|
||||
i < PIOS_PPM_NUM_INPUTS && pios_rcvr_max_channel < NELEMENTS(pios_rcvr_channel_to_id_map);
|
||||
i++) {
|
||||
pios_rcvr_channel_to_id_map[pios_rcvr_max_channel].id = pios_ppm_rcvr_id;
|
||||
pios_rcvr_channel_to_id_map[pios_rcvr_max_channel].channel = i;
|
||||
pios_rcvr_max_channel++;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_PPM */
|
||||
break;
|
||||
case MANUALCONTROLSETTINGS_INPUTMODE_SPEKTRUM:
|
||||
#if defined(PIOS_INCLUDE_SPEKTRUM)
|
||||
if (hwsettings_cc_mainport == HWSETTINGS_CC_MAINPORT_SPEKTRUM ||
|
||||
hwsettings_cc_flexiport == HWSETTINGS_CC_FLEXIPORT_SPEKTRUM) {
|
||||
uint32_t pios_spektrum_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_spektrum_rcvr_id, &pios_spektrum_rcvr_driver, 0)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
for (uint8_t i = 0;
|
||||
i < PIOS_SPEKTRUM_NUM_INPUTS && pios_rcvr_max_channel < NELEMENTS(pios_rcvr_channel_to_id_map);
|
||||
i++) {
|
||||
pios_rcvr_channel_to_id_map[pios_rcvr_max_channel].id = pios_spektrum_rcvr_id;
|
||||
pios_rcvr_channel_to_id_map[pios_rcvr_max_channel].channel = i;
|
||||
pios_rcvr_max_channel++;
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_SPEKTRUM */
|
||||
break;
|
||||
case MANUALCONTROLSETTINGS_INPUTMODE_SBUS:
|
||||
#if defined(PIOS_INCLUDE_SBUS)
|
||||
if (hwsettings_cc_mainport == HWSETTINGS_CC_MAINPORT_SBUS) {
|
||||
uint32_t pios_sbus_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_sbus_rcvr_id, &pios_sbus_rcvr_driver, 0)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
for (uint8_t i = 0;
|
||||
i < SBUS_NUMBER_OF_CHANNELS && pios_rcvr_max_channel < NELEMENTS(pios_rcvr_channel_to_id_map);
|
||||
i++) {
|
||||
pios_rcvr_channel_to_id_map[pios_rcvr_max_channel].id = pios_sbus_rcvr_id;
|
||||
pios_rcvr_channel_to_id_map[pios_rcvr_max_channel].channel = i;
|
||||
pios_rcvr_max_channel++;
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_SBUS */
|
||||
break;
|
||||
}
|
||||
|
||||
/* Remap AFIO pin */
|
||||
GPIO_PinRemapConfig( GPIO_Remap_SWJ_NoJTRST, ENABLE);
|
||||
@ -726,26 +1112,15 @@ void PIOS_Board_Init(void) {
|
||||
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);
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_com_driver, 0)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
#endif
|
||||
#endif /* PIOS_INCLUDE_USB_HID */
|
||||
|
||||
#if defined(PIOS_INCLUDE_I2C)
|
||||
if (PIOS_I2C_Init(&pios_i2c_main_adapter_id, &pios_i2c_main_adapter_cfg)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_I2C */
|
||||
PIOS_IAP_Init();
|
||||
PIOS_WDG_Init();
|
||||
}
|
||||
|
@ -61,7 +61,7 @@ static const struct pios_spi_cfg pios_spi_op_mag_cfg = {
|
||||
.ahb_clk = RCC_AHBPeriph_DMA1,
|
||||
|
||||
.irq = {
|
||||
.handler = PIOS_SPI_op_mag_irq_handler,
|
||||
.handler = NULL,
|
||||
.flags =
|
||||
(DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 |
|
||||
DMA1_FLAG_GL4),
|
||||
@ -175,7 +175,7 @@ static const struct pios_spi_cfg pios_spi_accel_cfg = {
|
||||
.ahb_clk = RCC_AHBPeriph_DMA1,
|
||||
|
||||
.irq = {
|
||||
.handler = PIOS_SPI_accel_irq_handler,
|
||||
.handler = NULL,
|
||||
.flags = (DMA1_FLAG_TC2 | DMA1_FLAG_TE2 | DMA1_FLAG_HT2 | DMA1_FLAG_GL2),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA1_Channel2_IRQn,
|
||||
@ -265,17 +265,10 @@ void PIOS_SPI_accel_irq_handler(void)
|
||||
/*
|
||||
* GPS USART
|
||||
*/
|
||||
void PIOS_USART_gps_irq_handler(void);
|
||||
void USART1_IRQHandler()
|
||||
__attribute__ ((alias("PIOS_USART_gps_irq_handler")));
|
||||
const struct pios_usart_cfg pios_usart_gps_cfg = {
|
||||
static const struct pios_usart_cfg pios_usart_gps_cfg = {
|
||||
.regs = USART1,
|
||||
.init = {
|
||||
#if defined (PIOS_USART_BAUDRATE)
|
||||
.USART_BaudRate = PIOS_USART_BAUDRATE,
|
||||
#else
|
||||
.USART_BaudRate = 57600,
|
||||
#endif
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
@ -284,7 +277,7 @@ const struct pios_usart_cfg pios_usart_gps_cfg = {
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.handler = PIOS_USART_gps_irq_handler,
|
||||
.handler = NULL,
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART1_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
@ -310,29 +303,16 @@ const struct pios_usart_cfg pios_usart_gps_cfg = {
|
||||
},
|
||||
};
|
||||
|
||||
static uint32_t pios_usart_gps_id;
|
||||
void PIOS_USART_gps_irq_handler(void)
|
||||
{
|
||||
PIOS_USART_IRQ_Handler(pios_usart_gps_id);
|
||||
}
|
||||
|
||||
#endif /* PIOS_INCLUDE_GPS */
|
||||
|
||||
#ifdef PIOS_COM_AUX
|
||||
/*
|
||||
* AUX USART
|
||||
*/
|
||||
void PIOS_USART_aux_irq_handler(void);
|
||||
void USART4_IRQHandler()
|
||||
__attribute__ ((alias("PIOS_USART_aux_irq_handler")));
|
||||
const struct pios_usart_cfg pios_usart_aux_cfg = {
|
||||
static const struct pios_usart_cfg pios_usart_aux_cfg = {
|
||||
.regs = USART4,
|
||||
.init = {
|
||||
#if defined (PIOS_USART_BAUDRATE)
|
||||
.USART_BaudRate = PIOS_USART_BAUDRATE,
|
||||
#else
|
||||
.USART_BaudRate = 57600,
|
||||
#endif
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
@ -341,7 +321,7 @@ const struct pios_usart_cfg pios_usart_aux_cfg = {
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.handler = PIOS_USART_aux_irq_handler,
|
||||
.handler = NULL,
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART4_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
@ -367,12 +347,6 @@ const struct pios_usart_cfg pios_usart_aux_cfg = {
|
||||
},
|
||||
};
|
||||
|
||||
static uint32_t pios_usart_aux_id;
|
||||
void PIOS_USART_aux_irq_handler(void)
|
||||
{
|
||||
PIOS_USART_IRQ_Handler(pios_usart_aux_id);
|
||||
}
|
||||
|
||||
#endif /* PIOS_COM_AUX */
|
||||
|
||||
|
||||
@ -391,7 +365,7 @@ void I2C1_EV_IRQHandler()
|
||||
void I2C1_ER_IRQHandler()
|
||||
__attribute__ ((alias("PIOS_I2C_pres_mag_adapter_er_irq_handler")));
|
||||
|
||||
const struct pios_i2c_adapter_cfg pios_i2c_pres_mag_adapter_cfg = {
|
||||
static const struct pios_i2c_adapter_cfg pios_i2c_pres_mag_adapter_cfg = {
|
||||
.regs = I2C1,
|
||||
.init = {
|
||||
.I2C_Mode = I2C_Mode_I2C,
|
||||
@ -419,7 +393,7 @@ const struct pios_i2c_adapter_cfg pios_i2c_pres_mag_adapter_cfg = {
|
||||
},
|
||||
},
|
||||
.event = {
|
||||
.handler = PIOS_I2C_pres_mag_adapter_ev_irq_handler,
|
||||
.handler = NULL,
|
||||
.flags = 0, /* FIXME: check this */
|
||||
.init = {
|
||||
.NVIC_IRQChannel = I2C1_EV_IRQn,
|
||||
@ -429,7 +403,7 @@ const struct pios_i2c_adapter_cfg pios_i2c_pres_mag_adapter_cfg = {
|
||||
},
|
||||
},
|
||||
.error = {
|
||||
.handler = PIOS_I2C_pres_mag_adapter_er_irq_handler,
|
||||
.handler = NULL,
|
||||
.flags = 0, /* FIXME: check this */
|
||||
.init = {
|
||||
.NVIC_IRQChannel = I2C1_ER_IRQn,
|
||||
@ -459,7 +433,7 @@ void PIOS_I2C_gyro_adapter_er_irq_handler(void);
|
||||
void I2C2_EV_IRQHandler() __attribute__ ((alias ("PIOS_I2C_gyro_adapter_ev_irq_handler")));
|
||||
void I2C2_ER_IRQHandler() __attribute__ ((alias ("PIOS_I2C_gyro_adapter_er_irq_handler")));
|
||||
|
||||
const struct pios_i2c_adapter_cfg pios_i2c_gyro_adapter_cfg = {
|
||||
static const struct pios_i2c_adapter_cfg pios_i2c_gyro_adapter_cfg = {
|
||||
.regs = I2C2,
|
||||
.init = {
|
||||
.I2C_Mode = I2C_Mode_I2C,
|
||||
@ -487,7 +461,7 @@ const struct pios_i2c_adapter_cfg pios_i2c_gyro_adapter_cfg = {
|
||||
},
|
||||
},
|
||||
.event = {
|
||||
.handler = PIOS_I2C_gyro_adapter_ev_irq_handler,
|
||||
.handler = NULL,
|
||||
.flags = 0, /* FIXME: check this */
|
||||
.init = {
|
||||
.NVIC_IRQChannel = I2C2_EV_IRQn,
|
||||
@ -497,7 +471,7 @@ const struct pios_i2c_adapter_cfg pios_i2c_gyro_adapter_cfg = {
|
||||
},
|
||||
},
|
||||
.error = {
|
||||
.handler = PIOS_I2C_gyro_adapter_er_irq_handler,
|
||||
.handler = NULL,
|
||||
.flags = 0, /* FIXME: check this */
|
||||
.init = {
|
||||
.NVIC_IRQChannel = I2C2_ER_IRQn,
|
||||
@ -547,6 +521,7 @@ void PIOS_Board_Init(void) {
|
||||
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
#if defined(PIOS_INCLUDE_GPS)
|
||||
uint32_t pios_usart_gps_id;
|
||||
if (PIOS_USART_Init(&pios_usart_gps_id, &pios_usart_gps_cfg)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
|
@ -69,7 +69,7 @@ static void ahrscommsTask(void *parameters);
|
||||
* Initialise the module, called on startup
|
||||
* \returns 0 on success or -1 if initialisation failed
|
||||
*/
|
||||
int32_t AHRSCommsInitialize(void)
|
||||
int32_t AHRSCommsStart(void)
|
||||
{
|
||||
// Start main task
|
||||
AHRSStatusInitialize();
|
||||
@ -83,6 +83,17 @@ int32_t AHRSCommsInitialize(void)
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialise the module, called on startup
|
||||
* \returns 0 on success or -1 if initialisation failed
|
||||
*/
|
||||
int32_t AHRSCommsInitialize(void)
|
||||
{
|
||||
|
||||
return 0;
|
||||
}
|
||||
MODULE_INITCALL(AHRSCommsInitialize, AHRSCommsStart)
|
||||
|
||||
/**
|
||||
* Module thread, should not return.
|
||||
*/
|
||||
|
@ -85,6 +85,19 @@ typedef struct {
|
||||
int8_t matrix[5];
|
||||
} __attribute__((packed)) Mixer_t;
|
||||
|
||||
/**
|
||||
* @brief Module initialization
|
||||
* @return 0
|
||||
*/
|
||||
int32_t ActuatorStart()
|
||||
{
|
||||
// Start main task
|
||||
xTaskCreate(actuatorTask, (signed char*)"Actuator", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_ACTUATOR, taskHandle);
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_ACTUATOR);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Module initialization
|
||||
@ -108,13 +121,9 @@ int32_t ActuatorInitialize()
|
||||
// If settings change, update the output rate
|
||||
ActuatorSettingsConnectCallback(actuator_update_rate);
|
||||
|
||||
// Start main task
|
||||
xTaskCreate(actuatorTask, (signed char*)"Actuator", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_ACTUATOR, taskHandle);
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_ACTUATOR);
|
||||
|
||||
return 0;
|
||||
}
|
||||
MODULE_INITCALL(ActuatorInitialize, ActuatorStart)
|
||||
|
||||
/**
|
||||
* @brief Main Actuator module task
|
||||
|
@ -37,6 +37,7 @@
|
||||
*/
|
||||
|
||||
#include "openpilot.h"
|
||||
#include "altitude.h"
|
||||
#include "baroaltitude.h" // object that will be updated by the module
|
||||
#if defined(PIOS_INCLUDE_HCSR04)
|
||||
#include "sonaraltitude.h" // object that will be updated by the module
|
||||
@ -66,7 +67,7 @@ static void altitudeTask(void *parameters);
|
||||
* Initialise the module, called on startup
|
||||
* \returns 0 on success or -1 if initialisation failed
|
||||
*/
|
||||
int32_t AltitudeInitialize()
|
||||
int32_t AltitudeStart()
|
||||
{
|
||||
|
||||
BaroAltitudeInitialize();
|
||||
@ -78,6 +79,16 @@ int32_t AltitudeInitialize()
|
||||
xTaskCreate(altitudeTask, (signed char *)"Altitude", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_ALTITUDE, taskHandle);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialise the module, called on startup
|
||||
* \returns 0 on success or -1 if initialisation failed
|
||||
*/
|
||||
int32_t AltitudeInitialize()
|
||||
{
|
||||
|
||||
// init down-sampling data
|
||||
alt_ds_temp = 0;
|
||||
alt_ds_pres = 0;
|
||||
@ -85,7 +96,7 @@ int32_t AltitudeInitialize()
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
MODULE_INITCALL(AltitudeInitialize, AltitudeStart)
|
||||
/**
|
||||
* Module thread, should not return.
|
||||
*/
|
||||
|
@ -3,7 +3,7 @@
|
||||
* @addtogroup OpenPilotModules OpenPilot Modules
|
||||
* @{
|
||||
* @addtogroup Attitude Copter Control Attitude Estimation
|
||||
* @brief Acquires sensor data and computes attitude estimate
|
||||
* @brief Acquires sensor data and computes attitude estimate
|
||||
* Specifically updates the the @ref AttitudeActual "AttitudeActual" and @ref AttitudeRaw "AttitudeRaw" settings objects
|
||||
* @{
|
||||
*
|
||||
@ -89,6 +89,22 @@ static float q[4] = {1,0,0,0};
|
||||
static float R[3][3];
|
||||
static int8_t rotate = 0;
|
||||
static bool zero_during_arming = false;
|
||||
static bool bias_correct_gyro = true;
|
||||
|
||||
/**
|
||||
* Initialise the module, called on startup
|
||||
* \returns 0 on success or -1 if initialisation failed
|
||||
*/
|
||||
int32_t AttitudeStart(void)
|
||||
{
|
||||
|
||||
// Start main task
|
||||
xTaskCreate(AttitudeTask, (signed char *)"Attitude", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_ATTITUDE, taskHandle);
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_ATTITUDE);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialise the module, called on startup
|
||||
@ -108,91 +124,107 @@ int32_t AttitudeInitialize(void)
|
||||
attitude.q3 = 0;
|
||||
attitude.q4 = 0;
|
||||
AttitudeActualSet(&attitude);
|
||||
|
||||
|
||||
// Cannot trust the values to init right above if BL runs
|
||||
gyro_correct_int[0] = 0;
|
||||
gyro_correct_int[1] = 0;
|
||||
gyro_correct_int[2] = 0;
|
||||
|
||||
q[0] = 1;
|
||||
q[1] = 0;
|
||||
q[2] = 0;
|
||||
q[3] = 0;
|
||||
for(uint8_t i = 0; i < 3; i++)
|
||||
for(uint8_t j = 0; j < 3; j++)
|
||||
R[i][j] = 0;
|
||||
|
||||
// Create queue for passing gyro data, allow 2 back samples in case
|
||||
gyro_queue = xQueueCreate(1, sizeof(float) * 4);
|
||||
if(gyro_queue == NULL)
|
||||
if(gyro_queue == NULL)
|
||||
return -1;
|
||||
|
||||
|
||||
PIOS_ADC_SetQueue(gyro_queue);
|
||||
|
||||
|
||||
AttitudeSettingsConnectCallback(&settingsUpdatedCb);
|
||||
|
||||
// Start main task
|
||||
xTaskCreate(AttitudeTask, (signed char *)"Attitude", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_ATTITUDE, taskHandle);
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_ATTITUDE);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
MODULE_INITCALL(AttitudeInitialize, AttitudeStart)
|
||||
|
||||
/**
|
||||
* Module thread, should not return.
|
||||
*/
|
||||
static void AttitudeTask(void *parameters)
|
||||
{
|
||||
|
||||
uint8_t init = 0;
|
||||
AlarmsClear(SYSTEMALARMS_ALARM_ATTITUDE);
|
||||
|
||||
PIOS_ADC_Config((PIOS_ADC_RATE / 1000.0f) * UPDATE_RATE);
|
||||
|
||||
// Keep flash CS pin high while talking accel
|
||||
PIOS_FLASH_DISABLE;
|
||||
PIOS_FLASH_DISABLE;
|
||||
PIOS_ADXL345_Init();
|
||||
|
||||
zero_during_arming = false;
|
||||
|
||||
|
||||
// Force settings update to make sure rotation loaded
|
||||
settingsUpdatedCb(AttitudeSettingsHandle());
|
||||
|
||||
// Main task loop
|
||||
while (1) {
|
||||
|
||||
|
||||
FlightStatusData flightStatus;
|
||||
FlightStatusGet(&flightStatus);
|
||||
|
||||
if(xTaskGetTickCount() < 7000) {
|
||||
// Force settings update to make sure rotation loaded
|
||||
settingsUpdatedCb(AttitudeSettingsHandle());
|
||||
if((xTaskGetTickCount() < 7000) && (xTaskGetTickCount() > 1000)) {
|
||||
// For first 7 seconds use accels to get gyro bias
|
||||
accelKp = 1;
|
||||
accelKi = 0.9;
|
||||
yawBiasRate = 0.23;
|
||||
init = 0;
|
||||
}
|
||||
}
|
||||
else if (zero_during_arming && (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMING)) {
|
||||
accelKp = 1;
|
||||
accelKi = 0.9;
|
||||
yawBiasRate = 0.23;
|
||||
init = 0;
|
||||
init = 0;
|
||||
} else if (init == 0) {
|
||||
settingsUpdatedCb(AttitudeSettingsHandle());
|
||||
// Reload settings (all the rates)
|
||||
AttitudeSettingsAccelKiGet(&accelKi);
|
||||
AttitudeSettingsAccelKpGet(&accelKp);
|
||||
AttitudeSettingsYawBiasRateGet(&yawBiasRate);
|
||||
init = 1;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
PIOS_WDG_UpdateFlag(PIOS_WDG_ATTITUDE);
|
||||
|
||||
|
||||
AttitudeRawData attitudeRaw;
|
||||
AttitudeRawGet(&attitudeRaw);
|
||||
updateSensors(&attitudeRaw);
|
||||
AttitudeRawGet(&attitudeRaw);
|
||||
updateSensors(&attitudeRaw);
|
||||
updateAttitude(&attitudeRaw);
|
||||
AttitudeRawSet(&attitudeRaw);
|
||||
AttitudeRawSet(&attitudeRaw);
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
static void updateSensors(AttitudeRawData * attitudeRaw)
|
||||
{
|
||||
static void updateSensors(AttitudeRawData * attitudeRaw)
|
||||
{
|
||||
struct pios_adxl345_data accel_data;
|
||||
float gyro[4];
|
||||
|
||||
|
||||
// Only wait the time for two nominal updates before setting an alarm
|
||||
if(xQueueReceive(gyro_queue, (void * const) gyro, UPDATE_RATE * 2) == errQUEUE_EMPTY) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE, SYSTEMALARMS_ALARM_ERROR);
|
||||
return;
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
// First sample is temperature
|
||||
attitudeRaw->gyros[ATTITUDERAW_GYROS_X] = -(gyro[1] - GYRO_NEUTRAL) * gyroGain;
|
||||
attitudeRaw->gyros[ATTITUDERAW_GYROS_Y] = (gyro[2] - GYRO_NEUTRAL) * gyroGain;
|
||||
attitudeRaw->gyros[ATTITUDERAW_GYROS_Z] = -(gyro[3] - GYRO_NEUTRAL) * gyroGain;
|
||||
|
||||
|
||||
int32_t x = 0;
|
||||
int32_t y = 0;
|
||||
int32_t z = 0;
|
||||
@ -207,9 +239,9 @@ static void updateSensors(AttitudeRawData * attitudeRaw)
|
||||
} while ( (i < 32) && (samples_remaining > 0) );
|
||||
attitudeRaw->gyrotemp[0] = samples_remaining;
|
||||
attitudeRaw->gyrotemp[1] = i;
|
||||
|
||||
|
||||
float accel[3] = {(float) x / i, (float) y / i, (float) z / i};
|
||||
|
||||
|
||||
if(rotate) {
|
||||
// TODO: rotate sensors too so stabilization is well behaved
|
||||
float vec_out[3];
|
||||
@ -225,68 +257,68 @@ static void updateSensors(AttitudeRawData * attitudeRaw)
|
||||
attitudeRaw->accels[0] = accel[0];
|
||||
attitudeRaw->accels[1] = accel[1];
|
||||
attitudeRaw->accels[2] = accel[2];
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
// Scale accels and correct bias
|
||||
attitudeRaw->accels[ATTITUDERAW_ACCELS_X] = (attitudeRaw->accels[ATTITUDERAW_ACCELS_X] - accelbias[0]) * 0.004f * 9.81f;
|
||||
attitudeRaw->accels[ATTITUDERAW_ACCELS_Y] = (attitudeRaw->accels[ATTITUDERAW_ACCELS_Y] - accelbias[1]) * 0.004f * 9.81f;
|
||||
attitudeRaw->accels[ATTITUDERAW_ACCELS_Z] = (attitudeRaw->accels[ATTITUDERAW_ACCELS_Z] - accelbias[2]) * 0.004f * 9.81f;
|
||||
|
||||
// Applying integral component here so it can be seen on the gyros and correct bias
|
||||
attitudeRaw->gyros[ATTITUDERAW_GYROS_X] += gyro_correct_int[0];
|
||||
attitudeRaw->gyros[ATTITUDERAW_GYROS_Y] += gyro_correct_int[1];
|
||||
|
||||
// Because most crafts wont get enough information from gravity to zero yaw gyro
|
||||
attitudeRaw->gyros[ATTITUDERAW_GYROS_Z] += gyro_correct_int[2];
|
||||
gyro_correct_int[2] += - attitudeRaw->gyros[ATTITUDERAW_GYROS_Z] * yawBiasRate;
|
||||
|
||||
if(bias_correct_gyro) {
|
||||
// Applying integral component here so it can be seen on the gyros and correct bias
|
||||
attitudeRaw->gyros[ATTITUDERAW_GYROS_X] += gyro_correct_int[0];
|
||||
attitudeRaw->gyros[ATTITUDERAW_GYROS_Y] += gyro_correct_int[1];
|
||||
attitudeRaw->gyros[ATTITUDERAW_GYROS_Z] += gyro_correct_int[2];
|
||||
}
|
||||
|
||||
// Because most crafts wont get enough information from gravity to zero yaw gyro, we try
|
||||
// and make it average zero (weakly)
|
||||
gyro_correct_int[2] += - attitudeRaw->gyros[ATTITUDERAW_GYROS_Z] * yawBiasRate;
|
||||
}
|
||||
|
||||
static void updateAttitude(AttitudeRawData * attitudeRaw)
|
||||
{
|
||||
float dT;
|
||||
portTickType thisSysTime = xTaskGetTickCount();
|
||||
static portTickType lastSysTime = 0;
|
||||
static portTickType thisSysTime;
|
||||
|
||||
static float dT = 0;
|
||||
|
||||
thisSysTime = xTaskGetTickCount();
|
||||
if(thisSysTime > lastSysTime) // reuse dt in case of wraparound
|
||||
dT = (thisSysTime - lastSysTime) / portTICK_RATE_MS / 1000.0f;
|
||||
|
||||
dT = (thisSysTime == lastSysTime) ? 0.001 : (portMAX_DELAY & (thisSysTime - lastSysTime)) / portTICK_RATE_MS / 1000.0f;
|
||||
lastSysTime = thisSysTime;
|
||||
|
||||
|
||||
// Bad practice to assume structure order, but saves memory
|
||||
float gyro[3];
|
||||
gyro[0] = attitudeRaw->gyros[0];
|
||||
gyro[1] = attitudeRaw->gyros[1];
|
||||
gyro[2] = attitudeRaw->gyros[2];
|
||||
|
||||
|
||||
{
|
||||
float * accels = attitudeRaw->accels;
|
||||
float grot[3];
|
||||
float accel_err[3];
|
||||
|
||||
|
||||
// Rotate gravity to body frame and cross with accels
|
||||
grot[0] = -(2 * (q[1] * q[3] - q[0] * q[2]));
|
||||
grot[1] = -(2 * (q[2] * q[3] + q[0] * q[1]));
|
||||
grot[2] = -(q[0] * q[0] - q[1]*q[1] - q[2]*q[2] + q[3]*q[3]);
|
||||
CrossProduct((const float *) accels, (const float *) grot, accel_err);
|
||||
|
||||
// Account for accel magnitude
|
||||
|
||||
// Account for accel magnitude
|
||||
float accel_mag = sqrt(accels[0]*accels[0] + accels[1]*accels[1] + accels[2]*accels[2]);
|
||||
accel_err[0] /= accel_mag;
|
||||
accel_err[1] /= accel_mag;
|
||||
accel_err[2] /= accel_mag;
|
||||
|
||||
// Accumulate integral of error. Scale here so that units are (rad/s) but Ki has units of s
|
||||
|
||||
// Accumulate integral of error. Scale here so that units are (deg/s) but Ki has units of s
|
||||
gyro_correct_int[0] += accel_err[0] * accelKi;
|
||||
gyro_correct_int[1] += accel_err[1] * accelKi;
|
||||
//gyro_correct_int[2] += accel_err[2] * settings.AccelKI * dT;
|
||||
|
||||
|
||||
// Correct rates based on error, integral component dealt with in updateSensors
|
||||
gyro[0] += accel_err[0] * accelKp / dT;
|
||||
gyro[1] += accel_err[1] * accelKp / dT;
|
||||
gyro[2] += accel_err[2] * accelKp / dT;
|
||||
}
|
||||
|
||||
|
||||
{ // scoping variables to save memory
|
||||
// Work out time derivative from INSAlgo writeup
|
||||
// Also accounts for the fact that gyros are in deg/s
|
||||
@ -295,28 +327,37 @@ static void updateAttitude(AttitudeRawData * attitudeRaw)
|
||||
qdot[1] = (q[0] * gyro[0] - q[3] * gyro[1] + q[2] * gyro[2]) * dT * M_PI / 180 / 2;
|
||||
qdot[2] = (q[3] * gyro[0] + q[0] * gyro[1] - q[1] * gyro[2]) * dT * M_PI / 180 / 2;
|
||||
qdot[3] = (-q[2] * gyro[0] + q[1] * gyro[1] + q[0] * gyro[2]) * dT * M_PI / 180 / 2;
|
||||
|
||||
|
||||
// Take a time step
|
||||
q[0] = q[0] + qdot[0];
|
||||
q[1] = q[1] + qdot[1];
|
||||
q[2] = q[2] + qdot[2];
|
||||
q[3] = q[3] + qdot[3];
|
||||
}
|
||||
|
||||
|
||||
// Renomalize
|
||||
float qmag = sqrt(q[0]*q[0] + q[1]*q[1] + q[2]*q[2] + q[3]*q[3]);
|
||||
q[0] = q[0] / qmag;
|
||||
q[1] = q[1] / qmag;
|
||||
q[2] = q[2] / qmag;
|
||||
q[3] = q[3] / qmag;
|
||||
|
||||
|
||||
// If quaternion has become inappropriately short or is nan reinit.
|
||||
// THIS SHOULD NEVER ACTUALLY HAPPEN
|
||||
if((fabs(qmag) < 1e-3) || (qmag != qmag)) {
|
||||
q[0] = 1;
|
||||
q[1] = 0;
|
||||
q[2] = 0;
|
||||
q[3] = 0;
|
||||
}
|
||||
|
||||
AttitudeActualData attitudeActual;
|
||||
AttitudeActualGet(&attitudeActual);
|
||||
|
||||
|
||||
quat_copy(q, &attitudeActual.q1);
|
||||
|
||||
|
||||
// Convert into eueler degrees (makes assumptions about RPY order)
|
||||
Quaternion2RPY(&attitudeActual.q1,&attitudeActual.Roll);
|
||||
Quaternion2RPY(&attitudeActual.q1,&attitudeActual.Roll);
|
||||
|
||||
AttitudeActualSet(&attitudeActual);
|
||||
}
|
||||
@ -324,36 +365,41 @@ static void updateAttitude(AttitudeRawData * attitudeRaw)
|
||||
static void settingsUpdatedCb(UAVObjEvent * objEv) {
|
||||
AttitudeSettingsData attitudeSettings;
|
||||
AttitudeSettingsGet(&attitudeSettings);
|
||||
|
||||
|
||||
|
||||
|
||||
accelKp = attitudeSettings.AccelKp;
|
||||
accelKi = attitudeSettings.AccelKi;
|
||||
accelKi = attitudeSettings.AccelKi;
|
||||
yawBiasRate = attitudeSettings.YawBiasRate;
|
||||
gyroGain = attitudeSettings.GyroGain;
|
||||
|
||||
|
||||
zero_during_arming = attitudeSettings.ZeroDuringArming == ATTITUDESETTINGS_ZERODURINGARMING_TRUE;
|
||||
|
||||
bias_correct_gyro = attitudeSettings.BiasCorrectGyro == ATTITUDESETTINGS_BIASCORRECTGYRO_TRUE;
|
||||
|
||||
accelbias[0] = attitudeSettings.AccelBias[ATTITUDESETTINGS_ACCELBIAS_X];
|
||||
accelbias[1] = attitudeSettings.AccelBias[ATTITUDESETTINGS_ACCELBIAS_Y];
|
||||
accelbias[2] = attitudeSettings.AccelBias[ATTITUDESETTINGS_ACCELBIAS_Z];
|
||||
|
||||
|
||||
gyro_correct_int[0] = attitudeSettings.GyroBias[ATTITUDESETTINGS_GYROBIAS_X] / 100.0f;
|
||||
gyro_correct_int[1] = attitudeSettings.GyroBias[ATTITUDESETTINGS_GYROBIAS_Y] / 100.0f;
|
||||
gyro_correct_int[2] = attitudeSettings.GyroBias[ATTITUDESETTINGS_GYROBIAS_Z] / 100.0f;
|
||||
|
||||
// Indicates not to expend cycles on rotation
|
||||
if(attitudeSettings.BoardRotation[0] == 0 && attitudeSettings.BoardRotation[1] == 0 &&
|
||||
attitudeSettings.BoardRotation[2] == 0) {
|
||||
rotate = 0;
|
||||
|
||||
|
||||
// Shouldn't be used but to be safe
|
||||
float rotationQuat[4] = {1,0,0,0};
|
||||
Quaternion2R(rotationQuat, R);
|
||||
} else {
|
||||
float rotationQuat[4];
|
||||
const float rpy[3] = {attitudeSettings.BoardRotation[ATTITUDESETTINGS_BOARDROTATION_ROLL],
|
||||
attitudeSettings.BoardRotation[ATTITUDESETTINGS_BOARDROTATION_PITCH],
|
||||
const float rpy[3] = {attitudeSettings.BoardRotation[ATTITUDESETTINGS_BOARDROTATION_ROLL],
|
||||
attitudeSettings.BoardRotation[ATTITUDESETTINGS_BOARDROTATION_PITCH],
|
||||
attitudeSettings.BoardRotation[ATTITUDESETTINGS_BOARDROTATION_YAW]};
|
||||
RPY2Quaternion(rpy, rotationQuat);
|
||||
Quaternion2R(rotationQuat, R);
|
||||
rotate = 1;
|
||||
}
|
||||
}
|
||||
}
|
||||
/**
|
||||
* @}
|
||||
|
@ -75,6 +75,8 @@ static void onTimer(UAVObjEvent* ev);
|
||||
* Initialise the module, called on startup
|
||||
* \returns 0 on success or -1 if initialisation failed
|
||||
*/
|
||||
MODULE_INITCALL(BatteryInitialize, 0)
|
||||
|
||||
int32_t BatteryInitialize(void)
|
||||
{
|
||||
BatteryStateInitialze();
|
||||
|
@ -49,9 +49,14 @@
|
||||
#include "examplemodperiodic.h"
|
||||
#include "examplemodthread.h"
|
||||
|
||||
void ExampleInitialize(void)
|
||||
void ExampleStart(void)
|
||||
{
|
||||
ExampleModEventInitialize();
|
||||
ExampleModPeriodicInitialize();
|
||||
ExampleModThreadInitialize();
|
||||
}
|
||||
|
||||
void ExampleInitialize(void)
|
||||
{
|
||||
ExampleModEventInitialize();
|
||||
}
|
||||
MODULE_INITCALL(ExampleInitialize, ExampleStart)
|
||||
|
@ -88,7 +88,7 @@ static void resetTask(UAVObjEvent *);
|
||||
* \note
|
||||
*
|
||||
*/
|
||||
|
||||
MODULE_INITCALL(FirmwareIAPInitialize, 0)
|
||||
int32_t FirmwareIAPInitialize()
|
||||
{
|
||||
|
||||
@ -103,7 +103,7 @@ int32_t FirmwareIAPInitialize()
|
||||
data.ArmReset=0;
|
||||
data.crc = 0;
|
||||
FirmwareIAPObjSet( &data );
|
||||
FirmwareIAPObjConnectCallback( &FirmwareIAPCallback );
|
||||
if(bdinfo->magic==PIOS_BOARD_INFO_BLOB_MAGIC) FirmwareIAPObjConnectCallback( &FirmwareIAPCallback );
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
@ -31,6 +31,7 @@
|
||||
|
||||
#include "openpilot.h"
|
||||
#include "pm.h"
|
||||
#include "flightplan.h"
|
||||
#include "flightplanstatus.h"
|
||||
#include "flightplancontrol.h"
|
||||
#include "flightplansettings.h"
|
||||
@ -53,6 +54,20 @@ static void objectUpdatedCb(UAVObjEvent * ev);
|
||||
// External variables (temporary, TODO: this will be loaded from the SD card)
|
||||
extern unsigned char usrlib_img[];
|
||||
|
||||
/**
|
||||
* Module initialization
|
||||
*/
|
||||
int32_t FlightPlanStart()
|
||||
{
|
||||
taskHandle = NULL;
|
||||
|
||||
// Start VM thread
|
||||
xTaskCreate(flightPlanTask, (signed char *)"FlightPlan", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_FLIGHTPLAN, taskHandle);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Module initialization
|
||||
*/
|
||||
@ -69,13 +84,9 @@ int32_t FlightPlanInitialize()
|
||||
// Listen for FlightPlanControl updates
|
||||
FlightPlanControlConnectQueue(queue);
|
||||
|
||||
// Start VM thread
|
||||
xTaskCreate(flightPlanTask, (signed char *)"FlightPlan", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_FLIGHTPLAN, taskHandle);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
MODULE_INITCALL(FlightPlanInitialize, FlightPlanStart)
|
||||
/**
|
||||
* Module task
|
||||
*/
|
||||
|
@ -109,23 +109,31 @@ static uint32_t numParsingErrors;
|
||||
* \return 0 on success
|
||||
*/
|
||||
|
||||
int32_t GPSStart(void)
|
||||
{
|
||||
// Start gps task
|
||||
xTaskCreate(gpsTask, (signed char *)"GPS", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &gpsTaskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_GPS, gpsTaskHandle);
|
||||
|
||||
return 0;
|
||||
}
|
||||
/**
|
||||
* Initialise the gps module
|
||||
* \return -1 if initialisation failed
|
||||
* \return 0 on success
|
||||
*/
|
||||
int32_t GPSInitialize(void)
|
||||
{
|
||||
GPSPositionInitialize();
|
||||
GPSTimeInitialize();
|
||||
HomeLocationInitialize();
|
||||
|
||||
signed portBASE_TYPE xReturn;
|
||||
|
||||
// TODO: Get gps settings object
|
||||
gpsPort = PIOS_COM_GPS;
|
||||
|
||||
// Start gps task
|
||||
xReturn = xTaskCreate(gpsTask, (signed char *)"GPS", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &gpsTaskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_GPS, gpsTaskHandle);
|
||||
|
||||
return 0;
|
||||
}
|
||||
MODULE_INITCALL(GPSInitialize, GPSStart)
|
||||
|
||||
// ****************
|
||||
/**
|
||||
|
@ -78,6 +78,19 @@ static void updateVtolDesiredVelocity();
|
||||
static void manualSetDesiredVelocity();
|
||||
static void updateVtolDesiredAttitude();
|
||||
|
||||
/**
|
||||
* Initialise the module, called on startup
|
||||
* \returns 0 on success or -1 if initialisation failed
|
||||
*/
|
||||
int32_t GuidanceStart()
|
||||
{
|
||||
// Start main task
|
||||
xTaskCreate(guidanceTask, (signed char *)"Guidance", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &guidanceTaskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_GUIDANCE, guidanceTaskHandle);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialise the module, called on startup
|
||||
* \returns 0 on success or -1 if initialisation failed
|
||||
@ -90,12 +103,9 @@ int32_t GuidanceInitialize()
|
||||
// Listen for updates.
|
||||
AttitudeRawConnectQueue(queue);
|
||||
|
||||
// Start main task
|
||||
xTaskCreate(guidanceTask, (signed char *)"Guidance", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &guidanceTaskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_GUIDANCE, guidanceTaskHandle);
|
||||
|
||||
return 0;
|
||||
}
|
||||
MODULE_INITCALL(GuidanceInitialize, GuidanceStart)
|
||||
|
||||
static float northVelIntegral = 0;
|
||||
static float eastVelIntegral = 0;
|
||||
|
@ -27,5 +27,5 @@
|
||||
#define EXAMPLEMODPERIODIC_H
|
||||
|
||||
int32_t ExampleModPeriodicInitialize();
|
||||
|
||||
int32_t GuidanceInitialize(void);
|
||||
#endif // EXAMPLEMODPERIODIC_H
|
||||
|
@ -1,7 +1,7 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup OpenPilotModules OpenPilot Modules
|
||||
* @{
|
||||
* @{
|
||||
* @addtogroup ManualControlModule Manual Control Module
|
||||
* @{
|
||||
*
|
||||
@ -45,4 +45,64 @@ typedef enum {FLIGHTMODE_UNDEFINED = 0, FLIGHTMODE_MANUAL = 1, FLIGHTMODE_STABIL
|
||||
|
||||
int32_t ManualControlInitialize();
|
||||
|
||||
|
||||
/*
|
||||
* These are assumptions we make in the flight code about the order of settings and their consistency between
|
||||
* objects. Please keep this synchronized to the UAVObjects
|
||||
*/
|
||||
#define assumptions1 ( \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_NONE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_RATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_AXISLOCK == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_WEAKLEVELING == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_ATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) \
|
||||
)
|
||||
|
||||
#define assumptions3 ( \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION2SETTINGS_NONE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION2SETTINGS_RATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION2SETTINGS_AXISLOCK == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION2SETTINGS_WEAKLEVELING == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION2SETTINGS_ATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) \
|
||||
)
|
||||
|
||||
#define assumptions5 ( \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION3SETTINGS_NONE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION3SETTINGS_RATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION3SETTINGS_AXISLOCK == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION3SETTINGS_WEAKLEVELING == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION3SETTINGS_ATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) \
|
||||
)
|
||||
|
||||
#define ARMING_CHANNEL_ROLL 0
|
||||
#define ARMING_CHANNEL_PITCH 1
|
||||
#define ARMING_CHANNEL_YAW 2
|
||||
|
||||
#define assumptions7 ( \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)/2 == ARMING_CHANNEL_ROLL) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_ROLLRIGHT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)/2 == ARMING_CHANNEL_ROLL) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_PITCHFORWARD -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)/2 == ARMING_CHANNEL_PITCH) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_PITCHAFT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)/2 == ARMING_CHANNEL_PITCH) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_YAWLEFT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)/2 == ARMING_CHANNEL_YAW) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_YAWRIGHT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)/2 == ARMING_CHANNEL_YAW) \
|
||||
)
|
||||
|
||||
#define assumptions8 ( \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)%2 == 0) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_ROLLRIGHT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)%2 != 0) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_PITCHFORWARD -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)%2 == 0) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_PITCHAFT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)%2 != 0) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_YAWLEFT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)%2 == 0) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_YAWRIGHT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)%2 != 0) \
|
||||
)
|
||||
|
||||
#define assumptions_flightmode ( \
|
||||
( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_MANUAL == (int) FLIGHTSTATUS_FLIGHTMODE_MANUAL) && \
|
||||
( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED1 == (int) FLIGHTSTATUS_FLIGHTMODE_STABILIZED1) && \
|
||||
( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED2 == (int) FLIGHTSTATUS_FLIGHTMODE_STABILIZED2) && \
|
||||
( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED3 == (int) FLIGHTSTATUS_FLIGHTMODE_STABILIZED3) && \
|
||||
( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_VELOCITYCONTROL == (int) FLIGHTSTATUS_FLIGHTMODE_VELOCITYCONTROL) && \
|
||||
( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_POSITIONHOLD == (int) FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD) \
|
||||
)
|
||||
|
||||
#endif // MANUALCONTROL_H
|
||||
|
@ -87,65 +87,27 @@ static uint32_t timeDifferenceMs(portTickType start_time, portTickType end_time)
|
||||
static bool okToArm(void);
|
||||
static bool validInputRange(int16_t min, int16_t max, uint16_t value);
|
||||
|
||||
#define assumptions1 ( \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_NONE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_RATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION1SETTINGS_ATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) \
|
||||
)
|
||||
|
||||
#define assumptions3 ( \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION2SETTINGS_NONE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION2SETTINGS_RATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION2SETTINGS_ATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) \
|
||||
)
|
||||
|
||||
#define assumptions5 ( \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION3SETTINGS_NONE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION3SETTINGS_RATE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) && \
|
||||
((int)MANUALCONTROLSETTINGS_STABILIZATION3SETTINGS_ATTITUDE == (int)STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) \
|
||||
)
|
||||
|
||||
|
||||
|
||||
#define ARMING_CHANNEL_ROLL 0
|
||||
#define ARMING_CHANNEL_PITCH 1
|
||||
#define ARMING_CHANNEL_YAW 2
|
||||
|
||||
#define assumptions7 ( \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)/2 == ARMING_CHANNEL_ROLL) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_ROLLRIGHT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)/2 == ARMING_CHANNEL_ROLL) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_PITCHFORWARD -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)/2 == ARMING_CHANNEL_PITCH) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_PITCHAFT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)/2 == ARMING_CHANNEL_PITCH) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_YAWLEFT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)/2 == ARMING_CHANNEL_YAW) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_YAWRIGHT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)/2 == ARMING_CHANNEL_YAW) \
|
||||
)
|
||||
|
||||
#define assumptions8 ( \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)%2 == 0) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_ROLLRIGHT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)%2 != 0) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_PITCHFORWARD -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)%2 == 0) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_PITCHAFT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)%2 != 0) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_YAWLEFT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)%2 == 0) && \
|
||||
( ((int)MANUALCONTROLSETTINGS_ARMING_YAWRIGHT -(int)MANUALCONTROLSETTINGS_ARMING_ROLLLEFT)%2 != 0) \
|
||||
)
|
||||
|
||||
|
||||
#define assumptions_flightmode ( \
|
||||
( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_MANUAL == (int) FLIGHTSTATUS_FLIGHTMODE_MANUAL) && \
|
||||
( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED1 == (int) FLIGHTSTATUS_FLIGHTMODE_STABILIZED1) && \
|
||||
( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED2 == (int) FLIGHTSTATUS_FLIGHTMODE_STABILIZED2) && \
|
||||
( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_STABILIZED3 == (int) FLIGHTSTATUS_FLIGHTMODE_STABILIZED3) && \
|
||||
( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_VELOCITYCONTROL == (int) FLIGHTSTATUS_FLIGHTMODE_VELOCITYCONTROL) && \
|
||||
( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_POSITIONHOLD == (int) FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD) \
|
||||
)
|
||||
|
||||
#define assumptions (assumptions1 && assumptions3 && assumptions5 && assumptions7 && assumptions8 && assumptions_flightmode)
|
||||
|
||||
/**
|
||||
* Module starting
|
||||
*/
|
||||
int32_t ManualControlStart()
|
||||
{
|
||||
// Start main task
|
||||
xTaskCreate(manualControlTask, (signed char *)"ManualControl", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_MANUALCONTROL, taskHandle);
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_MANUAL);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Module initialization
|
||||
*/
|
||||
int32_t ManualControlInitialize()
|
||||
{
|
||||
|
||||
/* Check the assumptions about uavobject enum's are correct */
|
||||
if(!assumptions)
|
||||
return -1;
|
||||
@ -156,14 +118,9 @@ int32_t ManualControlInitialize()
|
||||
FlightStatusInitialize();
|
||||
StabilizationDesiredInitialize();
|
||||
|
||||
// Start main task
|
||||
xTaskCreate(manualControlTask, (signed char *)"ManualControl", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_MANUALCONTROL, taskHandle);
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_MANUAL);
|
||||
|
||||
|
||||
return 0;
|
||||
}
|
||||
MODULE_INITCALL(ManualControlInitialize, ManualControlStart)
|
||||
|
||||
/**
|
||||
* Module task
|
||||
@ -216,17 +173,13 @@ static void manualControlTask(void *parameters)
|
||||
if (!ManualControlCommandReadOnly(&cmd)) {
|
||||
|
||||
// Read channel values in us
|
||||
// TODO: settings.InputMode is currently ignored because PIOS will not allow runtime
|
||||
// selection of PWM and PPM. The configuration is currently done at compile time in
|
||||
// the pios_config.h file.
|
||||
for (int n = 0; n < MANUALCONTROLCOMMAND_CHANNEL_NUMELEM; ++n) {
|
||||
#if defined(PIOS_INCLUDE_PWM)
|
||||
cmd.Channel[n] = PIOS_PWM_Get(n);
|
||||
#elif defined(PIOS_INCLUDE_PPM)
|
||||
cmd.Channel[n] = PIOS_PPM_Get(n);
|
||||
#elif defined(PIOS_INCLUDE_SPEKTRUM)
|
||||
cmd.Channel[n] = PIOS_SPEKTRUM_Get(n);
|
||||
#endif
|
||||
if (pios_rcvr_channel_to_id_map[n].id) {
|
||||
cmd.Channel[n] = PIOS_RCVR_Read(pios_rcvr_channel_to_id_map[n].id,
|
||||
pios_rcvr_channel_to_id_map[n].channel);
|
||||
} else {
|
||||
cmd.Channel[n] = -1;
|
||||
}
|
||||
scaledChannel[n] = scaleChannel(cmd.Channel[n], settings.ChannelMax[n], settings.ChannelMin[n], settings.ChannelNeutral[n]);
|
||||
}
|
||||
|
||||
@ -378,21 +331,25 @@ static void updateStabilizationDesired(ManualControlCommandData * cmd, ManualCon
|
||||
stabilization.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_YAW] = stab_settings[2];
|
||||
|
||||
stabilization.Roll = (stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) ? cmd->Roll :
|
||||
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) ? cmd->Roll * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_ROLL] :
|
||||
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd->Roll * stabSettings.RollMax :
|
||||
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? cmd->Roll * stabSettings.RollMax :
|
||||
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) ? cmd->Roll * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_ROLL] :
|
||||
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) ? cmd->Roll * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_ROLL] :
|
||||
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd->Roll * stabSettings.RollMax :
|
||||
(stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? cmd->Roll * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_ROLL] :
|
||||
0; // this is an invalid mode
|
||||
;
|
||||
stabilization.Pitch = (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) ? cmd->Pitch :
|
||||
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) ? cmd->Pitch * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_PITCH] :
|
||||
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd->Pitch * stabSettings.PitchMax :
|
||||
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? cmd->Pitch * stabSettings.PitchMax :
|
||||
0; // this is an invalid mode
|
||||
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) ? cmd->Pitch * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_PITCH] :
|
||||
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) ? cmd->Pitch * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_PITCH] :
|
||||
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd->Pitch * stabSettings.PitchMax :
|
||||
(stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? cmd->Pitch * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_PITCH] :
|
||||
0; // this is an invalid mode
|
||||
|
||||
stabilization.Yaw = (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) ? cmd->Yaw :
|
||||
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) ? cmd->Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW] :
|
||||
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? fmod(cmd->Yaw * 180.0, 360) :
|
||||
0; // this is an invalid mode
|
||||
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) ? cmd->Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW] :
|
||||
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) ? cmd->Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW] :
|
||||
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd->Yaw * stabSettings.YawMax :
|
||||
(stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? cmd->Yaw * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW] :
|
||||
0; // this is an invalid mode
|
||||
|
||||
stabilization.Throttle = (cmd->Throttle < 0) ? -1 : cmd->Throttle;
|
||||
StabilizationDesiredSet(&stabilization);
|
||||
|
@ -75,6 +75,14 @@ static xTaskHandle taskHandle;
|
||||
static StabilizationSettingsData settings;
|
||||
static xQueueHandle queue;
|
||||
float dT = 1;
|
||||
float gyro_alpha = 0;
|
||||
float gyro_filtered[3] = {0,0,0};
|
||||
float axis_lock_accum[3] = {0,0,0};
|
||||
uint8_t max_axis_lock = 0;
|
||||
uint8_t max_axislock_rate = 0;
|
||||
float weak_leveling_kp = 0;
|
||||
uint8_t weak_leveling_max = 0;
|
||||
|
||||
pid_type pids[PID_MAX];
|
||||
|
||||
// Private functions
|
||||
@ -84,6 +92,20 @@ static float bound(float val);
|
||||
static void ZeroPids(void);
|
||||
static void SettingsUpdatedCb(UAVObjEvent * ev);
|
||||
|
||||
/**
|
||||
* Module initialization
|
||||
*/
|
||||
int32_t StabilizationStart()
|
||||
{
|
||||
// Initialize variables
|
||||
|
||||
// Start main task
|
||||
xTaskCreate(stabilizationTask, (signed char*)"Stabilization", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_STABILIZATION, taskHandle);
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_STABILIZATION);
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Module initialization
|
||||
*/
|
||||
@ -98,21 +120,20 @@ int32_t StabilizationInitialize()
|
||||
|
||||
// Create object queue
|
||||
queue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(UAVObjEvent));
|
||||
|
||||
|
||||
// Listen for updates.
|
||||
// AttitudeActualConnectQueue(queue);
|
||||
AttitudeRawConnectQueue(queue);
|
||||
|
||||
|
||||
StabilizationSettingsConnectCallback(SettingsUpdatedCb);
|
||||
SettingsUpdatedCb(StabilizationSettingsHandle());
|
||||
// Start main task
|
||||
xTaskCreate(stabilizationTask, (signed char*)"Stabilization", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_STABILIZATION, taskHandle);
|
||||
PIOS_WDG_RegisterFlag(PIOS_WDG_STABILIZATION);
|
||||
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
MODULE_INITCALL(StabilizationInitialize, StabilizationStart)
|
||||
|
||||
/**
|
||||
* Module task
|
||||
*/
|
||||
@ -121,36 +142,36 @@ static void stabilizationTask(void* parameters)
|
||||
portTickType lastSysTime;
|
||||
portTickType thisSysTime;
|
||||
UAVObjEvent ev;
|
||||
|
||||
|
||||
|
||||
|
||||
ActuatorDesiredData actuatorDesired;
|
||||
StabilizationDesiredData stabDesired;
|
||||
RateDesiredData rateDesired;
|
||||
AttitudeActualData attitudeActual;
|
||||
AttitudeRawData attitudeRaw;
|
||||
FlightStatusData flightStatus;
|
||||
|
||||
|
||||
SettingsUpdatedCb((UAVObjEvent *) NULL);
|
||||
|
||||
|
||||
// Main task loop
|
||||
lastSysTime = xTaskGetTickCount();
|
||||
ZeroPids();
|
||||
while(1) {
|
||||
PIOS_WDG_UpdateFlag(PIOS_WDG_STABILIZATION);
|
||||
|
||||
|
||||
// Wait until the AttitudeRaw object is updated, if a timeout then go to failsafe
|
||||
if ( xQueueReceive(queue, &ev, FAILSAFE_TIMEOUT_MS / portTICK_RATE_MS) != pdTRUE )
|
||||
{
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_STABILIZATION,SYSTEMALARMS_ALARM_WARNING);
|
||||
continue;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
// Check how long since last update
|
||||
thisSysTime = xTaskGetTickCount();
|
||||
if(thisSysTime > lastSysTime) // reuse dt in case of wraparound
|
||||
dT = (thisSysTime - lastSysTime) / portTICK_RATE_MS / 1000.0f;
|
||||
lastSysTime = thisSysTime;
|
||||
|
||||
|
||||
FlightStatusGet(&flightStatus);
|
||||
StabilizationDesiredGet(&stabDesired);
|
||||
AttitudeActualGet(&attitudeActual);
|
||||
@ -166,11 +187,11 @@ static void stabilizationTask(void* parameters)
|
||||
float q_desired[4];
|
||||
float q_error[4];
|
||||
float local_error[3];
|
||||
|
||||
|
||||
// Essentially zero errors for anything in rate or none
|
||||
if(stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_ROLL] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE)
|
||||
rpy_desired[0] = stabDesired.Roll;
|
||||
else
|
||||
rpy_desired[0] = stabDesired.Roll;
|
||||
else
|
||||
rpy_desired[0] = attitudeActual.Roll;
|
||||
|
||||
if(stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_PITCH] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE)
|
||||
@ -182,13 +203,13 @@ static void stabilizationTask(void* parameters)
|
||||
rpy_desired[2] = stabDesired.Yaw;
|
||||
else
|
||||
rpy_desired[2] = attitudeActual.Yaw;
|
||||
|
||||
|
||||
RPY2Quaternion(rpy_desired, q_desired);
|
||||
quat_inverse(q_desired);
|
||||
quat_mult(q_desired, &attitudeActual.q1, q_error);
|
||||
quat_inverse(q_error);
|
||||
Quaternion2RPY(q_error, local_error);
|
||||
|
||||
|
||||
#else
|
||||
// Simpler algorithm for CC, less memory
|
||||
float local_error[3] = {stabDesired.Roll - attitudeActual.Roll,
|
||||
@ -196,26 +217,64 @@ static void stabilizationTask(void* parameters)
|
||||
stabDesired.Yaw - attitudeActual.Yaw};
|
||||
local_error[2] = fmod(local_error[2] + 180, 360) - 180;
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
for(uint8_t i = 0; i < MAX_AXES; i++) {
|
||||
gyro_filtered[i] = gyro_filtered[i] * gyro_alpha + attitudeRaw.gyros[i] * (1 - gyro_alpha);
|
||||
}
|
||||
|
||||
float *attitudeDesiredAxis = &stabDesired.Roll;
|
||||
float *actuatorDesiredAxis = &actuatorDesired.Roll;
|
||||
float *rateDesiredAxis = &rateDesired.Roll;
|
||||
|
||||
|
||||
//Calculate desired rate
|
||||
for(int8_t ct=0; ct< MAX_AXES; ct++)
|
||||
for(uint8_t i=0; i< MAX_AXES; i++)
|
||||
{
|
||||
switch(stabDesired.StabilizationMode[ct])
|
||||
switch(stabDesired.StabilizationMode[i])
|
||||
{
|
||||
case STABILIZATIONDESIRED_STABILIZATIONMODE_RATE:
|
||||
rateDesiredAxis[ct] = attitudeDesiredAxis[ct];
|
||||
rateDesiredAxis[i] = attitudeDesiredAxis[i];
|
||||
axis_lock_accum[i] = 0;
|
||||
break;
|
||||
|
||||
|
||||
case STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING:
|
||||
{
|
||||
float weak_leveling = local_error[i] * weak_leveling_kp;
|
||||
|
||||
if(weak_leveling > weak_leveling_max)
|
||||
weak_leveling = weak_leveling_max;
|
||||
if(weak_leveling < -weak_leveling_max)
|
||||
weak_leveling = -weak_leveling_max;
|
||||
|
||||
rateDesiredAxis[i] = attitudeDesiredAxis[i] + weak_leveling;
|
||||
|
||||
axis_lock_accum[i] = 0;
|
||||
break;
|
||||
}
|
||||
case STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE:
|
||||
rateDesiredAxis[ct] = ApplyPid(&pids[PID_ROLL + ct], local_error[ct]);
|
||||
rateDesiredAxis[i] = ApplyPid(&pids[PID_ROLL + i], local_error[i]);
|
||||
axis_lock_accum[i] = 0;
|
||||
break;
|
||||
|
||||
case STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK:
|
||||
if(fabs(attitudeDesiredAxis[i]) > max_axislock_rate) {
|
||||
// While getting strong commands act like rate mode
|
||||
rateDesiredAxis[i] = attitudeDesiredAxis[i];
|
||||
axis_lock_accum[i] = 0;
|
||||
} else {
|
||||
// For weaker commands or no command simply attitude lock (almost) on no gyro change
|
||||
axis_lock_accum[i] += (attitudeDesiredAxis[i] - gyro_filtered[i]) * dT;
|
||||
if(axis_lock_accum[i] > max_axis_lock)
|
||||
axis_lock_accum[i] = max_axis_lock;
|
||||
else if(axis_lock_accum[i] < -max_axis_lock)
|
||||
axis_lock_accum[i] = -max_axis_lock;
|
||||
|
||||
rateDesiredAxis[i] = ApplyPid(&pids[PID_ROLL + i], axis_lock_accum[i]);
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
uint8_t shouldUpdate = 1;
|
||||
#if defined(DIAGNOSTICS)
|
||||
RateDesiredSet(&rateDesired);
|
||||
@ -224,23 +283,19 @@ static void stabilizationTask(void* parameters)
|
||||
//Calculate desired command
|
||||
for(int8_t ct=0; ct< MAX_AXES; ct++)
|
||||
{
|
||||
if(fabs(rateDesiredAxis[ct]) > settings.MaximumRate[ct])
|
||||
{
|
||||
if(rateDesiredAxis[ct] > 0)
|
||||
{
|
||||
rateDesiredAxis[ct] = settings.MaximumRate[ct];
|
||||
}else
|
||||
{
|
||||
rateDesiredAxis[ct] = -settings.MaximumRate[ct];
|
||||
}
|
||||
|
||||
}
|
||||
if(rateDesiredAxis[ct] > settings.MaximumRate[ct])
|
||||
rateDesiredAxis[ct] = settings.MaximumRate[ct];
|
||||
else if(rateDesiredAxis[ct] < -settings.MaximumRate[ct])
|
||||
rateDesiredAxis[ct] = -settings.MaximumRate[ct];
|
||||
|
||||
switch(stabDesired.StabilizationMode[ct])
|
||||
{
|
||||
case STABILIZATIONDESIRED_STABILIZATIONMODE_RATE:
|
||||
case STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE:
|
||||
case STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK:
|
||||
case STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING:
|
||||
{
|
||||
float command = ApplyPid(&pids[PID_RATE_ROLL + ct], rateDesiredAxis[ct]-attitudeRaw.gyros[ct]);
|
||||
float command = ApplyPid(&pids[PID_RATE_ROLL + ct], rateDesiredAxis[ct] - gyro_filtered[ct]);
|
||||
actuatorDesiredAxis[ct] = bound(command);
|
||||
break;
|
||||
}
|
||||
@ -261,16 +316,16 @@ static void stabilizationTask(void* parameters)
|
||||
break;
|
||||
}
|
||||
break;
|
||||
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// Save dT
|
||||
actuatorDesired.UpdateTime = dT * 1000;
|
||||
|
||||
|
||||
if(PARSE_FLIGHT_MODE(flightStatus.FlightMode) == FLIGHTMODE_MANUAL)
|
||||
shouldUpdate = 0;
|
||||
|
||||
|
||||
if(shouldUpdate)
|
||||
{
|
||||
actuatorDesired.Throttle = stabDesired.Throttle;
|
||||
@ -278,16 +333,16 @@ static void stabilizationTask(void* parameters)
|
||||
actuatorDesired.NumLongUpdates++;
|
||||
ActuatorDesiredSet(&actuatorDesired);
|
||||
}
|
||||
|
||||
|
||||
if(flightStatus.Armed != FLIGHTSTATUS_ARMED_ARMED ||
|
||||
!shouldUpdate || (stabDesired.Throttle < 0))
|
||||
!shouldUpdate)
|
||||
{
|
||||
ZeroPids();
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
// Clear alarms
|
||||
AlarmsClear(SYSTEMALARMS_ALARM_STABILIZATION);
|
||||
AlarmsClear(SYSTEMALARMS_ALARM_STABILIZATION);
|
||||
}
|
||||
}
|
||||
|
||||
@ -295,15 +350,15 @@ float ApplyPid(pid_type * pid, const float err)
|
||||
{
|
||||
float diff = (err - pid->lastErr);
|
||||
pid->lastErr = err;
|
||||
pid->iAccumulator += err * pid->i * dT;
|
||||
if(fabs(pid->iAccumulator) > pid->iLim) {
|
||||
if(pid->iAccumulator >0) {
|
||||
pid->iAccumulator = pid->iLim;
|
||||
} else {
|
||||
pid->iAccumulator = -pid->iLim;
|
||||
}
|
||||
|
||||
// Scale up accumulator by 1000 while computing to avoid losing precision
|
||||
pid->iAccumulator += err * (pid->i * dT * 1000);
|
||||
if(pid->iAccumulator > (pid->iLim * 1000)) {
|
||||
pid->iAccumulator = pid->iLim * 1000;
|
||||
} else if (pid->iAccumulator < -(pid->iLim * 1000)) {
|
||||
pid->iAccumulator = -pid->iLim * 1000;
|
||||
}
|
||||
return ((err * pid->p) + pid->iAccumulator + (diff * pid->d / dT));
|
||||
return ((err * pid->p) + pid->iAccumulator / 1000 + (diff * pid->d / dT));
|
||||
}
|
||||
|
||||
|
||||
@ -313,6 +368,8 @@ static void ZeroPids(void)
|
||||
pids[ct].iAccumulator = 0;
|
||||
pids[ct].lastErr = 0;
|
||||
}
|
||||
for(uint8_t i = 0; i < 3; i++)
|
||||
axis_lock_accum[i] = 0;
|
||||
}
|
||||
|
||||
|
||||
@ -334,14 +391,58 @@ static void SettingsUpdatedCb(UAVObjEvent * ev)
|
||||
{
|
||||
memset(pids,0,sizeof (pid_type) * PID_MAX);
|
||||
StabilizationSettingsGet(&settings);
|
||||
|
||||
float * data = settings.RollRatePI;
|
||||
for(int8_t pid=0; pid < PID_MAX; pid++)
|
||||
{
|
||||
pids[pid].p = *data++;
|
||||
pids[pid].i = *data++;
|
||||
pids[pid].iLim = *data++;
|
||||
}
|
||||
|
||||
// Set the roll rate PID constants
|
||||
pids[0].p = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KP];
|
||||
pids[0].i = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KI];
|
||||
pids[0].d = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KD];
|
||||
pids[0].iLim = settings.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_ILIMIT];
|
||||
|
||||
// Set the pitch rate PID constants
|
||||
pids[1].p = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KP];
|
||||
pids[1].i = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KI];
|
||||
pids[1].d = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KD];
|
||||
pids[1].iLim = settings.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_ILIMIT];
|
||||
|
||||
// Set the yaw rate PID constants
|
||||
pids[2].p = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KP];
|
||||
pids[2].i = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KI];
|
||||
pids[2].d = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KD];
|
||||
pids[2].iLim = settings.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_ILIMIT];
|
||||
|
||||
// Set the roll attitude PI constants
|
||||
pids[3].p = settings.RollPI[STABILIZATIONSETTINGS_ROLLPI_KP];
|
||||
pids[3].i = settings.RollPI[STABILIZATIONSETTINGS_ROLLPI_KI];
|
||||
pids[3].iLim = settings.RollPI[STABILIZATIONSETTINGS_ROLLPI_ILIMIT];
|
||||
|
||||
// Set the pitch attitude PI constants
|
||||
pids[4].p = settings.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KP];
|
||||
pids[4].i = settings.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KI];
|
||||
pids[4].iLim = settings.PitchPI[STABILIZATIONSETTINGS_PITCHPI_ILIMIT];
|
||||
|
||||
// Set the yaw attitude PI constants
|
||||
pids[5].p = settings.YawPI[STABILIZATIONSETTINGS_YAWPI_KP];
|
||||
pids[5].i = settings.YawPI[STABILIZATIONSETTINGS_YAWPI_KI];
|
||||
pids[5].iLim = settings.YawPI[STABILIZATIONSETTINGS_YAWPI_ILIMIT];
|
||||
|
||||
// Maximum deviation to accumulate for axis lock
|
||||
max_axis_lock = settings.MaxAxisLock;
|
||||
max_axislock_rate = settings.MaxAxisLockRate;
|
||||
|
||||
// Settings for weak leveling
|
||||
weak_leveling_kp = settings.WeakLevelingKp;
|
||||
weak_leveling_max = settings.MaxWeakLevelingRate;
|
||||
|
||||
// The dT has some jitter iteration to iteration that we don't want to
|
||||
// make thie result unpredictable. Still, it's nicer to specify the constant
|
||||
// based on a time (in ms) rather than a fixed multiplier. The error between
|
||||
// update rates on OP (~300 Hz) and CC (~475 Hz) is negligible for this
|
||||
// calculation
|
||||
const float fakeDt = 0.0025;
|
||||
if(settings.GyroTau < 0.0001)
|
||||
gyro_alpha = 0; // not trusting this to resolve to 0
|
||||
else
|
||||
gyro_alpha = exp(-fakeDt / settings.GyroTau);
|
||||
}
|
||||
|
||||
|
||||
|
@ -87,27 +87,27 @@ static void updateI2Cstats();
|
||||
static void updateWDGstats();
|
||||
#endif
|
||||
/**
|
||||
* Initialise the module, called on startup.
|
||||
* \returns 0 on success or -1 if initialisation failed
|
||||
* Create the module task.
|
||||
* \returns 0 on success or -1 if initialization failed
|
||||
*/
|
||||
int32_t SystemModInitialize(void)
|
||||
int32_t SystemModStart(void)
|
||||
{
|
||||
// Initialize vars
|
||||
stackOverflow = 0;
|
||||
// Create system task
|
||||
xTaskCreate(systemTask, (signed char *)"System", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &systemTaskHandle);
|
||||
// Register task
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_SYSTEM, systemTaskHandle);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* System task, periodically executes every SYSTEM_UPDATE_PERIOD_MS
|
||||
* Initialize the module, called on startup.
|
||||
* \returns 0 on success or -1 if initialization failed
|
||||
*/
|
||||
static void systemTask(void *parameters)
|
||||
int32_t SystemModInitialize(void)
|
||||
{
|
||||
portTickType lastSysTime;
|
||||
|
||||
// System initialization
|
||||
OpenPilotInit();
|
||||
|
||||
// Must registers objects here for system thread because ObjectManager started in OpenPilotInit
|
||||
SystemSettingsInitialize();
|
||||
@ -119,8 +119,21 @@ static void systemTask(void *parameters)
|
||||
WatchdogStatusInitialize();
|
||||
#endif
|
||||
|
||||
// Register task
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_SYSTEM, systemTaskHandle);
|
||||
SystemModStart();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
MODULE_INITCALL(SystemModInitialize, 0)
|
||||
/**
|
||||
* System task, periodically executes every SYSTEM_UPDATE_PERIOD_MS
|
||||
*/
|
||||
static void systemTask(void *parameters)
|
||||
{
|
||||
portTickType lastSysTime;
|
||||
|
||||
/* create all modules thread */
|
||||
MODULE_TASKCREATE_ALL
|
||||
|
||||
// Initialize vars
|
||||
idleCounter = 0;
|
||||
@ -131,7 +144,7 @@ static void systemTask(void *parameters)
|
||||
ObjectPersistenceConnectCallback(&objectUpdatedCb);
|
||||
|
||||
// Main system loop
|
||||
while (1) {
|
||||
while (1) {
|
||||
// Update the system statistics
|
||||
updateStats();
|
||||
|
||||
@ -273,6 +286,48 @@ static void updateWDGstats()
|
||||
#endif
|
||||
|
||||
|
||||
/**
|
||||
* Called periodically to update the system stats
|
||||
*/
|
||||
static uint16_t GetFreeIrqStackSize(void)
|
||||
{
|
||||
uint32_t i = 0x200;
|
||||
|
||||
#if !defined(ARCH_POSIX) && !defined(ARCH_WIN32) && defined(CHECK_IRQ_STACK)
|
||||
extern uint32_t _irq_stack_top;
|
||||
extern uint32_t _irq_stack_end;
|
||||
uint32_t pattern = 0x0000A5A5;
|
||||
uint32_t *ptr = &_irq_stack_end;
|
||||
|
||||
#if 1 /* the ugly way accurate but takes more time, useful for debugging */
|
||||
uint32_t stack_size = (((uint32_t)&_irq_stack_top - (uint32_t)&_irq_stack_end) & ~3 ) / 4;
|
||||
|
||||
for (i=0; i< stack_size; i++)
|
||||
{
|
||||
if (ptr[i] != pattern)
|
||||
{
|
||||
i=i*4;
|
||||
break;
|
||||
}
|
||||
}
|
||||
#else /* faster way but not accurate */
|
||||
if (*(volatile uint32_t *)((uint32_t)ptr + IRQSTACK_LIMIT_CRITICAL) != pattern)
|
||||
{
|
||||
i = IRQSTACK_LIMIT_CRITICAL - 1;
|
||||
}
|
||||
else if (*(volatile uint32_t *)((uint32_t)ptr + IRQSTACK_LIMIT_WARNING) != pattern)
|
||||
{
|
||||
i = IRQSTACK_LIMIT_WARNING - 1;
|
||||
}
|
||||
else
|
||||
{
|
||||
i = IRQSTACK_LIMIT_WARNING;
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
return i;
|
||||
}
|
||||
|
||||
/**
|
||||
* Called periodically to update the system stats
|
||||
*/
|
||||
@ -291,6 +346,9 @@ static void updateStats()
|
||||
stats.HeapRemaining = xPortGetFreeHeapSize();
|
||||
#endif
|
||||
|
||||
// Get Irq stack status
|
||||
stats.IRQStackRemaining = GetFreeIrqStackSize();
|
||||
|
||||
// When idleCounterClear was not reset by the idle-task, it means the idle-task did not run
|
||||
if (idleCounterClear) {
|
||||
idleCounter = 0;
|
||||
@ -333,6 +391,17 @@ static void updateSystemAlarms()
|
||||
AlarmsClear(SYSTEMALARMS_ALARM_OUTOFMEMORY);
|
||||
}
|
||||
|
||||
#if !defined(ARCH_POSIX) && !defined(ARCH_WIN32) && defined(CHECK_IRQ_STACK)
|
||||
// Check IRQ stack
|
||||
if (stats.IRQStackRemaining < IRQSTACK_LIMIT_CRITICAL) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_OUTOFMEMORY, SYSTEMALARMS_ALARM_CRITICAL);
|
||||
} else if (stats.IRQStackRemaining < IRQSTACK_LIMIT_WARNING) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_OUTOFMEMORY, SYSTEMALARMS_ALARM_WARNING);
|
||||
} else {
|
||||
AlarmsClear(SYSTEMALARMS_ALARM_OUTOFMEMORY);
|
||||
}
|
||||
#endif
|
||||
|
||||
// Check CPU load
|
||||
if (stats.CPULoad > CPULOAD_LIMIT_CRITICAL) {
|
||||
AlarmsSet(SYSTEMALARMS_ALARM_CPUOVERLOAD, SYSTEMALARMS_ALARM_CRITICAL);
|
||||
|
@ -31,6 +31,7 @@
|
||||
*/
|
||||
|
||||
#include "openpilot.h"
|
||||
#include "telemetry.h"
|
||||
#include "flighttelemetrystats.h"
|
||||
#include "gcstelemetrystats.h"
|
||||
#include "telemetrysettings.h"
|
||||
@ -80,6 +81,28 @@ static void updateTelemetryStats();
|
||||
static void gcsTelemetryStatsUpdated();
|
||||
static void updateSettings();
|
||||
|
||||
/**
|
||||
* Initialise the telemetry module
|
||||
* \return -1 if initialisation failed
|
||||
* \return 0 on success
|
||||
*/
|
||||
int32_t TelemetryStart(void)
|
||||
{
|
||||
|
||||
// Start telemetry tasks
|
||||
xTaskCreate(telemetryTxTask, (signed char *)"TelTx", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY_TX, &telemetryTxTaskHandle);
|
||||
xTaskCreate(telemetryRxTask, (signed char *)"TelRx", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY_RX, &telemetryRxTaskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_TELEMETRYTX, telemetryTxTaskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_TELEMETRYRX, telemetryRxTaskHandle);
|
||||
|
||||
#if defined(PIOS_TELEM_PRIORITY_QUEUE)
|
||||
xTaskCreate(telemetryTxPriTask, (signed char *)"TelPriTx", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY_TXPRI, &telemetryTxPriTaskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_TELEMETRYTXPRI, telemetryTxPriTaskHandle);
|
||||
#endif
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialise the telemetry module
|
||||
* \return -1 if initialisation failed
|
||||
@ -121,20 +144,11 @@ int32_t TelemetryInitialize(void)
|
||||
GCSTelemetryStatsConnectQueue(priorityQueue);
|
||||
TelemetrySettingsConnectQueue(priorityQueue);
|
||||
|
||||
// Start telemetry tasks
|
||||
xTaskCreate(telemetryTxTask, (signed char *)"TelTx", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY_TX, &telemetryTxTaskHandle);
|
||||
xTaskCreate(telemetryRxTask, (signed char *)"TelRx", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY_RX, &telemetryRxTaskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_TELEMETRYTX, telemetryTxTaskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_TELEMETRYRX, telemetryRxTaskHandle);
|
||||
|
||||
#if defined(PIOS_TELEM_PRIORITY_QUEUE)
|
||||
xTaskCreate(telemetryTxPriTask, (signed char *)"TelPriTx", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY_TXPRI, &telemetryTxPriTaskHandle);
|
||||
TaskMonitorAdd(TASKINFO_RUNNING_TELEMETRYTXPRI, telemetryTxPriTaskHandle);
|
||||
#endif
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
MODULE_INITCALL(TelemetryInitialize, TelemetryStart)
|
||||
|
||||
/**
|
||||
* Register a new object, adds object to local list and connects the queue depending on the object's
|
||||
* telemetry settings.
|
||||
|
@ -43,9 +43,6 @@ 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_SPEKTRUM ?= NO
|
||||
|
||||
|
||||
# Set to YES when using Code Sourcery toolchain
|
||||
CODE_SOURCERY ?= YES
|
||||
|
||||
@ -115,8 +112,6 @@ UAVOBJSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight
|
||||
# List C source files here. (C dependencies are automatically generated.)
|
||||
# use file-extension c for "c-only"-files
|
||||
|
||||
MODNAMES = $(notdir ${MODULES} ${PYMODULES})
|
||||
|
||||
ifndef TESTAPP
|
||||
|
||||
## PyMite files and modules
|
||||
@ -131,7 +126,6 @@ SRC += $(PYSRC)
|
||||
|
||||
## MODULES
|
||||
SRC += ${foreach MOD, ${MODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}}
|
||||
SRC += ${OUTDIR}/InitMods.c
|
||||
## OPENPILOT CORE:
|
||||
SRC += ${OPMODULEDIR}/System/systemmod.c
|
||||
SRC += $(OPSYSTEM)/openpilot.c
|
||||
@ -170,6 +164,7 @@ SRC += $(PIOSSTM32F10X)/pios_spi.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_ppm.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_pwm.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_spektrum.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_sbus.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_debug.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_gpio.c
|
||||
SRC += $(PIOSSTM32F10X)/pios_exti.c
|
||||
@ -194,6 +189,7 @@ SRC += $(PIOSCOMMON)/pios_hcsr04.c
|
||||
SRC += $(PIOSCOMMON)/pios_i2c_esc.c
|
||||
SRC += $(PIOSCOMMON)/pios_iap.c
|
||||
SRC += $(PIOSCOMMON)/pios_bl_helper.c
|
||||
SRC += $(PIOSCOMMON)/pios_rcvr.c
|
||||
SRC += $(PIOSCOMMON)/printf-stdarg.c
|
||||
SRC += $(FLIGHTLIB)/ahrs_spi_comm.c
|
||||
SRC += $(FLIGHTLIB)/ahrs_comm_objects.c
|
||||
@ -363,11 +359,6 @@ ifeq ($(ENABLE_AUX_UART), YES)
|
||||
CDEFS += -DPIOS_ENABLE_AUX_UART
|
||||
endif
|
||||
|
||||
ifeq ($(USE_SPEKTRUM), YES)
|
||||
CDEFS += -DUSE_SPEKTRUM
|
||||
endif
|
||||
|
||||
|
||||
# Place project-specific -D and/or -U options for
|
||||
# Assembler with preprocessor here.
|
||||
#ADEFS = -DUSE_IRQ_ASM_WRAPPER
|
||||
@ -478,19 +469,10 @@ endif
|
||||
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
|
||||
gencode: ${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h
|
||||
|
||||
$(PYSRC): gencode
|
||||
|
||||
# Generate code for module initialization
|
||||
${OUTDIR}/InitMods.c: Makefile
|
||||
@echo $(MSG_MODINIT) $(call toprel, $@)
|
||||
@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) $(call toprel, $@)
|
||||
|
@ -173,6 +173,8 @@ SRC += $(PIOSPOSIX)/pios_servo.c
|
||||
SRC += $(PIOSPOSIX)/pios_wdg.c
|
||||
SRC += $(PIOSPOSIX)/pios_debug.c
|
||||
|
||||
SRC += $(PIOSPOSIX)/pios_rcvr.c
|
||||
|
||||
## Libraries for flight calculations
|
||||
#SRC += $(FLIGHTLIB)/fifo_buffer.c
|
||||
SRC += $(FLIGHTLIB)/WorldMagModel.c
|
||||
@ -441,9 +443,13 @@ ${OUTDIR}/InitMods.c: Makefile.posix
|
||||
@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}${foreach MOD, ${MODNAMES}, extern unsigned int ${MOD}Start(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
|
||||
@echo ${quote}void StartModules() {${quote} >> ${OUTDIR}/InitMods.c
|
||||
@echo ${quote}${foreach MOD, ${MODNAMES}, ${MOD}Start();}${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) $(wildcard $(UAVOBJPYTHONSYNTHDIR)/*.py)
|
||||
|
@ -166,6 +166,7 @@ SRC += $(PIOSWIN32)/pios_udp.c
|
||||
SRC += $(PIOSWIN32)/pios_com.c
|
||||
SRC += $(PIOSWIN32)/pios_servo.c
|
||||
SRC += $(PIOSWIN32)/pios_wdg.c
|
||||
SRC += $(PIOSWIN32)/pios_crc.c
|
||||
#
|
||||
## RTOS
|
||||
SRC += $(RTOSSRCDIR)/list.c
|
||||
|
@ -87,6 +87,9 @@ do {\
|
||||
#define configCHECK_FOR_STACK_OVERFLOW 1
|
||||
#endif
|
||||
|
||||
#if !defined(ARCH_POSIX) && !defined(ARCH_WIN32)
|
||||
#define CHECK_IRQ_STACK
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @}
|
||||
|
@ -42,12 +42,14 @@
|
||||
#define PIOS_INCLUDE_IRQ
|
||||
#define PIOS_INCLUDE_LED
|
||||
|
||||
#if defined(USE_SPEKTRUM)
|
||||
#define PIOS_INCLUDE_RCVR
|
||||
|
||||
#define PIOS_INCLUDE_SPEKTRUM
|
||||
#else
|
||||
//#define PIOS_INCLUDE_PPM
|
||||
//#define PIOS_INCLUDE_SBUS
|
||||
#define PIOS_INCLUDE_PWM
|
||||
#endif
|
||||
//#define PIOS_INCLUDE_PPM
|
||||
|
||||
#define PIOS_INCLUDE_TELEMETRY_RF
|
||||
|
||||
#define PIOS_INCLUDE_SERVO
|
||||
#define PIOS_INCLUDE_SPI
|
||||
@ -84,6 +86,8 @@
|
||||
/* Alarm Thresholds */
|
||||
#define HEAP_LIMIT_WARNING 4000
|
||||
#define HEAP_LIMIT_CRITICAL 1000
|
||||
#define IRQSTACK_LIMIT_WARNING 150
|
||||
#define IRQSTACK_LIMIT_CRITICAL 80
|
||||
#define CPULOAD_LIMIT_WARNING 80
|
||||
#define CPULOAD_LIMIT_CRITICAL 95
|
||||
|
||||
|
@ -38,7 +38,10 @@
|
||||
#define PIOS_INCLUDE_COM
|
||||
#define PIOS_INCLUDE_UDP
|
||||
#define PIOS_INCLUDE_SERVO
|
||||
#define PIOS_INCLUDE_RCVR
|
||||
|
||||
#define PIOS_RCVR_MAX_CHANNELS 12
|
||||
#define PIOS_RCVR_MAX_DEVS 3
|
||||
|
||||
/* Defaults for Logging */
|
||||
#define LOG_FILENAME "PIOS.LOG"
|
||||
|
@ -62,11 +62,10 @@ static void TaskSDCard(void *pvParameters);
|
||||
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);
|
||||
extern void Stack_Change(void);
|
||||
static void Stack_Change_Weak () __attribute__ ((weakref ("Stack_Change")));
|
||||
|
||||
/**
|
||||
* OpenPilot Main function:
|
||||
@ -85,48 +84,42 @@ int main()
|
||||
/* 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();
|
||||
MODULE_INITIALISE_ALL
|
||||
|
||||
#if INCLUDE_TEST_TASKS
|
||||
/* 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);
|
||||
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);
|
||||
#endif
|
||||
|
||||
/* swap the stack to use the IRQ stack (does nothing in sim mode) */
|
||||
Stack_Change_Weak();
|
||||
|
||||
/* Start the FreeRTOS scheduler which should never returns.*/
|
||||
vTaskStartScheduler();
|
||||
|
||||
/* If all is well we will never reach here as the scheduler will now be running. */
|
||||
|
||||
/* Do some indication to user that something bad just happened */
|
||||
PIOS_LED_Off(LED1); \
|
||||
for(;;) { \
|
||||
PIOS_LED_Toggle(LED1); \
|
||||
PIOS_DELAY_WaitmS(100); \
|
||||
};
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
#if INCLUDE_TEST_TASKS
|
||||
static void TaskTesting(void *pvParameters)
|
||||
{
|
||||
@ -153,6 +146,9 @@ static void TaskTesting(void *pvParameters)
|
||||
#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_SBUS)
|
||||
PIOS_COM_SendFormattedStringNonBlocking(COM_DEBUG_USART, "%u,%u,%u,%u,%u,%u,%u,%u\r", PIOS_SBUS_Get(0), PIOS_SBUS_Get(1), PIOS_SBUS_Get(2), PIOS_SBUS_Get(3), PIOS_SBUS_Get(4), PIOS_SBUS_Get(5), PIOS_SBUS_Get(6), PIOS_SBUS_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
|
||||
@ -339,5 +335,5 @@ static void TaskSDCard(void *pvParameters)
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
||||
*/
|
||||
|
||||
|
@ -30,6 +30,7 @@
|
||||
#include <pios.h>
|
||||
#include <openpilot.h>
|
||||
#include <uavobjectsinit.h>
|
||||
#include "manualcontrolsettings.h"
|
||||
|
||||
//#define I2C_DEBUG_PIN 0
|
||||
//#define USART_GPS_DEBUG_PIN 1
|
||||
@ -46,7 +47,7 @@
|
||||
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 = {
|
||||
static const struct pios_spi_cfg pios_spi_sdcard_cfg = {
|
||||
.regs = SPI1,
|
||||
.init = {
|
||||
.SPI_Mode = SPI_Mode_Master,
|
||||
@ -63,7 +64,7 @@ const struct pios_spi_cfg pios_spi_sdcard_cfg = {
|
||||
.ahb_clk = RCC_AHBPeriph_DMA1,
|
||||
|
||||
.irq = {
|
||||
.handler = PIOS_SPI_sdcard_irq_handler,
|
||||
.handler = NULL,
|
||||
.flags = (DMA1_FLAG_TC2 | DMA1_FLAG_TE2 | DMA1_FLAG_HT2 | DMA1_FLAG_GL2),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA1_Channel2_IRQn,
|
||||
@ -144,7 +145,7 @@ const struct pios_spi_cfg pios_spi_sdcard_cfg = {
|
||||
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 = {
|
||||
static const struct pios_spi_cfg pios_spi_ahrs_cfg = {
|
||||
.regs = SPI2,
|
||||
.init = {
|
||||
.SPI_Mode = SPI_Mode_Master,
|
||||
@ -162,7 +163,7 @@ const struct pios_spi_cfg pios_spi_ahrs_cfg = {
|
||||
.ahb_clk = RCC_AHBPeriph_DMA1,
|
||||
|
||||
.irq = {
|
||||
.handler = PIOS_SPI_ahrs_irq_handler,
|
||||
.handler = NULL,
|
||||
.flags = (DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 | DMA1_FLAG_GL4),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA1_Channel4_IRQn,
|
||||
@ -258,11 +259,11 @@ void PIOS_SPI_ahrs_irq_handler(void)
|
||||
extern void PIOS_ADC_handler(void);
|
||||
void DMA1_Channel1_IRQHandler() __attribute__ ((alias("PIOS_ADC_handler")));
|
||||
// Remap the ADC DMA handler to this one
|
||||
const struct pios_adc_cfg pios_adc_cfg = {
|
||||
static const struct pios_adc_cfg pios_adc_cfg = {
|
||||
.dma = {
|
||||
.ahb_clk = RCC_AHBPeriph_DMA1,
|
||||
.irq = {
|
||||
.handler = PIOS_ADC_DMA_Handler,
|
||||
.handler = NULL,
|
||||
.flags = (DMA1_FLAG_TC1 | DMA1_FLAG_TE1 | DMA1_FLAG_HT1 | DMA1_FLAG_GL1),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA1_Channel1_IRQn,
|
||||
@ -310,16 +311,10 @@ void PIOS_ADC_handler() {
|
||||
/*
|
||||
* 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 = {
|
||||
static 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_BaudRate = 57600,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
@ -327,7 +322,7 @@ const struct pios_usart_cfg pios_usart_telem_cfg = {
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.handler = PIOS_USART_telem_irq_handler,
|
||||
.handler = NULL,
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART2_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
@ -356,17 +351,11 @@ const struct pios_usart_cfg pios_usart_telem_cfg = {
|
||||
/*
|
||||
* 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 = {
|
||||
static 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_BaudRate = 57600,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
@ -374,7 +363,7 @@ const struct pios_usart_cfg pios_usart_gps_cfg = {
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.handler = PIOS_USART_gps_irq_handler,
|
||||
.handler = NULL,
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART3_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
@ -404,16 +393,9 @@ const struct pios_usart_cfg pios_usart_gps_cfg = {
|
||||
/*
|
||||
* 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 = {
|
||||
static 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,
|
||||
@ -422,7 +404,7 @@ const struct pios_usart_cfg pios_usart_aux_cfg = {
|
||||
.USART_Mode = USART_Mode_Rx | USART_Mode_Tx,
|
||||
},
|
||||
.irq = {
|
||||
.handler = PIOS_USART_aux_irq_handler,
|
||||
.handler = NULL,
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART1_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
@ -450,20 +432,45 @@ const struct pios_usart_cfg pios_usart_aux_cfg = {
|
||||
};
|
||||
#endif
|
||||
|
||||
#if defined(PIOS_INCLUDE_RTC)
|
||||
/*
|
||||
* Realtime Clock (RTC)
|
||||
*/
|
||||
#include <pios_rtc_priv.h>
|
||||
|
||||
void PIOS_RTC_IRQ_Handler (void);
|
||||
void RTC_IRQHandler() __attribute__ ((alias ("PIOS_RTC_IRQ_Handler")));
|
||||
static const struct pios_rtc_cfg pios_rtc_main_cfg = {
|
||||
.clksrc = RCC_RTCCLKSource_HSE_Div128,
|
||||
.prescaler = 100,
|
||||
.irq = {
|
||||
.handler = NULL,
|
||||
.init = {
|
||||
.NVIC_IRQChannel = RTC_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
},
|
||||
};
|
||||
|
||||
void PIOS_RTC_IRQ_Handler (void)
|
||||
{
|
||||
PIOS_RTC_irq_handler ();
|
||||
}
|
||||
|
||||
#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 = {
|
||||
#include <pios_spektrum_priv.h>
|
||||
|
||||
static 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_BaudRate = 115200,
|
||||
.USART_WordLength = USART_WordLength_8b,
|
||||
.USART_Parity = USART_Parity_No,
|
||||
.USART_StopBits = USART_StopBits_1,
|
||||
@ -471,7 +478,7 @@ const struct pios_usart_cfg pios_usart_spektrum_cfg = {
|
||||
.USART_Mode = USART_Mode_Rx,
|
||||
},
|
||||
.irq = {
|
||||
.handler = PIOS_USART_spektrum_irq_handler,
|
||||
.handler = PIOS_SPEKTRUM_irq_handler,
|
||||
.init = {
|
||||
.NVIC_IRQChannel = USART1_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
@ -497,74 +504,30 @@ const struct pios_usart_cfg pios_usart_spektrum_cfg = {
|
||||
},
|
||||
};
|
||||
|
||||
#include <pios_spektrum_priv.h>
|
||||
static uint32_t pios_usart_spektrum_id;
|
||||
void PIOS_USART_spektrum_irq_handler(void)
|
||||
{
|
||||
SPEKTRUM_IRQHandler(pios_usart_spektrum_id);
|
||||
PIOS_SPEKTRUM_irq_handler(pios_usart_spektrum_id);
|
||||
}
|
||||
|
||||
#include <pios_spektrum_priv.h>
|
||||
void RTC_IRQHandler();
|
||||
void RTC_IRQHandler() __attribute__ ((alias ("PIOS_SUPV_irq_handler")));
|
||||
const struct pios_spektrum_cfg pios_spektrum_cfg = {
|
||||
.pios_usart_spektrum_cfg = &pios_usart_spektrum_cfg,
|
||||
.gpio_init = { //used for bind feature
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
},
|
||||
.remap = 0,
|
||||
.irq = {
|
||||
.handler = RTC_IRQHandler,
|
||||
.init = {
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
static const struct pios_spektrum_cfg pios_spektrum_cfg = {
|
||||
.bind = {
|
||||
.gpio = GPIOA,
|
||||
.init = {
|
||||
.GPIO_Pin = GPIO_Pin_10,
|
||||
.GPIO_Speed = GPIO_Speed_2MHz,
|
||||
.GPIO_Mode = GPIO_Mode_Out_PP,
|
||||
},
|
||||
},
|
||||
.port = GPIOA,
|
||||
.pin = GPIO_Pin_10,
|
||||
.remap = 0,
|
||||
};
|
||||
|
||||
void PIOS_SUPV_irq_handler() {
|
||||
if (RTC_GetITStatus(RTC_IT_SEC))
|
||||
{
|
||||
/* Call the right handler */
|
||||
PIOS_SPEKTRUM_irq_handler(pios_usart_spektrum_id);
|
||||
|
||||
/* Wait until last write operation on RTC registers has finished */
|
||||
RTC_WaitForLastTask();
|
||||
/* Clear the RTC Second interrupt */
|
||||
RTC_ClearITPendingBit(RTC_IT_SEC);
|
||||
}
|
||||
}
|
||||
#endif /* PIOS_COM_SPEKTRUM */
|
||||
|
||||
static uint32_t pios_usart_telem_rf_id;
|
||||
void PIOS_USART_telem_irq_handler(void)
|
||||
{
|
||||
PIOS_USART_IRQ_Handler(pios_usart_telem_rf_id);
|
||||
}
|
||||
|
||||
static uint32_t pios_usart_gps_id;
|
||||
void PIOS_USART_gps_irq_handler(void)
|
||||
{
|
||||
#ifdef USART_GPS_DEBUG_PIN
|
||||
PIOS_DEBUG_PinHigh(USART_GPS_DEBUG_PIN);
|
||||
#endif
|
||||
PIOS_USART_IRQ_Handler(pios_usart_gps_id);
|
||||
#ifdef USART_GPS_DEBUG_PIN
|
||||
PIOS_DEBUG_PinLow(USART_GPS_DEBUG_PIN);
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
#ifdef PIOS_COM_AUX
|
||||
static uint32_t pios_usart_aux_id;
|
||||
void PIOS_USART_aux_irq_handler(void)
|
||||
{
|
||||
PIOS_USART_IRQ_Handler(pios_usart_aux_id);
|
||||
}
|
||||
#endif
|
||||
#if defined(PIOS_INCLUDE_SBUS)
|
||||
#error PIOS_INCLUDE_SBUS not implemented
|
||||
#endif /* PIOS_INCLUDE_SBUS */
|
||||
|
||||
#endif /* PIOS_INCLUDE_USART */
|
||||
|
||||
@ -578,7 +541,7 @@ void PIOS_USART_aux_irq_handler(void)
|
||||
* Pios servo configuration structures
|
||||
*/
|
||||
#include <pios_servo_priv.h>
|
||||
const struct pios_servo_channel pios_servo_channels[] = {
|
||||
static const struct pios_servo_channel pios_servo_channels[] = {
|
||||
{
|
||||
.timer = TIM4,
|
||||
.port = GPIOB,
|
||||
@ -662,7 +625,7 @@ const struct pios_servo_cfg pios_servo_cfg = {
|
||||
*/
|
||||
#if defined(PIOS_INCLUDE_PWM)
|
||||
#include <pios_pwm_priv.h>
|
||||
const struct pios_pwm_channel pios_pwm_channels[] = {
|
||||
static const struct pios_pwm_channel pios_pwm_channels[] = {
|
||||
{
|
||||
.timer = TIM1,
|
||||
.port = GPIOA,
|
||||
@ -747,7 +710,7 @@ const struct pios_pwm_cfg pios_pwm_cfg = {
|
||||
},
|
||||
.remap = GPIO_PartialRemap_TIM3,
|
||||
.irq = {
|
||||
.handler = TIM1_CC_IRQHandler,
|
||||
.handler = NULL,
|
||||
.init = {
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
@ -778,7 +741,7 @@ void PIOS_TIM5_irq_handler()
|
||||
#include <pios_ppm_priv.h>
|
||||
void TIM6_IRQHandler();
|
||||
void TIM6_IRQHandler() __attribute__ ((alias ("PIOS_TIM6_irq_handler")));
|
||||
const struct pios_ppmsv_cfg pios_ppmsv_cfg = {
|
||||
static const struct pios_ppmsv_cfg pios_ppmsv_cfg = {
|
||||
.tim_base_init = {
|
||||
.TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1, /* For 1 uS accuracy */
|
||||
.TIM_ClockDivision = TIM_CKD_DIV1,
|
||||
@ -787,7 +750,7 @@ const struct pios_ppmsv_cfg pios_ppmsv_cfg = {
|
||||
.TIM_RepetitionCounter = 0x0000,
|
||||
},
|
||||
.irq = {
|
||||
.handler = TIM6_IRQHandler,
|
||||
.handler = NULL,
|
||||
.init = {
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
@ -798,14 +761,14 @@ const struct pios_ppmsv_cfg pios_ppmsv_cfg = {
|
||||
.ccr = TIM_IT_Update,
|
||||
};
|
||||
|
||||
void PIOS_TIM6_irq_handler()
|
||||
void PIOS_TIM6_irq_handler(void)
|
||||
{
|
||||
PIOS_PPMSV_irq_handler();
|
||||
}
|
||||
|
||||
void TIM1_CC_IRQHandler();
|
||||
void TIM1_CC_IRQHandler() __attribute__ ((alias ("PIOS_TIM1_CC_irq_handler")));
|
||||
const struct pios_ppm_cfg pios_ppm_cfg = {
|
||||
static const struct pios_ppm_cfg pios_ppm_cfg = {
|
||||
.tim_base_init = {
|
||||
.TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1, /* For 1 uS accuracy */
|
||||
.TIM_ClockDivision = TIM_CKD_DIV1,
|
||||
@ -827,7 +790,7 @@ const struct pios_ppm_cfg pios_ppm_cfg = {
|
||||
},
|
||||
.remap = 0,
|
||||
.irq = {
|
||||
.handler = TIM1_CC_IRQHandler,
|
||||
.handler = NULL,
|
||||
.init = {
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
@ -840,7 +803,7 @@ const struct pios_ppm_cfg pios_ppm_cfg = {
|
||||
.ccr = TIM_IT_CC2,
|
||||
};
|
||||
|
||||
void PIOS_TIM1_CC_irq_handler()
|
||||
void PIOS_TIM1_CC_irq_handler(void)
|
||||
{
|
||||
PIOS_PPM_irq_handler();
|
||||
}
|
||||
@ -860,7 +823,7 @@ 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 = {
|
||||
static const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = {
|
||||
.regs = I2C2,
|
||||
.init = {
|
||||
.I2C_Mode = I2C_Mode_I2C,
|
||||
@ -888,7 +851,7 @@ const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = {
|
||||
},
|
||||
},
|
||||
.event = {
|
||||
.handler = PIOS_I2C_main_adapter_ev_irq_handler,
|
||||
.handler = NULL,
|
||||
.flags = 0, /* FIXME: check this */
|
||||
.init = {
|
||||
.NVIC_IRQChannel = I2C2_EV_IRQn,
|
||||
@ -898,7 +861,7 @@ const struct pios_i2c_adapter_cfg pios_i2c_main_adapter_cfg = {
|
||||
},
|
||||
},
|
||||
.error = {
|
||||
.handler = PIOS_I2C_main_adapter_er_irq_handler,
|
||||
.handler = NULL,
|
||||
.flags = 0, /* FIXME: check this */
|
||||
.init = {
|
||||
.NVIC_IRQChannel = I2C2_ER_IRQn,
|
||||
@ -1009,6 +972,13 @@ static const struct stm32_gpio pios_debug_pins[] = {
|
||||
|
||||
#endif /* PIOS_ENABLE_DEBUG_PINS */
|
||||
|
||||
#if defined(PIOS_INCLUDE_RCVR)
|
||||
#include "pios_rcvr_priv.h"
|
||||
|
||||
struct pios_rcvr_channel_map pios_rcvr_channel_to_id_map[PIOS_RCVR_MAX_CHANNELS];
|
||||
uint32_t pios_rcvr_max_channel;
|
||||
#endif /* PIOS_INCLUDE_RCVR */
|
||||
|
||||
extern const struct pios_com_driver pios_usb_com_driver;
|
||||
|
||||
uint32_t pios_com_telem_rf_id;
|
||||
@ -1038,7 +1008,7 @@ void PIOS_Board_Init(void) {
|
||||
#if defined(PIOS_INCLUDE_SPI)
|
||||
/* Set up the SPI interface to the SD card */
|
||||
if (PIOS_SPI_Init(&pios_spi_sdcard_id, &pios_spi_sdcard_cfg)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
/* Enable and mount the SDCard */
|
||||
@ -1046,23 +1016,16 @@ void PIOS_Board_Init(void) {
|
||||
PIOS_SDCARD_MountFS(0);
|
||||
#endif /* PIOS_INCLUDE_SPI */
|
||||
|
||||
#if defined(PIOS_INCLUDE_SPEKTRUM)
|
||||
/* SPEKTRUM init must come before comms */
|
||||
PIOS_RTC_Init(); // Spektrum uses RTC to check for frame failures
|
||||
PIOS_SPEKTRUM_Init();
|
||||
|
||||
if (PIOS_USART_Init(&pios_usart_spektrum_id, &pios_usart_spektrum_cfg)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
if (PIOS_COM_Init(&pios_com_spektrum_id, &pios_usart_com_driver, pios_usart_spektrum_id)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
#endif
|
||||
/* Initialize UAVObject libraries */
|
||||
EventDispatcherInitialize();
|
||||
UAVObjInitialize();
|
||||
UAVObjectsInitializeAll();
|
||||
|
||||
#if defined(PIOS_INCLUDE_RTC)
|
||||
/* Initialize the real-time clock and its associated tick */
|
||||
PIOS_RTC_Init(&pios_rtc_main_cfg);
|
||||
#endif
|
||||
|
||||
/* Initialize the alarms library */
|
||||
AlarmsInitialize();
|
||||
|
||||
@ -1074,7 +1037,7 @@ void PIOS_Board_Init(void) {
|
||||
|
||||
/* Set up the SPI interface to the AHRS */
|
||||
if (PIOS_SPI_Init(&pios_spi_ahrs_id, &pios_spi_ahrs_cfg)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
|
||||
/* Bind the AHRS comms layer to the AHRS SPI link */
|
||||
@ -1082,43 +1045,119 @@ void PIOS_Board_Init(void) {
|
||||
|
||||
/* Initialize the PiOS library */
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
#if defined(PIOS_INCLUDE_TELEMETRY_RF)
|
||||
uint32_t pios_usart_telem_rf_id;
|
||||
if (PIOS_USART_Init(&pios_usart_telem_rf_id, &pios_usart_telem_cfg)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_usart_com_driver, pios_usart_telem_rf_id)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_TELEMETRY_RF */
|
||||
|
||||
#if defined(PIOS_INCLUDE_GPS)
|
||||
uint32_t pios_usart_gps_id;
|
||||
if (PIOS_USART_Init(&pios_usart_gps_id, &pios_usart_gps_cfg)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
if (PIOS_COM_Init(&pios_com_gps_id, &pios_usart_com_driver, pios_usart_gps_id)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_GPS */
|
||||
#endif
|
||||
|
||||
PIOS_Servo_Init();
|
||||
PIOS_ADC_Init();
|
||||
PIOS_GPIO_Init();
|
||||
|
||||
/* Configure the selected receiver */
|
||||
uint8_t manualcontrolsettings_inputmode;
|
||||
ManualControlSettingsInputModeGet(&manualcontrolsettings_inputmode);
|
||||
|
||||
switch (manualcontrolsettings_inputmode) {
|
||||
case MANUALCONTROLSETTINGS_INPUTMODE_PWM:
|
||||
#if defined(PIOS_INCLUDE_PWM)
|
||||
PIOS_PWM_Init();
|
||||
#if (PIOS_PWM_NUM_INPUTS > PIOS_RCVR_MAX_CHANNELS)
|
||||
#error More receiver inputs than available devices
|
||||
#endif
|
||||
PIOS_PWM_Init();
|
||||
uint32_t pios_pwm_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_pwm_rcvr_id, &pios_pwm_rcvr_driver, 0)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
for (uint8_t i = 0;
|
||||
i < PIOS_PWM_NUM_INPUTS && pios_rcvr_max_channel < NELEMENTS(pios_rcvr_channel_to_id_map);
|
||||
i++) {
|
||||
pios_rcvr_channel_to_id_map[pios_rcvr_max_channel].id = pios_pwm_rcvr_id;
|
||||
pios_rcvr_channel_to_id_map[pios_rcvr_max_channel].channel = i;
|
||||
pios_rcvr_max_channel++;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_PWM */
|
||||
break;
|
||||
case MANUALCONTROLSETTINGS_INPUTMODE_PPM:
|
||||
#if defined(PIOS_INCLUDE_PPM)
|
||||
PIOS_PPM_Init();
|
||||
#if (PIOS_PPM_NUM_INPUTS > PIOS_RCVR_MAX_CHANNELS)
|
||||
#error More receiver inputs than available devices
|
||||
#endif
|
||||
PIOS_PPM_Init();
|
||||
uint32_t pios_ppm_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, 0)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
for (uint8_t i = 0;
|
||||
i < PIOS_PPM_NUM_INPUTS && pios_rcvr_max_channel < NELEMENTS(pios_rcvr_channel_to_id_map);
|
||||
i++) {
|
||||
pios_rcvr_channel_to_id_map[pios_rcvr_max_channel].id = pios_ppm_rcvr_id;
|
||||
pios_rcvr_channel_to_id_map[pios_rcvr_max_channel].channel = i;
|
||||
pios_rcvr_max_channel++;
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_PPM */
|
||||
break;
|
||||
case MANUALCONTROLSETTINGS_INPUTMODE_SPEKTRUM:
|
||||
#if defined(PIOS_INCLUDE_SPEKTRUM)
|
||||
#if (PIOS_SPEKTRUM_NUM_INPUTS > PIOS_RCVR_MAX_CHANNELS)
|
||||
#error More receiver inputs than available devices
|
||||
#endif
|
||||
/* SPEKTRUM init must come before comms */
|
||||
PIOS_SPEKTRUM_Init(&pios_spektrum_cfg, false);
|
||||
|
||||
uint32_t pios_usart_spektrum_id;
|
||||
if (PIOS_USART_Init(&pios_usart_spektrum_id, &pios_usart_spektrum_cfg)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
uint32_t pios_spektrum_rcvr_id;
|
||||
if (PIOS_RCVR_Init(&pios_spektrum_rcvr_id, &pios_spektrum_rcvr_driver, 0)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
for (uint8_t i = 0;
|
||||
i < PIOS_SPEKTRUM_NUM_INPUTS && pios_rcvr_max_channel < NELEMENTS(pios_rcvr_channel_to_id_map);
|
||||
i++) {
|
||||
pios_rcvr_channel_to_id_map[pios_rcvr_max_channel].id = pios_spektrum_rcvr_id;
|
||||
pios_rcvr_channel_to_id_map[pios_rcvr_max_channel].channel = i;
|
||||
pios_rcvr_max_channel++;
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
case MANUALCONTROLSETTINGS_INPUTMODE_SBUS:
|
||||
#if defined(PIOS_INCLUDE_SBUS)
|
||||
#error SBUS NOT ON OP YET
|
||||
#endif /* PIOS_INCLUDE_SBUS */
|
||||
break;
|
||||
}
|
||||
|
||||
|
||||
#if defined(PIOS_INCLUDE_USB_HID)
|
||||
PIOS_USB_HID_Init(0);
|
||||
#if defined(PIOS_INCLUDE_COM)
|
||||
if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_com_driver, 0)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_COM */
|
||||
#endif /* PIOS_INCLUDE_USB_HID */
|
||||
|
||||
#if defined(PIOS_INCLUDE_I2C)
|
||||
if (PIOS_I2C_Init(&pios_i2c_main_adapter_id, &pios_i2c_main_adapter_cfg)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
#endif /* PIOS_INCLUDE_I2C */
|
||||
PIOS_IAP_Init();
|
||||
|
@ -29,6 +29,17 @@
|
||||
#include <openpilot.h>
|
||||
#include <uavobjectsinit.h>
|
||||
|
||||
#include "pios_rcvr_priv.h"
|
||||
|
||||
struct pios_rcvr_channel_map pios_rcvr_channel_to_id_map[PIOS_RCVR_MAX_CHANNELS];
|
||||
uint32_t pios_rcvr_max_channel;
|
||||
|
||||
void Stack_Change() {
|
||||
}
|
||||
|
||||
void Stack_Change_Weak() {
|
||||
}
|
||||
|
||||
/**
|
||||
* PIOS_Board_Init()
|
||||
* initializes all the core systems on this specific hardware
|
||||
|
@ -38,7 +38,32 @@
|
||||
* and we cannot define a linker script for each of them atm
|
||||
*/
|
||||
|
||||
#define uavobj_initcall(fn)
|
||||
|
||||
typedef int32_t (*initcall_t)(void);
|
||||
typedef struct {
|
||||
initcall_t fn_minit;
|
||||
initcall_t fn_tinit;
|
||||
} initmodule_t;
|
||||
|
||||
/* Init module section */
|
||||
extern initmodule_t __module_initcall_start[], __module_initcall_end[];
|
||||
|
||||
extern void InitModules();
|
||||
extern void StartModules();
|
||||
|
||||
#define UAVOBJ_INITCALL(fn)
|
||||
#define MODULE_INITCALL(ifn, sfn)
|
||||
|
||||
#define MODULE_TASKCREATE_ALL { \
|
||||
/* Start all module threads */ \
|
||||
StartModules(); \
|
||||
}
|
||||
|
||||
#define MODULE_INITIALISE_ALL { \
|
||||
/* Initialize modules */ \
|
||||
InitModules(); \
|
||||
/* Initialize the system thread */ \
|
||||
SystemModInitialize();}
|
||||
|
||||
#endif /* PIOS_INITCALL_H */
|
||||
|
||||
|
54
flight/PiOS.posix/inc/pios_rcvr.h
Normal file
@ -0,0 +1,54 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_RCVR RCVR layer functions
|
||||
* @brief Hardware communication layer
|
||||
* @{
|
||||
*
|
||||
* @file pios_rcvr.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief RCVR layer functions 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 PIOS_RCVR_H
|
||||
#define PIOS_RCVR_H
|
||||
|
||||
struct pios_rcvr_channel_map {
|
||||
uint32_t id;
|
||||
uint8_t channel;
|
||||
};
|
||||
|
||||
extern struct pios_rcvr_channel_map pios_rcvr_channel_to_id_map[];
|
||||
|
||||
struct pios_rcvr_driver {
|
||||
void (*init)(uint32_t id);
|
||||
int32_t (*read)(uint32_t id, uint8_t channel);
|
||||
};
|
||||
|
||||
/* Public Functions */
|
||||
extern int32_t PIOS_RCVR_Read(uint32_t rcvr_id, uint8_t channel);
|
||||
|
||||
#endif /* PIOS_RCVR_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
48
flight/PiOS.posix/inc/pios_rcvr_priv.h
Normal file
@ -0,0 +1,48 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_RCVR RCVR Functions
|
||||
* @brief PIOS interface for RCVR drivers
|
||||
* @{
|
||||
*
|
||||
* @file pios_rcvr_priv.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* Parts by Thorsten Klose (tk@midibox.org)
|
||||
* @brief USART private definitions.
|
||||
* @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_RCVR_PRIV_H
|
||||
#define PIOS_RCVR_PRIV_H
|
||||
|
||||
#include <pios.h>
|
||||
|
||||
extern uint32_t pios_rcvr_max_channel;
|
||||
|
||||
extern int32_t PIOS_RCVR_Init(uint32_t * rcvr_id, const struct pios_rcvr_driver * driver, const uint32_t lower_id);
|
||||
|
||||
extern void PIOS_RCVR_IRQ_Handler(uint32_t rcvr_id);
|
||||
|
||||
#endif /* PIOS_RCVR_PRIV_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -65,6 +65,7 @@
|
||||
#include <pios_wdg.h>
|
||||
#include <pios_debug.h>
|
||||
#include <pios_crc.h>
|
||||
#include <pios_rcvr.h>
|
||||
|
||||
#define NELEMENTS(x) (sizeof(x) / sizeof(*(x)))
|
||||
|
||||
|
@ -67,10 +67,6 @@ int32_t PIOS_DELAY_WaituS(uint16_t uS)
|
||||
while (!nanosleep(&wait,&rest)) {
|
||||
wait=rest;
|
||||
}
|
||||
//uint16_t start = PIOS_DELAY_TIMER->CNT;
|
||||
|
||||
/* Note that this event works on 16bit counter wrap-arounds */
|
||||
//while((uint16_t)(PIOS_DELAY_TIMER->CNT - start) <= uS);
|
||||
|
||||
/* No error */
|
||||
return 0;
|
||||
|
100
flight/PiOS.posix/posix/pios_rcvr.c
Normal file
@ -0,0 +1,100 @@
|
||||
/* Project Includes */
|
||||
#include "pios.h"
|
||||
|
||||
#if defined(PIOS_INCLUDE_RCVR)
|
||||
|
||||
#include <pios_rcvr_priv.h>
|
||||
|
||||
enum pios_rcvr_dev_magic {
|
||||
PIOS_RCVR_DEV_MAGIC = 0x99aabbcc,
|
||||
};
|
||||
|
||||
struct pios_rcvr_dev {
|
||||
enum pios_rcvr_dev_magic magic;
|
||||
uint32_t lower_id;
|
||||
const struct pios_rcvr_driver * driver;
|
||||
};
|
||||
|
||||
static bool PIOS_RCVR_validate(struct pios_rcvr_dev * rcvr_dev)
|
||||
{
|
||||
return (rcvr_dev->magic == PIOS_RCVR_DEV_MAGIC);
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_FREERTOS) && 0
|
||||
static struct pios_rcvr_dev * PIOS_RCVR_alloc(void)
|
||||
{
|
||||
struct pios_rcvr_dev * rcvr_dev;
|
||||
|
||||
rcvr_dev = (struct pios_rcvr_dev *)malloc(sizeof(*rcvr_dev));
|
||||
if (!rcvr_dev) return (NULL);
|
||||
|
||||
rcvr_dev->magic = PIOS_RCVR_DEV_MAGIC;
|
||||
return(rcvr_dev);
|
||||
}
|
||||
#else
|
||||
static struct pios_rcvr_dev pios_rcvr_devs[PIOS_RCVR_MAX_DEVS];
|
||||
static uint8_t pios_rcvr_num_devs;
|
||||
static struct pios_rcvr_dev * PIOS_RCVR_alloc(void)
|
||||
{
|
||||
struct pios_rcvr_dev * rcvr_dev;
|
||||
|
||||
if (pios_rcvr_num_devs >= PIOS_RCVR_MAX_DEVS) {
|
||||
return (NULL);
|
||||
}
|
||||
|
||||
rcvr_dev = &pios_rcvr_devs[pios_rcvr_num_devs++];
|
||||
rcvr_dev->magic = PIOS_RCVR_DEV_MAGIC;
|
||||
|
||||
return (rcvr_dev);
|
||||
}
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Initialises RCVR layer
|
||||
* \param[out] handle
|
||||
* \param[in] driver
|
||||
* \param[in] id
|
||||
* \return < 0 if initialisation failed
|
||||
*/
|
||||
int32_t PIOS_RCVR_Init(uint32_t * rcvr_id, const struct pios_rcvr_driver * driver, const uint32_t lower_id)
|
||||
{
|
||||
PIOS_DEBUG_Assert(rcvr_id);
|
||||
PIOS_DEBUG_Assert(driver);
|
||||
|
||||
struct pios_rcvr_dev * rcvr_dev;
|
||||
|
||||
rcvr_dev = (struct pios_rcvr_dev *) PIOS_RCVR_alloc();
|
||||
if (!rcvr_dev) goto out_fail;
|
||||
|
||||
rcvr_dev->driver = driver;
|
||||
rcvr_dev->lower_id = lower_id;
|
||||
|
||||
|
||||
*rcvr_id = pios_rcvr_num_devs - 1;
|
||||
|
||||
return(0);
|
||||
|
||||
out_fail:
|
||||
return(-1);
|
||||
}
|
||||
|
||||
int32_t PIOS_RCVR_Read(uint32_t rcvr_id, uint8_t channel)
|
||||
{
|
||||
struct pios_rcvr_dev * rcvr_dev = &pios_rcvr_devs[rcvr_id];
|
||||
|
||||
if (!PIOS_RCVR_validate(rcvr_dev)) {
|
||||
/* Undefined RCVR port for this board (see pios_board.c) */
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
|
||||
PIOS_DEBUG_Assert(rcvr_dev->driver->read);
|
||||
|
||||
return rcvr_dev->driver->read(rcvr_dev->lower_id, channel);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
31
flight/PiOS.win32/inc/pios_crc.h
Normal file
@ -0,0 +1,31 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_CRC CRC Functions
|
||||
* @{
|
||||
*
|
||||
* @file pios_crc.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief CRC functions 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
|
||||
*/
|
||||
|
||||
uint8_t PIOS_CRC_updateByte(uint8_t crc, const uint8_t data);
|
||||
uint8_t PIOS_CRC_updateCRC(uint8_t crc, const uint8_t* data, int32_t length);
|
@ -38,7 +38,18 @@
|
||||
* and we cannot define a linker script for each of them atm
|
||||
*/
|
||||
|
||||
#define uavobj_initcall(fn)
|
||||
#define UAVOBJ_INITCALL(fn)
|
||||
#define MODULE_INITCALL(ifn, iparam, sfn, sparam, flags)
|
||||
|
||||
#define MODULE_TASKCREATE_ALL
|
||||
|
||||
#define MODULE_INITIALISE_ALL { \
|
||||
/* Initialize modules */ \
|
||||
InitModules(); \
|
||||
/* Start the FreeRTOS scheduler which never returns.*/ \
|
||||
/* Initialize the system thread */ \
|
||||
SystemModInitialize();}
|
||||
|
||||
|
||||
#endif /* PIOS_INITCALL_H */
|
||||
|
||||
|
@ -63,6 +63,7 @@
|
||||
#include <pios_com.h>
|
||||
#include <pios_servo.h>
|
||||
#include <pios_wdg.h>
|
||||
#include <pios_crc.h>
|
||||
|
||||
#define NELEMENTS(x) (sizeof(x) / sizeof(*(x)))
|
||||
|
||||
|
@ -941,3 +941,8 @@ void vPortExitCritical( void )
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
unsigned long ulPortGetTimerValue( void )
|
||||
{
|
||||
return (unsigned long) clock();
|
||||
}
|
74
flight/PiOS.win32/win32/pios_crc.c
Normal file
@ -0,0 +1,74 @@
|
||||
/*
|
||||
* pios_crc.c
|
||||
* OpenPilotOSX
|
||||
*
|
||||
* Created by James Cotton on 6/4/11.
|
||||
* Copyright 2011 OpenPilot. All rights reserved.
|
||||
*
|
||||
*/
|
||||
|
||||
#include "pios.h"
|
||||
|
||||
// CRC lookup table
|
||||
static const uint8_t crc_table[256] = {
|
||||
0x00, 0x07, 0x0e, 0x09, 0x1c, 0x1b, 0x12, 0x15, 0x38, 0x3f, 0x36, 0x31, 0x24, 0x23, 0x2a, 0x2d,
|
||||
0x70, 0x77, 0x7e, 0x79, 0x6c, 0x6b, 0x62, 0x65, 0x48, 0x4f, 0x46, 0x41, 0x54, 0x53, 0x5a, 0x5d,
|
||||
0xe0, 0xe7, 0xee, 0xe9, 0xfc, 0xfb, 0xf2, 0xf5, 0xd8, 0xdf, 0xd6, 0xd1, 0xc4, 0xc3, 0xca, 0xcd,
|
||||
0x90, 0x97, 0x9e, 0x99, 0x8c, 0x8b, 0x82, 0x85, 0xa8, 0xaf, 0xa6, 0xa1, 0xb4, 0xb3, 0xba, 0xbd,
|
||||
0xc7, 0xc0, 0xc9, 0xce, 0xdb, 0xdc, 0xd5, 0xd2, 0xff, 0xf8, 0xf1, 0xf6, 0xe3, 0xe4, 0xed, 0xea,
|
||||
0xb7, 0xb0, 0xb9, 0xbe, 0xab, 0xac, 0xa5, 0xa2, 0x8f, 0x88, 0x81, 0x86, 0x93, 0x94, 0x9d, 0x9a,
|
||||
0x27, 0x20, 0x29, 0x2e, 0x3b, 0x3c, 0x35, 0x32, 0x1f, 0x18, 0x11, 0x16, 0x03, 0x04, 0x0d, 0x0a,
|
||||
0x57, 0x50, 0x59, 0x5e, 0x4b, 0x4c, 0x45, 0x42, 0x6f, 0x68, 0x61, 0x66, 0x73, 0x74, 0x7d, 0x7a,
|
||||
0x89, 0x8e, 0x87, 0x80, 0x95, 0x92, 0x9b, 0x9c, 0xb1, 0xb6, 0xbf, 0xb8, 0xad, 0xaa, 0xa3, 0xa4,
|
||||
0xf9, 0xfe, 0xf7, 0xf0, 0xe5, 0xe2, 0xeb, 0xec, 0xc1, 0xc6, 0xcf, 0xc8, 0xdd, 0xda, 0xd3, 0xd4,
|
||||
0x69, 0x6e, 0x67, 0x60, 0x75, 0x72, 0x7b, 0x7c, 0x51, 0x56, 0x5f, 0x58, 0x4d, 0x4a, 0x43, 0x44,
|
||||
0x19, 0x1e, 0x17, 0x10, 0x05, 0x02, 0x0b, 0x0c, 0x21, 0x26, 0x2f, 0x28, 0x3d, 0x3a, 0x33, 0x34,
|
||||
0x4e, 0x49, 0x40, 0x47, 0x52, 0x55, 0x5c, 0x5b, 0x76, 0x71, 0x78, 0x7f, 0x6a, 0x6d, 0x64, 0x63,
|
||||
0x3e, 0x39, 0x30, 0x37, 0x22, 0x25, 0x2c, 0x2b, 0x06, 0x01, 0x08, 0x0f, 0x1a, 0x1d, 0x14, 0x13,
|
||||
0xae, 0xa9, 0xa0, 0xa7, 0xb2, 0xb5, 0xbc, 0xbb, 0x96, 0x91, 0x98, 0x9f, 0x8a, 0x8d, 0x84, 0x83,
|
||||
0xde, 0xd9, 0xd0, 0xd7, 0xc2, 0xc5, 0xcc, 0xcb, 0xe6, 0xe1, 0xe8, 0xef, 0xfa, 0xfd, 0xf4, 0xf3
|
||||
};
|
||||
|
||||
/**
|
||||
* Update the crc value with new data.
|
||||
*
|
||||
* Generated by pycrc v0.7.5, http://www.tty1.net/pycrc/
|
||||
* using the configuration:
|
||||
* Width = 8
|
||||
* Poly = 0x07
|
||||
* XorIn = 0x00
|
||||
* ReflectIn = False
|
||||
* XorOut = 0x00
|
||||
* ReflectOut = False
|
||||
* Algorithm = table-driven
|
||||
*
|
||||
* \param crc The current crc value.
|
||||
* \param data Pointer to a buffer of \a data_len bytes.
|
||||
* \param length Number of bytes in the \a data buffer.
|
||||
* \return The updated crc value.
|
||||
*/
|
||||
uint8_t PIOS_CRC_updateByte(uint8_t crc, const uint8_t data)
|
||||
{
|
||||
return crc_table[crc ^ data];
|
||||
}
|
||||
|
||||
/*
|
||||
* @brief Update a CRC with a data buffer
|
||||
* @param[in] crc Starting CRC value
|
||||
* @param[in] data Data buffer
|
||||
* @param[in] length Number of bytes to process
|
||||
* @returns Updated CRC
|
||||
*/
|
||||
uint8_t PIOS_CRC_updateCRC(uint8_t crc, const uint8_t* data, int32_t length)
|
||||
{
|
||||
// use registers for speed
|
||||
register int32_t len = length;
|
||||
register uint8_t crc8 = crc;
|
||||
register const uint8_t *p = data;
|
||||
|
||||
while (len--)
|
||||
crc8 = crc_table[crc8 ^ *p++];
|
||||
|
||||
return crc8;
|
||||
}
|
||||
|
@ -62,11 +62,7 @@ int32_t PIOS_DELAY_Init(void)
|
||||
int32_t PIOS_DELAY_WaituS(uint16_t uS)
|
||||
{
|
||||
Sleep(uS/1000);
|
||||
//uint16_t start = PIOS_DELAY_TIMER->CNT;
|
||||
/* Note that this event works on 16bit counter wrap-arounds */
|
||||
//while((uint16_t)(PIOS_DELAY_TIMER->CNT - start) <= uS);
|
||||
|
||||
/* No error */
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
@ -79,12 +79,6 @@ TIM8 | | | |
|
||||
#define PIOS_LED_PINS { PIOS_LED_LED1_GPIO_PIN }
|
||||
#define PIOS_LED_CLKS { PIOS_LED_LED1_GPIO_CLK }
|
||||
|
||||
//-------------------------
|
||||
// Delay Timer
|
||||
//-------------------------
|
||||
#define PIOS_DELAY_TIMER TIM2
|
||||
#define PIOS_DELAY_TIMER_RCC_FUNC RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE)
|
||||
|
||||
//-------------------------
|
||||
// System Settings
|
||||
//-------------------------
|
||||
@ -120,7 +114,6 @@ extern uint32_t pios_i2c_main_adapter_id;
|
||||
#define PIOS_USART_MAX_DEVS 2
|
||||
#define PIOS_USART_RX_BUFFER_SIZE 256
|
||||
#define PIOS_USART_TX_BUFFER_SIZE 256
|
||||
#define PIOS_USART_BAUDRATE 230400
|
||||
|
||||
//-------------------------
|
||||
// PIOS_COM
|
||||
|
@ -34,7 +34,7 @@
|
||||
Timer | Channel 1 | Channel 2 | Channel 3 | Channel 4
|
||||
------+-----------+-----------+-----------+----------
|
||||
TIM1 | Servo 4 | | |
|
||||
TIM2 | RC In 5 | RC In 6 | Servo 6 |
|
||||
TIM2 | RC In 5 | RC In 6 | Servo 6 |
|
||||
TIM3 | Servo 5 | RC In 2 | RC In 3 | RC In 4
|
||||
TIM4 | RC In 1 | Servo 3 | Servo 2 | Servo 1
|
||||
------+-----------+-----------+-----------+----------
|
||||
@ -76,7 +76,7 @@ TIM4 | RC In 1 | Servo 3 | Servo 2 | Servo 1
|
||||
#define PIOS_WDG_MANUAL 0x0008
|
||||
|
||||
//------------------------
|
||||
// TELEMETRY
|
||||
// TELEMETRY
|
||||
//------------------------
|
||||
#define TELEM_QUEUE_SIZE 20
|
||||
|
||||
@ -91,12 +91,6 @@ TIM4 | RC In 1 | Servo 3 | Servo 2 | Servo 1
|
||||
#define PIOS_LED_PINS { PIOS_LED_LED1_GPIO_PIN }
|
||||
#define PIOS_LED_CLKS { PIOS_LED_LED1_GPIO_CLK }
|
||||
|
||||
//-------------------------
|
||||
// Delay Timer
|
||||
//-------------------------
|
||||
#define PIOS_DELAY_TIMER TIM3
|
||||
#define PIOS_DELAY_TIMER_RCC_FUNC RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE)
|
||||
|
||||
//-------------------------
|
||||
// System Settings
|
||||
//-------------------------
|
||||
@ -141,13 +135,11 @@ extern uint32_t pios_i2c_main_adapter_id;
|
||||
//-------------------------
|
||||
#define PIOS_COM_MAX_DEVS 4
|
||||
|
||||
#define PIOS_COM_TELEM_BAUDRATE 57600
|
||||
extern uint32_t pios_com_telem_rf_id;
|
||||
#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id)
|
||||
#define PIOS_COM_DEBUG PIOS_COM_TELEM_RF
|
||||
|
||||
#if defined(PIOS_INCLUDE_GPS)
|
||||
#define PIOS_COM_GPS_BAUDRATE 57600
|
||||
extern uint32_t pios_com_gps_id;
|
||||
#define PIOS_COM_GPS (pios_com_gps_id)
|
||||
#endif /* PIOS_INCLUDE_GPS */
|
||||
@ -156,11 +148,15 @@ extern uint32_t pios_com_telem_usb_id;
|
||||
#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id)
|
||||
|
||||
#ifdef PIOS_INCLUDE_SPEKTRUM
|
||||
#define PIOS_COM_SPEKTRUM_BAUDRATE 115200
|
||||
extern uint32_t pios_com_spektrum_id;
|
||||
#define PIOS_COM_SPEKTRUM (pios_com_spektrum_id)
|
||||
#endif
|
||||
|
||||
#ifdef PIOS_INCLUDE_SBUS
|
||||
extern uint32_t pios_com_sbus_id;
|
||||
#define PIOS_COM_SBUS (pios_com_sbus_id)
|
||||
#endif
|
||||
|
||||
//-------------------------
|
||||
// ADC
|
||||
// PIOS_ADC_PinGet(0) = Gyro Z
|
||||
@ -197,7 +193,7 @@ extern uint32_t pios_com_spektrum_id;
|
||||
#define PIOS_ADC_CHANNELS { PIOS_ADC_PIN1_GPIO_CHANNEL, PIOS_ADC_PIN2_GPIO_CHANNEL, PIOS_ADC_PIN3_GPIO_CHANNEL }
|
||||
#define PIOS_ADC_MAPPING { PIOS_ADC_PIN1_ADC, PIOS_ADC_PIN2_ADC, PIOS_ADC_PIN3_ADC }
|
||||
#define PIOS_ADC_CHANNEL_MAPPING { PIOS_ADC_PIN1_ADC_NUMBER, PIOS_ADC_PIN2_ADC_NUMBER, PIOS_ADC_PIN3_ADC_NUMBER }
|
||||
#define PIOS_ADC_NUM_CHANNELS (PIOS_ADC_NUM_PINS + PIOS_ADC_USE_TEMP_SENSOR)
|
||||
#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)
|
||||
@ -219,10 +215,27 @@ extern uint32_t pios_com_spektrum_id;
|
||||
#define PIOS_ADC_RATE (72.0e6 / 1.0 / 8.0 / 252.0 / (PIOS_ADC_NUM_CHANNELS >> PIOS_ADC_USE_ADC2))
|
||||
#define PIOS_ADC_MAX_OVERSAMPLING 36
|
||||
|
||||
//------------------------
|
||||
// PIOS_RCVR
|
||||
// See also pios_board.c
|
||||
//------------------------
|
||||
#define PIOS_RCVR_MAX_DEVS 1
|
||||
#define PIOS_RCVR_MAX_CHANNELS 12
|
||||
|
||||
//-------------------------
|
||||
// Receiver PWM inputs
|
||||
// Receiver PPM input
|
||||
//-------------------------
|
||||
#define PIOS_PWM_MAX_INPUTS 6
|
||||
#define PIOS_PPM_NUM_INPUTS 6 //Could be more if needed
|
||||
|
||||
//-------------------------
|
||||
// Receiver PWM input
|
||||
//-------------------------
|
||||
#define PIOS_PWM_NUM_INPUTS 6
|
||||
|
||||
//-------------------------
|
||||
// Receiver SPEKTRUM input
|
||||
//-------------------------
|
||||
#define PIOS_SPEKTRUM_NUM_INPUTS 12
|
||||
|
||||
//-------------------------
|
||||
// Servo outputs
|
||||
@ -257,5 +270,5 @@ extern uint32_t pios_com_spektrum_id;
|
||||
#define PIOS_USB_DETECT_EXTI_LINE EXTI_Line15
|
||||
#define PIOS_IRQ_USB_PRIORITY PIOS_IRQ_PRIO_MID
|
||||
#define PIOS_USB_RX_BUFFER_SIZE 128
|
||||
#define PIOS_USB_TX_BUFFER_SIZE 128
|
||||
#define PIOS_USB_TX_BUFFER_SIZE 256
|
||||
#endif /* STM32103CB_AHRS_H_ */
|
||||
|
@ -117,14 +117,6 @@ TIM4 | STOPWATCH |
|
||||
#define TX_LED_OFF PIOS_LED_Off(LED4)
|
||||
#define TX_LED_TOGGLE PIOS_LED_Toggle(LED4)
|
||||
|
||||
// *****************************************************************
|
||||
// Delay Timer
|
||||
|
||||
//#define PIOS_DELAY_TIMER TIM2
|
||||
//#define PIOS_DELAY_TIMER_RCC_FUNC RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE)
|
||||
#define PIOS_DELAY_TIMER TIM1
|
||||
#define PIOS_DELAY_TIMER_RCC_FUNC RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1, ENABLE)
|
||||
|
||||
// *****************************************************************
|
||||
// Timer interrupt
|
||||
|
||||
|
@ -135,23 +135,15 @@ extern uint32_t pios_i2c_gyro_adapter_id;
|
||||
//-------------------------
|
||||
#define PIOS_COM_MAX_DEVS 2
|
||||
|
||||
#define PIOS_COM_GPS_BAUDRATE 57600
|
||||
extern uint32_t pios_com_gps_id;
|
||||
#define PIOS_COM_GPS (pios_com_gps_id)
|
||||
|
||||
#ifdef PIOS_ENABLE_AUX_UART
|
||||
#define PIOS_COM_AUX_BAUDRATE 57600
|
||||
extern uint32_t pios_com_aux_id;
|
||||
#define PIOS_COM_AUX (pios_com_aux_id)
|
||||
#define PIOS_COM_DEBUG PIOS_COM_AUX
|
||||
#endif
|
||||
|
||||
//-------------------------
|
||||
// Delay Timer
|
||||
//-------------------------
|
||||
#define PIOS_DELAY_TIMER TIM2
|
||||
#define PIOS_DELAY_TIMER_RCC_FUNC RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE)
|
||||
|
||||
//-------------------------
|
||||
// System Settings
|
||||
//-------------------------
|
||||
|
@ -149,11 +149,9 @@ extern uint32_t pios_i2c_main_adapter_id;
|
||||
//-------------------------
|
||||
#define PIOS_COM_MAX_DEVS 4
|
||||
|
||||
#define PIOS_COM_TELEM_BAUDRATE 57600
|
||||
extern uint32_t pios_com_telem_rf_id;
|
||||
#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id)
|
||||
|
||||
#define PIOS_COM_GPS_BAUDRATE 57600
|
||||
extern uint32_t pios_com_gps_id;
|
||||
#define PIOS_COM_GPS (pios_com_gps_id)
|
||||
|
||||
@ -161,23 +159,20 @@ extern uint32_t pios_com_telem_usb_id;
|
||||
#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id)
|
||||
|
||||
#ifdef PIOS_ENABLE_AUX_UART
|
||||
#define PIOS_COM_AUX_BAUDRATE 57600
|
||||
extern uint32_t pios_com_aux_id;
|
||||
#define PIOS_COM_AUX (pios_com_aux_id)
|
||||
#define PIOS_COM_DEBUG PIOS_COM_AUX
|
||||
#endif
|
||||
|
||||
#ifdef PIOS_INCLUDE_SPEKTRUM
|
||||
#define PIOS_COM_SPEKTRUM_BAUDRATE 115200
|
||||
extern uint32_t pios_com_spektrum_id;
|
||||
#define PIOS_COM_SPEKTRUM (pios_com_spektrum_id)
|
||||
#endif
|
||||
|
||||
//-------------------------
|
||||
// Delay Timer
|
||||
//-------------------------
|
||||
#define PIOS_DELAY_TIMER TIM2
|
||||
#define PIOS_DELAY_TIMER_RCC_FUNC RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE)
|
||||
#ifdef PIOS_INCLUDE_SBUS
|
||||
extern uint32_t pios_com_sbus_id;
|
||||
#define PIOS_COM_SBUS (pios_com_sbus_id)
|
||||
#endif
|
||||
|
||||
//-------------------------
|
||||
// System Settings
|
||||
@ -193,37 +188,34 @@ extern uint32_t pios_com_spektrum_id;
|
||||
#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_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)*/
|
||||
//------------------------
|
||||
// PIOS_RCVR
|
||||
// See also pios_board.c
|
||||
//------------------------
|
||||
#define PIOS_RCVR_MAX_DEVS 1
|
||||
#define PIOS_RCVR_MAX_CHANNELS 12
|
||||
|
||||
//-------------------------
|
||||
// Receiver PPM input
|
||||
//-------------------------
|
||||
#define PIOS_PPM_NUM_INPUTS 8 //Could be more if needed
|
||||
#define PIOS_PPM_SUPV_ENABLED 1
|
||||
|
||||
//-------------------------
|
||||
// SPEKTRUM input
|
||||
// Receiver PWM 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)
|
||||
#define PIOS_PWM_NUM_INPUTS 8
|
||||
|
||||
//-------------------------
|
||||
// Receiver SPEKTRUM input
|
||||
//-------------------------
|
||||
#define PIOS_SPEKTRUM_NUM_INPUTS 12
|
||||
|
||||
//-------------------------
|
||||
// Servo outputs
|
||||
//-------------------------
|
||||
#define PIOS_SERVO_UPDATE_HZ 50
|
||||
#define PIOS_SERVOS_INITIAL_POSITION 0 /* dont want to start motors, have no pulse till settings loaded */
|
||||
#define PIOS_PWM_MAX_INPUTS 8
|
||||
|
||||
//-------------------------
|
||||
// ADC
|
||||
|
@ -38,7 +38,7 @@
|
||||
|
||||
static bool PIOS_COM_validate(struct pios_com_dev * com_dev)
|
||||
{
|
||||
return (com_dev->magic == PIOS_COM_DEV_MAGIC);
|
||||
return (com_dev && (com_dev->magic == PIOS_COM_DEV_MAGIC));
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_FREERTOS) && 0
|
||||
@ -298,7 +298,9 @@ int32_t PIOS_COM_ReceiveBufferUsed(uint32_t com_id)
|
||||
|
||||
if (!PIOS_COM_validate(com_dev)) {
|
||||
/* Undefined COM port for this board (see pios_board.c) */
|
||||
PIOS_DEBUG_Assert(0);
|
||||
/* This is commented out so com_id=NULL can be used to disable telemetry */
|
||||
//PIOS_DEBUG_Assert(0);
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (!com_dev->driver->rx_avail) {
|
||||
|
@ -41,11 +41,11 @@ static uint8_t PIOS_Flash_W25X_Busy() ;
|
||||
|
||||
static uint32_t PIOS_SPI_FLASH;
|
||||
|
||||
/**
|
||||
/**
|
||||
* @brief Claim the SPI bus for flash use and assert CS pin
|
||||
* @return 0 for sucess, -1 for failure to get semaphore
|
||||
*/
|
||||
static int8_t PIOS_Flash_W25X_ClaimBus()
|
||||
static int8_t PIOS_Flash_W25X_ClaimBus()
|
||||
{
|
||||
int8_t ret = PIOS_SPI_ClaimBus(PIOS_SPI_FLASH);
|
||||
PIOS_FLASH_ENABLE;
|
||||
@ -55,7 +55,7 @@ static int8_t PIOS_Flash_W25X_ClaimBus()
|
||||
/**
|
||||
* @brief Release the SPI bus sempahore and ensure flash chip not using bus
|
||||
*/
|
||||
static void PIOS_Flash_W25X_ReleaseBus()
|
||||
static void PIOS_Flash_W25X_ReleaseBus()
|
||||
{
|
||||
PIOS_FLASH_DISABLE;
|
||||
PIOS_SPI_ReleaseBus(PIOS_SPI_FLASH);
|
||||
@ -64,8 +64,8 @@ static void PIOS_Flash_W25X_ReleaseBus()
|
||||
/**
|
||||
* @brief Returns if the flash chip is busy
|
||||
*/
|
||||
static uint8_t PIOS_Flash_W25X_Busy()
|
||||
{
|
||||
static uint8_t PIOS_Flash_W25X_Busy()
|
||||
{
|
||||
return PIOS_Flash_W25X_ReadStatus() & W25X_STATUS_BUSY;
|
||||
}
|
||||
|
||||
@ -73,12 +73,12 @@ static uint8_t PIOS_Flash_W25X_Busy()
|
||||
* @brief Execute the write enable instruction and returns the status
|
||||
* @returns 0 if successful, -1 if unable to claim bus
|
||||
*/
|
||||
static uint8_t PIOS_Flash_W25X_WriteEnable()
|
||||
static uint8_t PIOS_Flash_W25X_WriteEnable()
|
||||
{
|
||||
uint8_t out[] = {W25X_WRITE_ENABLE};
|
||||
if(PIOS_Flash_W25X_ClaimBus() != 0)
|
||||
return -1;
|
||||
PIOS_SPI_TransferBlock(PIOS_SPI_FLASH,out,NULL,sizeof(out),NULL);
|
||||
PIOS_SPI_TransferBlock(PIOS_SPI_FLASH,out,NULL,sizeof(out),NULL);
|
||||
PIOS_Flash_W25X_ReleaseBus();
|
||||
return 0;
|
||||
}
|
||||
@ -97,27 +97,27 @@ int8_t PIOS_Flash_W25X_Init(uint32_t spi_id)
|
||||
|
||||
|
||||
/**
|
||||
* @brief Read the status register from flash chip and return it
|
||||
* @brief Read the status register from flash chip and return it
|
||||
*/
|
||||
uint8_t PIOS_Flash_W25X_ReadStatus()
|
||||
uint8_t PIOS_Flash_W25X_ReadStatus()
|
||||
{
|
||||
uint8_t out[2] = {W25X_READ_STATUS, 0};
|
||||
uint8_t in[2] = {0,0};
|
||||
PIOS_Flash_W25X_ClaimBus();
|
||||
PIOS_SPI_TransferBlock(PIOS_SPI_FLASH,out,in,sizeof(out),NULL);
|
||||
PIOS_SPI_TransferBlock(PIOS_SPI_FLASH,out,in,sizeof(out),NULL);
|
||||
PIOS_Flash_W25X_ReleaseBus();
|
||||
return in[1];
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Read the status register from flash chip and return it
|
||||
* @brief Read the status register from flash chip and return it
|
||||
*/
|
||||
uint8_t PIOS_Flash_W25X_ReadID()
|
||||
uint8_t PIOS_Flash_W25X_ReadID()
|
||||
{
|
||||
uint8_t out[] = {W25X_DEVICE_ID, 0, 0, 0, 0, 0};
|
||||
uint8_t in[6];
|
||||
PIOS_Flash_W25X_ClaimBus();
|
||||
PIOS_SPI_TransferBlock(PIOS_SPI_FLASH,out,in,sizeof(out),NULL);
|
||||
PIOS_SPI_TransferBlock(PIOS_SPI_FLASH,out,in,sizeof(out),NULL);
|
||||
PIOS_Flash_W25X_ReleaseBus();
|
||||
return in[5];
|
||||
}
|
||||
@ -127,28 +127,27 @@ uint8_t PIOS_Flash_W25X_ReadID()
|
||||
* @param[in] add Address of flash to erase
|
||||
* @returns 0 if successful
|
||||
* @retval -1 if unable to claim bus
|
||||
* @retval
|
||||
* @retval
|
||||
*/
|
||||
int8_t PIOS_Flash_W25X_EraseSector(uint32_t addr)
|
||||
{
|
||||
uint8_t ret;
|
||||
uint8_t out[] = {W25X_SECTOR_ERASE, (addr >> 16) & 0xff, (addr >> 8) & 0xff , addr & 0xff};
|
||||
|
||||
|
||||
if((ret = PIOS_Flash_W25X_WriteEnable()) != 0)
|
||||
return ret;
|
||||
|
||||
|
||||
if(PIOS_Flash_W25X_ClaimBus() != 0)
|
||||
return -1;
|
||||
return -1;
|
||||
PIOS_SPI_TransferBlock(PIOS_SPI_FLASH,out,NULL,sizeof(out),NULL);
|
||||
PIOS_Flash_W25X_ReleaseBus();
|
||||
|
||||
uint32_t i = 1;
|
||||
while(PIOS_Flash_W25X_Busy()) {
|
||||
//TODO: Fail on timeout
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
vTaskDelay(1);
|
||||
#endif
|
||||
if(++i == 0)
|
||||
return -1;
|
||||
}
|
||||
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
@ -160,25 +159,26 @@ int8_t PIOS_Flash_W25X_EraseChip()
|
||||
{
|
||||
uint8_t ret;
|
||||
uint8_t out[] = {W25X_CHIP_ERASE};
|
||||
|
||||
|
||||
if((ret = PIOS_Flash_W25X_WriteEnable()) != 0)
|
||||
return ret;
|
||||
|
||||
|
||||
if(PIOS_Flash_W25X_ClaimBus() != 0)
|
||||
return -1;
|
||||
PIOS_SPI_TransferBlock(PIOS_SPI_FLASH,out,NULL,sizeof(out),NULL);
|
||||
PIOS_SPI_TransferBlock(PIOS_SPI_FLASH,out,NULL,sizeof(out),NULL);
|
||||
PIOS_Flash_W25X_ReleaseBus();
|
||||
|
||||
uint32_t i = 1;
|
||||
while(PIOS_Flash_W25X_Busy()) {
|
||||
//TODO: Fail on timeout
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
vTaskDelay(1);
|
||||
#endif
|
||||
if(++i == 0)
|
||||
return -1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
/**
|
||||
* @brief Write one page of data (up to 256 bytes) aligned to a page start
|
||||
* @param[in] addr Address in flash to write to
|
||||
* @param[in] data Pointer to data to write to flash
|
||||
@ -192,37 +192,38 @@ int8_t PIOS_Flash_W25X_WriteData(uint32_t addr, uint8_t * data, uint16_t len)
|
||||
{
|
||||
uint8_t ret;
|
||||
uint8_t out[4] = {W25X_PAGE_WRITE, (addr >> 16) & 0xff, (addr >> 8) & 0xff , addr & 0xff};
|
||||
|
||||
|
||||
/* Can only write one page at a time */
|
||||
if(len > 0x100)
|
||||
if(len > 0x100)
|
||||
return -2;
|
||||
|
||||
|
||||
/* Ensure number of bytes fits after starting address before end of page */
|
||||
if(((addr & 0xff) + len) > 0x100)
|
||||
if(((addr & 0xff) + len) > 0x100)
|
||||
return -3;
|
||||
|
||||
|
||||
if((ret = PIOS_Flash_W25X_WriteEnable()) != 0)
|
||||
return ret;
|
||||
|
||||
|
||||
/* Execute write page command and clock in address. Keep CS asserted */
|
||||
if(PIOS_Flash_W25X_ClaimBus() != 0)
|
||||
return -1;
|
||||
PIOS_SPI_TransferBlock(PIOS_SPI_FLASH,out,NULL,sizeof(out),NULL);
|
||||
|
||||
|
||||
/* Clock out data to flash */
|
||||
PIOS_SPI_TransferBlock(PIOS_SPI_FLASH,data,NULL,len,NULL);
|
||||
|
||||
PIOS_Flash_W25X_ReleaseBus();
|
||||
|
||||
uint32_t i = 1;
|
||||
while(PIOS_Flash_W25X_Busy()) {
|
||||
#if defined(PIOS_INCLUDE_FREERTOS)
|
||||
vTaskDelay(1);
|
||||
#endif
|
||||
if(++i == 0)
|
||||
return -1;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
/**
|
||||
* @brief Read data from a location in flash memory
|
||||
* @param[in] addr Address in flash to write to
|
||||
* @param[in] data Pointer to data to write from flash
|
||||
@ -243,6 +244,6 @@ int8_t PIOS_Flash_W25X_ReadData(uint32_t addr, uint8_t * data, uint16_t len)
|
||||
PIOS_SPI_TransferBlock(PIOS_SPI_FLASH,NULL,data,len,NULL);
|
||||
|
||||
PIOS_Flash_W25X_ReleaseBus();
|
||||
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
@ -12,19 +12,19 @@
|
||||
* @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
|
||||
/*
|
||||
* 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
|
||||
*
|
||||
* 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.,
|
||||
*
|
||||
* 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
|
||||
*/
|
||||
|
||||
@ -33,7 +33,7 @@
|
||||
#include "uavobjectmanager.h"
|
||||
|
||||
// Private functions
|
||||
static int32_t PIOS_FLASHFS_CleabObjectTableHeader();
|
||||
static int32_t PIOS_FLASHFS_ClearObjectTableHeader();
|
||||
static int32_t PIOS_FLASHFS_GetObjAddress(uint32_t objId, uint16_t instId);
|
||||
static int32_t PIOS_FLASHFS_GetNewAddress(uint32_t objId, uint16_t instId);
|
||||
|
||||
@ -56,11 +56,12 @@ struct fileHeader {
|
||||
} __attribute__((packed));
|
||||
|
||||
|
||||
#define OBJECT_TABLE_MAGIC 0x85FB3C34
|
||||
#define OBJECT_TABLE_MAGIC 0x85FB3C35
|
||||
#define OBJ_MAGIC 0x3015AE71
|
||||
#define OBJECT_TABLE_START 0x00000010
|
||||
#define OBJECT_TABLE_END 0x00001000
|
||||
#define SECTOR_SIZE 0x00001000
|
||||
#define MAX_BADMAGIC 4
|
||||
|
||||
/**
|
||||
* @brief Initialize the flash object setting FS
|
||||
@ -68,34 +69,50 @@ struct fileHeader {
|
||||
*/
|
||||
int32_t PIOS_FLASHFS_Init()
|
||||
{
|
||||
|
||||
|
||||
// Check for valid object table or create one
|
||||
uint32_t object_table_magic;
|
||||
if (PIOS_Flash_W25X_ReadData(0, (uint8_t *)&object_table_magic, sizeof(object_table_magic)) != 0)
|
||||
return -1;
|
||||
if(object_table_magic != OBJECT_TABLE_MAGIC) {
|
||||
if(PIOS_FLASHFS_CleabObjectTableHeader() < 0)
|
||||
uint8_t magic_fail_count = 0;
|
||||
bool magic_good = false;
|
||||
|
||||
while(!magic_good) {
|
||||
if (PIOS_Flash_W25X_ReadData(0, (uint8_t *)&object_table_magic, sizeof(object_table_magic)) != 0)
|
||||
return -1;
|
||||
if(object_table_magic != OBJECT_TABLE_MAGIC) {
|
||||
if(magic_fail_count++ > MAX_BADMAGIC) {
|
||||
PIOS_FLASHFS_ClearObjectTableHeader();
|
||||
PIOS_LED_Toggle(LED1);
|
||||
magic_fail_count = 0;
|
||||
magic_good = true;
|
||||
} else {
|
||||
PIOS_DELAY_WaituS(100);
|
||||
}
|
||||
|
||||
}
|
||||
else {
|
||||
magic_good = true;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
int32_t addr = OBJECT_TABLE_START;
|
||||
struct objectHeader header;
|
||||
numObjects = 0;
|
||||
|
||||
|
||||
// Loop through header area while objects detect to count how many saved
|
||||
while(addr < OBJECT_TABLE_END) {
|
||||
// Read the instance data
|
||||
if (PIOS_Flash_W25X_ReadData(addr, (uint8_t *)&header, sizeof(header)) != 0)
|
||||
return -1;
|
||||
|
||||
// Counting number of valid headers
|
||||
if(header.objMagic != OBJ_MAGIC)
|
||||
|
||||
// Counting number of valid headers
|
||||
if(header.objMagic != OBJ_MAGIC)
|
||||
break;
|
||||
|
||||
|
||||
numObjects++;
|
||||
addr += sizeof(header);
|
||||
}
|
||||
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
@ -103,7 +120,7 @@ int32_t PIOS_FLASHFS_Init()
|
||||
* @brief Erase the headers for all objects in the flash chip
|
||||
* @return 0 if successful, -1 if not
|
||||
*/
|
||||
static int32_t PIOS_FLASHFS_CleabObjectTableHeader()
|
||||
static int32_t PIOS_FLASHFS_ClearObjectTableHeader()
|
||||
{
|
||||
if(PIOS_Flash_W25X_EraseSector(0) != 0)
|
||||
return -1;
|
||||
@ -121,26 +138,26 @@ static int32_t PIOS_FLASHFS_CleabObjectTableHeader()
|
||||
* @parma instId Instance id for that object
|
||||
* @return address if successful, -1 if not found
|
||||
*/
|
||||
static int32_t PIOS_FLASHFS_GetObjAddress(uint32_t objId, uint16_t instId)
|
||||
static int32_t PIOS_FLASHFS_GetObjAddress(uint32_t objId, uint16_t instId)
|
||||
{
|
||||
int32_t addr = OBJECT_TABLE_START;
|
||||
struct objectHeader header;
|
||||
|
||||
|
||||
// Loop through header area while objects detect to count how many saved
|
||||
while(addr < OBJECT_TABLE_END) {
|
||||
// Read the instance data
|
||||
if (PIOS_Flash_W25X_ReadData(addr, (uint8_t *) &header, sizeof(header)) != 0)
|
||||
return -1;
|
||||
if(header.objMagic != OBJ_MAGIC)
|
||||
if(header.objMagic != OBJ_MAGIC)
|
||||
break; // stop searching once hit first non-object header
|
||||
else if (header.objId == objId && header.instId == instId)
|
||||
break;
|
||||
addr += sizeof(header);
|
||||
}
|
||||
|
||||
|
||||
if (header.objId == objId && header.instId == instId)
|
||||
return header.address;
|
||||
|
||||
|
||||
return -1;
|
||||
}
|
||||
|
||||
@ -150,7 +167,7 @@ static int32_t PIOS_FLASHFS_GetObjAddress(uint32_t objId, uint16_t instId)
|
||||
* @param[in] instId The instance id of object to be saved
|
||||
* @return 0 if success or error code
|
||||
* @retval -1 Object not found
|
||||
* @retval -2 No room in object table
|
||||
* @retval -2 No room in object table
|
||||
* @retval -3 Unable to write entry into object table
|
||||
* @retval -4 FS not initialized
|
||||
*/
|
||||
@ -160,26 +177,26 @@ int32_t PIOS_FLASHFS_GetNewAddress(uint32_t objId, uint16_t instId)
|
||||
|
||||
if(numObjects < 0)
|
||||
return -4;
|
||||
|
||||
|
||||
// Don't worry about max size of flash chip here, other code will catch that
|
||||
header.objMagic = OBJ_MAGIC;
|
||||
header.objId = objId;
|
||||
header.instId = instId;
|
||||
header.address = OBJECT_TABLE_END + SECTOR_SIZE * numObjects;
|
||||
|
||||
|
||||
int32_t addr = OBJECT_TABLE_START + sizeof(header) * numObjects;
|
||||
|
||||
// No room for this header in object table
|
||||
if((addr + sizeof(header)) > OBJECT_TABLE_END)
|
||||
return -2;
|
||||
|
||||
if((addr + sizeof(header)) > OBJECT_TABLE_END)
|
||||
return -2;
|
||||
|
||||
if(PIOS_Flash_W25X_WriteData(addr, (uint8_t *) &header, sizeof(header)) != 0)
|
||||
return -3;
|
||||
|
||||
|
||||
// This numObejcts value must stay consistent or there will be a break in the table
|
||||
// and later the table will have bad values in it
|
||||
numObjects++;
|
||||
return header.address;
|
||||
numObjects++;
|
||||
return header.address;
|
||||
}
|
||||
|
||||
|
||||
@ -191,38 +208,38 @@ int32_t PIOS_FLASHFS_GetNewAddress(uint32_t objId, uint16_t instId)
|
||||
* @note This uses one sector on the flash chip per object so that no buffering in ram
|
||||
* must be done when erasing the sector before a save
|
||||
*/
|
||||
int32_t PIOS_FLASHFS_ObjSave(UAVObjHandle obj, uint16_t instId, uint8_t * data)
|
||||
int32_t PIOS_FLASHFS_ObjSave(UAVObjHandle obj, uint16_t instId, uint8_t * data)
|
||||
{
|
||||
uint32_t objId = UAVObjGetID(obj);
|
||||
uint8_t crc = 0;
|
||||
|
||||
int32_t addr = PIOS_FLASHFS_GetObjAddress(objId, instId);
|
||||
|
||||
|
||||
// Object currently not saved
|
||||
if(addr < 0)
|
||||
if(addr < 0)
|
||||
addr = PIOS_FLASHFS_GetNewAddress(objId, instId);
|
||||
|
||||
|
||||
// Could not allocate a sector
|
||||
if(addr < 0)
|
||||
return -1;
|
||||
|
||||
|
||||
struct fileHeader header = {
|
||||
.id = objId,
|
||||
.instId = instId,
|
||||
.size = UAVObjGetNumBytes(obj)
|
||||
};
|
||||
|
||||
|
||||
if(PIOS_Flash_W25X_EraseSector(addr) != 0)
|
||||
return -2;
|
||||
|
||||
// Save header
|
||||
// This information IS redundant with the object table id. Oh well. Better safe than sorry.
|
||||
// This information IS redundant with the object table id. Oh well. Better safe than sorry.
|
||||
if(PIOS_Flash_W25X_WriteData(addr, (uint8_t *) &header, sizeof(header)) != 0)
|
||||
return -3;
|
||||
|
||||
|
||||
// Update CRC
|
||||
crc = PIOS_CRC_updateCRC(0, (uint8_t *) &header, sizeof(header));
|
||||
|
||||
|
||||
// Save data
|
||||
if(PIOS_Flash_W25X_WriteData(addr + sizeof(header), data, UAVObjGetNumBytes(obj)) != 0)
|
||||
return -4;
|
||||
@ -233,7 +250,7 @@ int32_t PIOS_FLASHFS_ObjSave(UAVObjHandle obj, uint16_t instId, uint8_t * data)
|
||||
// Save CRC (written so will work when CRC changes to uint16)
|
||||
if(PIOS_Flash_W25X_WriteData(addr + sizeof(header) + UAVObjGetNumBytes(obj), (uint8_t *) &crc, sizeof(crc)) != 0)
|
||||
return -4;
|
||||
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
@ -259,20 +276,20 @@ int32_t PIOS_FLASHFS_ObjLoad(UAVObjHandle obj, uint16_t instId, uint8_t * data)
|
||||
uint8_t crcFlash = 0;
|
||||
const uint8_t crc_read_step = 8;
|
||||
uint8_t crc_read_buffer[crc_read_step];
|
||||
|
||||
|
||||
int32_t addr = PIOS_FLASHFS_GetObjAddress(objId, instId);
|
||||
|
||||
|
||||
// Object currently not saved
|
||||
if(addr < 0)
|
||||
if(addr < 0)
|
||||
return -1;
|
||||
|
||||
struct fileHeader header;
|
||||
|
||||
|
||||
// Load header
|
||||
// This information IS redundant with the object table id. Oh well. Better safe than sorry.
|
||||
if(PIOS_Flash_W25X_ReadData(addr, (uint8_t *) &header, sizeof(header)) != 0)
|
||||
return -2;
|
||||
|
||||
|
||||
// Update CRC
|
||||
crc = PIOS_CRC_updateCRC(0, (uint8_t *) &header, sizeof(header));
|
||||
|
||||
@ -290,7 +307,7 @@ int32_t PIOS_FLASHFS_ObjLoad(UAVObjHandle obj, uint16_t instId, uint8_t * data)
|
||||
// Read CRC (written so will work when CRC changes to uint16)
|
||||
if(PIOS_Flash_W25X_ReadData(addr + sizeof(header) + objSize, (uint8_t *) &crcFlash, sizeof(crcFlash)) != 0)
|
||||
return -5;
|
||||
|
||||
|
||||
if(crc != crcFlash)
|
||||
return -6;
|
||||
|
||||
@ -308,22 +325,22 @@ int32_t PIOS_FLASHFS_ObjLoad(UAVObjHandle obj, uint16_t instId, uint8_t * data)
|
||||
* @return 0 if success or error code
|
||||
* @retval -1 if object not in file table
|
||||
* @retval -2 Erase failed
|
||||
* @note To avoid buffering the file table (1k ram!) the entry in the file table
|
||||
* remains but destination sector is erased. This will make the load fail as the
|
||||
* @note To avoid buffering the file table (1k ram!) the entry in the file table
|
||||
* remains but destination sector is erased. This will make the load fail as the
|
||||
* file header won't match the object. At next save it goes back there.
|
||||
*/
|
||||
int32_t PIOS_FLASHFS_ObjDelete(UAVObjHandle obj, uint16_t instId)
|
||||
{
|
||||
uint32_t objId = UAVObjGetID(obj);
|
||||
|
||||
|
||||
int32_t addr = PIOS_FLASHFS_GetObjAddress(objId, instId);
|
||||
|
||||
|
||||
// Object currently not saved
|
||||
if(addr < 0)
|
||||
if(addr < 0)
|
||||
return -1;
|
||||
|
||||
if(PIOS_Flash_W25X_EraseSector(addr) != 0)
|
||||
return -2;
|
||||
|
||||
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
@ -32,8 +32,8 @@
|
||||
#include "pios.h"
|
||||
|
||||
#if defined(PIOS_INCLUDE_HCSR04)
|
||||
#if !defined(PIOS_INCLUDE_SPEKTRUM)
|
||||
#error Only supported with spektrum interface!
|
||||
#if !(defined(PIOS_INCLUDE_SPEKTRUM) || defined(PIOS_INCLUDE_SBUS))
|
||||
#error Only supported with Spektrum or S.Bus interface!
|
||||
#endif
|
||||
|
||||
/* Local Variables */
|
||||
|
98
flight/PiOS/Common/pios_rcvr.c
Normal file
@ -0,0 +1,98 @@
|
||||
/* Project Includes */
|
||||
#include "pios.h"
|
||||
|
||||
#if defined(PIOS_INCLUDE_RCVR)
|
||||
|
||||
#include <pios_rcvr_priv.h>
|
||||
|
||||
enum pios_rcvr_dev_magic {
|
||||
PIOS_RCVR_DEV_MAGIC = 0x99aabbcc,
|
||||
};
|
||||
|
||||
struct pios_rcvr_dev {
|
||||
enum pios_rcvr_dev_magic magic;
|
||||
uint32_t lower_id;
|
||||
const struct pios_rcvr_driver * driver;
|
||||
};
|
||||
|
||||
static bool PIOS_RCVR_validate(struct pios_rcvr_dev * rcvr_dev)
|
||||
{
|
||||
return (rcvr_dev->magic == PIOS_RCVR_DEV_MAGIC);
|
||||
}
|
||||
|
||||
#if defined(PIOS_INCLUDE_FREERTOS) && 0
|
||||
static struct pios_rcvr_dev * PIOS_RCVR_alloc(void)
|
||||
{
|
||||
struct pios_rcvr_dev * rcvr_dev;
|
||||
|
||||
rcvr_dev = (struct pios_rcvr_dev *)malloc(sizeof(*rcvr_dev));
|
||||
if (!rcvr_dev) return (NULL);
|
||||
|
||||
rcvr_dev->magic = PIOS_RCVR_DEV_MAGIC;
|
||||
return(rcvr_dev);
|
||||
}
|
||||
#else
|
||||
static struct pios_rcvr_dev pios_rcvr_devs[PIOS_RCVR_MAX_DEVS];
|
||||
static uint8_t pios_rcvr_num_devs;
|
||||
static struct pios_rcvr_dev * PIOS_RCVR_alloc(void)
|
||||
{
|
||||
struct pios_rcvr_dev * rcvr_dev;
|
||||
|
||||
if (pios_rcvr_num_devs >= PIOS_RCVR_MAX_DEVS) {
|
||||
return (NULL);
|
||||
}
|
||||
|
||||
rcvr_dev = &pios_rcvr_devs[pios_rcvr_num_devs++];
|
||||
rcvr_dev->magic = PIOS_RCVR_DEV_MAGIC;
|
||||
|
||||
return (rcvr_dev);
|
||||
}
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Initialises RCVR layer
|
||||
* \param[out] handle
|
||||
* \param[in] driver
|
||||
* \param[in] id
|
||||
* \return < 0 if initialisation failed
|
||||
*/
|
||||
int32_t PIOS_RCVR_Init(uint32_t * rcvr_id, const struct pios_rcvr_driver * driver, const uint32_t lower_id)
|
||||
{
|
||||
PIOS_DEBUG_Assert(rcvr_id);
|
||||
PIOS_DEBUG_Assert(driver);
|
||||
|
||||
struct pios_rcvr_dev * rcvr_dev;
|
||||
|
||||
rcvr_dev = (struct pios_rcvr_dev *) PIOS_RCVR_alloc();
|
||||
if (!rcvr_dev) goto out_fail;
|
||||
|
||||
rcvr_dev->driver = driver;
|
||||
rcvr_dev->lower_id = lower_id;
|
||||
|
||||
*rcvr_id = (uint32_t)rcvr_dev;
|
||||
return(0);
|
||||
|
||||
out_fail:
|
||||
return(-1);
|
||||
}
|
||||
|
||||
int32_t PIOS_RCVR_Read(uint32_t rcvr_id, uint8_t channel)
|
||||
{
|
||||
struct pios_rcvr_dev * rcvr_dev = (struct pios_rcvr_dev *)rcvr_id;
|
||||
|
||||
if (!PIOS_RCVR_validate(rcvr_dev)) {
|
||||
/* Undefined RCVR port for this board (see pios_board.c) */
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
|
||||
PIOS_DEBUG_Assert(rcvr_dev->driver->read);
|
||||
|
||||
return rcvr_dev->driver->read(rcvr_dev->lower_id, channel);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -1,6 +1,6 @@
|
||||
/*
|
||||
FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd.
|
||||
|
||||
|
||||
|
||||
***************************************************************************
|
||||
* *
|
||||
@ -79,16 +79,18 @@ static union xRTOS_HEAP
|
||||
volatile portDOUBLE dDummy;
|
||||
#else
|
||||
volatile unsigned long ulDummy;
|
||||
#endif
|
||||
#endif
|
||||
unsigned char ucHeap[ configTOTAL_HEAP_SIZE ];
|
||||
} xHeap;
|
||||
} xHeap __attribute__ ((section (".heap")));
|
||||
|
||||
static size_t xNextFreeByte = ( size_t ) 0;
|
||||
static size_t currentTOTAL_HEAP_SIZE = configTOTAL_HEAP_SIZE;
|
||||
|
||||
/*-----------------------------------------------------------*/
|
||||
|
||||
void *pvPortMalloc( size_t xWantedSize )
|
||||
{
|
||||
void *pvReturn = NULL;
|
||||
void *pvReturn = NULL;
|
||||
|
||||
/* Ensure that blocks are always aligned to the required number of bytes. */
|
||||
#if portBYTE_ALIGNMENT != 1
|
||||
@ -102,17 +104,17 @@ void *pvReturn = NULL;
|
||||
vTaskSuspendAll();
|
||||
{
|
||||
/* Check there is enough room left for the allocation. */
|
||||
if( ( ( xNextFreeByte + xWantedSize ) < configTOTAL_HEAP_SIZE ) &&
|
||||
if( ( ( xNextFreeByte + xWantedSize ) < currentTOTAL_HEAP_SIZE ) &&
|
||||
( ( xNextFreeByte + xWantedSize ) > xNextFreeByte ) )/* Check for overflow. */
|
||||
{
|
||||
/* Return the next free byte then increment the index past this
|
||||
block. */
|
||||
pvReturn = &( xHeap.ucHeap[ xNextFreeByte ] );
|
||||
xNextFreeByte += xWantedSize;
|
||||
}
|
||||
xNextFreeByte += xWantedSize;
|
||||
}
|
||||
}
|
||||
xTaskResumeAll();
|
||||
|
||||
|
||||
#if( configUSE_MALLOC_FAILED_HOOK == 1 )
|
||||
{
|
||||
if( pvReturn == NULL )
|
||||
@ -121,7 +123,7 @@ void *pvReturn = NULL;
|
||||
vApplicationMallocFailedHook();
|
||||
}
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
|
||||
return pvReturn;
|
||||
}
|
||||
@ -129,8 +131,8 @@ void *pvReturn = NULL;
|
||||
|
||||
void vPortFree( void *pv )
|
||||
{
|
||||
/* Memory cannot be freed using this scheme. See heap_2.c and heap_3.c
|
||||
for alternative implementations, and the memory management pages of
|
||||
/* Memory cannot be freed using this scheme. See heap_2.c and heap_3.c
|
||||
for alternative implementations, and the memory management pages of
|
||||
http://www.FreeRTOS.org for more information. */
|
||||
( void ) pv;
|
||||
}
|
||||
@ -145,8 +147,14 @@ void vPortInitialiseBlocks( void )
|
||||
|
||||
size_t xPortGetFreeHeapSize( void )
|
||||
{
|
||||
return ( configTOTAL_HEAP_SIZE - xNextFreeByte );
|
||||
return ( currentTOTAL_HEAP_SIZE - xNextFreeByte );
|
||||
}
|
||||
/*-----------------------------------------------------------*/
|
||||
|
||||
|
||||
|
||||
void xPortIncreaseHeapSize( size_t bytes )
|
||||
{
|
||||
vTaskSuspendAll();
|
||||
currentTOTAL_HEAP_SIZE = configTOTAL_HEAP_SIZE + bytes;
|
||||
xTaskResumeAll();
|
||||
}
|
||||
/*-----------------------------------------------------------*/
|
||||
|
@ -1,6 +1,6 @@
|
||||
/*
|
||||
FreeRTOS V7.0.1 - Copyright (C) 2011 Real Time Engineers Ltd.
|
||||
|
||||
|
||||
|
||||
***************************************************************************
|
||||
* *
|
||||
@ -81,7 +81,7 @@ static union xRTOS_HEAP
|
||||
volatile unsigned long ulDummy;
|
||||
#endif
|
||||
unsigned char ucHeap[ configTOTAL_HEAP_SIZE ];
|
||||
} xHeap;
|
||||
} xHeap __attribute__ ((section (".heap")));
|
||||
|
||||
/* Define the linked list structure. This is used to link free blocks in order
|
||||
of their size. */
|
||||
@ -101,6 +101,7 @@ static xBlockLink xStart, xEnd;
|
||||
/* Keeps track of the number of free bytes remaining, but says nothing about
|
||||
fragmentation. */
|
||||
static size_t xFreeBytesRemaining = configTOTAL_HEAP_SIZE;
|
||||
static size_t currentTOTAL_HEAP_SIZE = configTOTAL_HEAP_SIZE;
|
||||
|
||||
/* STATIC FUNCTIONS ARE DEFINED AS MACROS TO MINIMIZE THE FUNCTION CALL DEPTH. */
|
||||
|
||||
@ -140,13 +141,13 @@ xBlockLink *pxFirstFreeBlock; \
|
||||
xStart.xBlockSize = ( size_t ) 0; \
|
||||
\
|
||||
/* xEnd is used to mark the end of the list of free blocks. */ \
|
||||
xEnd.xBlockSize = configTOTAL_HEAP_SIZE; \
|
||||
xEnd.xBlockSize = currentTOTAL_HEAP_SIZE; \
|
||||
xEnd.pxNextFreeBlock = NULL; \
|
||||
\
|
||||
/* To start with there is a single free block that is sized to take up the \
|
||||
entire heap space. */ \
|
||||
pxFirstFreeBlock = ( void * ) xHeap.ucHeap; \
|
||||
pxFirstFreeBlock->xBlockSize = configTOTAL_HEAP_SIZE; \
|
||||
pxFirstFreeBlock->xBlockSize = currentTOTAL_HEAP_SIZE; \
|
||||
pxFirstFreeBlock->pxNextFreeBlock = &xEnd; \
|
||||
}
|
||||
/*-----------------------------------------------------------*/
|
||||
@ -181,7 +182,7 @@ void *pvReturn = NULL;
|
||||
}
|
||||
}
|
||||
|
||||
if( ( xWantedSize > 0 ) && ( xWantedSize < configTOTAL_HEAP_SIZE ) )
|
||||
if( ( xWantedSize > 0 ) && ( xWantedSize < currentTOTAL_HEAP_SIZE ) )
|
||||
{
|
||||
/* Blocks are stored in byte order - traverse the list from the start
|
||||
(smallest) block until one of adequate size is found. */
|
||||
@ -220,7 +221,7 @@ void *pvReturn = NULL;
|
||||
/* Insert the new block into the list of free blocks. */
|
||||
prvInsertBlockIntoFreeList( ( pxNewBlockLink ) );
|
||||
}
|
||||
|
||||
|
||||
xFreeBytesRemaining -= pxBlock->xBlockSize;
|
||||
}
|
||||
}
|
||||
@ -276,3 +277,18 @@ void vPortInitialiseBlocks( void )
|
||||
{
|
||||
/* This just exists to keep the linker quiet. */
|
||||
}
|
||||
|
||||
void xPortIncreaseHeapSize( size_t bytes )
|
||||
{
|
||||
xBlockLink *pxNewBlockLink;
|
||||
vTaskSuspendAll();
|
||||
currentTOTAL_HEAP_SIZE = configTOTAL_HEAP_SIZE + bytes;
|
||||
xEnd.xBlockSize = currentTOTAL_HEAP_SIZE;
|
||||
xFreeBytesRemaining += bytes;
|
||||
/* Insert the new block into the list of free blocks. */
|
||||
pxNewBlockLink = ( void * ) &xHeap.ucHeap[ configTOTAL_HEAP_SIZE ];
|
||||
pxNewBlockLink->xBlockSize = bytes;
|
||||
prvInsertBlockIntoFreeList( ( pxNewBlockLink ) );
|
||||
xTaskResumeAll();
|
||||
}
|
||||
/*-----------------------------------------------------------*/
|
||||
|
@ -3,7 +3,8 @@ PROVIDE ( vPortSVCHandler = 0 ) ;
|
||||
PROVIDE ( xPortPendSVHandler = 0 ) ;
|
||||
PROVIDE ( xPortSysTickHandler = 0 ) ;
|
||||
|
||||
_estack = 0x20004FF0;
|
||||
/* This is the size of the stack for early init and for all FreeRTOS IRQs */
|
||||
_irq_stack_size = 0x400;
|
||||
|
||||
/* Section Definitions */
|
||||
SECTIONS
|
||||
@ -59,6 +60,24 @@ SECTIONS
|
||||
_ebss = . ;
|
||||
} > SRAM
|
||||
|
||||
/*
|
||||
* This stack is used both as the initial sp during early init as well as ultimately
|
||||
* being used as the STM32's MSP (Main Stack Pointer) which is the same stack that
|
||||
* is used for _all_ interrupt handlers. The end of this stack should be placed
|
||||
* against the lowest address in RAM so that a stack overrun results in a hard fault
|
||||
* at the first access beyond the end of the stack.
|
||||
*/
|
||||
.irq_stack :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_irq_stack_end = . ;
|
||||
. = . + _irq_stack_size ;
|
||||
. = ALIGN(4);
|
||||
_irq_stack_top = . - 4 ;
|
||||
_init_stack_top = _irq_stack_top;
|
||||
. = ALIGN(4);
|
||||
} > SRAM
|
||||
|
||||
. = ALIGN(4);
|
||||
_end = . ;
|
||||
|
||||
|
@ -1,3 +1,8 @@
|
||||
/* This is the size of the stack for all FreeRTOS IRQs */
|
||||
_irq_stack_size = 0x180;
|
||||
/* This is the size of the stack for early init: life span is until scheduler starts */
|
||||
_init_stack_size = 0x100;
|
||||
|
||||
/* Stub out these functions since we don't use them anyway */
|
||||
PROVIDE ( vPortSVCHandler = 0 ) ;
|
||||
PROVIDE ( xPortPendSVHandler = 0 ) ;
|
||||
@ -5,8 +10,6 @@ PROVIDE ( xPortSysTickHandler = 0 ) ;
|
||||
|
||||
PROVIDE(pios_board_info_blob = ORIGIN(BD_INFO));
|
||||
|
||||
_estack = 0x20004FF0;
|
||||
|
||||
/* Section Definitions */
|
||||
SECTIONS
|
||||
{
|
||||
@ -29,6 +32,16 @@ SECTIONS
|
||||
__uavobj_initcall_end = .;
|
||||
} >FLASH
|
||||
|
||||
/* module sections */
|
||||
.initcallmodule.init :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__module_initcall_start = .;
|
||||
KEEP(*(.initcallmodule.init))
|
||||
. = ALIGN(4);
|
||||
__module_initcall_end = .;
|
||||
} >FLASH
|
||||
|
||||
.ARM.extab :
|
||||
{
|
||||
*(.ARM.extab* .gnu.linkonce.armextab.*)
|
||||
@ -43,6 +56,23 @@ SECTIONS
|
||||
_etext = .;
|
||||
_sidata = .;
|
||||
|
||||
/*
|
||||
* This stack is used both as the initial sp during early init as well as ultimately
|
||||
* being used as the STM32's MSP (Main Stack Pointer) which is the same stack that
|
||||
* is used for _all_ interrupt handlers. The end of this stack should be placed
|
||||
* against the lowest address in RAM so that a stack overrun results in a hard fault
|
||||
* at the first access beyond the end of the stack.
|
||||
*/
|
||||
.irq_stack :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_irq_stack_end = . ;
|
||||
. = . + _irq_stack_size ;
|
||||
. = ALIGN(4);
|
||||
_irq_stack_top = . - 4 ;
|
||||
. = ALIGN(4);
|
||||
} > SRAM
|
||||
|
||||
.data : AT (_etext)
|
||||
{
|
||||
_sdata = .;
|
||||
@ -51,18 +81,49 @@ SECTIONS
|
||||
_edata = . ;
|
||||
} > SRAM
|
||||
|
||||
|
||||
|
||||
/* .bss section which is used for uninitialized data */
|
||||
.bss (NOLOAD) :
|
||||
{
|
||||
_sbss = . ;
|
||||
*(.bss .bss.*)
|
||||
*(COMMON)
|
||||
. = ALIGN(4);
|
||||
_ebss = . ;
|
||||
} > SRAM
|
||||
|
||||
. = ALIGN(4);
|
||||
_end = . ;
|
||||
.heap (NOLOAD) :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sheap = . ;
|
||||
_sheap_pre_rtos = . ;
|
||||
*(.heap)
|
||||
. = ALIGN(4);
|
||||
_eheap = . ;
|
||||
_eheap_pre_rtos = . ;
|
||||
_init_stack_end = . ;
|
||||
_sheap_post_rtos = . ;
|
||||
. = . + _init_stack_size ;
|
||||
. = ALIGN(4);
|
||||
_eheap_post_rtos = . ;
|
||||
_init_stack_top = . - 4 ;
|
||||
} > SRAM
|
||||
|
||||
|
||||
_free_ram = . ;
|
||||
.free_ram (NOLOAD) :
|
||||
{
|
||||
. = ORIGIN(SRAM) + LENGTH(SRAM) - _free_ram ;
|
||||
/* This is used by the startup in order to initialize the .bss section */
|
||||
_ebss = . ;
|
||||
_eram = . ;
|
||||
} > SRAM
|
||||
|
||||
/* keep the heap section at the end of the SRAM
|
||||
* this will allow to claim the remaining bytes not used
|
||||
* at run time! (done by the reset vector).
|
||||
*/
|
||||
|
||||
PROVIDE ( _end = _ebss ) ;
|
||||
|
||||
/* Stabs debugging sections. */
|
||||
.stab 0 : { *(.stab) }
|
||||
|
@ -250,6 +250,7 @@ SECTIONS
|
||||
. = . + _irq_stack_size ;
|
||||
. = ALIGN(4);
|
||||
_irq_stack_top = . - 4 ;
|
||||
_init_stack_top = _irq_stack_top;
|
||||
. = ALIGN(4);
|
||||
} >RAM
|
||||
|
||||
|
@ -223,6 +223,7 @@ SECTIONS
|
||||
. = . + _irq_stack_size ;
|
||||
. = ALIGN(4);
|
||||
_irq_stack_top = . - 4 ;
|
||||
_init_stack_top = _irq_stack_top;
|
||||
. = ALIGN(4);
|
||||
} >RAM
|
||||
|
||||
@ -364,5 +365,3 @@ SECTIONS
|
||||
.debug_typenames 0 : { *(.debug_typenames) }
|
||||
.debug_varnames 0 : { *(.debug_varnames) }
|
||||
}
|
||||
|
||||
|
||||
|
@ -1,5 +1,7 @@
|
||||
/* This is the size of the stack for early init and for all FreeRTOS IRQs */
|
||||
_irq_stack_size = 0x400;
|
||||
/* This is the size of the stack for early init: life span is until scheduler starts */
|
||||
_init_stack_size = 0x400;
|
||||
|
||||
/* Check valid alignment for VTOR */
|
||||
ASSERT(ORIGIN(FLASH) == ALIGN(ORIGIN(FLASH), 0x80), "Start of memory region flash not aligned for startup vector table");
|
||||
@ -191,6 +193,16 @@ SECTIONS
|
||||
__uavobj_initcall_end = .;
|
||||
} >FLASH
|
||||
|
||||
/* module sections */
|
||||
.initcallmodule.init :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
__module_initcall_start = .;
|
||||
KEEP(*(.initcallmodule.init))
|
||||
. = ALIGN(4);
|
||||
__module_initcall_end = .;
|
||||
} >FLASH
|
||||
|
||||
/* the program code is stored in the .text section, which goes to Flash */
|
||||
.text :
|
||||
{
|
||||
@ -250,17 +262,44 @@ SECTIONS
|
||||
.bss :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
/* This is used by the startup in order to initialize the .bss secion */
|
||||
/* This is used by the startup in order to initialize the .bss section */
|
||||
_sbss = .;
|
||||
|
||||
*(.bss)
|
||||
*(COMMON)
|
||||
|
||||
. = ALIGN(4);
|
||||
/* This is used by the startup in order to initialize the .bss secion */
|
||||
_ebss = . ;
|
||||
} >RAM
|
||||
|
||||
.heap (NOLOAD) :
|
||||
{
|
||||
. = ALIGN(4);
|
||||
_sheap = . ;
|
||||
_sheap_pre_rtos = . ;
|
||||
*(.heap)
|
||||
. = ALIGN(4);
|
||||
_eheap = . ;
|
||||
_eheap_pre_rtos = . ;
|
||||
_init_stack_end = . ;
|
||||
_sheap_post_rtos = . ;
|
||||
. = . + _init_stack_size ;
|
||||
. = ALIGN(4);
|
||||
_eheap_post_rtos = . ;
|
||||
_init_stack_top = . - 4 ;
|
||||
} > RAM
|
||||
|
||||
_free_ram = . ;
|
||||
.free_ram (NOLOAD) :
|
||||
{
|
||||
. = ORIGIN(RAM) + LENGTH(RAM) - _free_ram ;
|
||||
/* This is used by the startup in order to initialize the .bss section */
|
||||
_ebss = . ;
|
||||
_eram = . ;
|
||||
} > RAM
|
||||
|
||||
/* keep the heap section at the end of the SRAM
|
||||
* this will allow to claim the remaining bytes not used
|
||||
* at run time! (done by the reset vector).
|
||||
*/
|
||||
|
||||
PROVIDE ( end = _ebss );
|
||||
PROVIDE ( _end = _ebss );
|
||||
|
||||
|
@ -7,10 +7,10 @@
|
||||
* @{
|
||||
*
|
||||
* @file pios_delay.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org)
|
||||
* @author Michael Smith Copyright (C) 2011
|
||||
* @brief Delay Functions
|
||||
* - Provides a micro-second granular delay using a TIM
|
||||
* - Provides a micro-second granular delay using the CPU
|
||||
* cycle counter.
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
*
|
||||
*****************************************************************************/
|
||||
@ -31,72 +31,97 @@
|
||||
*/
|
||||
|
||||
/* Project Includes */
|
||||
#include "pios.h"
|
||||
#include <pios.h>
|
||||
|
||||
#if defined(PIOS_INCLUDE_DELAY)
|
||||
|
||||
/* these should be defined by CMSIS, but they aren't */
|
||||
#define DWT_CTRL (*(volatile uint32_t *)0xe0001000)
|
||||
#define CYCCNTENA (1<<0)
|
||||
#define DWT_CYCCNT (*(volatile uint32_t *)0xe0001004)
|
||||
|
||||
|
||||
/* cycles per microsecond */
|
||||
static uint32_t us_ticks;
|
||||
|
||||
/**
|
||||
* Initialises the Timer used by PIOS_DELAY functions<BR>
|
||||
* This is called from pios.c as part of the main() function
|
||||
* at system start up.
|
||||
* \return < 0 if initialisation failed
|
||||
*/
|
||||
* Initialises the Timer used by PIOS_DELAY functions.
|
||||
*
|
||||
* \return always zero (success)
|
||||
*/
|
||||
|
||||
int32_t PIOS_DELAY_Init(void)
|
||||
{
|
||||
/* Enable timer clock */
|
||||
PIOS_DELAY_TIMER_RCC_FUNC;
|
||||
RCC_ClocksTypeDef clocks;
|
||||
|
||||
/* Time base configuration */
|
||||
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
|
||||
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
|
||||
TIM_TimeBaseStructure.TIM_Period = 65535; // maximum value
|
||||
TIM_TimeBaseStructure.TIM_Prescaler = 72 - 1; // for 1 uS accuracy fixed to 72Mhz
|
||||
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
|
||||
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
|
||||
TIM_TimeBaseInit(PIOS_DELAY_TIMER, &TIM_TimeBaseStructure);
|
||||
/* compute the number of system clocks per microsecond */
|
||||
RCC_GetClocksFreq(&clocks);
|
||||
us_ticks = clocks.SYSCLK_Frequency / 1000000;
|
||||
PIOS_DEBUG_Assert(us_ticks > 1);
|
||||
|
||||
/* Enable counter */
|
||||
TIM_Cmd(PIOS_DELAY_TIMER, ENABLE);
|
||||
/* turn on access to the DWT registers */
|
||||
CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk;
|
||||
|
||||
/* enable the CPU cycle counter */
|
||||
DWT_CTRL |= CYCCNTENA;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Waits for a specific number of uS
|
||||
*
|
||||
* Example:<BR>
|
||||
* \code
|
||||
* // Wait for 500 uS
|
||||
* PIOS_DELAY_Wait_uS(500);
|
||||
* \endcode
|
||||
* \param[in] uS delay
|
||||
* \return < 0 on errors
|
||||
*/
|
||||
int32_t PIOS_DELAY_WaituS(uint32_t uS)
|
||||
{
|
||||
uint32_t elapsed = 0;
|
||||
uint32_t last_count = DWT_CYCCNT;
|
||||
|
||||
for (;;) {
|
||||
uint32_t current_count = DWT_CYCCNT;
|
||||
uint32_t elapsed_uS;
|
||||
|
||||
/* measure the time elapsed since the last time we checked */
|
||||
elapsed += current_count - last_count;
|
||||
last_count = current_count;
|
||||
|
||||
/* convert to microseconds */
|
||||
elapsed_uS = elapsed / us_ticks;
|
||||
if (elapsed_uS >= uS)
|
||||
break;
|
||||
|
||||
/* reduce the delay by the elapsed time */
|
||||
uS -= elapsed_uS;
|
||||
|
||||
/* keep fractional microseconds for the next iteration */
|
||||
elapsed %= us_ticks;
|
||||
}
|
||||
|
||||
/* No error */
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Waits for a specific number of uS<BR>
|
||||
* Example:<BR>
|
||||
* \code
|
||||
* // Wait for 500 uS
|
||||
* PIOS_DELAY_Wait_uS(500);
|
||||
* \endcode
|
||||
* \param[in] uS delay (1..65535 microseconds)
|
||||
* \return < 0 on errors
|
||||
*/
|
||||
int32_t PIOS_DELAY_WaituS(uint16_t uS)
|
||||
* Waits for a specific number of mS
|
||||
*
|
||||
* Example:<BR>
|
||||
* \code
|
||||
* // Wait for 500 mS
|
||||
* PIOS_DELAY_Wait_mS(500);
|
||||
* \endcode
|
||||
* \param[in] mS delay (1..65535 milliseconds)
|
||||
* \return < 0 on errors
|
||||
*/
|
||||
int32_t PIOS_DELAY_WaitmS(uint32_t mS)
|
||||
{
|
||||
uint16_t start = PIOS_DELAY_TIMER->CNT;
|
||||
|
||||
/* Note that this event works on 16bit counter wrap-arounds */
|
||||
while ((uint16_t) (PIOS_DELAY_TIMER->CNT - start) <= uS) ;
|
||||
|
||||
/* No error */
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Waits for a specific number of mS<BR>
|
||||
* Example:<BR>
|
||||
* \code
|
||||
* // Wait for 500 mS
|
||||
* PIOS_DELAY_Wait_mS(500);
|
||||
* \endcode
|
||||
* \param[in] mS delay (1..65535 milliseconds)
|
||||
* \return < 0 on errors
|
||||
*/
|
||||
int32_t PIOS_DELAY_WaitmS(uint16_t mS)
|
||||
{
|
||||
for (int i = 0; i < mS; i++) {
|
||||
while (mS--) {
|
||||
PIOS_DELAY_WaituS(1000);
|
||||
}
|
||||
|
||||
@ -108,22 +133,9 @@ int32_t PIOS_DELAY_WaitmS(uint16_t mS)
|
||||
* @brief Query the Delay timer for the current uS
|
||||
* @return A microsecond value
|
||||
*/
|
||||
uint16_t PIOS_DELAY_GetuS()
|
||||
uint32_t PIOS_DELAY_GetuS()
|
||||
{
|
||||
return PIOS_DELAY_TIMER->CNT;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Compute the difference between now and a reference time
|
||||
* @param[in] the reference time to compare now to
|
||||
* @return The number of uS since the delay
|
||||
*
|
||||
* @note the user is responsible for worrying about rollover on the 16 bit uS counter
|
||||
*/
|
||||
int32_t PIOS_DELAY_DiffuS(uint16_t ref)
|
||||
{
|
||||
int32_t ret_t = ref;
|
||||
return (int16_t) (PIOS_DELAY_GetuS() - ret_t);
|
||||
return DWT_CYCCNT / us_ticks;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
@ -34,22 +34,29 @@
|
||||
|
||||
#if defined(PIOS_INCLUDE_PPM)
|
||||
|
||||
/* Local Variables */
|
||||
/* Provide a RCVR driver */
|
||||
static int32_t PIOS_PPM_Get(uint32_t rcvr_id, uint8_t channel);
|
||||
|
||||
const struct pios_rcvr_driver pios_ppm_rcvr_driver = {
|
||||
.read = PIOS_PPM_Get,
|
||||
};
|
||||
|
||||
/* Local Variables */
|
||||
static TIM_ICInitTypeDef TIM_ICInitStructure;
|
||||
static uint8_t PulseIndex;
|
||||
static uint32_t PreviousValue;
|
||||
static uint32_t CurrentValue;
|
||||
static uint32_t CapturedValue;
|
||||
static uint32_t CaptureValue[PIOS_PPM_NUM_INPUTS];
|
||||
|
||||
static uint8_t SupervisorState = 0;
|
||||
static uint32_t CapCounter[PIOS_PPM_NUM_INPUTS];
|
||||
static uint16_t TimerCounter;
|
||||
|
||||
static uint8_t supv_timer = 0;
|
||||
static uint8_t SupervisorState = 0;
|
||||
static uint32_t CapCounterPrev[PIOS_PPM_NUM_INPUTS];
|
||||
|
||||
/**
|
||||
* Initialises all the LED's
|
||||
*/
|
||||
static void PIOS_PPM_Supervisor(uint32_t ppm_id);
|
||||
|
||||
void PIOS_PPM_Init(void)
|
||||
{
|
||||
/* Flush counter variables */
|
||||
@ -59,6 +66,7 @@ void PIOS_PPM_Init(void)
|
||||
PreviousValue = 0;
|
||||
CurrentValue = 0;
|
||||
CapturedValue = 0;
|
||||
TimerCounter = 0;
|
||||
|
||||
for (i = 0; i < PIOS_PPM_NUM_INPUTS; i++) {
|
||||
CaptureValue[i] = 0;
|
||||
@ -121,13 +129,12 @@ void PIOS_PPM_Init(void)
|
||||
TIM_TimeBaseInit(pios_ppm_cfg.timer, &TIM_TimeBaseStructure);
|
||||
|
||||
/* Enable the Capture Compare Interrupt Request */
|
||||
TIM_ITConfig(pios_ppm_cfg.timer, pios_ppm_cfg.ccr, ENABLE);
|
||||
TIM_ITConfig(pios_ppm_cfg.timer, pios_ppm_cfg.ccr | TIM_IT_Update, ENABLE);
|
||||
|
||||
/* Enable timers */
|
||||
TIM_Cmd(pios_ppm_cfg.timer, ENABLE);
|
||||
|
||||
/* Supervisor Setup */
|
||||
#if (PIOS_PPM_SUPV_ENABLED)
|
||||
/* Flush counter variables */
|
||||
for (i = 0; i < PIOS_PPM_NUM_INPUTS; i++) {
|
||||
CapCounter[i] = 0;
|
||||
@ -136,70 +143,15 @@ void PIOS_PPM_Init(void)
|
||||
CapCounterPrev[i] = 0;
|
||||
}
|
||||
|
||||
NVIC_InitStructure = pios_ppmsv_cfg.irq.init;
|
||||
|
||||
/* Enable appropriate clock to timer module */
|
||||
switch((int32_t) pios_ppmsv_cfg.timer) {
|
||||
case (int32_t)TIM1:
|
||||
NVIC_InitStructure.NVIC_IRQChannel = TIM1_CC_IRQn;
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1, ENABLE);
|
||||
break;
|
||||
case (int32_t)TIM2:
|
||||
NVIC_InitStructure.NVIC_IRQChannel = TIM2_IRQn;
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE);
|
||||
break;
|
||||
case (int32_t)TIM3:
|
||||
NVIC_InitStructure.NVIC_IRQChannel = TIM3_IRQn;
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE);
|
||||
break;
|
||||
case (int32_t)TIM4:
|
||||
NVIC_InitStructure.NVIC_IRQChannel = TIM4_IRQn;
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM4, ENABLE);
|
||||
break;
|
||||
#ifdef STM32F10X_HD
|
||||
|
||||
case (int32_t)TIM5:
|
||||
NVIC_InitStructure.NVIC_IRQChannel = TIM5_IRQn;
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM5, ENABLE);
|
||||
break;
|
||||
case (int32_t)TIM6:
|
||||
NVIC_InitStructure.NVIC_IRQChannel = TIM6_IRQn;
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM6, ENABLE);
|
||||
break;
|
||||
case (int32_t)TIM7:
|
||||
NVIC_InitStructure.NVIC_IRQChannel = TIM7_IRQn;
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM7, ENABLE);
|
||||
break;
|
||||
case (int32_t)TIM8:
|
||||
NVIC_InitStructure.NVIC_IRQChannel = TIM8_CC_IRQn;
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM8, ENABLE);
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
|
||||
/* Configure interrupts */
|
||||
NVIC_Init(&NVIC_InitStructure);
|
||||
|
||||
/* Time base configuration */
|
||||
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
|
||||
TIM_TimeBaseStructure = pios_ppmsv_cfg.tim_base_init;
|
||||
TIM_TimeBaseInit(pios_ppmsv_cfg.timer, &TIM_TimeBaseStructure);
|
||||
|
||||
/* Enable the CCx Interrupt Request */
|
||||
TIM_ITConfig(pios_ppmsv_cfg.timer, pios_ppmsv_cfg.ccr, ENABLE);
|
||||
|
||||
/* Clear update pending flag */
|
||||
TIM_ClearFlag(pios_ppmsv_cfg.timer, TIM_FLAG_Update);
|
||||
|
||||
/* Enable counter */
|
||||
TIM_Cmd(pios_ppmsv_cfg.timer, ENABLE);
|
||||
#endif
|
||||
|
||||
/* Setup local variable which stays in this scope */
|
||||
/* Doing this here and using a local variable saves doing it in the ISR */
|
||||
TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI;
|
||||
TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1;
|
||||
TIM_ICInitStructure.TIM_ICFilter = 0x0;
|
||||
|
||||
if (!PIOS_RTC_RegisterTickCallback(PIOS_PPM_Supervisor, 0)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
@ -208,13 +160,13 @@ void PIOS_PPM_Init(void)
|
||||
* \output -1 Channel not available
|
||||
* \output >0 Channel value
|
||||
*/
|
||||
int32_t PIOS_PPM_Get(int8_t Channel)
|
||||
static int32_t PIOS_PPM_Get(uint32_t rcvr_id, uint8_t channel)
|
||||
{
|
||||
/* Return error if channel not available */
|
||||
if (Channel >= PIOS_PPM_NUM_INPUTS) {
|
||||
if (channel >= PIOS_PPM_NUM_INPUTS) {
|
||||
return -1;
|
||||
}
|
||||
return CaptureValue[Channel];
|
||||
return CaptureValue[channel];
|
||||
}
|
||||
|
||||
/**
|
||||
@ -224,6 +176,15 @@ int32_t PIOS_PPM_Get(int8_t Channel)
|
||||
*/
|
||||
void PIOS_PPM_irq_handler(void)
|
||||
{
|
||||
if (TIM_GetITStatus(pios_ppm_cfg.timer, TIM_IT_Update) == SET) {
|
||||
TimerCounter+=pios_ppm_cfg.timer->ARR;
|
||||
TIM_ClearITPendingBit(pios_ppm_cfg.timer, TIM_IT_Update);
|
||||
if (TIM_GetITStatus(pios_ppm_cfg.timer, pios_ppm_cfg.ccr) != SET) {
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/* Do this as it's more efficient */
|
||||
if (TIM_GetITStatus(pios_ppm_cfg.timer, pios_ppm_cfg.ccr) == SET) {
|
||||
PreviousValue = CurrentValue;
|
||||
@ -241,37 +202,44 @@ void PIOS_PPM_irq_handler(void)
|
||||
CurrentValue = TIM_GetCapture4(pios_ppm_cfg.timer);
|
||||
break;
|
||||
}
|
||||
}
|
||||
CurrentValue+=TimerCounter;
|
||||
if(CurrentValue > 0xFFFF) {
|
||||
CurrentValue-=0xFFFF;
|
||||
}
|
||||
|
||||
/* Clear TIMx Capture compare interrupt pending bit */
|
||||
TIM_ClearITPendingBit(pios_ppm_cfg.timer, pios_ppm_cfg.ccr);
|
||||
/* Clear TIMx Capture compare interrupt pending bit */
|
||||
TIM_ClearITPendingBit(pios_ppm_cfg.timer, pios_ppm_cfg.ccr);
|
||||
|
||||
/* Capture computation */
|
||||
if (CurrentValue > PreviousValue) {
|
||||
CapturedValue = (CurrentValue - PreviousValue);
|
||||
} else {
|
||||
CapturedValue = ((0xFFFF - PreviousValue) + CurrentValue);
|
||||
}
|
||||
/* Capture computation */
|
||||
if (CurrentValue > PreviousValue) {
|
||||
CapturedValue = (CurrentValue - PreviousValue);
|
||||
} else {
|
||||
CapturedValue = ((0xFFFF - PreviousValue) + CurrentValue);
|
||||
}
|
||||
|
||||
/* sync pulse */
|
||||
if (CapturedValue > 8000) {
|
||||
PulseIndex = 0;
|
||||
/* trying to detect bad pulses, not sure this is working correctly yet. I need a scope :P */
|
||||
} else if (CapturedValue > 750 && CapturedValue < 2500) {
|
||||
if (PulseIndex < PIOS_PPM_NUM_INPUTS) {
|
||||
CaptureValue[PulseIndex] = CapturedValue;
|
||||
CapCounter[PulseIndex]++;
|
||||
PulseIndex++;
|
||||
/* sync pulse */
|
||||
if (CapturedValue > 8000) {
|
||||
PulseIndex = 0;
|
||||
/* trying to detect bad pulses, not sure this is working correctly yet. I need a scope :P */
|
||||
} else if (CapturedValue > 750 && CapturedValue < 2500) {
|
||||
if (PulseIndex < PIOS_PPM_NUM_INPUTS) {
|
||||
CaptureValue[PulseIndex] = CapturedValue;
|
||||
CapCounter[PulseIndex]++;
|
||||
PulseIndex++;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* This function handles TIM3 global interrupt request.
|
||||
*/
|
||||
void PIOS_PPMSV_irq_handler(void) {
|
||||
/* Clear timer interrupt pending bit */
|
||||
TIM_ClearITPendingBit(pios_ppmsv_cfg.timer, pios_ppmsv_cfg.ccr);
|
||||
static void PIOS_PPM_Supervisor(uint32_t ppm_id) {
|
||||
/*
|
||||
* RTC runs at 625Hz so divide down the base rate so
|
||||
* that this loop runs at 25Hz.
|
||||
*/
|
||||
if(++supv_timer < 25) {
|
||||
return;
|
||||
}
|
||||
supv_timer = 0;
|
||||
|
||||
/* Simple state machine */
|
||||
if (SupervisorState == 0) {
|
||||
|
@ -34,15 +34,20 @@
|
||||
|
||||
#if defined(PIOS_INCLUDE_PWM)
|
||||
|
||||
/* Local Variables */
|
||||
static uint8_t CaptureState[PIOS_PWM_MAX_INPUTS];
|
||||
static uint16_t RiseValue[PIOS_PWM_MAX_INPUTS];
|
||||
static uint16_t FallValue[PIOS_PWM_MAX_INPUTS];
|
||||
static uint32_t CaptureValue[PIOS_PWM_MAX_INPUTS];
|
||||
/* Provide a RCVR driver */
|
||||
static int32_t PIOS_PWM_Get(uint32_t rcvr_id, uint8_t chan_id);
|
||||
|
||||
//static uint8_t SupervisorState = 0;
|
||||
static uint32_t CapCounter[PIOS_PWM_MAX_INPUTS];
|
||||
//static uint32_t CapCounterPrev[MAX_CHANNELS];
|
||||
const struct pios_rcvr_driver pios_pwm_rcvr_driver = {
|
||||
.read = PIOS_PWM_Get,
|
||||
};
|
||||
|
||||
/* Local Variables */
|
||||
static uint8_t CaptureState[PIOS_PWM_NUM_INPUTS];
|
||||
static uint16_t RiseValue[PIOS_PWM_NUM_INPUTS];
|
||||
static uint16_t FallValue[PIOS_PWM_NUM_INPUTS];
|
||||
static uint32_t CaptureValue[PIOS_PWM_NUM_INPUTS];
|
||||
|
||||
static uint32_t CapCounter[PIOS_PWM_NUM_INPUTS];
|
||||
|
||||
/**
|
||||
* Initialises all the pins
|
||||
@ -127,52 +132,6 @@ void PIOS_PWM_Init(void)
|
||||
/* Warning, I don't think this will work for multiple remaps at once */
|
||||
GPIO_PinRemapConfig(pios_pwm_cfg.remap, ENABLE);
|
||||
}
|
||||
|
||||
#if 0
|
||||
/* Supervisor Setup */
|
||||
#if (PIOS_PWM_SUPV_ENABLED)
|
||||
/* Flush counter variables */
|
||||
for (i = 0; i < PIOS_PWM_NUM_INPUTS; i++) {
|
||||
CapCounter[i] = 0;
|
||||
}
|
||||
for (i = 0; i < PIOS_PWM_NUM_INPUTS; i++) {
|
||||
CapCounterPrev[i] = 0;
|
||||
}
|
||||
|
||||
/* Enable timer clock */
|
||||
PIOS_PWM_SUPV_TIMER_RCC_FUNC;
|
||||
|
||||
/* Configure interrupts */
|
||||
NVIC_InitStructure.NVIC_IRQChannel = PIOS_PWM_SUPV_IRQ_CHANNEL;
|
||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID;
|
||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
|
||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||
NVIC_Init(&NVIC_InitStructure);
|
||||
|
||||
/* Time base configuration */
|
||||
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
|
||||
TIM_TimeBaseStructure.TIM_Period = ((1000000 / PIOS_PWM_SUPV_HZ) - 1);
|
||||
TIM_TimeBaseStructure.TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1; /* For 1 uS accuracy */
|
||||
TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1;
|
||||
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
|
||||
TIM_TimeBaseInit(PIOS_PWM_SUPV_TIMER, &TIM_TimeBaseStructure);
|
||||
|
||||
/* Enable the CC2 Interrupt Request */
|
||||
TIM_ITConfig(PIOS_PWM_SUPV_TIMER, TIM_IT_Update, ENABLE);
|
||||
|
||||
/* Clear update pending flag */
|
||||
TIM_ClearFlag(TIM2, TIM_FLAG_Update);
|
||||
|
||||
/* Enable counter */
|
||||
TIM_Cmd(PIOS_PWM_SUPV_TIMER, ENABLE);
|
||||
#endif
|
||||
|
||||
/* Setup local variable which stays in this scope */
|
||||
/* Doing this here and using a local variable saves doing it in the ISR */
|
||||
TIM_ICInitStructure.TIM_ICSelection = TIM_ICSelection_DirectTI;
|
||||
TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1;
|
||||
TIM_ICInitStructure.TIM_ICFilter = 0x0;
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
@ -181,13 +140,13 @@ void PIOS_PWM_Init(void)
|
||||
* \output -1 Channel not available
|
||||
* \output >0 Channel value
|
||||
*/
|
||||
int32_t PIOS_PWM_Get(int8_t Channel)
|
||||
static int32_t PIOS_PWM_Get(uint32_t rcvr_id, uint8_t channel)
|
||||
{
|
||||
/* Return error if channel not available */
|
||||
if (Channel >= pios_pwm_cfg.num_channels) {
|
||||
if (channel >= pios_pwm_cfg.num_channels) {
|
||||
return -1;
|
||||
}
|
||||
return CaptureValue[Channel];
|
||||
return CaptureValue[channel];
|
||||
}
|
||||
|
||||
void PIOS_PWM_irq_handler(TIM_TypeDef * timer)
|
||||
@ -254,84 +213,6 @@ void PIOS_PWM_irq_handler(TIM_TypeDef * timer)
|
||||
}
|
||||
}
|
||||
|
||||
#if 0
|
||||
/**
|
||||
* Handle TIM5 global interrupt request
|
||||
*/
|
||||
void TIM5_IRQHandler(void)
|
||||
{
|
||||
/* Do this as it's more efficient */
|
||||
if (TIM_GetITStatus(PIOS_PWM_TIM_PORT[2], PIOS_PWM_TIM_CCR[2]) == SET) {
|
||||
if (CaptureState[2] == 0) {
|
||||
RiseValue[2] = TIM_GetCapture1(PIOS_PWM_TIM_PORT[2]);
|
||||
} else {
|
||||
FallValue[2] = TIM_GetCapture1(PIOS_PWM_TIM_PORT[2]);
|
||||
}
|
||||
|
||||
/* Clear TIM3 Capture compare interrupt pending bit */
|
||||
TIM_ClearITPendingBit(PIOS_PWM_TIM_PORT[2], PIOS_PWM_TIM_CCR[2]);
|
||||
|
||||
/* Simple rise or fall state machine */
|
||||
if (CaptureState[2] == 0) {
|
||||
/* Switch states */
|
||||
CaptureState[2] = 1;
|
||||
|
||||
/* Switch polarity of input capture */
|
||||
TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Falling;
|
||||
TIM_ICInitStructure.TIM_Channel = PIOS_PWM_TIM_CHANNEL[2];
|
||||
TIM_ICInit(PIOS_PWM_TIM_PORT[2], &TIM_ICInitStructure);
|
||||
|
||||
} else {
|
||||
/* Capture computation */
|
||||
if (FallValue[2] > RiseValue[2]) {
|
||||
CaptureValue[2] = (FallValue[2] - RiseValue[2]);
|
||||
} else {
|
||||
CaptureValue[2] = ((0xFFFF - RiseValue[2]) + FallValue[2]);
|
||||
}
|
||||
|
||||
/* Switch states */
|
||||
CaptureState[2] = 0;
|
||||
|
||||
/* Increase supervisor counter */
|
||||
CapCounter[2]++;
|
||||
|
||||
/* Switch polarity of input capture */
|
||||
TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Rising;
|
||||
TIM_ICInitStructure.TIM_Channel = PIOS_PWM_TIM_CHANNEL[2];
|
||||
TIM_ICInit(PIOS_PWM_TIM_PORT[2], &TIM_ICInitStructure);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* This function handles TIM3 global interrupt request.
|
||||
*/
|
||||
PIOS_PWM_SUPV_IRQ_FUNC {
|
||||
/* Clear timer interrupt pending bit */
|
||||
TIM_ClearITPendingBit(PIOS_PWM_SUPV_TIMER, TIM_IT_Update);
|
||||
|
||||
/* Simple state machine */
|
||||
if (SupervisorState == 0) {
|
||||
/* Save this states values */
|
||||
for (int32_t i = 0; i < PIOS_PWM_NUM_INPUTS; i++) {
|
||||
CapCounterPrev[i] = CapCounter[i];
|
||||
}
|
||||
|
||||
/* Move to next state */
|
||||
SupervisorState = 1;
|
||||
} else {
|
||||
/* See what channels have been updated */
|
||||
for (int32_t i = 0; i < PIOS_PWM_NUM_INPUTS; i++) {
|
||||
if (CapCounter[i] == CapCounterPrev[i]) {
|
||||
CaptureValue[i] = 0;
|
||||
}
|
||||
}
|
||||
|
||||
/* Move to next state */
|
||||
SupervisorState = 0;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
@ -32,30 +32,39 @@
|
||||
#include "pios.h"
|
||||
|
||||
#if defined(PIOS_INCLUDE_RTC)
|
||||
#include <pios_rtc_priv.h>
|
||||
|
||||
#ifndef PIOS_RTC_PRESCALAR
|
||||
#define PIOS_RTC_PRESCALAR 100
|
||||
#ifndef PIOS_RTC_PRESCALER
|
||||
#define PIOS_RTC_PRESCALER 100
|
||||
#endif
|
||||
|
||||
void PIOS_RTC_Init()
|
||||
struct rtc_callback_entry {
|
||||
void (*fn)(uint32_t);
|
||||
uint32_t data;
|
||||
};
|
||||
|
||||
#define PIOS_RTC_MAX_CALLBACKS 3
|
||||
struct rtc_callback_entry rtc_callback_list[PIOS_RTC_MAX_CALLBACKS];
|
||||
static uint8_t rtc_callback_next = 0;
|
||||
|
||||
void PIOS_RTC_Init(const struct pios_rtc_cfg * cfg)
|
||||
{
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_BKP | RCC_APB1Periph_PWR,
|
||||
ENABLE);
|
||||
PWR_BackupAccessCmd(ENABLE);
|
||||
|
||||
RCC_RTCCLKConfig(RCC_RTCCLKSource_HSE_Div128);
|
||||
RCC_RTCCLKConfig(cfg->clksrc);
|
||||
RCC_RTCCLKCmd(ENABLE);
|
||||
RTC_WaitForLastTask();
|
||||
RTC_WaitForSynchro();
|
||||
RTC_WaitForLastTask();
|
||||
|
||||
#if defined(PIOS_INCLUDE_SPEKTRUM)
|
||||
/* Enable the RTC Second interrupt */
|
||||
/* Configure and enable the RTC Second interrupt */
|
||||
NVIC_Init(&cfg->irq.init);
|
||||
RTC_ITConfig( RTC_IT_SEC, ENABLE );
|
||||
/* Wait until last write operation on RTC registers has finished */
|
||||
RTC_WaitForLastTask();
|
||||
#endif
|
||||
RTC_SetPrescaler(PIOS_RTC_PRESCALAR); // counting at 8e6 / 128
|
||||
|
||||
RTC_SetPrescaler(cfg->prescaler);
|
||||
RTC_WaitForLastTask();
|
||||
RTC_SetCounter(0);
|
||||
RTC_WaitForLastTask();
|
||||
@ -66,9 +75,12 @@ uint32_t PIOS_RTC_Counter()
|
||||
return RTC_GetCounter();
|
||||
}
|
||||
|
||||
/* FIXME: This shouldn't use hard-coded clock rates, dividers or prescalers.
|
||||
* Should get these from the cfg struct passed to init.
|
||||
*/
|
||||
float PIOS_RTC_Rate()
|
||||
{
|
||||
return (float) (8e6 / 128) / (1 + PIOS_RTC_PRESCALAR);
|
||||
return (float) (8e6 / 128) / (1 + PIOS_RTC_PRESCALER);
|
||||
}
|
||||
|
||||
float PIOS_RTC_MsPerTick()
|
||||
@ -76,6 +88,39 @@ float PIOS_RTC_MsPerTick()
|
||||
return 1000.0f / PIOS_RTC_Rate();
|
||||
}
|
||||
|
||||
/* TODO: This needs a mutex around rtc_callbacks[] */
|
||||
bool PIOS_RTC_RegisterTickCallback(void (*fn)(uint32_t id), uint32_t data)
|
||||
{
|
||||
struct rtc_callback_entry * cb;
|
||||
if (rtc_callback_next >= PIOS_RTC_MAX_CALLBACKS) {
|
||||
return false;
|
||||
}
|
||||
|
||||
cb = &rtc_callback_list[rtc_callback_next++];
|
||||
|
||||
cb->fn = fn;
|
||||
cb->data = data;
|
||||
return true;
|
||||
}
|
||||
|
||||
void PIOS_RTC_irq_handler (void)
|
||||
{
|
||||
if (RTC_GetITStatus(RTC_IT_SEC))
|
||||
{
|
||||
/* Call all registered callbacks */
|
||||
for (uint8_t i = 0; i < rtc_callback_next; i++) {
|
||||
struct rtc_callback_entry * cb = &rtc_callback_list[i];
|
||||
if (cb->fn) {
|
||||
(cb->fn)(cb->data);
|
||||
}
|
||||
}
|
||||
|
||||
/* Wait until last write operation on RTC registers has finished */
|
||||
RTC_WaitForLastTask();
|
||||
/* Clear the RTC Second interrupt */
|
||||
RTC_ClearITPendingBit(RTC_IT_SEC);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/**
|
||||
|
227
flight/PiOS/STM32F10x/pios_sbus.c
Normal file
@ -0,0 +1,227 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_SBUS Futaba S.Bus receiver functions
|
||||
* @brief Code to read Futaba S.Bus input
|
||||
* @{
|
||||
*
|
||||
* @file pios_sbus.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011.
|
||||
* @brief USART commands. Inits USARTs, controls USARTs & Interrupt handlers. (STM32 dependent)
|
||||
* @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
|
||||
*/
|
||||
|
||||
/* Project Includes */
|
||||
#include "pios.h"
|
||||
#include "pios_sbus_priv.h"
|
||||
|
||||
#if defined(PIOS_INCLUDE_SBUS)
|
||||
|
||||
/* Global Variables */
|
||||
|
||||
/* Provide a RCVR driver */
|
||||
static int32_t PIOS_SBUS_Get(uint32_t rcvr_id, uint8_t channel);
|
||||
|
||||
const struct pios_rcvr_driver pios_sbus_rcvr_driver = {
|
||||
.read = PIOS_SBUS_Get,
|
||||
};
|
||||
|
||||
/* Local Variables */
|
||||
static uint16_t channel_data[SBUS_NUMBER_OF_CHANNELS];
|
||||
static uint8_t received_data[SBUS_FRAME_LENGTH - 2];
|
||||
static uint8_t receive_timer;
|
||||
static uint8_t failsafe_timer;
|
||||
static uint8_t frame_found;
|
||||
|
||||
static void PIOS_SBUS_Supervisor(uint32_t sbus_id);
|
||||
|
||||
/**
|
||||
* reset_channels() function clears all channel data in case of
|
||||
* lost signal or explicit failsafe flag from the S.Bus data stream
|
||||
*/
|
||||
static void reset_channels(void)
|
||||
{
|
||||
for (int i = 0; i < SBUS_NUMBER_OF_CHANNELS; i++) {
|
||||
channel_data[i] = 0;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* unroll_channels() function computes channel_data[] from received_data[]
|
||||
* For efficiency it unrolls first 8 channels without loops. If other
|
||||
* 8 channels are needed they can be unrolled using the same code
|
||||
* starting from s[11] instead of s[0]. Two extra digital channels are
|
||||
* accessible using (s[22] & SBUS_FLAG_DGx) logical expressions.
|
||||
*/
|
||||
static void unroll_channels(void)
|
||||
{
|
||||
uint8_t *s = received_data;
|
||||
uint16_t *d = channel_data;
|
||||
|
||||
#if (SBUS_NUMBER_OF_CHANNELS != 8)
|
||||
#error Current S.Bus code unrolls only first 8 channels
|
||||
#endif
|
||||
|
||||
#define F(v,s) ((v) >> s) & 0x7ff
|
||||
*d++ = F(s[0] | s[1] << 8, 0);
|
||||
*d++ = F(s[1] | s[2] << 8, 3);
|
||||
*d++ = F(s[2] | s[3] << 8 | s[4] << 16, 6);
|
||||
*d++ = F(s[4] | s[5] << 8, 1);
|
||||
*d++ = F(s[5] | s[6] << 8, 4);
|
||||
*d++ = F(s[6] | s[7] << 8 | s[8] << 16, 7);
|
||||
*d++ = F(s[8] | s[9] << 8, 2);
|
||||
*d++ = F(s[9] | s[10] << 8, 5);
|
||||
}
|
||||
|
||||
/**
|
||||
* process_byte() function processes incoming byte from S.Bus stream
|
||||
*/
|
||||
static void process_byte(uint8_t b)
|
||||
{
|
||||
static uint8_t byte_count;
|
||||
|
||||
if (frame_found == 0) {
|
||||
/* no frame found yet, waiting for start byte */
|
||||
if (b == SBUS_SOF_BYTE) {
|
||||
byte_count = 0;
|
||||
frame_found = 1;
|
||||
}
|
||||
} else {
|
||||
/* do not store start and end of frame bytes */
|
||||
if (byte_count < SBUS_FRAME_LENGTH - 2) {
|
||||
/* store next byte */
|
||||
received_data[byte_count++] = b;
|
||||
} else {
|
||||
if (b == SBUS_EOF_BYTE) {
|
||||
/* full frame received */
|
||||
uint8_t flags = received_data[SBUS_FRAME_LENGTH - 3];
|
||||
if (flags & SBUS_FLAG_FL) {
|
||||
/* frame lost, do not update */
|
||||
} else if (flags & SBUS_FLAG_FS) {
|
||||
/* failsafe flag active */
|
||||
reset_channels();
|
||||
} else {
|
||||
/* data looking good */
|
||||
unroll_channels();
|
||||
failsafe_timer = 0;
|
||||
}
|
||||
} else {
|
||||
/* discard whole frame */
|
||||
}
|
||||
|
||||
/* prepare for the next frame */
|
||||
frame_found = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialise S.Bus receiver interface
|
||||
*/
|
||||
void PIOS_SBUS_Init(const struct pios_sbus_cfg *cfg)
|
||||
{
|
||||
/* Enable inverter clock and enable the inverter */
|
||||
(*cfg->gpio_clk_func)(cfg->gpio_clk_periph, ENABLE);
|
||||
GPIO_Init(cfg->inv.gpio, &cfg->inv.init);
|
||||
GPIO_WriteBit(cfg->inv.gpio,
|
||||
cfg->inv.init.GPIO_Pin,
|
||||
cfg->gpio_inv_enable);
|
||||
|
||||
if (!PIOS_RTC_RegisterTickCallback(PIOS_SBUS_Supervisor, 0)) {
|
||||
PIOS_Assert(0);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the value of an input channel
|
||||
* \param[in] channel Number of the channel desired (zero based)
|
||||
* \output -1 channel not available
|
||||
* \output >0 channel value
|
||||
*/
|
||||
static int32_t PIOS_SBUS_Get(uint32_t rcvr_id, uint8_t channel)
|
||||
{
|
||||
/* return error if channel is not available */
|
||||
if (channel >= SBUS_NUMBER_OF_CHANNELS) {
|
||||
return -1;
|
||||
}
|
||||
return channel_data[channel];
|
||||
}
|
||||
|
||||
/**
|
||||
* Interrupt handler for USART
|
||||
*/
|
||||
void PIOS_SBUS_irq_handler(uint32_t usart_id)
|
||||
{
|
||||
/* Grab the config for this device from the underlying USART device */
|
||||
const struct pios_usart_cfg * cfg;
|
||||
cfg = PIOS_USART_GetConfig(usart_id);
|
||||
PIOS_Assert(cfg);
|
||||
|
||||
/* by always reading DR after SR make sure to clear any error interrupts */
|
||||
volatile uint16_t sr = cfg->regs->SR;
|
||||
volatile uint8_t b = cfg->regs->DR;
|
||||
|
||||
/* process received byte if one has arrived */
|
||||
if (sr & USART_SR_RXNE) {
|
||||
/* process byte and clear receive timer */
|
||||
process_byte(b);
|
||||
receive_timer = 0;
|
||||
}
|
||||
|
||||
/* ignore TXE interrupts */
|
||||
if (sr & USART_SR_TXE) {
|
||||
/* disable TXE interrupt (TXEIE=0) */
|
||||
USART_ITConfig(cfg->regs, USART_IT_TXE, DISABLE);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Input data supervisor is called periodically and provides
|
||||
* two functions: frame syncing and failsafe triggering.
|
||||
*
|
||||
* S.Bus frames come at 7ms (HS) or 14ms (FS) rate at 100000bps. RTC
|
||||
* timer is running at 625Hz (1.6ms). So with divider 2 it gives
|
||||
* 3.2ms pause between frames which is good for both S.Bus data rates.
|
||||
*
|
||||
* Data receive function must clear the receive_timer to confirm new
|
||||
* data reception. If no new data received in 100ms, we must call the
|
||||
* failsafe function which clears all channels.
|
||||
*/
|
||||
static void PIOS_SBUS_Supervisor(uint32_t sbus_id)
|
||||
{
|
||||
/* waiting for new frame if no bytes were received in 3.2ms */
|
||||
if (++receive_timer > 2) {
|
||||
receive_timer = 0;
|
||||
frame_found = 0;
|
||||
}
|
||||
|
||||
/* activate failsafe if no frames have arrived in 102.4ms */
|
||||
if (++failsafe_timer > 64) {
|
||||
reset_channels();
|
||||
failsafe_timer = 0;
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -6,25 +6,25 @@
|
||||
* @brief Code to do set RC servo output
|
||||
* @{
|
||||
*
|
||||
* @file pios_servo.c
|
||||
* @file pios_servo.c
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief RC Servo routines (STM32 dependent)
|
||||
* @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
|
||||
/*
|
||||
* 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
|
||||
*
|
||||
* 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.,
|
||||
*
|
||||
* 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
|
||||
*/
|
||||
|
||||
@ -41,15 +41,15 @@ void PIOS_Servo_Init(void)
|
||||
{
|
||||
#ifndef PIOS_ENABLE_DEBUG_PINS
|
||||
#if defined(PIOS_INCLUDE_SERVO)
|
||||
|
||||
|
||||
|
||||
|
||||
for (uint8_t i = 0; i < pios_servo_cfg.num_channels; i++) {
|
||||
GPIO_InitTypeDef GPIO_InitStructure = pios_servo_cfg.gpio_init;
|
||||
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure = pios_servo_cfg.tim_base_init;
|
||||
TIM_OCInitTypeDef TIM_OCInitStructure = pios_servo_cfg.tim_oc_init;
|
||||
|
||||
struct pios_servo_channel channel = pios_servo_cfg.channels[i];
|
||||
|
||||
|
||||
/* Enable appropriate clock to timer module */
|
||||
switch((int32_t) channel.timer) {
|
||||
case (int32_t)TIM1:
|
||||
@ -81,12 +81,12 @@ void PIOS_Servo_Init(void)
|
||||
/* Enable GPIO */
|
||||
GPIO_InitStructure.GPIO_Pin = channel.pin;
|
||||
GPIO_Init(channel.port, &GPIO_InitStructure);
|
||||
|
||||
|
||||
/* Enable time base */
|
||||
TIM_TimeBaseInit(channel.timer, &TIM_TimeBaseStructure);
|
||||
|
||||
|
||||
channel.timer->PSC = (PIOS_MASTER_CLOCK / 1000000) - 1;
|
||||
|
||||
|
||||
/* Set up for output compare function */
|
||||
switch(channel.channel) {
|
||||
case TIM_Channel_1:
|
||||
@ -106,19 +106,19 @@ void PIOS_Servo_Init(void)
|
||||
TIM_OC4PreloadConfig(channel.timer, TIM_OCPreload_Enable);
|
||||
break;
|
||||
}
|
||||
|
||||
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
|
||||
TIM_ARRPreloadConfig(channel.timer, ENABLE);
|
||||
TIM_CtrlPWMOutputs(channel.timer, ENABLE);
|
||||
TIM_Cmd(channel.timer, ENABLE);
|
||||
|
||||
}
|
||||
|
||||
TIM_Cmd(channel.timer, ENABLE);
|
||||
|
||||
}
|
||||
|
||||
if(pios_servo_cfg.remap) {
|
||||
/* Warning, I don't think this will work for multiple remaps at once */
|
||||
GPIO_PinRemapConfig(pios_servo_cfg.remap, ENABLE);
|
||||
}
|
||||
|
||||
|
||||
|
||||
#endif // PIOS_INCLUDE_SERVO
|
||||
#endif // PIOS_ENABLE_DEBUG_PINS
|
||||
@ -137,19 +137,19 @@ void PIOS_Servo_SetHz(uint16_t * speeds, uint8_t banks)
|
||||
TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1;
|
||||
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
|
||||
TIM_TimeBaseStructure.TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1;
|
||||
|
||||
|
||||
uint8_t set = 0;
|
||||
|
||||
for(uint8_t i = 0; (i < pios_servo_cfg.num_channels) && (set < banks); i++) {
|
||||
|
||||
for(uint8_t i = 0; (i < pios_servo_cfg.num_channels) && (set < banks); i++) {
|
||||
bool new = true;
|
||||
struct pios_servo_channel channel = pios_servo_cfg.channels[i];
|
||||
|
||||
|
||||
/* See if any previous channels use that same timer */
|
||||
for(uint8_t j = 0; (j < i) && new; j++)
|
||||
for(uint8_t j = 0; (j < i) && new; j++)
|
||||
new &= channel.timer != pios_servo_cfg.channels[j].timer;
|
||||
|
||||
|
||||
if(new) {
|
||||
TIM_TimeBaseStructure.TIM_Period = ((1000000 / speeds[set]) - 1);
|
||||
TIM_TimeBaseStructure.TIM_Period = ((1000000 / speeds[set]) - 1);
|
||||
TIM_TimeBaseInit(channel.timer, &TIM_TimeBaseStructure);
|
||||
set++;
|
||||
}
|
||||
@ -161,7 +161,7 @@ void PIOS_Servo_SetHz(uint16_t * speeds, uint8_t banks)
|
||||
/**
|
||||
* Set servo position
|
||||
* \param[in] Servo Servo number (0-7)
|
||||
* \param[in] Position Servo position in milliseconds
|
||||
* \param[in] Position Servo position in microseconds
|
||||
*/
|
||||
void PIOS_Servo_Set(uint8_t Servo, uint16_t Position)
|
||||
{
|
||||
@ -184,7 +184,7 @@ void PIOS_Servo_Set(uint8_t Servo, uint16_t Position)
|
||||
case TIM_Channel_4:
|
||||
TIM_SetCompare4(pios_servo_cfg.channels[Servo].timer, Position);
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif // PIOS_INCLUDE_SERVO
|
||||
#endif // PIOS_ENABLE_DEBUG_PINS
|
||||
|
@ -34,12 +34,6 @@
|
||||
#include "pios_spektrum_priv.h"
|
||||
|
||||
#if defined(PIOS_INCLUDE_SPEKTRUM)
|
||||
#if defined(PIOS_INCLUDE_PWM)
|
||||
#error "Both PWM and SPEKTRUM input defined, choose only one"
|
||||
#endif
|
||||
#if defined(PIOS_COM_AUX)
|
||||
#error "AUX com cannot be used with SPEKTRUM"
|
||||
#endif
|
||||
|
||||
/**
|
||||
* @Note Framesyncing:
|
||||
@ -51,31 +45,35 @@
|
||||
|
||||
/* Global Variables */
|
||||
|
||||
/* Provide a RCVR driver */
|
||||
static int32_t PIOS_SPEKTRUM_Get(uint32_t rcvr_id, uint8_t channel);
|
||||
|
||||
const struct pios_rcvr_driver pios_spektrum_rcvr_driver = {
|
||||
.read = PIOS_SPEKTRUM_Get,
|
||||
};
|
||||
|
||||
/* Local Variables */
|
||||
static uint16_t CaptureValue[12],CaptureValueTemp[12];
|
||||
static uint16_t CaptureValue[PIOS_SPEKTRUM_NUM_INPUTS],CaptureValueTemp[PIOS_SPEKTRUM_NUM_INPUTS];
|
||||
static uint8_t prev_byte = 0xFF, sync = 0, bytecount = 0, datalength=0, frame_error=0, byte_array[20] = { 0 };
|
||||
uint8_t sync_of = 0;
|
||||
uint16_t supv_timer=0;
|
||||
|
||||
static void PIOS_SPEKTRUM_Supervisor(uint32_t spektrum_id);
|
||||
static bool PIOS_SPEKTRUM_Bind(const struct pios_spektrum_cfg * cfg);
|
||||
|
||||
/**
|
||||
* Bind and Initialise Spektrum satellite receiver
|
||||
*/
|
||||
void PIOS_SPEKTRUM_Init(void)
|
||||
void PIOS_SPEKTRUM_Init(const struct pios_spektrum_cfg * cfg, bool bind)
|
||||
{
|
||||
// TODO: need setting flag for bind on next powerup
|
||||
if (0) {
|
||||
PIOS_SPEKTRUM_Bind();
|
||||
if (bind) {
|
||||
PIOS_SPEKTRUM_Bind(cfg);
|
||||
}
|
||||
|
||||
/* Init RTC supervisor timer interrupt */
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
NVIC_InitStructure.NVIC_IRQChannel = RTC_IRQn;
|
||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID;
|
||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
|
||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||
NVIC_Init(&NVIC_InitStructure);
|
||||
/* Init RTC clock */
|
||||
PIOS_RTC_Init();
|
||||
if (!PIOS_RTC_RegisterTickCallback(PIOS_SPEKTRUM_Supervisor, 0)) {
|
||||
PIOS_DEBUG_Assert(0);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
@ -84,59 +82,42 @@ void PIOS_SPEKTRUM_Init(void)
|
||||
* \output -1 Channel not available
|
||||
* \output >0 Channel value
|
||||
*/
|
||||
int16_t PIOS_SPEKTRUM_Get(int8_t Channel)
|
||||
static int32_t PIOS_SPEKTRUM_Get(uint32_t rcvr_id, uint8_t channel)
|
||||
{
|
||||
/* Return error if channel not available */
|
||||
if (Channel >= 12) {
|
||||
if (channel >= PIOS_SPEKTRUM_NUM_INPUTS) {
|
||||
return -1;
|
||||
}
|
||||
return CaptureValue[Channel];
|
||||
return CaptureValue[channel];
|
||||
}
|
||||
|
||||
/**
|
||||
* Spektrum bind function
|
||||
* \output 1 Successful bind
|
||||
* \output 0 Bind failed
|
||||
* \note Applications shouldn't call these functions directly
|
||||
* \output true Successful bind
|
||||
* \output false Bind failed
|
||||
*/
|
||||
uint8_t PIOS_SPEKTRUM_Bind(void)
|
||||
static bool PIOS_SPEKTRUM_Bind(const struct pios_spektrum_cfg * cfg)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStructure = pios_spektrum_cfg.gpio_init;
|
||||
GPIO_InitStructure.GPIO_Pin = pios_spektrum_cfg.pin;
|
||||
GPIO_Init(pios_spektrum_cfg.port, &GPIO_InitStructure);
|
||||
#define BIND_PULSES 5
|
||||
|
||||
pios_spektrum_cfg.port->BRR = pios_spektrum_cfg.pin;
|
||||
//PIOS_DELAY_WaitmS(75);
|
||||
/* RX line, drive high for 10us */
|
||||
pios_spektrum_cfg.port->BSRR = pios_spektrum_cfg.pin;
|
||||
PIOS_DELAY_WaituS(10);
|
||||
/* RX line, drive low for 120us */
|
||||
pios_spektrum_cfg.port->BRR = pios_spektrum_cfg.pin;
|
||||
PIOS_DELAY_WaituS(120);
|
||||
/* RX line, drive high for 120us */
|
||||
pios_spektrum_cfg.port->BSRR = pios_spektrum_cfg.pin;
|
||||
PIOS_DELAY_WaituS(120);
|
||||
/* RX line, drive low for 120us */
|
||||
pios_spektrum_cfg.port->BRR = pios_spektrum_cfg.pin;
|
||||
PIOS_DELAY_WaituS(120);
|
||||
/* RX line, drive high for 120us */
|
||||
pios_spektrum_cfg.port->BSRR = pios_spektrum_cfg.pin;
|
||||
PIOS_DELAY_WaituS(120);
|
||||
/* RX line, drive low for 120us */
|
||||
pios_spektrum_cfg.port->BRR = pios_spektrum_cfg.pin;
|
||||
PIOS_DELAY_WaituS(120);
|
||||
/* RX line, drive high for 120us */
|
||||
pios_spektrum_cfg.port->BSRR = pios_spektrum_cfg.pin;
|
||||
PIOS_DELAY_WaituS(120);
|
||||
/* RX line, drive low for 120us */
|
||||
pios_spektrum_cfg.port->BRR = pios_spektrum_cfg.pin;
|
||||
PIOS_DELAY_WaituS(120);
|
||||
/* RX line, drive high for 120us */
|
||||
pios_spektrum_cfg.port->BSRR = pios_spektrum_cfg.pin;
|
||||
PIOS_DELAY_WaituS(120);
|
||||
GPIO_Init(cfg->bind.gpio, &cfg->bind.init);
|
||||
/* RX line, set high */
|
||||
GPIO_SetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
|
||||
|
||||
/* on CC works upto 140ms, I guess bind window is around 20-140ms after powerup */
|
||||
PIOS_DELAY_WaitmS(60);
|
||||
|
||||
for (int i = 0; i < BIND_PULSES ; i++) {
|
||||
/* RX line, drive low for 120us */
|
||||
GPIO_ResetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
|
||||
PIOS_DELAY_WaituS(120);
|
||||
/* RX line, drive high for 120us */
|
||||
GPIO_SetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin);
|
||||
PIOS_DELAY_WaituS(120);
|
||||
}
|
||||
/* RX line, set input and wait for data, PIOS_SPEKTRUM_Init */
|
||||
|
||||
return 1;
|
||||
return true;
|
||||
}
|
||||
|
||||
/**
|
||||
@ -147,7 +128,7 @@ uint8_t PIOS_SPEKTRUM_Bind(void)
|
||||
* \return -2 if buffer full (retry)
|
||||
* \note Applications shouldn't call these functions directly
|
||||
*/
|
||||
int32_t PIOS_SPEKTRUM_Decode(uint8_t b)
|
||||
static int32_t PIOS_SPEKTRUM_Decode(uint8_t b)
|
||||
{
|
||||
static uint16_t channel = 0; /*, sync_word = 0;*/
|
||||
uint8_t channeln = 0, frame = 0;
|
||||
@ -201,7 +182,7 @@ int32_t PIOS_SPEKTRUM_Decode(uint8_t b)
|
||||
{
|
||||
frame_error=1;
|
||||
}
|
||||
if (channeln < 12 && !frame_error)
|
||||
if (channeln < PIOS_SPEKTRUM_NUM_INPUTS && !frame_error)
|
||||
CaptureValueTemp[channeln] = data;
|
||||
}
|
||||
}
|
||||
@ -212,7 +193,7 @@ int32_t PIOS_SPEKTRUM_Decode(uint8_t b)
|
||||
sync_of = 0;
|
||||
if (!frame_error)
|
||||
{
|
||||
for(int i=0;i<12;i++)
|
||||
for(int i=0;i<PIOS_SPEKTRUM_NUM_INPUTS;i++)
|
||||
{
|
||||
CaptureValue[i] = CaptureValueTemp[i];
|
||||
}
|
||||
@ -223,11 +204,16 @@ int32_t PIOS_SPEKTRUM_Decode(uint8_t b)
|
||||
return 0;
|
||||
}
|
||||
|
||||
/* Interrupt handler for USART */
|
||||
void SPEKTRUM_IRQHandler(uint32_t usart_id) {
|
||||
/* Custom interrupt handler for USART */
|
||||
void PIOS_SPEKTRUM_irq_handler(uint32_t usart_id) {
|
||||
/* Grab the config for this device from the underlying USART device */
|
||||
const struct pios_usart_cfg * cfg;
|
||||
cfg = PIOS_USART_GetConfig(usart_id);
|
||||
PIOS_Assert(cfg);
|
||||
|
||||
/* by always reading DR after SR make sure to clear any error interrupts */
|
||||
volatile uint16_t sr = pios_spektrum_cfg.pios_usart_spektrum_cfg->regs->SR;
|
||||
volatile uint8_t b = pios_spektrum_cfg.pios_usart_spektrum_cfg->regs->DR;
|
||||
volatile uint16_t sr = cfg->regs->SR;
|
||||
volatile uint8_t b = cfg->regs->DR;
|
||||
|
||||
/* check if RXNE flag is set */
|
||||
if (sr & USART_SR_RXNE) {
|
||||
@ -238,7 +224,7 @@ void SPEKTRUM_IRQHandler(uint32_t usart_id) {
|
||||
|
||||
if (sr & USART_SR_TXE) { // check if TXE flag is set
|
||||
/* Disable TXE interrupt (TXEIE=0) */
|
||||
USART_ITConfig(pios_spektrum_cfg.pios_usart_spektrum_cfg->regs, USART_IT_TXE, DISABLE);
|
||||
USART_ITConfig(cfg->regs, USART_IT_TXE, DISABLE);
|
||||
}
|
||||
/* byte arrived so clear "watchdog" timer */
|
||||
supv_timer=0;
|
||||
@ -248,7 +234,7 @@ void SPEKTRUM_IRQHandler(uint32_t usart_id) {
|
||||
*@brief This function is called between frames and when a spektrum word hasnt been decoded for too long
|
||||
*@brief clears the channel values
|
||||
*/
|
||||
void PIOS_SPEKTRUM_irq_handler() {
|
||||
static void PIOS_SPEKTRUM_Supervisor(uint32_t spektrum_id) {
|
||||
/* 125hz */
|
||||
supv_timer++;
|
||||
if(supv_timer > 5) {
|
||||
@ -262,7 +248,7 @@ void PIOS_SPEKTRUM_irq_handler() {
|
||||
if (sync_of > 12) {
|
||||
/* signal lost */
|
||||
sync_of = 0;
|
||||
for (int i = 0; i < 12; i++) {
|
||||
for (int i = 0; i < PIOS_SPEKTRUM_NUM_INPUTS; i++) {
|
||||
CaptureValue[i] = 0;
|
||||
CaptureValueTemp[i] = 0;
|
||||
}
|
||||
|
@ -51,6 +51,23 @@ const struct pios_com_driver pios_usart_com_driver = {
|
||||
.rx_avail = PIOS_USART_RxBufferUsed,
|
||||
};
|
||||
|
||||
enum pios_usart_dev_magic {
|
||||
PIOS_USART_DEV_MAGIC = 0x11223344,
|
||||
};
|
||||
|
||||
struct pios_usart_dev {
|
||||
enum pios_usart_dev_magic magic;
|
||||
const struct pios_usart_cfg * cfg;
|
||||
|
||||
// align to 32-bit to try and provide speed improvement;
|
||||
uint8_t rx_buffer[PIOS_USART_RX_BUFFER_SIZE] __attribute__ ((aligned(4)));
|
||||
t_fifo_buffer rx;
|
||||
|
||||
// align to 32-bit to try and provide speed improvement;
|
||||
uint8_t tx_buffer[PIOS_USART_TX_BUFFER_SIZE] __attribute__ ((aligned(4)));
|
||||
t_fifo_buffer tx;
|
||||
};
|
||||
|
||||
static bool PIOS_USART_validate(struct pios_usart_dev * usart_dev)
|
||||
{
|
||||
return (usart_dev->magic == PIOS_USART_DEV_MAGIC);
|
||||
@ -85,6 +102,34 @@ static struct pios_usart_dev * PIOS_USART_alloc(void)
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Bind Interrupt Handlers
|
||||
*
|
||||
* Map all valid USART IRQs to the common interrupt handler
|
||||
* and provide storage for a 32-bit device id IRQ to map
|
||||
* each physical IRQ to a specific registered device instance.
|
||||
*/
|
||||
static void PIOS_USART_generic_irq_handler(uint32_t usart_id);
|
||||
|
||||
static uint32_t PIOS_USART_1_id;
|
||||
void USART1_IRQHandler(void) __attribute__ ((alias ("PIOS_USART_1_irq_handler")));
|
||||
static void PIOS_USART_1_irq_handler (void)
|
||||
{
|
||||
PIOS_USART_generic_irq_handler (PIOS_USART_1_id);
|
||||
}
|
||||
|
||||
static uint32_t PIOS_USART_2_id;
|
||||
void USART2_IRQHandler(void) __attribute__ ((alias ("PIOS_USART_2_irq_handler")));
|
||||
static void PIOS_USART_2_irq_handler (void)
|
||||
{
|
||||
PIOS_USART_generic_irq_handler (PIOS_USART_2_id);
|
||||
}
|
||||
|
||||
static uint32_t PIOS_USART_3_id;
|
||||
void USART3_IRQHandler(void) __attribute__ ((alias ("PIOS_USART_3_irq_handler")));
|
||||
static void PIOS_USART_3_irq_handler (void)
|
||||
{
|
||||
PIOS_USART_generic_irq_handler (PIOS_USART_3_id);
|
||||
}
|
||||
|
||||
/**
|
||||
* Initialise a single USART device
|
||||
@ -134,6 +179,17 @@ int32_t PIOS_USART_Init(uint32_t * usart_id, const struct pios_usart_cfg * cfg)
|
||||
*usart_id = (uint32_t)usart_dev;
|
||||
|
||||
/* Configure USART Interrupts */
|
||||
switch ((uint32_t)usart_dev->cfg->regs) {
|
||||
case (uint32_t)USART1:
|
||||
PIOS_USART_1_id = (uint32_t)usart_dev;
|
||||
break;
|
||||
case (uint32_t)USART2:
|
||||
PIOS_USART_2_id = (uint32_t)usart_dev;
|
||||
break;
|
||||
case (uint32_t)USART3:
|
||||
PIOS_USART_3_id = (uint32_t)usart_dev;
|
||||
break;
|
||||
}
|
||||
NVIC_Init(&usart_dev->cfg->irq.init);
|
||||
USART_ITConfig(usart_dev->cfg->regs, USART_IT_RXNE, ENABLE);
|
||||
USART_ITConfig(usart_dev->cfg->regs, USART_IT_TXE, ENABLE);
|
||||
@ -147,6 +203,19 @@ out_fail:
|
||||
return(-1);
|
||||
}
|
||||
|
||||
const struct pios_usart_cfg * PIOS_USART_GetConfig(uint32_t usart_id)
|
||||
{
|
||||
struct pios_usart_dev * usart_dev = (struct pios_usart_dev *)usart_id;
|
||||
|
||||
bool valid = PIOS_USART_validate(usart_dev);
|
||||
|
||||
if (!valid) {
|
||||
return (NULL);
|
||||
}
|
||||
|
||||
return usart_dev->cfg;
|
||||
}
|
||||
|
||||
/**
|
||||
* Changes the baud rate of the USART peripheral without re-initialising.
|
||||
* \param[in] usart_id USART name (GPS, TELEM, AUX)
|
||||
@ -157,7 +226,7 @@ static void PIOS_USART_ChangeBaud(uint32_t usart_id, uint32_t baud)
|
||||
struct pios_usart_dev * usart_dev = (struct pios_usart_dev *)usart_id;
|
||||
|
||||
bool valid = PIOS_USART_validate(usart_dev);
|
||||
PIOS_Assert(valid)
|
||||
PIOS_Assert(valid);
|
||||
|
||||
USART_InitTypeDef USART_InitStructure;
|
||||
|
||||
@ -337,12 +406,20 @@ static int32_t PIOS_USART_TxBufferPutMore(uint32_t usart_id, const uint8_t *buff
|
||||
return rc;
|
||||
}
|
||||
|
||||
void PIOS_USART_IRQ_Handler(uint32_t usart_id)
|
||||
static void PIOS_USART_generic_irq_handler(uint32_t usart_id)
|
||||
{
|
||||
struct pios_usart_dev * usart_dev = (struct pios_usart_dev *)usart_id;
|
||||
|
||||
bool valid = PIOS_USART_validate(usart_dev);
|
||||
PIOS_Assert(valid)
|
||||
PIOS_Assert(valid);
|
||||
|
||||
/* Call any user provided callback function instead of processing
|
||||
* the interrupt ourselves.
|
||||
*/
|
||||
if (usart_dev->cfg->irq.handler) {
|
||||
(usart_dev->cfg->irq.handler)(usart_id);
|
||||
return;
|
||||
}
|
||||
|
||||
/* Force read of dr after sr to make sure to clear error flags */
|
||||
volatile uint16_t sr = usart_dev->cfg->regs->SR;
|
||||
|
@ -36,6 +36,8 @@
|
||||
.global g_pfnVectors
|
||||
.global SystemInit_ExtMemCtl_Dummy
|
||||
.global Default_Handler
|
||||
.global xPortIncreaseHeapSize
|
||||
.global Stack_Change
|
||||
|
||||
/* start address for the initialization values of the .data section.
|
||||
defined in linker script */
|
||||
@ -71,6 +73,35 @@ Reset_Handler:
|
||||
/* restore original stack pointer */
|
||||
LDR r0, =_irq_stack_top
|
||||
MSR msp, r0
|
||||
LDR r2, =_init_stack_top
|
||||
MSR psp, r2
|
||||
/* check if irq and init stack are the same */
|
||||
/* if they are, we don't do stack swap */
|
||||
/* and lets bypass the monitoring as well for now */
|
||||
cmp r0, r2
|
||||
beq SectionBssInit
|
||||
/* DO
|
||||
* - stay in thread process mode
|
||||
* - stay in privilege level
|
||||
* - use process stack
|
||||
*/
|
||||
movs r0, #2
|
||||
MSR control, r0
|
||||
ISB
|
||||
/* Fill IRQ stack for watermark monitoring */
|
||||
ldr r2, =_irq_stack_end
|
||||
b LoopFillIRQStack
|
||||
|
||||
FillIRQStack:
|
||||
movw r3, #0xA5A5
|
||||
str r3, [r2], #4
|
||||
|
||||
LoopFillIRQStack:
|
||||
ldr r3, = _irq_stack_top
|
||||
cmp r2, r3
|
||||
bcc FillIRQStack
|
||||
|
||||
SectionBssInit:
|
||||
/* Copy the data segment initializers from flash to SRAM */
|
||||
movs r1, #0
|
||||
b LoopCopyDataInit
|
||||
@ -100,9 +131,37 @@ LoopFillZerobss:
|
||||
bcc FillZerobss
|
||||
/* Call the application's entry point.*/
|
||||
bl main
|
||||
bx lr
|
||||
/* will never return here */
|
||||
bx lr
|
||||
.size Reset_Handler, .-Reset_Handler
|
||||
|
||||
/**
|
||||
* @brief This is the code that swaps stack (from end of heap to irq_stack).
|
||||
* Also reclaim the heap that was used as a stack.
|
||||
* @param None
|
||||
* @retval : None
|
||||
*/
|
||||
.section .text.Stack_Change
|
||||
.weak Stack_Change
|
||||
.type Stack_Change, %function
|
||||
Stack_Change:
|
||||
mov r4, lr
|
||||
/* Switches stack back momentarily to MSP */
|
||||
movs r0, #0
|
||||
msr control, r0
|
||||
Heap_Reclaim:
|
||||
/* add heap_post_rtos to the heap (if the capability/function exist) */
|
||||
/* Also claim the unused memory (between end of heap to end of memory */
|
||||
/* CAREFULL: the heap section must be the last section in RAM in order this to work */
|
||||
ldr r0, = _init_stack_size
|
||||
ldr r1, = _eheap_post_rtos
|
||||
ldr r2, = _eram
|
||||
subs r2, r2, r1
|
||||
adds r0, r0, r2
|
||||
bl xPortIncreaseHeapSize
|
||||
bx r4
|
||||
.size Stack_Change, .-Stack_Change
|
||||
|
||||
/**
|
||||
* @brief Dummy SystemInit_ExtMemCtl function
|
||||
* @param None
|
||||
@ -114,12 +173,12 @@ SystemInit_ExtMemCtl_Dummy:
|
||||
.size SystemInit_ExtMemCtl_Dummy, .-SystemInit_ExtMemCtl_Dummy
|
||||
|
||||
/**
|
||||
* @brief This is the code that gets called when the processor receives an
|
||||
* @brief This is the code that gets called when the processor receives an
|
||||
* unexpected interrupt. This simply enters an infinite loop, preserving
|
||||
* the system state for examination by a debugger.
|
||||
*
|
||||
* @param None
|
||||
* @retval : None
|
||||
* @param None
|
||||
* @retval : None
|
||||
*/
|
||||
.section .text.Default_Handler,"ax",%progbits
|
||||
Default_Handler:
|
||||
@ -272,13 +331,13 @@ g_pfnVectors:
|
||||
|
||||
.weak NMI_Handler
|
||||
.thumb_set NMI_Handler,Default_Handler
|
||||
|
||||
|
||||
.weak HardFault_Handler
|
||||
.thumb_set HardFault_Handler,Default_Handler
|
||||
|
||||
|
||||
.weak MemManage_Handler
|
||||
.thumb_set MemManage_Handler,Default_Handler
|
||||
|
||||
|
||||
.weak BusFault_Handler
|
||||
.thumb_set BusFault_Handler,Default_Handler
|
||||
|
||||
|
@ -33,6 +33,8 @@
|
||||
|
||||
.global g_pfnVectors
|
||||
.global Default_Handler
|
||||
.global xPortIncreaseHeapSize
|
||||
.global Stack_Change
|
||||
|
||||
/* start address for the initialization values of the .data section.
|
||||
defined in linker script */
|
||||
@ -61,6 +63,47 @@ defined in linker script */
|
||||
.type Reset_Handler, %function
|
||||
Reset_Handler:
|
||||
|
||||
/*
|
||||
* From COrtex-M3 reference manual:
|
||||
* - Handler IRQ always use SP_main
|
||||
* - Process use SP_main or SP_process
|
||||
* Here, we will use beginning of SRAM for IRQ (SP_main)
|
||||
* and end of heap for initialization (SP_process).
|
||||
* Once the schedule starts, all threads will use their own stack
|
||||
* from heap and NOBOBY should use SP_process again.
|
||||
*/
|
||||
/* Do set/reset the stack pointers */
|
||||
LDR r0, =_irq_stack_top
|
||||
MSR msp, r0
|
||||
LDR r2, =_init_stack_top
|
||||
MSR psp, r2
|
||||
/* check if irq and init stack are the same */
|
||||
/* if they are, we don't do stack swap */
|
||||
/* and lets bypass the monitoring as well for now */
|
||||
cmp r0, r2
|
||||
beq SectionBssInit
|
||||
/* DO
|
||||
* - stay in thread process mode
|
||||
* - stay in privilege level
|
||||
* - use process stack
|
||||
*/
|
||||
movs r0, #2
|
||||
MSR control, r0
|
||||
ISB
|
||||
/* Fill IRQ stack for watermark monitoring */
|
||||
ldr r2, =_irq_stack_end
|
||||
b LoopFillIRQStack
|
||||
|
||||
FillIRQStack:
|
||||
movw r3, #0xA5A5
|
||||
str r3, [r2], #4
|
||||
|
||||
LoopFillIRQStack:
|
||||
ldr r3, = _irq_stack_top
|
||||
cmp r2, r3
|
||||
bcc FillIRQStack
|
||||
|
||||
SectionBssInit:
|
||||
/* Copy the data segment initializers from flash to SRAM */
|
||||
movs r1, #0
|
||||
b LoopCopyDataInit
|
||||
@ -90,16 +133,45 @@ LoopFillZerobss:
|
||||
bcc FillZerobss
|
||||
/* Call the application's entry point.*/
|
||||
bl main
|
||||
/* will never return here */
|
||||
bx lr
|
||||
.size Reset_Handler, .-Reset_Handler
|
||||
|
||||
/**
|
||||
* @brief This is the code that gets called when the processor receives an
|
||||
* @brief This is the code that swaps stack (from end of heap to irq_stack).
|
||||
* Also reclaim the heap that was used as a stack.
|
||||
* @param None
|
||||
* @retval : None
|
||||
*/
|
||||
.section .text.Stack_Change
|
||||
.weak Stack_Change
|
||||
.type Stack_Change, %function
|
||||
Stack_Change:
|
||||
mov r4, lr
|
||||
/* Switches stack back momentarily to MSP */
|
||||
movs r0, #0
|
||||
msr control, r0
|
||||
Heap_Reclaim:
|
||||
/* add heap_post_rtos to the heap (if the capability/function exist) */
|
||||
/* Also claim the unused memory (between end of heap to end of memory */
|
||||
/* CAREFULL: the heap section must be the last section in RAM in order this to work */
|
||||
ldr r0, = _init_stack_size
|
||||
ldr r1, = _eheap_post_rtos
|
||||
ldr r2, = _eram
|
||||
subs r2, r2, r1
|
||||
adds r0, r0, r2
|
||||
bl xPortIncreaseHeapSize
|
||||
bx r4
|
||||
.size Stack_Change, .-Stack_Change
|
||||
|
||||
|
||||
/**
|
||||
* @brief This is the code that gets called when the processor receives an
|
||||
* unexpected interrupt. This simply enters an infinite loop, preserving
|
||||
* the system state for examination by a debugger.
|
||||
*
|
||||
* @param None
|
||||
* @retval : None
|
||||
* @param None
|
||||
* @retval : None
|
||||
*/
|
||||
.section .text.Default_Handler,"ax",%progbits
|
||||
Default_Handler:
|
||||
@ -119,7 +191,7 @@ Infinite_Loop:
|
||||
|
||||
|
||||
g_pfnVectors:
|
||||
.word _estack
|
||||
.word _irq_stack_top
|
||||
.word Reset_Handler
|
||||
.word NMI_Handler
|
||||
.word HardFault_Handler
|
||||
|
@ -34,10 +34,9 @@
|
||||
|
||||
/* Public Functions */
|
||||
extern int32_t PIOS_DELAY_Init(void);
|
||||
extern int32_t PIOS_DELAY_WaituS(uint16_t uS);
|
||||
extern int32_t PIOS_DELAY_WaitmS(uint16_t mS);
|
||||
extern uint16_t PIOS_DELAY_GetuS();
|
||||
extern int32_t PIOS_DELAY_DiffuS(uint16_t ref);
|
||||
extern int32_t PIOS_DELAY_WaituS(uint32_t uS);
|
||||
extern int32_t PIOS_DELAY_WaitmS(uint32_t mS);
|
||||
extern uint32_t PIOS_DELAY_GetuS();
|
||||
|
||||
#endif /* PIOS_DELAY_H */
|
||||
|
||||
|
@ -41,7 +41,15 @@
|
||||
/*
|
||||
* Used for initialization calls..
|
||||
*/
|
||||
|
||||
typedef int32_t (*initcall_t)(void);
|
||||
typedef struct {
|
||||
initcall_t fn_minit;
|
||||
initcall_t fn_tinit;
|
||||
} initmodule_t;
|
||||
|
||||
/* Init module section */
|
||||
extern initmodule_t __module_initcall_start[], __module_initcall_end[];
|
||||
|
||||
/* initcalls are now grouped by functionality into separate
|
||||
* subsections. Ordering inside the subsections is determined
|
||||
@ -55,7 +63,20 @@ typedef int32_t (*initcall_t)(void);
|
||||
static initcall_t __initcall_##fn##id __attribute__((__used__)) \
|
||||
__attribute__((__section__(".initcall" level ".init"))) = fn
|
||||
|
||||
#define uavobj_initcall(fn) __define_initcall("uavobj",fn,1)
|
||||
#define __define_module_initcall(level, ifn, sfn) \
|
||||
static initmodule_t __initcall_##fn __attribute__((__used__)) \
|
||||
__attribute__((__section__(".initcall" level ".init"))) = { .fn_minit = ifn, .fn_tinit = sfn };
|
||||
|
||||
#define UAVOBJ_INITCALL(fn) __define_initcall("uavobj",fn,1)
|
||||
#define MODULE_INITCALL(ifn, sfn) __define_module_initcall("module", ifn, sfn)
|
||||
|
||||
#define MODULE_INITIALISE_ALL { for (initmodule_t *fn = __module_initcall_start; fn < __module_initcall_end; fn++) \
|
||||
if (fn->fn_minit) \
|
||||
(fn->fn_minit)(); }
|
||||
|
||||
#define MODULE_TASKCREATE_ALL { for (initmodule_t *fn = __module_initcall_start; fn < __module_initcall_end; fn++) \
|
||||
if (fn->fn_tinit) \
|
||||
(fn->fn_tinit)(); }
|
||||
|
||||
#endif /* PIOS_INITCALL_H */
|
||||
|
||||
|
@ -30,8 +30,4 @@
|
||||
#ifndef PIOS_PPM_H
|
||||
#define PIOS_PPM_H
|
||||
|
||||
/* Public Functions */
|
||||
extern void PIOS_PPM_Init(void);
|
||||
extern int32_t PIOS_PPM_Get(int8_t Channel);
|
||||
|
||||
#endif /* PIOS_PPM_H */
|
||||
|
@ -34,13 +34,6 @@
|
||||
#include <pios.h>
|
||||
#include <pios_stm32.h>
|
||||
|
||||
struct pios_ppmsv_cfg {
|
||||
TIM_TimeBaseInitTypeDef tim_base_init;
|
||||
struct stm32_irq irq;
|
||||
TIM_TypeDef * timer;
|
||||
uint16_t ccr;
|
||||
};
|
||||
|
||||
struct pios_ppm_cfg {
|
||||
TIM_TimeBaseInitTypeDef tim_base_init;
|
||||
TIM_ICInitTypeDef tim_ic_init;
|
||||
@ -53,11 +46,13 @@ struct pios_ppm_cfg {
|
||||
};
|
||||
|
||||
extern void PIOS_PPM_irq_handler();
|
||||
extern void PIOS_PPMSV_irq_handler();
|
||||
|
||||
extern uint8_t pios_ppm_num_channels;
|
||||
extern const struct pios_ppm_cfg pios_ppm_cfg;
|
||||
extern const struct pios_ppmsv_cfg pios_ppmsv_cfg;
|
||||
|
||||
extern const struct pios_rcvr_driver pios_ppm_rcvr_driver;
|
||||
|
||||
extern void PIOS_PPM_Init(void);
|
||||
|
||||
#endif /* PIOS_PPM_PRIV_H */
|
||||
|
||||
|
@ -30,9 +30,4 @@
|
||||
#ifndef PIOS_PWM_H
|
||||
#define PIOS_PWM_H
|
||||
|
||||
/* Public Functions */
|
||||
extern void PIOS_PWM_Init(void);
|
||||
extern int32_t PIOS_PWM_Get(int8_t Channel);
|
||||
//extern void PIOS_PWM_irq_handler(TIM_TypeDef * timer);
|
||||
|
||||
#endif /* PIOS_PWM_H */
|
||||
|
@ -57,6 +57,10 @@ extern void PIOS_PWM_irq_handler(TIM_TypeDef * timer);
|
||||
extern uint8_t pios_pwm_num_channels;
|
||||
extern const struct pios_pwm_cfg pios_pwm_cfg;
|
||||
|
||||
extern const struct pios_rcvr_driver pios_pwm_rcvr_driver;
|
||||
|
||||
extern void PIOS_PWM_Init(void);
|
||||
|
||||
#endif /* PIOS_PWM_PRIV_H */
|
||||
|
||||
/**
|
||||
|
54
flight/PiOS/inc/pios_rcvr.h
Normal file
@ -0,0 +1,54 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_RCVR RCVR layer functions
|
||||
* @brief Hardware communication layer
|
||||
* @{
|
||||
*
|
||||
* @file pios_rcvr.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief RCVR layer functions 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 PIOS_RCVR_H
|
||||
#define PIOS_RCVR_H
|
||||
|
||||
struct pios_rcvr_channel_map {
|
||||
uint32_t id;
|
||||
uint8_t channel;
|
||||
};
|
||||
|
||||
extern struct pios_rcvr_channel_map pios_rcvr_channel_to_id_map[];
|
||||
|
||||
struct pios_rcvr_driver {
|
||||
void (*init)(uint32_t id);
|
||||
int32_t (*read)(uint32_t id, uint8_t channel);
|
||||
};
|
||||
|
||||
/* Public Functions */
|
||||
extern int32_t PIOS_RCVR_Read(uint32_t rcvr_id, uint8_t channel);
|
||||
|
||||
#endif /* PIOS_RCVR_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
48
flight/PiOS/inc/pios_rcvr_priv.h
Normal file
@ -0,0 +1,48 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_RCVR RCVR Functions
|
||||
* @brief PIOS interface for RCVR drivers
|
||||
* @{
|
||||
*
|
||||
* @file pios_rcvr_priv.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* Parts by Thorsten Klose (tk@midibox.org)
|
||||
* @brief USART private definitions.
|
||||
* @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_RCVR_PRIV_H
|
||||
#define PIOS_RCVR_PRIV_H
|
||||
|
||||
#include <pios.h>
|
||||
|
||||
extern uint32_t pios_rcvr_max_channel;
|
||||
|
||||
extern int32_t PIOS_RCVR_Init(uint32_t * rcvr_id, const struct pios_rcvr_driver * driver, const uint32_t lower_id);
|
||||
|
||||
extern void PIOS_RCVR_IRQ_Handler(uint32_t rcvr_id);
|
||||
|
||||
#endif /* PIOS_RCVR_PRIV_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
@ -30,13 +30,15 @@
|
||||
#ifndef PIOS_RTC_H
|
||||
#define PIOS_RTC_H
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
/* Public Functions */
|
||||
extern void PIOS_RTC_Init();
|
||||
extern uint32_t PIOS_RTC_Counter();
|
||||
extern float PIOS_RTC_Rate();
|
||||
extern float PIOS_RTC_MsPerTick();
|
||||
extern bool PIOS_RTC_RegisterTickCallback(void (*fn)(uint32_t id), uint32_t data);
|
||||
|
||||
#endif /* PIOS_SERVO_H */
|
||||
#endif /* PIOS_RTC_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
|
52
flight/PiOS/inc/pios_rtc_priv.h
Normal file
@ -0,0 +1,52 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
* @addtogroup PIOS PIOS Core hardware abstraction layer
|
||||
* @{
|
||||
* @addtogroup PIOS_RTC RTC Functions
|
||||
* @brief PIOS interface for RTC tick
|
||||
* @{
|
||||
*
|
||||
* @file pios_rtc_priv.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @brief ADC private definitions.
|
||||
* @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_RTC_PRIV_H
|
||||
#define PIOS_RTC_PRIV_H
|
||||
|
||||
#include <pios.h>
|
||||
#include <pios_stm32.h>
|
||||
|
||||
struct pios_rtc_cfg {
|
||||
uint32_t clksrc;
|
||||
uint32_t prescaler;
|
||||
struct stm32_irq irq;
|
||||
};
|
||||
|
||||
extern void PIOS_RTC_Init(const struct pios_rtc_cfg * cfg);
|
||||
|
||||
extern void PIOS_RTC_irq_handler(void);
|
||||
#endif /* PIOS_RTC_PRIV_H */
|
||||
|
||||
/**
|
||||
* @}
|
||||
* @}
|
||||
*/
|
||||
|