diff --git a/.gitignore b/.gitignore index 6c4d8b39f..03797f84f 100644 --- a/.gitignore +++ b/.gitignore @@ -1,3 +1,5 @@ +# Exclude temporary and system files +.DS_Store # /flight/ /flight/*.pnproj diff --git a/HISTORY.txt b/HISTORY.txt index ac278b889..aba9effab 100644 --- a/HISTORY.txt +++ b/HISTORY.txt @@ -1,5 +1,60 @@ Short summary of changes. For a complete list see the git log. +2011-12-10 +Merged a change that sorts the UAVO fields based on size. Because this changes +all of the objects, erase all existing flash files based on this. + +2011-11-04 +New Spektrum/JR satellite receiver driver implementation. +It now provides explicit selection of DSM2 (and DSMJ), DSMX (10bit) and +DSMX (11bit) serial protocol variations to better serve different frame +and resolution modes. The protocol name used now is DSM instead of +previously used Spektrum to make it less ambiguous when used with JR +2.4GHz radios. + +2011-10-20 +Inputs can be remapped to outputs to allow up to 10 channels of control. The +receiver inputs remap as follows: +Receiver 3 because output channel 7 +Receiver 4 because output channel 8 +Receiver 5 because output channel 9 +Receiver 6 because output channel 10 + +2011-10-11 +Fix for the Mac telemetry rates and specifically how long enumeration took. + +2011-10-08 +Make the flash chip need to be have bad magic for a full second before erasing +settings. Should avoid random lost settings. + +2011-09-12 +Max rate now ONLY applies to attitude and axis lock mode. Manual rate is the +only term that limits the rate mode now (and in axis lock when you push stick +only manual rate applies). Also integrals are reset when unused. + +2011-09-09 +Some large updates to the input system. Now multiple receivers can be +connected at once. A wizard was added for configuring the input channels. A +specific collective pitch channel was added. + +2011-09-04 +Improvements to the failsafe handling code for inputs. PWM power off is now +detected properly. Powering on transmitter for Spektrum Satellite no longer +causes a glitch on servos. + +2011-08-10 +Added Camera Stabilization and a gui to configure this. This is a software +selectable module from the GUI. However, a restart is required to make it +active. The GUI does not currently expose the configuration for using the +transmitter to change the view angle but this is supported by the hardware. + +2011-08-10 +By default a lot of diagnostic objects that were enabled by default are now +disabled in the build. This include TaskInfo (and all the FreeRTOS options +that provide that debugging information). Also MixerStatus, I2CStatus, +WatchdogStatus and RateDesired. These can be reenabled for debugging with +-DDIAGNOSTICS. + 2011-08-04 Fixed packaging aesthetic issues. Also avoid runtime issues on OSX Lion by disabling the ModelView and Notify plugins for now (sorry). @@ -28,3 +83,4 @@ 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. + diff --git a/MILESTONES.txt b/MILESTONES.txt index d2a0b33ed..14242d2f2 100644 --- a/MILESTONES.txt +++ b/MILESTONES.txt @@ -137,11 +137,31 @@ C: Mat Wellington D: July 2011 V: http://www.youtube.com/watch?v=YE4Fd9vdg1I +M: First CopterControl Flybared Heli inverted flight (2:33) +C: Maxim Izergin (Maximus43) +D: August 2011 +V: http://www.youtube.com/watch?v=8SrfIS7OkB4 + +M: First CopterControl Flybared Heli funnel (4:18), loop (5:35) +C: Sergey Solodennikov (alconaft43) +D: August 2011 +V: http://www.youtube.com/watch?v=8SrfIS7OkB4 + M: First CopterControl Return to Base Fixed Wing C: Eric Price (Corvus Corax) -D: AUgust 2011 +D: August 2011 V: http://www.youtube.com/watch?v=CugI0oBSQn8 +M: First CopterControl flip on a Flybarless Heli +C: Anders Johansson (dezent) +D: November 2011 +V: http://www.youtube.com/watch?v=Xfas2TUhOPw + +M: First OpenPilot over 1km FixedWing navigation flight +C: Eric Price (Corvus Corax) +D: December 2011 +V: http://www.youtube.com/watch?v=nWNWuUiUTNg + M: First Altitude Hold using Sonar C: @@ -158,11 +178,6 @@ C: D: V: -M: First CopterControl flip on a Flybarless Heli -C: -D: -V: - An incomplete list of some future Milestones is below: @@ -174,8 +189,6 @@ An incomplete list of some future Milestones is below: * First fixed wing navigation flight * First Multirotor navigation flight * First Helicopter navigation flight -* First over 1km navigation flight * First over 5km navigation flight * First "Follow Me" navigation flight * First Channel Crossing with OpenPilot - diff --git a/Makefile b/Makefile index 18cdb3b2e..438f697a4 100644 --- a/Makefile +++ b/Makefile @@ -183,13 +183,13 @@ qt_sdk_clean: 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/package8734/public/arm-none-eabi/arm-2011.03-42-arm-none-eabi-i686-pc-linux-gnu.tar.bz2 +arm_sdk_install: ARM_SDK_URL := https://sourcery.mentor.com/sgpp/lite/arm/portal/package8736/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) arm_sdk_install: arm_sdk_clean # download the source only if it's newer than what we already have - $(V1) wget -N -P "$(DL_DIR)" "$(ARM_SDK_URL)" + $(V1) wget --no-check-certificate -N -P "$(DL_DIR)" "$(ARM_SDK_URL)" # binary only release so just extract it $(V1) tar -C $(TOOLS_DIR) -xjf "$(DL_DIR)/$(ARM_SDK_FILE)" @@ -202,8 +202,8 @@ arm_sdk_clean: OPENOCD_DIR := $(TOOLS_DIR)/openocd .PHONY: openocd_install -openocd_install: OPENOCD_URL := http://sourceforge.net/projects/openocd/files/openocd/0.4.0/openocd-0.4.0.tar.bz2/download -openocd_install: OPENOCD_FILE := openocd-0.4.0.tar.bz2 +openocd_install: OPENOCD_URL := http://sourceforge.net/projects/openocd/files/openocd/0.5.0/openocd-0.5.0.tar.bz2/download +openocd_install: OPENOCD_FILE := openocd-0.5.0.tar.bz2 # order-only prereq on directory existance: openocd_install: | $(DL_DIR) $(TOOLS_DIR) openocd_install: openocd_clean @@ -218,8 +218,8 @@ openocd_install: openocd_clean # build and install $(V1) mkdir -p "$(OPENOCD_DIR)" $(V1) ( \ - cd $(DL_DIR)/openocd-build/openocd-0.4.0 ; \ - ./configure --prefix="$(OPENOCD_DIR)" --enable-ft2232_libftdi ; \ + cd $(DL_DIR)/openocd-build/openocd-0.5.0 ; \ + ./configure --prefix="$(OPENOCD_DIR)" --enable-ft2232_libftdi --enable-buspirate; \ $(MAKE) ; \ $(MAKE) install ; \ ) diff --git a/artwork/3D Model/multi/ricoo/CC.PNG b/artwork/3D Model/multi/ricoo/CC.PNG new file mode 100644 index 000000000..467f34a97 Binary files /dev/null and b/artwork/3D Model/multi/ricoo/CC.PNG differ diff --git a/artwork/3D Model/multi/ricoo/TEXTURE.PNG b/artwork/3D Model/multi/ricoo/TEXTURE.PNG new file mode 100644 index 000000000..d6e63425a Binary files /dev/null and b/artwork/3D Model/multi/ricoo/TEXTURE.PNG differ diff --git a/artwork/3D Model/multi/ricoo/ricoo.3DS b/artwork/3D Model/multi/ricoo/ricoo.3DS new file mode 100644 index 000000000..226920061 Binary files /dev/null and b/artwork/3D Model/multi/ricoo/ricoo.3DS differ diff --git a/artwork/3D Model/multi/ricoo/ricoo.jpg b/artwork/3D Model/multi/ricoo/ricoo.jpg new file mode 100644 index 000000000..93df97866 Binary files /dev/null and b/artwork/3D Model/multi/ricoo/ricoo.jpg differ diff --git a/flight/AHRS/Makefile b/flight/AHRS/Makefile index 46405ca6c..1943cc3a6 100644 --- a/flight/AHRS/Makefile +++ b/flight/AHRS/Makefile @@ -355,7 +355,7 @@ $(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin $(eval $(call OPFW_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BOARD_TYPE),$(BOARD_REVISION))) # Add jtag targets (program and wipe) -$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE))) +$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE),$(OPENOCD_CONFIG))) .PHONY: elf lss sym hex bin bino opfw elf: $(OUTDIR)/$(TARGET).elf diff --git a/flight/Bootloaders/AHRS/Makefile b/flight/Bootloaders/AHRS/Makefile index 18bf8a269..833dba72b 100644 --- a/flight/Bootloaders/AHRS/Makefile +++ b/flight/Bootloaders/AHRS/Makefile @@ -354,7 +354,7 @@ $(eval $(call PARTIAL_COMPILE_ARM_TEMPLATE, SRCARM)) $(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin # Add jtag targets (program and wipe) -$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BL_BANK_BASE),$(BL_BANK_SIZE))) +$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BL_BANK_BASE),$(BL_BANK_SIZE),$(OPENOCD_CONFIG))) .PHONY: elf lss sym hex bin bino elf: $(OUTDIR)/$(TARGET).elf diff --git a/flight/Bootloaders/BootloaderUpdater/Makefile b/flight/Bootloaders/BootloaderUpdater/Makefile index 81aa163ec..aabfc88bf 100644 --- a/flight/Bootloaders/BootloaderUpdater/Makefile +++ b/flight/Bootloaders/BootloaderUpdater/Makefile @@ -258,7 +258,9 @@ CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I. CFLAGS += -mapcs-frame CFLAGS += -fomit-frame-pointer +ifeq ($(CODE_SOURCERY), YES) CFLAGS += -fpromote-loop-indices +endif CFLAGS += -Wall CFLAGS += -Werror diff --git a/flight/Bootloaders/CopterControl/Makefile b/flight/Bootloaders/CopterControl/Makefile index fe613f909..e630f9839 100644 --- a/flight/Bootloaders/CopterControl/Makefile +++ b/flight/Bootloaders/CopterControl/Makefile @@ -300,7 +300,9 @@ CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I. CFLAGS += -mapcs-frame CFLAGS += -fomit-frame-pointer +ifeq ($(CODE_SOURCERY), YES) CFLAGS += -fpromote-loop-indices +endif CFLAGS += -Wall CFLAGS += -Werror @@ -411,7 +413,7 @@ $(eval $(call PARTIAL_COMPILE_ARM_TEMPLATE, SRCARM)) $(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin # Add jtag targets (program and wipe) -$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BL_BANK_BASE),$(BL_BANK_SIZE))) +$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BL_BANK_BASE),$(BL_BANK_SIZE),$(OPENOCD_CONFIG))) .PHONY: elf lss sym hex bin bino elf: $(OUTDIR)/$(TARGET).elf diff --git a/flight/Bootloaders/OpenPilot/Makefile b/flight/Bootloaders/OpenPilot/Makefile index e4285f7e0..75891289f 100644 --- a/flight/Bootloaders/OpenPilot/Makefile +++ b/flight/Bootloaders/OpenPilot/Makefile @@ -306,7 +306,9 @@ CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I. CFLAGS += -mapcs-frame CFLAGS += -fomit-frame-pointer +ifeq ($(CODE_SOURCERY), YES) CFLAGS += -fpromote-loop-indices +endif CFLAGS += -Wall CFLAGS += -Werror @@ -417,7 +419,7 @@ $(eval $(call PARTIAL_COMPILE_ARM_TEMPLATE, SRCARM)) $(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin # Add jtag targets (program and wipe) -$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BL_BANK_BASE),$(BL_BANK_SIZE))) +$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BL_BANK_BASE),$(BL_BANK_SIZE),$(OPENOCD_CONFIG))) .PHONY: elf lss sym hex bin bino elf: $(OUTDIR)/$(TARGET).elf diff --git a/flight/Bootloaders/OpenPilot/inc/pios_config.h b/flight/Bootloaders/OpenPilot/inc/pios_config.h index ab9719b14..c4ace5f90 100644 --- a/flight/Bootloaders/OpenPilot/inc/pios_config.h +++ b/flight/Bootloaders/OpenPilot/inc/pios_config.h @@ -43,23 +43,12 @@ #define PIOS_INCLUDE_OPAHRS #define PIOS_INCLUDE_COM #define PIOS_INCLUDE_GPIO -#define PIOS_NO_GPS //#define DEBUG_SSP /* Defaults for Logging */ #define LOG_FILENAME "PIOS.LOG" #define STARTUP_LOG_ENABLED 1 -/* COM Module */ -#define GPS_BAUDRATE 19200 -#define TELEM_BAUDRATE 19200 -#define AUXUART_ENABLED 0 -#define AUXUART_BAUDRATE 19200 - -/* Servos */ -#define SERVOS_POSITION_MIN 800 -#define SERVOS_POSITION_MAX 2200 - #endif /* PIOS_CONFIG_H */ /** * @} diff --git a/flight/Bootloaders/PipXtreme/Makefile b/flight/Bootloaders/PipXtreme/Makefile index 64f13d0d2..7aadcf1c9 100644 --- a/flight/Bootloaders/PipXtreme/Makefile +++ b/flight/Bootloaders/PipXtreme/Makefile @@ -301,7 +301,9 @@ CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I. CFLAGS += -mapcs-frame CFLAGS += -fomit-frame-pointer +ifeq ($(CODE_SOURCERY), YES) CFLAGS += -fpromote-loop-indices +endif CFLAGS += -Wall CFLAGS += -Werror @@ -412,7 +414,7 @@ $(eval $(call PARTIAL_COMPILE_ARM_TEMPLATE, SRCARM)) $(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin # Add jtag targets (program and wipe) -$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BL_BANK_BASE),$(BL_BANK_SIZE))) +$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BL_BANK_BASE),$(BL_BANK_SIZE),$(OPENOCD_CONFIG))) .PHONY: elf lss sym hex bin bino elf: $(OUTDIR)/$(TARGET).elf diff --git a/flight/Bootloaders/PipXtreme/inc/pios_config.h b/flight/Bootloaders/PipXtreme/inc/pios_config.h index 2868cbd1d..799847992 100644 --- a/flight/Bootloaders/PipXtreme/inc/pios_config.h +++ b/flight/Bootloaders/PipXtreme/inc/pios_config.h @@ -40,23 +40,12 @@ #define PIOS_INCLUDE_USB_HID #define PIOS_INCLUDE_COM #define PIOS_INCLUDE_GPIO -#define PIOS_NO_GPS //#define DEBUG_SSP /* Defaults for Logging */ #define LOG_FILENAME "PIOS.LOG" #define STARTUP_LOG_ENABLED 1 -/* COM Module */ -#define GPS_BAUDRATE 19200 -#define TELEM_BAUDRATE 19200 -#define AUXUART_ENABLED 0 -#define AUXUART_BAUDRATE 19200 - -/* Servos */ -#define SERVOS_POSITION_MIN 800 -#define SERVOS_POSITION_MAX 2200 - #endif /* PIOS_CONFIG_H */ /** * @} diff --git a/flight/CopterControl/Makefile b/flight/CopterControl/Makefile index 78e62bb89..a357af633 100644 --- a/flight/CopterControl/Makefile +++ b/flight/CopterControl/Makefile @@ -37,6 +37,9 @@ OUTDIR := $(TOP)/build/$(TARGET) # Set to YES to compile for debugging DEBUG ?= NO +# Include objects that are just nice information to show +DIAGNOSTICS ?= NO + # Set to YES to build a FW version that will erase all flash memory ERASE_FLASH ?= NO # Set to YES to use the Servo output pins for debugging via scope or logic analyser @@ -45,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_GPS ?= NO +USE_GPS ?= YES USE_I2C ?= NO @@ -62,7 +65,14 @@ endif FLASH_TOOL = OPENOCD # List of modules to include -MODULES = Telemetry Attitude Stabilization Actuator ManualControl FirmwareIAP +OPTMODULES = CameraStab +ifeq ($(USE_GPS), YES) +OPTMODULES += GPS +endif + +MODULES = Attitude Stabilization Actuator ManualControl FirmwareIAP +# Telemetry must be last to grab the optional modules (why?) +MODULES += Telemetry # Paths OPSYSTEM = ./System @@ -115,6 +125,7 @@ OPUAVSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/flight ifndef TESTAPP ## MODULES +SRC += ${foreach MOD, ${OPTMODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} SRC += ${foreach MOD, ${MODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} ## OPENPILOT CORE: SRC += ${OPMODULEDIR}/System/systemmod.c @@ -125,7 +136,6 @@ SRC += $(OPSYSTEM)/taskmonitor.c SRC += $(OPUAVTALK)/uavtalk.c SRC += $(OPUAVOBJ)/uavobjectmanager.c SRC += $(OPUAVOBJ)/eventdispatcher.c -SRC += $(OPUAVOBJ)/uavobjectsinit_linker.c SRC += $(OPSYSTEM)/pios_usb_hid_desc.c else ## TESTCODE @@ -153,21 +163,22 @@ SRC += $(OPUAVSYNTHDIR)/actuatorsettings.c SRC += $(OPUAVSYNTHDIR)/attituderaw.c SRC += $(OPUAVSYNTHDIR)/attitudeactual.c SRC += $(OPUAVSYNTHDIR)/manualcontrolcommand.c -SRC += $(OPUAVSYNTHDIR)/taskinfo.c SRC += $(OPUAVSYNTHDIR)/i2cstats.c SRC += $(OPUAVSYNTHDIR)/watchdogstatus.c -SRC += $(OPUAVSYNTHDIR)/telemetrysettings.c -SRC += $(OPUAVSYNTHDIR)/ratedesired.c SRC += $(OPUAVSYNTHDIR)/manualcontrolsettings.c SRC += $(OPUAVSYNTHDIR)/mixersettings.c -SRC += $(OPUAVSYNTHDIR)/mixerstatus.c SRC += $(OPUAVSYNTHDIR)/firmwareiapobj.c SRC += $(OPUAVSYNTHDIR)/attitudesettings.c +SRC += $(OPUAVSYNTHDIR)/camerastabsettings.c +SRC += $(OPUAVSYNTHDIR)/cameradesired.c +SRC += $(OPUAVSYNTHDIR)/gpsposition.c SRC += $(OPUAVSYNTHDIR)/hwsettings.c -#${wildcard ${OBJ}/$(shell echo $(VAR) | tr A-Z a-z)/*.c} -#SRC += ${foreach OBJ, ${UAVOBJECTS}, $(UAVOBJECTS)/$(OBJ).c} -# Cant use until i can automatically generate list of UAVObjects -#SRC += ${OUTDIR}/InitObjects.c +SRC += $(OPUAVSYNTHDIR)/gcsreceiver.c +SRC += $(OPUAVSYNTHDIR)/receiveractivity.c +SRC += $(OPUAVSYNTHDIR)/taskinfo.c +SRC += $(OPUAVSYNTHDIR)/mixerstatus.c +SRC += $(OPUAVSYNTHDIR)/ratedesired.c + endif ## PIOS Hardware (STM32F10x) @@ -182,13 +193,14 @@ SRC += $(PIOSSTM32F10X)/pios_i2c.c SRC += $(PIOSSTM32F10X)/pios_spi.c SRC += $(PIOSSTM32F10X)/pios_ppm.c SRC += $(PIOSSTM32F10X)/pios_pwm.c -SRC += $(PIOSSTM32F10X)/pios_spektrum.c +SRC += $(PIOSSTM32F10X)/pios_dsm.c SRC += $(PIOSSTM32F10X)/pios_sbus.c SRC += $(PIOSSTM32F10X)/pios_debug.c SRC += $(PIOSSTM32F10X)/pios_gpio.c SRC += $(PIOSSTM32F10X)/pios_exti.c SRC += $(PIOSSTM32F10X)/pios_rtc.c SRC += $(PIOSSTM32F10X)/pios_wdg.c +SRC += $(PIOSSTM32F10X)/pios_tim.c # PIOS USB related files (seperated to make code maintenance more easy) @@ -207,6 +219,7 @@ SRC += $(PIOSCOMMON)/pios_i2c_esc.c SRC += $(PIOSCOMMON)/pios_iap.c SRC += $(PIOSCOMMON)/pios_bl_helper.c SRC += $(PIOSCOMMON)/pios_rcvr.c +SRC += $(PIOSCOMMON)/pios_gcsrcvr.c SRC += $(PIOSCOMMON)/printf-stdarg.c ## Libraries for flight calculations SRC += $(FLIGHTLIB)/fifo_buffer.c @@ -325,7 +338,7 @@ EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/ARM_CM3 EXTRAINCDIRS += $(AHRSBOOTLOADERINC) EXTRAINCDIRS += $(PYMITEINC) -EXTRAINCDIRS += ${foreach MOD, ${MODULES}, ${OPMODULEDIR}/${MOD}/inc} ${OPMODULEDIR}/System/inc +EXTRAINCDIRS += ${foreach MOD, ${OPTMODULES} ${MODULES}, ${OPMODULEDIR}/${MOD}/inc} ${OPMODULEDIR}/System/inc # List any extra directories to look for library files here. @@ -417,6 +430,10 @@ ifeq ($(DEBUG),YES) CFLAGS = -DDEBUG endif +ifeq ($(DIAGNOSTICS),YES) +CFLAGS = -DDIAGNOSTICS +endif + CFLAGS += -g$(DEBUGF) CFLAGS += -O$(OPT) CFLAGS += -mcpu=$(MCU) @@ -425,14 +442,16 @@ CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I. #CFLAGS += -fno-cprop-registers -fno-defer-pop -fno-guess-branch-probability -fno-section-anchors #CFLAGS += -fno-if-conversion -fno-if-conversion2 -fno-ipa-pure-const -fno-ipa-reference -fno-merge-constants -#CFLAGS += -fno-split-wide-types -fno-tree-ccp -fno-tree-ch -fno-tree-copy-prop -fno-tree-copyrename +#CFLAGS += -fno-split-wide-types -fno-tree-ccp -fno-tree-ch -fno-tree-copy-prop -fno-tree-copyrename #CFLAGS += -fno-tree-dce -fno-tree-dominator-opts -fno-tree-dse -fno-tree-fre -fno-tree-sink -fno-tree-sra #CFLAGS += -fno-tree-ter #CFLAGS += -g$(DEBUGF) -DDEBUG CFLAGS += -mapcs-frame CFLAGS += -fomit-frame-pointer +ifeq ($(CODE_SOURCERY), YES) CFLAGS += -fpromote-loop-indices +endif CFLAGS += -Wall CFLAGS += -Werror @@ -504,7 +523,7 @@ endif endif # 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) +#$(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, $@) # @$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -s --memspace=flash -o $(OUTDIR)/pmlib_img.c --native-file=$(OUTDIR)/pmlib_nat.c $(PYMITELIB)/list.py $(PYMITELIB)/dict.py $(PYMITELIB)/__bi.py $(PYMITELIB)/sys.py $(PYMITELIB)/string.py $(wildcard $(FLIGHTPLANLIB)/*.py) # @$(PYTHON) $(PYMITETOOLS)/pmGenPmFeatures.py $(PYMITEPLAT)/pmfeatures.py > $(OUTDIR)/pmfeatures.h @@ -542,7 +561,7 @@ $(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin $(eval $(call OPFW_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BOARD_TYPE),$(BOARD_REVISION))) # Add jtag targets (program and wipe) -$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE))) +$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE),$(OPENOCD_CONFIG))) .PHONY: elf lss sym hex bin bino opfw elf: $(OUTDIR)/$(TARGET).elf diff --git a/flight/CopterControl/System/alarms.c b/flight/CopterControl/System/alarms.c index e899be779..01d79a1e5 100644 --- a/flight/CopterControl/System/alarms.c +++ b/flight/CopterControl/System/alarms.c @@ -41,10 +41,12 @@ static xSemaphoreHandle lock; static int32_t hasSeverity(SystemAlarmsAlarmOptions severity); /** - * Initialize the alarms library + * Initialize the alarms library */ int32_t AlarmsInitialize(void) { + SystemAlarmsInitialize(); + lock = xSemaphoreCreateRecursiveMutex(); //do not change the default states of the alarms, let the init code generated by the uavobjectgenerator handle that //AlarmsClearAll(); @@ -56,7 +58,7 @@ int32_t AlarmsInitialize(void) * Set an alarm * @param alarm The system alarm to be modified * @param severity The alarm severity - * @return 0 if success, -1 if an error + * @return 0 if success, -1 if an error */ int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity) { @@ -151,7 +153,7 @@ void AlarmsClearAll() /** * Check if there are any alarms with the given or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found + * @return 0 if no alarms are found, 1 if at least one alarm is found */ int32_t AlarmsHasWarnings() { @@ -208,5 +210,5 @@ static int32_t hasSeverity(SystemAlarmsAlarmOptions severity) /** * @} * @} - */ + */ diff --git a/flight/CopterControl/System/coptercontrol.c b/flight/CopterControl/System/coptercontrol.c index f66cf1cf5..a7cd909d9 100644 --- a/flight/CopterControl/System/coptercontrol.c +++ b/flight/CopterControl/System/coptercontrol.c @@ -1,97 +1,104 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotSystem OpenPilot System - * @brief These files are the core system files of OpenPilot. - * They are the ground layer just above PiOS. In practice, OpenPilot actually starts - * in the main() function of openpilot.c - * @{ - * @addtogroup OpenPilotCore OpenPilot Core - * @brief This is where the OP firmware starts. Those files also define the compile-time - * options of the firmware. - * @{ - * @file openpilot.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Sets up and runs main OpenPilot tasks. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -/* OpenPilot Includes */ -#include "openpilot.h" -#include "uavobjectsinit.h" -#include "systemmod.h" - -/* Task Priorities */ -#define PRIORITY_TASK_HOOKS (tskIDLE_PRIORITY + 3) - -/* Global Variables */ - -/* Prototype of PIOS_Board_Init() function */ -extern void PIOS_Board_Init(void); -extern void Stack_Change(void); - -/** -* OpenPilot Main function: -* -* Initialize PiOS
-* Create the "System" task (SystemModInitializein Modules/System/systemmod.c)
-* Start FreeRTOS Scheduler (vTaskStartScheduler) (Now handled by caller) -* If something goes wrong, blink LED1 and LED2 every 100ms -* -*/ -int main() -{ - /* NOTE: Do NOT modify the following start-up sequence */ - /* Any new initialization functions should be added in OpenPilotInit() */ - - /* Brings up System using CMSIS functions, enables the LEDs. */ - PIOS_SYS_Init(); - - /* Architecture dependant Hardware and - * core subsystem initialisation - * (see pios_board.c for your arch) - * */ - PIOS_Board_Init(); - - /* Initialize modules */ - 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; -} - -/** - * @} - * @} - */ - +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @brief These files are the core system files of OpenPilot. + * They are the ground layer just above PiOS. In practice, OpenPilot actually starts + * in the main() function of openpilot.c + * @{ + * @addtogroup OpenPilotCore OpenPilot Core + * @brief This is where the OP firmware starts. Those files also define the compile-time + * options of the firmware. + * @{ + * @file openpilot.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Sets up and runs main OpenPilot tasks. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +/* OpenPilot Includes */ +#include "openpilot.h" +#include "uavobjectsinit.h" +#include "hwsettings.h" +#include "systemmod.h" + +/* Task Priorities */ +#define PRIORITY_TASK_HOOKS (tskIDLE_PRIORITY + 3) + +/* Global Variables */ + +/* Prototype of PIOS_Board_Init() function */ +extern void PIOS_Board_Init(void); +extern void Stack_Change(void); + +/** +* OpenPilot Main function: +* +* Initialize PiOS
+* Create the "System" task (SystemModInitializein Modules/System/systemmod.c)
+* Start FreeRTOS Scheduler (vTaskStartScheduler) (Now handled by caller) +* If something goes wrong, blink LED1 and LED2 every 100ms +* +*/ +int main() +{ + /* NOTE: Do NOT modify the following start-up sequence */ + /* Any new initialization functions should be added in OpenPilotInit() */ + + /* Brings up System using CMSIS functions, enables the LEDs. */ + PIOS_SYS_Init(); + + /* Architecture dependant Hardware and + * core subsystem initialisation + * (see pios_board.c for your arch) + * */ + PIOS_Board_Init(); + +#ifdef ERASE_FLASH + PIOS_Flash_W25X_EraseChip(); + PIOS_LED_Off(LED1); + while (1) ; +#endif + + /* Initialize modules */ + 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); + while (1) { + PIOS_LED_Toggle(LED1); + PIOS_DELAY_WaitmS(100); + } + + return 0; +} + +/** + * @} + * @} + */ + diff --git a/flight/CopterControl/System/inc/FreeRTOSConfig.h b/flight/CopterControl/System/inc/FreeRTOSConfig.h index 45b0b8902..994956008 100644 --- a/flight/CopterControl/System/inc/FreeRTOSConfig.h +++ b/flight/CopterControl/System/inc/FreeRTOSConfig.h @@ -26,6 +26,7 @@ #define configUSE_PREEMPTION 1 #define configUSE_IDLE_HOOK 1 #define configUSE_TICK_HOOK 0 +#define configUSE_MALLOC_FAILED_HOOK 1 #define configCPU_CLOCK_HZ ( ( unsigned long ) 72000000 ) #define configTICK_RATE_HZ ( ( portTickType ) 1000 ) #define configMAX_PRIORITIES ( ( unsigned portBASE_TYPE ) 5 ) @@ -39,7 +40,6 @@ #define configUSE_RECURSIVE_MUTEXES 1 #define configUSE_COUNTING_SEMAPHORES 0 #define configUSE_ALTERNATIVE_API 0 -#define configCHECK_FOR_STACK_OVERFLOW 2 #define configQUEUE_REGISTRY_SIZE 10 /* Co-routine definitions. */ @@ -76,7 +76,9 @@ NVIC value of 255. */ #endif /* Enable run time stats collection */ -//#if defined(DEBUG) +#if defined(DIAGNOSTICS) +#define configCHECK_FOR_STACK_OVERFLOW 2 + #define configGENERATE_RUN_TIME_STATS 1 #define INCLUDE_uxTaskGetRunTime 1 #define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS()\ @@ -85,7 +87,9 @@ do {\ (*(unsigned long *)0xe0001000) |= 1; /* DWT_CTRL |= DWT_CYCCNT_ENA */\ } while(0) #define portGET_RUN_TIME_COUNTER_VALUE() (*(unsigned long *)0xe0001004)/* DWT_CYCCNT */ -//#endif +#else +#define configCHECK_FOR_STACK_OVERFLOW 1 +#endif /** diff --git a/flight/CopterControl/System/inc/pios_config.h b/flight/CopterControl/System/inc/pios_config.h index 8e09d71ca..8e29e0b73 100644 --- a/flight/CopterControl/System/inc/pios_config.h +++ b/flight/CopterControl/System/inc/pios_config.h @@ -46,14 +46,16 @@ #define PIOS_INCLUDE_RCVR /* Supported receiver interfaces */ -#define PIOS_INCLUDE_SPEKTRUM +#define PIOS_INCLUDE_DSM #define PIOS_INCLUDE_SBUS -//#define PIOS_INCLUDE_PPM +#define PIOS_INCLUDE_PPM #define PIOS_INCLUDE_PWM +#define PIOS_INCLUDE_GCSRCVR /* Supported USART-based PIOS modules */ #define PIOS_INCLUDE_TELEMETRY_RF -//#define PIOS_INCLUDE_GPS +#define PIOS_INCLUDE_GPS +#define PIOS_GPS_MINIMAL #define PIOS_INCLUDE_SERVO #define PIOS_INCLUDE_SPI @@ -79,12 +81,6 @@ #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 @@ -106,6 +102,9 @@ // This can't be too high to stop eventdispatcher thread overflowing #define PIOS_EVENTDISAPTCHER_QUEUE 10 +/* PIOS Initcall infrastructure */ +#define PIOS_INCLUDE_INITCALL + #endif /* PIOS_CONFIG_H */ /** * @} diff --git a/flight/CopterControl/System/inc/pios_config_posix.h b/flight/CopterControl/System/inc/pios_config_posix.h index ddf7ee5d4..f7dd4aa2e 100644 --- a/flight/CopterControl/System/inc/pios_config_posix.h +++ b/flight/CopterControl/System/inc/pios_config_posix.h @@ -44,11 +44,4 @@ #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 - - #endif /* PIOS_CONFIG_POSIX_H */ diff --git a/flight/CopterControl/System/pios_board.c b/flight/CopterControl/System/pios_board.c index ee3deaf5c..d89342787 100644 --- a/flight/CopterControl/System/pios_board.c +++ b/flight/CopterControl/System/pios_board.c @@ -32,6 +32,7 @@ #include #include #include +#include #if defined(PIOS_INCLUDE_SPI) @@ -195,6 +196,347 @@ void PIOS_ADC_handler() { PIOS_ADC_DMA_Handler(); } +#include "pios_tim_priv.h" + +static const TIM_TimeBaseInitTypeDef tim_1_2_3_4_time_base = { + .TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1, + .TIM_ClockDivision = TIM_CKD_DIV1, + .TIM_CounterMode = TIM_CounterMode_Up, + .TIM_Period = ((1000000 / PIOS_SERVO_UPDATE_HZ) - 1), + .TIM_RepetitionCounter = 0x0000, +}; + +static const struct pios_tim_clock_cfg tim_1_cfg = { + .timer = TIM1, + .time_base_init = &tim_1_2_3_4_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM1_CC_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const struct pios_tim_clock_cfg tim_2_cfg = { + .timer = TIM2, + .time_base_init = &tim_1_2_3_4_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM2_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const struct pios_tim_clock_cfg tim_3_cfg = { + .timer = TIM3, + .time_base_init = &tim_1_2_3_4_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM3_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const struct pios_tim_clock_cfg tim_4_cfg = { + .timer = TIM4, + .time_base_init = &tim_1_2_3_4_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM4_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const struct pios_tim_channel pios_tim_rcvrport_all_channels[] = { + { + .timer = TIM4, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_6, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM3, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_5, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + .remap = GPIO_PartialRemap_TIM3, + }, + { + .timer = TIM3, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_0, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM3, + .timer_chan = TIM_Channel_4, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_1, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM2, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_0, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM2, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_1, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, +}; + +static const struct pios_tim_channel pios_tim_servoport_all_pins[] = { + { + .timer = TIM4, + .timer_chan = TIM_Channel_4, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_9, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM4, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_8, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM4, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_7, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM1, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_8, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM3, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_4, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + .remap = GPIO_PartialRemap_TIM3, + }, + { + .timer = TIM2, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_2, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, +}; + + +static const struct pios_tim_channel pios_tim_servoport_rcvrport_pins[] = { + { + .timer = TIM4, + .timer_chan = TIM_Channel_4, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_9, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM4, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_8, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM4, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_7, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM1, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_8, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM3, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_4, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + .remap = GPIO_PartialRemap_TIM3, + }, + { + .timer = TIM2, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_2, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + + // Receiver port pins + // S3-S6 inputs are used as outputs in this case + { + .timer = TIM3, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_0, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM3, + .timer_chan = TIM_Channel_4, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_1, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM2, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_0, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM2, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_1, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, +}; #if defined(PIOS_INCLUDE_USART) #include "pios_usart_priv.h" @@ -353,13 +695,13 @@ static const struct pios_usart_cfg pios_usart_gps_flexi_cfg = { }; #endif /* PIOS_INCLUDE_GPS */ -#if defined(PIOS_INCLUDE_SPEKTRUM) +#if defined(PIOS_INCLUDE_DSM) /* - * SPEKTRUM USART + * Spektrum/JR DSM USART */ -#include +#include -static const struct pios_usart_cfg pios_usart_spektrum_main_cfg = { +static const struct pios_usart_cfg pios_usart_dsm_main_cfg = { .regs = USART1, .init = { .USART_BaudRate = 115200, @@ -395,7 +737,7 @@ static const struct pios_usart_cfg pios_usart_spektrum_main_cfg = { }, }; -static const struct pios_spektrum_cfg pios_spektrum_main_cfg = { +static const struct pios_dsm_cfg pios_dsm_main_cfg = { .bind = { .gpio = GPIOA, .init = { @@ -404,10 +746,9 @@ static const struct pios_spektrum_cfg pios_spektrum_main_cfg = { .GPIO_Mode = GPIO_Mode_Out_PP, }, }, - .remap = 0, }; -static const struct pios_usart_cfg pios_usart_spektrum_flexi_cfg = { +static const struct pios_usart_cfg pios_usart_dsm_flexi_cfg = { .regs = USART3, .init = { .USART_BaudRate = 115200, @@ -443,7 +784,7 @@ static const struct pios_usart_cfg pios_usart_spektrum_flexi_cfg = { }, }; -static const struct pios_spektrum_cfg pios_spektrum_flexi_cfg = { +static const struct pios_dsm_cfg pios_dsm_flexi_cfg = { .bind = { .gpio = GPIOB, .init = { @@ -452,14 +793,13 @@ static const struct pios_spektrum_cfg pios_spektrum_flexi_cfg = { .GPIO_Mode = GPIO_Mode_Out_PP, }, }, - .remap = 0, }; -#endif /* PIOS_INCLUDE_SPEKTRUM */ +#endif /* PIOS_INCLUDE_DSM */ #if defined(PIOS_INCLUDE_SBUS) /* - * SBUS USART + * S.Bus USART */ #include @@ -525,7 +865,7 @@ static const struct pios_sbus_cfg pios_sbus_cfg = { #define PIOS_COM_TELEM_RF_RX_BUF_LEN 192 #define PIOS_COM_TELEM_RF_TX_BUF_LEN 192 -#define PIOS_COM_GPS_RX_BUF_LEN 96 +#define PIOS_COM_GPS_RX_BUF_LEN 32 #define PIOS_COM_TELEM_USB_RX_BUF_LEN 192 #define PIOS_COM_TELEM_USB_TX_BUF_LEN 192 @@ -564,75 +904,37 @@ void PIOS_RTC_IRQ_Handler (void) * Servo outputs */ #include -static const struct pios_servo_channel pios_servo_channels[] = { - { - .timer = TIM4, - .port = GPIOB, - .channel = TIM_Channel_4, - .pin = GPIO_Pin_9, - }, - { - .timer = TIM4, - .port = GPIOB, - .channel = TIM_Channel_3, - .pin = GPIO_Pin_8, - }, - { - .timer = TIM4, - .port = GPIOB, - .channel = TIM_Channel_2, - .pin = GPIO_Pin_7, - }, - { - .timer = TIM1, - .port = GPIOA, - .channel = TIM_Channel_1, - .pin = GPIO_Pin_8, - }, - { /* needs to remap to alternative function */ - .timer = TIM3, - .port = GPIOB, - .channel = TIM_Channel_1, - .pin = GPIO_Pin_4, - }, - { - .timer = TIM2, - .port = GPIOA, - .channel = TIM_Channel_3, - .pin = GPIO_Pin_2, - }, -}; const struct pios_servo_cfg pios_servo_cfg = { - .tim_base_init = { - .TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1, - .TIM_ClockDivision = TIM_CKD_DIV1, - .TIM_CounterMode = TIM_CounterMode_Up, - .TIM_Period = ((1000000 / PIOS_SERVO_UPDATE_HZ) - 1), - .TIM_RepetitionCounter = 0x0000, - }, .tim_oc_init = { .TIM_OCMode = TIM_OCMode_PWM1, .TIM_OutputState = TIM_OutputState_Enable, .TIM_OutputNState = TIM_OutputNState_Disable, - .TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION, + .TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION, .TIM_OCPolarity = TIM_OCPolarity_High, .TIM_OCNPolarity = TIM_OCPolarity_High, .TIM_OCIdleState = TIM_OCIdleState_Reset, .TIM_OCNIdleState = TIM_OCNIdleState_Reset, }, - .gpio_init = { - .GPIO_Mode = GPIO_Mode_AF_PP, - .GPIO_Speed = GPIO_Speed_2MHz, - }, - .remap = GPIO_PartialRemap_TIM3, - .channels = pios_servo_channels, - .num_channels = NELEMENTS(pios_servo_channels), + .channels = pios_tim_servoport_all_pins, + .num_channels = NELEMENTS(pios_tim_servoport_all_pins), +}; + +const struct pios_servo_cfg pios_servo_rcvr_cfg = { + .tim_oc_init = { + .TIM_OCMode = TIM_OCMode_PWM1, + .TIM_OutputState = TIM_OutputState_Enable, + .TIM_OutputNState = TIM_OutputNState_Disable, + .TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION, + .TIM_OCPolarity = TIM_OCPolarity_High, + .TIM_OCNPolarity = TIM_OCPolarity_High, + .TIM_OCIdleState = TIM_OCIdleState_Reset, + .TIM_OCNIdleState = TIM_OCNIdleState_Reset, + }, + .channels = pios_tim_servoport_rcvrport_pins, + .num_channels = NELEMENTS(pios_tim_servoport_rcvrport_pins), }; -#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 @@ -640,45 +942,18 @@ const struct pios_servo_cfg pios_servo_cfg = { #if defined(PIOS_INCLUDE_PPM) #include -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 = { - .init = { - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .timer = TIM4, - .port = GPIOB, - .ccr = TIM_IT_CC1, + /* Use only the first channel for ppm */ + .channels = &pios_tim_rcvrport_all_channels[0], + .num_channels = 1, }; -void PIOS_TIM4_irq_handler() -{ - PIOS_PPM_irq_handler(); -} #endif /* PIOS_INCLUDE_PPM */ /* @@ -687,98 +962,16 @@ void PIOS_TIM4_irq_handler() #if defined(PIOS_INCLUDE_PWM) #include -static const struct pios_pwm_channel pios_pwm_channels[] = { - { - .timer = TIM4, - .port = GPIOB, - .ccr = TIM_IT_CC1, - .channel = TIM_Channel_1, - .pin = GPIO_Pin_6, - }, - { - .timer = TIM3, - .port = GPIOB, - .ccr = TIM_IT_CC2, - .channel = TIM_Channel_2, - .pin = GPIO_Pin_5, - }, - { - .timer = TIM3, - .port = GPIOB, - .ccr = TIM_IT_CC3, - .channel = TIM_Channel_3, - .pin = GPIO_Pin_0 - }, - { - .timer = TIM3, - .port = GPIOB, - .ccr = TIM_IT_CC4, - .channel = TIM_Channel_4, - .pin = GPIO_Pin_1, - }, - { - .timer = TIM2, - .port = GPIOA, - .ccr = TIM_IT_CC1, - .channel = TIM_Channel_1, - .pin = GPIO_Pin_0, - }, - { - .timer = TIM2, - .port = GPIOA, - .ccr = TIM_IT_CC2, - .channel = TIM_Channel_2, - .pin = GPIO_Pin_1, - }, -}; - -void TIM2_IRQHandler(); -void TIM3_IRQHandler(); -void TIM4_IRQHandler(); -void TIM2_IRQHandler() __attribute__ ((alias ("PIOS_TIM2_irq_handler"))); -void TIM3_IRQHandler() __attribute__ ((alias ("PIOS_TIM3_irq_handler"))); -void TIM4_IRQHandler() __attribute__ ((alias ("PIOS_TIM4_irq_handler"))); const struct pios_pwm_cfg pios_pwm_cfg = { - .tim_base_init = { - .TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1, - .TIM_ClockDivision = TIM_CKD_DIV1, - .TIM_CounterMode = TIM_CounterMode_Up, - .TIM_Period = 0xFFFF, - .TIM_RepetitionCounter = 0x0000, - }, .tim_ic_init = { .TIM_ICPolarity = TIM_ICPolarity_Rising, .TIM_ICSelection = TIM_ICSelection_DirectTI, .TIM_ICPrescaler = TIM_ICPSC_DIV1, - .TIM_ICFilter = 0x0, + .TIM_ICFilter = 0x0, }, - .gpio_init = { - .GPIO_Mode = GPIO_Mode_IPD, - .GPIO_Speed = GPIO_Speed_2MHz, - }, - .remap = 0, - .irq = { - .init = { - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .channels = pios_pwm_channels, - .num_channels = NELEMENTS(pios_pwm_channels), + .channels = pios_tim_rcvrport_all_channels, + .num_channels = NELEMENTS(pios_tim_rcvrport_all_channels), }; -void PIOS_TIM2_irq_handler() -{ - PIOS_PWM_irq_handler(TIM2); -} -void PIOS_TIM3_irq_handler() -{ - PIOS_PWM_irq_handler(TIM3); -} -void PIOS_TIM4_irq_handler() -{ - PIOS_PWM_irq_handler(TIM4); -} #endif #if defined(PIOS_INCLUDE_I2C) @@ -856,11 +1049,19 @@ void PIOS_I2C_main_adapter_er_irq_handler(void) #endif /* PIOS_INCLUDE_I2C */ +#if defined(PIOS_INCLUDE_GCSRCVR) +#include "pios_gcsrcvr_priv.h" +#endif /* PIOS_INCLUDE_GCSRCVR */ + #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; +/* One slot per selectable receiver group. + * eg. PWM, PPM, GCS, DSMMAINPORT, DSMFLEXIPORT, SBUS + * NOTE: No slot in this map for NONE. + */ +uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE]; + #endif /* PIOS_INCLUDE_RCVR */ #if defined(PIOS_INCLUDE_USB_HID) @@ -907,8 +1108,9 @@ void PIOS_Board_Init(void) { /* Initialize UAVObject libraries */ EventDispatcherInitialize(); UAVObjInitialize(); - UAVObjectsInitializeAll(); + HwSettingsInitialize(); + #if defined(PIOS_INCLUDE_RTC) /* Initialize the real-time clock and its associated tick */ PIOS_RTC_Init(&pios_rtc_main_cfg); @@ -920,7 +1122,15 @@ void PIOS_Board_Init(void) { /* Initialize the task monitor library */ TaskMonitorInitialize(); + /* Set up pulse timers */ + PIOS_TIM_InitClock(&tim_1_cfg); + PIOS_TIM_InitClock(&tim_2_cfg); + PIOS_TIM_InitClock(&tim_3_cfg); + PIOS_TIM_InitClock(&tim_4_cfg); + /* Configure the main IO port */ + uint8_t hwsettings_DSMxBind; + HwSettingsDSMxBindGet(&hwsettings_DSMxBind); uint8_t hwsettings_cc_mainport; HwSettingsCC_MainPortGet(&hwsettings_cc_mainport); @@ -956,9 +1166,16 @@ void PIOS_Board_Init(void) { } uint32_t pios_sbus_id; - if (PIOS_SBUS_Init(&pios_sbus_id, &pios_sbus_cfg, &pios_usart_com_driver, pios_usart_sbus_id)) { + if (PIOS_SBus_Init(&pios_sbus_id, &pios_sbus_cfg, &pios_usart_com_driver, pios_usart_sbus_id)) { PIOS_Assert(0); } + + uint32_t pios_sbus_rcvr_id; + if (PIOS_RCVR_Init(&pios_sbus_rcvr_id, &pios_sbus_rcvr_driver, pios_sbus_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS] = pios_sbus_rcvr_id; + } #endif /* PIOS_INCLUDE_SBUS */ break; @@ -980,20 +1197,48 @@ void PIOS_Board_Init(void) { } #endif /* PIOS_INCLUDE_GPS */ break; - case HWSETTINGS_CC_MAINPORT_SPEKTRUM: -#if defined(PIOS_INCLUDE_SPEKTRUM) + case HWSETTINGS_CC_MAINPORT_DSM2: + case HWSETTINGS_CC_MAINPORT_DSMX10BIT: + case HWSETTINGS_CC_MAINPORT_DSMX11BIT: +#if defined(PIOS_INCLUDE_DSM) { - uint32_t pios_usart_spektrum_id; - if (PIOS_USART_Init(&pios_usart_spektrum_id, &pios_usart_spektrum_main_cfg)) { + enum pios_dsm_proto proto; + switch (hwsettings_cc_mainport) { + case HWSETTINGS_CC_MAINPORT_DSM2: + proto = PIOS_DSM_PROTO_DSM2; + break; + case HWSETTINGS_CC_MAINPORT_DSMX10BIT: + proto = PIOS_DSM_PROTO_DSMX10BIT; + break; + case HWSETTINGS_CC_MAINPORT_DSMX11BIT: + proto = PIOS_DSM_PROTO_DSMX11BIT; + break; + default: + PIOS_Assert(0); + break; + } + + uint32_t pios_usart_dsm_id; + if (PIOS_USART_Init(&pios_usart_dsm_id, &pios_usart_dsm_main_cfg)) { PIOS_Assert(0); } - uint32_t pios_spektrum_id; - if (PIOS_SPEKTRUM_Init(&pios_spektrum_id, &pios_spektrum_main_cfg, &pios_usart_com_driver, pios_usart_spektrum_id, false)) { + uint32_t pios_dsm_id; + if (PIOS_DSM_Init(&pios_dsm_id, + &pios_dsm_main_cfg, + &pios_usart_com_driver, + pios_usart_dsm_id, + proto, 0)) { PIOS_Assert(0); } + + uint32_t pios_dsm_rcvr_id; + if (PIOS_RCVR_Init(&pios_dsm_rcvr_id, &pios_dsm_rcvr_driver, pios_dsm_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT] = pios_dsm_rcvr_id; } -#endif /* PIOS_INCLUDE_SPEKTRUM */ +#endif /* PIOS_INCLUDE_DSM */ break; case HWSETTINGS_CC_MAINPORT_COMAUX: break; @@ -1042,20 +1287,48 @@ void PIOS_Board_Init(void) { } #endif /* PIOS_INCLUDE_GPS */ break; - case HWSETTINGS_CC_FLEXIPORT_SPEKTRUM: -#if defined(PIOS_INCLUDE_SPEKTRUM) + case HWSETTINGS_CC_FLEXIPORT_DSM2: + case HWSETTINGS_CC_FLEXIPORT_DSMX10BIT: + case HWSETTINGS_CC_FLEXIPORT_DSMX11BIT: +#if defined(PIOS_INCLUDE_DSM) { - uint32_t pios_usart_spektrum_id; - if (PIOS_USART_Init(&pios_usart_spektrum_id, &pios_usart_spektrum_flexi_cfg)) { + enum pios_dsm_proto proto; + switch (hwsettings_cc_flexiport) { + case HWSETTINGS_CC_FLEXIPORT_DSM2: + proto = PIOS_DSM_PROTO_DSM2; + break; + case HWSETTINGS_CC_FLEXIPORT_DSMX10BIT: + proto = PIOS_DSM_PROTO_DSMX10BIT; + break; + case HWSETTINGS_CC_FLEXIPORT_DSMX11BIT: + proto = PIOS_DSM_PROTO_DSMX11BIT; + break; + default: + PIOS_Assert(0); + break; + } + + uint32_t pios_usart_dsm_id; + if (PIOS_USART_Init(&pios_usart_dsm_id, &pios_usart_dsm_flexi_cfg)) { PIOS_Assert(0); } - uint32_t pios_spektrum_id; - if (PIOS_SPEKTRUM_Init(&pios_spektrum_id, &pios_spektrum_flexi_cfg, &pios_usart_com_driver, pios_usart_spektrum_id, false)) { + uint32_t pios_dsm_id; + if (PIOS_DSM_Init(&pios_dsm_id, + &pios_dsm_flexi_cfg, + &pios_usart_com_driver, + pios_usart_dsm_id, + proto, hwsettings_DSMxBind)) { PIOS_Assert(0); } + + uint32_t pios_dsm_rcvr_id; + if (PIOS_RCVR_Init(&pios_dsm_rcvr_id, &pios_dsm_rcvr_driver, pios_dsm_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMFLEXIPORT] = pios_dsm_rcvr_id; } -#endif /* PIOS_INCLUDE_SPEKTRUM */ +#endif /* PIOS_INCLUDE_DSM */ break; case HWSETTINGS_CC_FLEXIPORT_COMAUX: break; @@ -1070,83 +1343,72 @@ void PIOS_Board_Init(void) { break; } - /* Configure the selected receiver */ - uint8_t manualcontrolsettings_inputmode; - ManualControlSettingsInputModeGet(&manualcontrolsettings_inputmode); + /* Configure the rcvr port */ + uint8_t hwsettings_rcvrport; + HwSettingsCC_RcvrPortGet(&hwsettings_rcvrport); - switch (manualcontrolsettings_inputmode) { - case MANUALCONTROLSETTINGS_INPUTMODE_PWM: + switch (hwsettings_rcvrport) { + case HWSETTINGS_CC_RCVRPORT_DISABLED: + break; + case HWSETTINGS_CC_RCVRPORT_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++; + { + uint32_t pios_pwm_id; + PIOS_PWM_Init(&pios_pwm_id, &pios_pwm_cfg); + + uint32_t pios_pwm_rcvr_id; + if (PIOS_RCVR_Init(&pios_pwm_rcvr_id, &pios_pwm_rcvr_driver, pios_pwm_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PWM] = pios_pwm_rcvr_id; } #endif /* PIOS_INCLUDE_PWM */ break; - case MANUALCONTROLSETTINGS_INPUTMODE_PPM: + case HWSETTINGS_CC_RCVRPORT_PPM: + case HWSETTINGS_CC_RCVRPORT_PPMOUTPUTS: #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++; + { + uint32_t pios_ppm_id; + PIOS_PPM_Init(&pios_ppm_id, &pios_ppm_cfg); + + uint32_t pios_ppm_rcvr_id; + if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PPM] = pios_ppm_rcvr_id; } #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; } +#if defined(PIOS_INCLUDE_GCSRCVR) + GCSReceiverInitialize(); + PIOS_GCSRCVR_Init(); + uint32_t pios_gcsrcvr_rcvr_id; + if (PIOS_RCVR_Init(&pios_gcsrcvr_rcvr_id, &pios_gcsrcvr_rcvr_driver, 0)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_GCS] = pios_gcsrcvr_rcvr_id; +#endif /* PIOS_INCLUDE_GCSRCVR */ + /* Remap AFIO pin */ GPIO_PinRemapConfig( GPIO_Remap_SWJ_NoJTRST, ENABLE); - PIOS_Servo_Init(); + +#ifndef PIOS_DEBUG_ENABLE_DEBUG_PINS + switch (hwsettings_rcvrport) { + case HWSETTINGS_CC_RCVRPORT_DISABLED: + case HWSETTINGS_CC_RCVRPORT_PWM: + case HWSETTINGS_CC_RCVRPORT_PPM: + PIOS_Servo_Init(&pios_servo_cfg); + break; + case HWSETTINGS_CC_RCVRPORT_PPMOUTPUTS: + case HWSETTINGS_CC_RCVRPORT_OUTPUTS: + PIOS_Servo_Init(&pios_servo_rcvr_cfg); + break; + } +#else + PIOS_DEBUG_Init(&pios_tim_servo_all_channels, NELEMENTS(pios_tim_servo_all_channels)); +#endif /* PIOS_DEBUG_ENABLE_DEBUG_PINS */ PIOS_ADC_Init(); PIOS_GPIO_Init(); @@ -1168,7 +1430,9 @@ void PIOS_Board_Init(void) { #endif /* PIOS_INCLUDE_USB_HID */ PIOS_IAP_Init(); +#ifndef ERASE_FLASH PIOS_WDG_Init(); +#endif } /** diff --git a/flight/CopterControl/System/pios_board_posix.c b/flight/CopterControl/System/pios_board_posix.c index 87d8e7402..30f949830 100644 --- a/flight/CopterControl/System/pios_board_posix.c +++ b/flight/CopterControl/System/pios_board_posix.c @@ -42,7 +42,6 @@ void PIOS_Board_Init(void) { /* Initialize UAVObject libraries */ EventDispatcherInitialize(); UAVObjInitialize(); - UAVObjectsInitializeAll(); /* Initialize the alarms library */ AlarmsInitialize(); diff --git a/flight/CopterControl/System/taskmonitor.c b/flight/CopterControl/System/taskmonitor.c index 8941a616b..6ff6299d0 100644 --- a/flight/CopterControl/System/taskmonitor.c +++ b/flight/CopterControl/System/taskmonitor.c @@ -46,7 +46,10 @@ int32_t TaskMonitorInitialize(void) { lock = xSemaphoreCreateRecursiveMutex(); memset(handles, 0, sizeof(xTaskHandle)*TASKINFO_RUNNING_NUMELEM); + lastMonitorTime = 0; +#if defined(DIAGNOSTICS) lastMonitorTime = portGET_RUN_TIME_COUNTER_VALUE(); +#endif return 0; } @@ -73,6 +76,7 @@ int32_t TaskMonitorAdd(TaskInfoRunningElem task, xTaskHandle handle) */ void TaskMonitorUpdateAll(void) { +#if defined(DIAGNOSTICS) TaskInfoData data; int n; @@ -123,4 +127,5 @@ void TaskMonitorUpdateAll(void) // Done xSemaphoreGiveRecursive(lock); +#endif } diff --git a/flight/INS/Makefile b/flight/INS/Makefile index bd3bb52a9..4b39267f7 100644 --- a/flight/INS/Makefile +++ b/flight/INS/Makefile @@ -363,7 +363,7 @@ $(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin $(eval $(call OPFW_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BOARD_TYPE),$(BOARD_REVISION))) # Add jtag targets (program and wipe) -$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE))) +$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE),$(OPENOCD_CONFIG))) .PHONY: elf lss sym hex bin bino opfw elf: $(OUTDIR)/$(TARGET).elf diff --git a/flight/INS/inc/pios_config.h b/flight/INS/inc/pios_config.h index 41e7b4f44..ae6561236 100644 --- a/flight/INS/inc/pios_config.h +++ b/flight/INS/inc/pios_config.h @@ -54,13 +54,7 @@ #define PIOS_INCLUDE_BMA180 -/* COM Module */ -#define GPS_BAUDRATE 19200 -#define AUXUART_ENABLED 0 -#define AUXUART_BAUDRATE 19200 - #endif /* PIOS_CONFIG_H */ - /** * @} * @} diff --git a/flight/Libraries/ahrs_comm_objects.c b/flight/Libraries/ahrs_comm_objects.c index e43c380e4..0f98e6a6c 100644 --- a/flight/Libraries/ahrs_comm_objects.c +++ b/flight/Libraries/ahrs_comm_objects.c @@ -24,6 +24,7 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ +#include "pios.h" #include "ahrs_spi_comm.h" #include "pios_debug.h" @@ -79,6 +80,7 @@ CREATEHANDLE(10, FirmwareIAPObj); static void ObjectUpdatedCb(UAVObjEvent * ev); #define ADDHANDLE(idx,obj) {\ + obj##Initialize();\ int n = idx;\ objectHandles[n].data = &obj;\ objectHandles[n].uavHandle = obj##Handle();\ diff --git a/flight/Modules/AHRSComms/ahrs_comms.c b/flight/Modules/AHRSComms/ahrs_comms.c index 0c98969e3..c3fb45fae 100644 --- a/flight/Modules/AHRSComms/ahrs_comms.c +++ b/flight/Modules/AHRSComms/ahrs_comms.c @@ -52,6 +52,8 @@ #include "ahrs_comms.h" #include "ahrs_spi_comm.h" +#include "ahrsstatus.h" +#include "ahrscalibration.h" // Private constants #define STACK_SIZE configMINIMAL_STACK_SIZE-128 @@ -71,7 +73,7 @@ static void ahrscommsTask(void *parameters); */ int32_t AHRSCommsStart(void) { - // Start main task + // Start main task xTaskCreate(ahrscommsTask, (signed char *)"AHRSComms", STACK_SIZE, NULL, TASK_PRIORITY, &taskHandle); TaskMonitorAdd(TASKINFO_RUNNING_AHRSCOMMS, taskHandle); PIOS_WDG_RegisterFlag(PIOS_WDG_AHRS); @@ -85,6 +87,11 @@ int32_t AHRSCommsStart(void) */ int32_t AHRSCommsInitialize(void) { + AhrsStatusInitialize(); + AHRSCalibrationInitialize(); + AttitudeRawInitialize(); + VelocityActualInitialize(); + PositionActualInitialize(); return 0; } diff --git a/flight/Modules/Actuator/actuator.c b/flight/Modules/Actuator/actuator.c index 269b9dda6..9cc856487 100644 --- a/flight/Modules/Actuator/actuator.c +++ b/flight/Modules/Actuator/actuator.c @@ -41,7 +41,8 @@ #include "flightstatus.h" #include "mixersettings.h" #include "mixerstatus.h" - +#include "cameradesired.h" +#include "manualcontrolcommand.h" // Private constants #define MAX_QUEUE_SIZE 2 @@ -73,7 +74,7 @@ static void actuatorTask(void* parameters); static void actuator_update_rate(UAVObjEvent *); static int16_t scaleChannel(float value, int16_t max, int16_t min, int16_t neutral); static void setFailsafe(); -static float MixerCurve(const float throttle, const float* curve); +static float MixerCurve(const float throttle, const float* curve, uint8_t elements); static bool set_channel(uint8_t mixer_channel, uint16_t value); float ProcessMixer(const int index, const float curve1, const float curve2, MixerSettingsData* mixerSettings, ActuatorDesiredData* desired, @@ -108,9 +109,17 @@ int32_t ActuatorInitialize() // Create object queue queue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(UAVObjEvent)); + ActuatorSettingsInitialize(); + ActuatorDesiredInitialize(); + MixerSettingsInitialize(); + ActuatorCommandInitialize(); +#if defined(DIAGNOSTICS) + MixerStatusInitialize(); +#endif + // Listen for ExampleObject1 updates ActuatorDesiredConnectQueue(queue); - + // If settings change, update the output rate ActuatorSettingsConnectCallback(actuator_update_rate); @@ -160,7 +169,7 @@ static void actuatorTask(void* parameters) // Main task loop lastSysTime = xTaskGetTickCount(); while (1) - { + { PIOS_WDG_UpdateFlag(PIOS_WDG_ACTUATOR); // Wait until the ActuatorDesired object is updated, if a timeout then go to failsafe @@ -177,11 +186,13 @@ static void actuatorTask(void* parameters) lastSysTime = thisSysTime; FlightStatusGet(&flightStatus); - MixerStatusGet(&mixerStatus); MixerSettingsGet (&mixerSettings); ActuatorDesiredGet(&desired); ActuatorCommandGet(&command); +#if defined(DIAGNOSTICS) + MixerStatusGet(&mixerStatus); +#endif ActuatorSettingsMotorsSpinWhileArmedGet(&MotorsSpinWhileArmed); ActuatorSettingsChannelMaxGet(ChannelMax); ActuatorSettingsChannelMinGet(ChannelMin); @@ -196,7 +207,7 @@ static void actuatorTask(void* parameters) nMixers ++; } } - if((nMixers < 2) && !ActuatorCommandReadOnly(dummy)) //Nothing can fly with less than two mixers. + if((nMixers < 2) && !ActuatorCommandReadOnly()) //Nothing can fly with less than two mixers. { setFailsafe(); // So that channels like PWM buzzer keep working continue; @@ -207,23 +218,30 @@ static void actuatorTask(void* parameters) bool armed = flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED; bool positiveThrottle = desired.Throttle >= 0.00; bool spinWhileArmed = MotorsSpinWhileArmed == ACTUATORSETTINGS_MOTORSSPINWHILEARMED_TRUE; + + float curve1 = MixerCurve(desired.Throttle,mixerSettings.ThrottleCurve1,MIXERSETTINGS_THROTTLECURVE1_NUMELEM); - float curve1 = MixerCurve(desired.Throttle,mixerSettings.ThrottleCurve1); //The source for the secondary curve is selectable float curve2 = 0; AccessoryDesiredData accessory; switch(mixerSettings.Curve2Source) { case MIXERSETTINGS_CURVE2SOURCE_THROTTLE: - curve2 = MixerCurve(desired.Throttle,mixerSettings.ThrottleCurve2); + curve2 = MixerCurve(desired.Throttle,mixerSettings.ThrottleCurve2,MIXERSETTINGS_THROTTLECURVE2_NUMELEM); break; case MIXERSETTINGS_CURVE2SOURCE_ROLL: - curve2 = MixerCurve(desired.Roll,mixerSettings.ThrottleCurve2); + curve2 = MixerCurve(desired.Roll,mixerSettings.ThrottleCurve2,MIXERSETTINGS_THROTTLECURVE2_NUMELEM); break; case MIXERSETTINGS_CURVE2SOURCE_PITCH: - curve2 = MixerCurve(desired.Pitch,mixerSettings.ThrottleCurve2); + curve2 = MixerCurve(desired.Pitch,mixerSettings.ThrottleCurve2, + MIXERSETTINGS_THROTTLECURVE2_NUMELEM); break; case MIXERSETTINGS_CURVE2SOURCE_YAW: - curve2 = MixerCurve(desired.Yaw,mixerSettings.ThrottleCurve2); + curve2 = MixerCurve(desired.Yaw,mixerSettings.ThrottleCurve2,MIXERSETTINGS_THROTTLECURVE2_NUMELEM); + break; + case MIXERSETTINGS_CURVE2SOURCE_COLLECTIVE: + ManualControlCommandCollectiveGet(&curve2); + curve2 = MixerCurve(curve2,mixerSettings.ThrottleCurve2, + MIXERSETTINGS_THROTTLECURVE2_NUMELEM); break; case MIXERSETTINGS_CURVE2SOURCE_ACCESSORY0: case MIXERSETTINGS_CURVE2SOURCE_ACCESSORY1: @@ -232,12 +250,12 @@ static void actuatorTask(void* parameters) case MIXERSETTINGS_CURVE2SOURCE_ACCESSORY4: case MIXERSETTINGS_CURVE2SOURCE_ACCESSORY5: if(AccessoryDesiredInstGet(mixerSettings.Curve2Source - MIXERSETTINGS_CURVE2SOURCE_ACCESSORY0,&accessory) == 0) - curve2 = MixerCurve(accessory.AccessoryVal,mixerSettings.ThrottleCurve2); - else - curve2 = 0; + curve2 = MixerCurve(accessory.AccessoryVal,mixerSettings.ThrottleCurve2,MIXERSETTINGS_THROTTLECURVE2_NUMELEM); + else + curve2 = 0; break; } - + for(int ct=0; ct < MAX_MIX_ACTUATORS; ct++) { if(mixers[ct].type == MIXERSETTINGS_MIXER1TYPE_DISABLED) { @@ -246,53 +264,82 @@ static void actuatorTask(void* parameters) command.Channel[ct] = 0; continue; } - - status[ct] = ProcessMixer(ct, curve1, curve2, &mixerSettings, &desired, dT); - + + if((mixers[ct].type == MIXERSETTINGS_MIXER1TYPE_MOTOR) || (mixers[ct].type == MIXERSETTINGS_MIXER1TYPE_SERVO)) + status[ct] = ProcessMixer(ct, curve1, curve2, &mixerSettings, &desired, dT); + else + status[ct] = -1; + + + // Motors have additional protection for when to be on - if(mixers[ct].type == MIXERSETTINGS_MIXER1TYPE_MOTOR) { + if(mixers[ct].type == MIXERSETTINGS_MIXER1TYPE_MOTOR) { // If not armed or motors aren't meant to spin all the time if( !armed || (!spinWhileArmed && !positiveThrottle)) { filterAccumulator[ct] = 0; - lastResult[ct] = 0; + lastResult[ct] = 0; status[ct] = -1; //force min throttle - } - // If armed meant to keep spinning, + } + // If armed meant to keep spinning, else if ((spinWhileArmed && !positiveThrottle) || (status[ct] < 0) ) - status[ct] = 0; + status[ct] = 0; } - + // If an accessory channel is selected for direct bypass mode // In this configuration the accessory channel is scaled and mapped // directly to output. Note: THERE IS NO SAFETY CHECK HERE FOR ARMING - // these also will not be updated in failsafe mode. I'm not sure what + // these also will not be updated in failsafe mode. I'm not sure what // the correct behavior is since it seems domain specific. I don't love // this code - if( (mixers[ct].type >= MIXERSETTINGS_MIXER1TYPE_ACCESSORY0) && - (mixers[ct].type <= MIXERSETTINGS_MIXER1TYPE_ACCESSORY2)) + if( (mixers[ct].type >= MIXERSETTINGS_MIXER1TYPE_ACCESSORY0) && + (mixers[ct].type <= MIXERSETTINGS_MIXER1TYPE_ACCESSORY5)) { if(AccessoryDesiredInstGet(mixers[ct].type - MIXERSETTINGS_MIXER1TYPE_ACCESSORY0,&accessory) == 0) status[ct] = accessory.AccessoryVal; else status[ct] = -1; } - + if( (mixers[ct].type >= MIXERSETTINGS_MIXER1TYPE_CAMERAROLL) && + (mixers[ct].type <= MIXERSETTINGS_MIXER1TYPE_CAMERAYAW)) + { + CameraDesiredData cameraDesired; + if( CameraDesiredGet(&cameraDesired) == 0 ) { + switch(mixers[ct].type) { + case MIXERSETTINGS_MIXER1TYPE_CAMERAROLL: + status[ct] = cameraDesired.Roll; + break; + case MIXERSETTINGS_MIXER1TYPE_CAMERAPITCH: + status[ct] = cameraDesired.Pitch; + break; + case MIXERSETTINGS_MIXER1TYPE_CAMERAYAW: + status[ct] = cameraDesired.Yaw; + break; + default: + break; + } + } + else + status[ct] = -1; + } + command.Channel[ct] = scaleChannel(status[ct], ChannelMax[ct], ChannelMin[ct], ChannelNeutral[ct]); } +#if defined(DIAGNOSTICS) MixerStatusSet(&mixerStatus); +#endif // Store update time command.UpdateTime = 1000*dT; if(1000*dT > command.MaxUpdateTime) command.MaxUpdateTime = 1000*dT; - + // Update output object ActuatorCommandSet(&command); // Update in case read only (eg. during servo configuration) @@ -300,7 +347,7 @@ static void actuatorTask(void* parameters) // Update servo outputs bool success = true; - + for (int n = 0; n < ACTUATORCOMMAND_CHANNEL_NUMELEM; ++n) { success &= set_channel(n, command.Channel[n]); @@ -309,7 +356,7 @@ static void actuatorTask(void* parameters) if(!success) { command.NumFailedUpdates++; ActuatorCommandSet(&command); - AlarmsSet(SYSTEMALARMS_ALARM_ACTUATOR, SYSTEMALARMS_ALARM_CRITICAL); + AlarmsSet(SYSTEMALARMS_ALARM_ACTUATOR, SYSTEMALARMS_ALARM_CRITICAL); } } @@ -383,12 +430,9 @@ float ProcessMixer(const int index, const float curve1, const float curve2, *Interpolate a throttle curve. Throttle input should be in the range 0 to 1. *Output is in the range 0 to 1. */ - -#define MIXER_CURVE_ENTRIES 5 - -static float MixerCurve(const float throttle, const float* curve) +static float MixerCurve(const float throttle, const float* curve, uint8_t elements) { - float scale = throttle * MIXER_CURVE_ENTRIES; + float scale = throttle * (elements - 1); int idx1 = scale; scale -= (float)idx1; //remainder if(curve[0] < -1) @@ -401,12 +445,12 @@ static float MixerCurve(const float throttle, const float* curve) scale = 0; } int idx2 = idx1 + 1; - if(idx2 >= MIXER_CURVE_ENTRIES) + if(idx2 >= elements) { - idx2 = MIXER_CURVE_ENTRIES -1; //clamp to highest entry in table - if(idx1 >= MIXER_CURVE_ENTRIES) + idx2 = elements -1; //clamp to highest entry in table + if(idx1 >= elements) { - idx1 = MIXER_CURVE_ENTRIES -1; + idx1 = elements -1; } } return((curve[idx1] * (1 - scale)) + (curve[idx2] * scale)); @@ -463,7 +507,7 @@ static void setFailsafe() // Reset ActuatorCommand to safe values for (int n = 0; n < ACTUATORCOMMAND_CHANNEL_NUMELEM; ++n) { - + if(mixers[n].type == MIXERSETTINGS_MIXER1TYPE_MOTOR) { Channel[n] = ChannelMin[n]; @@ -510,10 +554,10 @@ static bool set_channel(uint8_t mixer_channel, uint16_t value) { } #else static bool set_channel(uint8_t mixer_channel, uint16_t value) { - + ActuatorSettingsData settings; ActuatorSettingsGet(&settings); - + switch(settings.ChannelType[mixer_channel]) { case ACTUATORSETTINGS_CHANNELTYPE_PWMALARMBUZZER: { // This is for buzzers that take a PWM input @@ -565,7 +609,7 @@ static bool set_channel(uint8_t mixer_channel, uint16_t value) { PIOS_Servo_Set(settings.ChannelAddr[mixer_channel], value); return true; #if defined(PIOS_INCLUDE_I2C_ESC) - case ACTUATORSETTINGS_CHANNELTYPE_MK: + case ACTUATORSETTINGS_CHANNELTYPE_MK: return PIOS_SetMKSpeed(settings.ChannelAddr[mixer_channel],value); case ACTUATORSETTINGS_CHANNELTYPE_ASTEC4: return PIOS_SetAstec4Speed(settings.ChannelAddr[mixer_channel],value); @@ -573,10 +617,10 @@ static bool set_channel(uint8_t mixer_channel, uint16_t value) { #endif default: return false; - } - + } + return false; - + } #endif diff --git a/flight/Modules/Altitude/altitude.c b/flight/Modules/Altitude/altitude.c index 363cba15f..d1655aaa8 100644 --- a/flight/Modules/Altitude/altitude.c +++ b/flight/Modules/Altitude/altitude.c @@ -69,6 +69,12 @@ static void altitudeTask(void *parameters); */ int32_t AltitudeStart() { + + BaroAltitudeInitialize(); +#if defined(PIOS_INCLUDE_HCSR04) + SonarAltitudeInitialze(); +#endif + // Start main task xTaskCreate(altitudeTask, (signed char *)"Altitude", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &taskHandle); TaskMonitorAdd(TASKINFO_RUNNING_ALTITUDE, taskHandle); diff --git a/flight/Modules/Attitude/attitude.c b/flight/Modules/Attitude/attitude.c index c70751fa6..fdfa4681c 100644 --- a/flight/Modules/Attitude/attitude.c +++ b/flight/Modules/Attitude/attitude.c @@ -54,6 +54,7 @@ #include "attitudeactual.h" #include "attitudesettings.h" #include "flightstatus.h" +#include "manualcontrolcommand.h" #include "CoordinateConversions.h" #include "pios_flash_w25x.h" @@ -91,18 +92,28 @@ static int8_t rotate = 0; static bool zero_during_arming = false; static bool bias_correct_gyro = true; +// For running trim flights +static volatile bool trim_requested = false; +static volatile int32_t trim_accels[3]; +static volatile int32_t trim_samples; +int32_t const MAX_TRIM_FLIGHT_SAMPLES = 65535; + +#define GRAV 9.81f +#define ACCEL_SCALE (GRAV * 0.004f) +/* 0.004f is gravity / LSB */ + /** * 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; } @@ -112,6 +123,10 @@ int32_t AttitudeStart(void) */ int32_t AttitudeInitialize(void) { + AttitudeActualInitialize(); + AttitudeRawInitialize(); + AttitudeSettingsInitialize(); + // Initialize quaternion AttitudeActualData attitude; AttitudeActualGet(&attitude); @@ -120,12 +135,12 @@ 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; @@ -133,17 +148,19 @@ int32_t AttitudeInitialize(void) for(uint8_t i = 0; i < 3; i++) for(uint8_t j = 0; j < 3; j++) R[i][j] = 0; - + + trim_requested = false; + // Create queue for passing gyro data, allow 2 back samples in case gyro_queue = xQueueCreate(1, sizeof(float) * 4); if(gyro_queue == NULL) return -1; - - + + PIOS_ADC_SetQueue(gyro_queue); - + AttitudeSettingsConnectCallback(&settingsUpdatedCb); - + return 0; } @@ -156,9 +173,9 @@ 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_ADXL345_Init(); @@ -171,13 +188,13 @@ static void AttitudeTask(void *parameters) // Force settings update to make sure rotation loaded settingsUpdatedCb(AttitudeSettingsHandle()); - + // Main task loop while (1) { - + FlightStatusData flightStatus; FlightStatusGet(&flightStatus); - + if((xTaskGetTickCount() < 7000) && (xTaskGetTickCount() > 1000)) { // For first 7 seconds use accels to get gyro bias accelKp = 1; @@ -197,9 +214,9 @@ static void AttitudeTask(void *parameters) AttitudeSettingsYawBiasRateGet(&yawBiasRate); init = 1; } - + PIOS_WDG_UpdateFlag(PIOS_WDG_ATTITUDE); - + AttitudeRawData attitudeRaw; AttitudeRawGet(&attitudeRaw); if(updateSensors(&attitudeRaw) != 0) @@ -210,7 +227,7 @@ static void AttitudeTask(void *parameters) AttitudeRawSet(&attitudeRaw); AlarmsClear(SYSTEMALARMS_ALARM_ATTITUDE); } - + } } @@ -223,22 +240,22 @@ static int8_t 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 -1; } - + // No accel data available if(PIOS_ADXL345_FifoElements() == 0) return -1; - + // 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; @@ -253,9 +270,9 @@ static int8_t 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]; @@ -272,19 +289,37 @@ static int8_t updateSensors(AttitudeRawData * attitudeRaw) attitudeRaw->accels[1] = accel[1]; attitudeRaw->accels[2] = accel[2]; } - + + if (trim_requested) { + if (trim_samples >= MAX_TRIM_FLIGHT_SAMPLES) { + trim_requested = false; + } else { + uint8_t armed; + float throttle; + FlightStatusArmedGet(&armed); + ManualControlCommandThrottleGet(&throttle); // Until flight status indicates airborne + if ((armed == FLIGHTSTATUS_ARMED_ARMED) && (throttle > 0)) { + trim_samples++; + // Store the digitally scaled version since that is what we use for bias + trim_accels[0] += attitudeRaw->accels[ATTITUDERAW_ACCELS_X]; + trim_accels[1] += attitudeRaw->accels[ATTITUDERAW_ACCELS_Y]; + trim_accels[2] += attitudeRaw->accels[ATTITUDERAW_ACCELS_Z]; + } + } + } + // 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; - + attitudeRaw->accels[ATTITUDERAW_ACCELS_X] = (attitudeRaw->accels[ATTITUDERAW_ACCELS_X] - accelbias[0]) * ACCEL_SCALE; + attitudeRaw->accels[ATTITUDERAW_ACCELS_Y] = (attitudeRaw->accels[ATTITUDERAW_ACCELS_Y] - accelbias[1]) * ACCEL_SCALE; + attitudeRaw->accels[ATTITUDERAW_ACCELS_Z] = (attitudeRaw->accels[ATTITUDERAW_ACCELS_Z] - accelbias[2]) * ACCEL_SCALE; + 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; @@ -297,45 +332,45 @@ static void updateAttitude(AttitudeRawData * attitudeRaw) float dT; portTickType thisSysTime = xTaskGetTickCount(); static portTickType lastSysTime = 0; - + 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 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 (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; - + + //gyro_correct_int[2] += accel_err[2] * accelKi; + // 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 @@ -344,7 +379,7 @@ 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]; @@ -358,14 +393,14 @@ static void updateAttitude(AttitudeRawData * attitudeRaw) q[3] = -q[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)) { @@ -374,44 +409,44 @@ static void updateAttitude(AttitudeRawData * attitudeRaw) 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); - + AttitudeActualSet(&attitudeActual); } static void settingsUpdatedCb(UAVObjEvent * objEv) { AttitudeSettingsData attitudeSettings; AttitudeSettingsGet(&attitudeSettings); - - + + accelKp = attitudeSettings.AccelKp; 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); @@ -424,8 +459,25 @@ static void settingsUpdatedCb(UAVObjEvent * objEv) { Quaternion2R(rotationQuat, R); rotate = 1; } + + if (attitudeSettings.TrimFlight == ATTITUDESETTINGS_TRIMFLIGHT_START) { + trim_accels[0] = 0; + trim_accels[1] = 0; + trim_accels[2] = 0; + trim_samples = 0; + trim_requested = true; + } else if (attitudeSettings.TrimFlight == ATTITUDESETTINGS_TRIMFLIGHT_LOAD) { + trim_requested = false; + attitudeSettings.AccelBias[ATTITUDESETTINGS_ACCELBIAS_X] = trim_accels[0] / trim_samples; + attitudeSettings.AccelBias[ATTITUDESETTINGS_ACCELBIAS_Y] = trim_accels[1] / trim_samples; + // Z should average -grav + attitudeSettings.AccelBias[ATTITUDESETTINGS_ACCELBIAS_Z] = trim_accels[2] / trim_samples + GRAV / ACCEL_SCALE; + attitudeSettings.TrimFlight = ATTITUDESETTINGS_TRIMFLIGHT_NORMAL; + AttitudeSettingsSet(&attitudeSettings); + } else + trim_requested = false; } /** - * @} - * @} - */ + * @} + * @} + */ diff --git a/flight/Modules/Battery/battery.c b/flight/Modules/Battery/battery.c index fe36745bb..a57efd69a 100644 --- a/flight/Modules/Battery/battery.c +++ b/flight/Modules/Battery/battery.c @@ -79,6 +79,9 @@ MODULE_INITCALL(BatteryInitialize, 0) int32_t BatteryInitialize(void) { + BatteryStateInitialze(); + BatterySettingsInitialize(); + static UAVObjEvent ev; memset(&ev,0,sizeof(UAVObjEvent)); diff --git a/flight/Modules/CameraStab/camerastab.c b/flight/Modules/CameraStab/camerastab.c new file mode 100644 index 000000000..770ff7ab6 --- /dev/null +++ b/flight/Modules/CameraStab/camerastab.c @@ -0,0 +1,169 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotModules OpenPilot Modules + * @{ + * @addtogroup CameraStab Camera Stabilization Module + * @brief Camera stabilization module + * Updates accessory outputs with values appropriate for camera stabilization + * @{ + * + * @file camerastab.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Stabilize camera against the roll pitch and yaw of aircraft + * + * @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 + */ + +/** + * Output object: Accessory + * + * This module will periodically calculate the output values for stabilizing the camera + * + * UAVObjects are automatically generated by the UAVObjectGenerator from + * the object definition XML file. + * + * Modules have no API, all communication to other modules is done through UAVObjects. + * However modules may use the API exposed by shared libraries. + * See the OpenPilot wiki for more details. + * http://www.openpilot.org/OpenPilot_Application_Architecture + * + */ + +#include "openpilot.h" + +#include "accessorydesired.h" +#include "attitudeactual.h" +#include "camerastabsettings.h" +#include "cameradesired.h" +#include "hwsettings.h" + +// +// Configuration +// +#define SAMPLE_PERIOD_MS 10 + +// Private types + +// Private variables + +// Private functions +static void attitudeUpdated(UAVObjEvent* ev); +static float bound(float val); + +/** + * Initialise the module, called on startup + * \returns 0 on success or -1 if initialisation failed + */ +int32_t CameraStabInitialize(void) +{ + static UAVObjEvent ev; + + bool cameraStabEnabled; + uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM]; + + HwSettingsInitialize(); + HwSettingsOptionalModulesGet(optionalModules); + + if (optionalModules[HWSETTINGS_OPTIONALMODULES_CAMERASTAB] == HWSETTINGS_OPTIONALMODULES_ENABLED) + cameraStabEnabled = true; + else + cameraStabEnabled = false; + + if (cameraStabEnabled) { + + AttitudeActualInitialize(); + + ev.obj = AttitudeActualHandle(); + ev.instId = 0; + ev.event = 0; + + CameraStabSettingsInitialize(); + CameraDesiredInitialize(); + + EventPeriodicCallbackCreate(&ev, attitudeUpdated, SAMPLE_PERIOD_MS / portTICK_RATE_MS); + + return 0; + } + + return -1; +} + +/* stub: module has no module thread */ +int32_t CameraStabStart(void) +{ + return 0; +} + +MODULE_INITCALL(CameraStabInitialize, CameraStabStart) + +static void attitudeUpdated(UAVObjEvent* ev) +{ + if (ev->obj != AttitudeActualHandle()) + return; + + float attitude; + float output; + AccessoryDesiredData accessory; + + CameraStabSettingsData cameraStab; + CameraStabSettingsGet(&cameraStab); + + // Read any input channels + float inputs[3] = {0,0,0}; + if(cameraStab.Inputs[CAMERASTABSETTINGS_INPUTS_ROLL] != CAMERASTABSETTINGS_INPUTS_NONE) { + if(AccessoryDesiredInstGet(cameraStab.Inputs[CAMERASTABSETTINGS_INPUTS_ROLL] - CAMERASTABSETTINGS_INPUTS_ACCESSORY0, &accessory) == 0) + inputs[0] = accessory.AccessoryVal * cameraStab.InputRange[CAMERASTABSETTINGS_INPUTRANGE_ROLL]; + } + if(cameraStab.Inputs[CAMERASTABSETTINGS_INPUTS_PITCH] != CAMERASTABSETTINGS_INPUTS_NONE) { + if(AccessoryDesiredInstGet(cameraStab.Inputs[CAMERASTABSETTINGS_INPUTS_PITCH] - CAMERASTABSETTINGS_INPUTS_ACCESSORY0, &accessory) == 0) + inputs[1] = accessory.AccessoryVal * cameraStab.InputRange[CAMERASTABSETTINGS_INPUTRANGE_PITCH]; + } + if(cameraStab.Inputs[CAMERASTABSETTINGS_INPUTS_YAW] != CAMERASTABSETTINGS_INPUTS_NONE) { + if(AccessoryDesiredInstGet(cameraStab.Inputs[CAMERASTABSETTINGS_INPUTS_YAW] - CAMERASTABSETTINGS_INPUTS_ACCESSORY0, &accessory) == 0) + inputs[2] = accessory.AccessoryVal * cameraStab.InputRange[CAMERASTABSETTINGS_INPUTRANGE_YAW]; + } + + // Set output channels + AttitudeActualRollGet(&attitude); + output = bound((attitude + inputs[0]) / cameraStab.OutputRange[CAMERASTABSETTINGS_OUTPUTRANGE_ROLL]); + CameraDesiredRollSet(&output); + + AttitudeActualPitchGet(&attitude); + output = bound((attitude + inputs[1]) / cameraStab.OutputRange[CAMERASTABSETTINGS_OUTPUTRANGE_PITCH]); + CameraDesiredPitchSet(&output); + + AttitudeActualYawGet(&attitude); + output = bound((attitude + inputs[2]) / cameraStab.OutputRange[CAMERASTABSETTINGS_OUTPUTRANGE_YAW]); + CameraDesiredYawSet(&output); + +} + +float bound(float val) +{ + return (val > 1) ? 1 : + (val < -1) ? -1 : + val; +} +/** + * @} + */ + +/** + * @} + */ diff --git a/flight/Modules/GPS/inc/GTOP_BIN.h b/flight/Modules/CameraStab/inc/camerastab.h similarity index 71% rename from flight/Modules/GPS/inc/GTOP_BIN.h rename to flight/Modules/CameraStab/inc/camerastab.h index 6a5234430..5d7bf9d06 100644 --- a/flight/Modules/GPS/inc/GTOP_BIN.h +++ b/flight/Modules/CameraStab/inc/camerastab.h @@ -1,14 +1,14 @@ /** ****************************************************************************** * @addtogroup OpenPilotModules OpenPilot Modules - * @{ - * @addtogroup GSPModule GPS Module - * @brief Process GPS information - * @{ + * @{ + * @addtogroup BatteryModule Battery Module + * @{ * - * @file GTOP_BIN.h + * @file battery.h * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief GPS module, handles GPS and NMEA stream + * @brief Module to read the battery Voltage and Current periodically and set alarms appropriately. + * * @see The GNU Public License (GPL) Version 3 * *****************************************************************************/ @@ -27,16 +27,16 @@ * with this program; if not, write to the Free Software Foundation, Inc., * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ +#ifndef BATTERY_H +#define BATTERY_H -#ifndef GTOP_BIN_H -#define GTOP_BIN_H +#include "openpilot.h" -#include -#include "gps_mode.h" +int32_t CameraStabInitialize(void); -#ifdef ENABLE_GPS_BINARY_GTOP - extern int GTOP_BIN_update_position(uint8_t b, volatile uint32_t *chksum_errors, volatile uint32_t *parsing_errors); - extern void GTOP_BIN_init(void); -#endif +#endif // BATTERY_H -#endif +/** + * @} + * @} + */ diff --git a/flight/Modules/FirmwareIAP/firmwareiap.c b/flight/Modules/FirmwareIAP/firmwareiap.c index e3372019c..21678397e 100644 --- a/flight/Modules/FirmwareIAP/firmwareiap.c +++ b/flight/Modules/FirmwareIAP/firmwareiap.c @@ -91,6 +91,9 @@ static void resetTask(UAVObjEvent *); MODULE_INITCALL(FirmwareIAPInitialize, 0) int32_t FirmwareIAPInitialize() { + + FirmwareIAPObjInitialize(); + const struct pios_board_info * bdinfo = &pios_board_info_blob; data.BoardType= bdinfo->board_type; diff --git a/flight/Modules/FlightPlan/flightplan.c b/flight/Modules/FlightPlan/flightplan.c index 5537c8f15..e919dd41e 100644 --- a/flight/Modules/FlightPlan/flightplan.c +++ b/flight/Modules/FlightPlan/flightplan.c @@ -74,7 +74,11 @@ int32_t FlightPlanStart() int32_t FlightPlanInitialize() { taskHandle = NULL; - + + FlightPlanStatusInitialize(); + FlightPlanControlInitialize(); + FlightPlanSettingsInitialize(); + // Listen for object updates FlightPlanControlConnectCallback(&objectUpdatedCb); diff --git a/flight/Modules/GPS/GPS.c b/flight/Modules/GPS/GPS.c index dd0905257..bc8f92c17 100644 --- a/flight/Modules/GPS/GPS.c +++ b/flight/Modules/GPS/GPS.c @@ -35,24 +35,22 @@ #include -#ifdef ENABLE_GPS_BINARY_GTOP - #include "GTOP_BIN.h" -#endif - -#if defined(ENABLE_GPS_ONESENTENCE_GTOP) || defined(ENABLE_GPS_NMEA) - #include "NMEA.h" -#endif +#include "NMEA.h" #include "gpsposition.h" #include "homelocation.h" #include "gpstime.h" +#include "gpssatellites.h" #include "WorldMagModel.h" #include "CoordinateConversions.h" +#include "hwsettings.h" + // **************** // Private functions static void gpsTask(void *parameters); +static void updateSettings(); #ifdef PIOS_GPS_SETS_HOMELOCATION static void setHomeLocation(GPSPositionData * gpsData); @@ -62,25 +60,16 @@ static float GravityAccel(float latitude, float longitude, float altitude); // **************** // Private constants -//#define FULL_COLD_RESTART // uncomment this to tell the GPS to do a FULL COLD restart -//#define DISABLE_GPS_THRESHOLD // - #define GPS_TIMEOUT_MS 500 -#define GPS_COMMAND_RESEND_TIMEOUT_MS 2000 +#define NMEA_MAX_PACKET_LENGTH 96 // 82 max NMEA msg size plus 12 margin (because some vendors add custom crap) plus CR plus Linefeed +// same as in COM buffer + #ifdef PIOS_GPS_SETS_HOMELOCATION // Unfortunately need a good size stack for the WMM calculation - #ifdef ENABLE_GPS_BINARY_GTOP - #define STACK_SIZE_BYTES 800 - #else - #define STACK_SIZE_BYTES 800 - #endif + #define STACK_SIZE_BYTES 800 #else - #ifdef ENABLE_GPS_BINARY_GTOP - #define STACK_SIZE_BYTES 440 - #else - #define STACK_SIZE_BYTES 440 - #endif + #define STACK_SIZE_BYTES 650 #endif #define TASK_PRIORITY (tskIDLE_PRIORITY + 1) @@ -89,12 +78,11 @@ static float GravityAccel(float latitude, float longitude, float altitude); // Private variables static uint32_t gpsPort; +static bool gpsEnabled = false; static xTaskHandle gpsTaskHandle; -#ifndef ENABLE_GPS_BINARY_GTOP - static char gps_rx_buffer[128]; -#endif +static char* gps_rx_buffer; static uint32_t timeOfLastCommandMs; static uint32_t timeOfLastUpdateMs; @@ -111,12 +99,19 @@ static uint32_t numParsingErrors; 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); + if (gpsEnabled) { + if (gpsPort) { + // Start gps task + xTaskCreate(gpsTask, (signed char *)"GPS", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &gpsTaskHandle); + TaskMonitorAdd(TASKINFO_RUNNING_GPS, gpsTaskHandle); + return 0; + } - return 0; + AlarmsSet(SYSTEMALARMS_ALARM_GPS, SYSTEMALARMS_ALARM_CRITICAL); + } + return -1; } + /** * Initialise the gps module * \return -1 if initialisation failed @@ -124,11 +119,39 @@ int32_t GPSStart(void) */ int32_t GPSInitialize(void) { - // TODO: Get gps settings object gpsPort = PIOS_COM_GPS; - return 0; + HwSettingsInitialize(); + uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM]; + + HwSettingsOptionalModulesGet(optionalModules); + + if (optionalModules[HWSETTINGS_OPTIONALMODULES_GPS] == HWSETTINGS_OPTIONALMODULES_ENABLED) + gpsEnabled = true; + else + gpsEnabled = false; + + if (gpsPort && gpsEnabled) { + GPSPositionInitialize(); +#if !defined(PIOS_GPS_MINIMAL) + GPSTimeInitialize(); + GPSSatellitesInitialize(); +#endif +#ifdef PIOS_GPS_SETS_HOMELOCATION + HomeLocationInitialize(); +#endif + HwSettingsInitialize(); + updateSettings(); + + gps_rx_buffer = pvPortMalloc(NMEA_MAX_PACKET_LENGTH); + PIOS_Assert(gps_rx_buffer); + + return 0; + } + + return -1; } + MODULE_INITCALL(GPSInitialize, GPSStart) // **************** @@ -142,45 +165,11 @@ static void gpsTask(void *parameters) uint32_t timeNowMs = xTaskGetTickCount() * portTICK_RATE_MS;; GPSPositionData GpsData; -#ifdef ENABLE_GPS_BINARY_GTOP - GTOP_BIN_init(); -#else uint8_t rx_count = 0; bool start_flag = false; bool found_cr = false; int32_t gpsRxOverflow = 0; -#endif -#ifdef FULL_COLD_RESTART - // tell the GPS to do a FULL COLD restart - PIOS_COM_SendStringNonBlocking(gpsPort, "$PMTK104*37\r\n"); - timeOfLastCommandMs = timeNowMs; - while (timeNowMs - timeOfLastCommandMs < 300) // delay for 300ms to let the GPS sort itself out - { - vTaskDelay(xDelay); // Block task until next update - timeNowMs = xTaskGetTickCount() * portTICK_RATE_MS;; - } -#endif - -#ifdef DISABLE_GPS_THRESHOLD - PIOS_COM_SendStringNonBlocking(gpsPort, "$PMTK397,0*23\r\n"); -#endif - -#ifdef ENABLE_GPS_BINARY_GTOP - // switch to GTOP binary mode - PIOS_COM_SendStringNonBlocking(gpsPort ,"$PGCMD,21,1*6F\r\n"); -#endif - -#ifdef ENABLE_GPS_ONESENTENCE_GTOP - // switch to single sentence mode - PIOS_COM_SendStringNonBlocking(gpsPort, "$PGCMD,21,2*6C\r\n"); -#endif - -#ifdef ENABLE_GPS_NMEA - // switch to NMEA mode - PIOS_COM_SendStringNonBlocking(gpsPort, "$PGCMD,21,3*6D\r\n"); -#endif - numUpdates = 0; numChecksumErrors = 0; numParsingErrors = 0; @@ -191,108 +180,87 @@ static void gpsTask(void *parameters) // Loop forever while (1) { - #ifdef ENABLE_GPS_BINARY_GTOP - // GTOP BINARY GPS mode + uint8_t c; + // NMEA or SINGLE-SENTENCE GPS mode - while (PIOS_COM_ReceiveBufferUsed(gpsPort) > 0) + // This blocks the task until there is something on the buffer + while (PIOS_COM_ReceiveBuffer(gpsPort, &c, 1, xDelay) > 0) + { + + // detect start while acquiring stream + if (!start_flag && (c == '$')) { - uint8_t c; - PIOS_COM_ReceiveBuffer(gpsPort, &c, 1, 0); + start_flag = true; + found_cr = false; + rx_count = 0; + } + else + if (!start_flag) + continue; + + if (rx_count >= NMEA_MAX_PACKET_LENGTH) + { + // The buffer is already full and we haven't found a valid NMEA sentence. + // Flush the buffer and note the overflow event. + gpsRxOverflow++; + start_flag = false; + found_cr = false; + rx_count = 0; + } + else + { + gps_rx_buffer[rx_count] = c; + rx_count++; + } + + // look for ending '\r\n' sequence + if (!found_cr && (c == '\r') ) + found_cr = true; + else + if (found_cr && (c != '\n') ) + found_cr = false; // false end flag + else + if (found_cr && (c == '\n') ) + { + // The NMEA functions require a zero-terminated string + // As we detected \r\n, the string as for sure 2 bytes long, we will also strip the \r\n + gps_rx_buffer[rx_count-2] = 0; - if (GTOP_BIN_update_position(c, &numChecksumErrors, &numParsingErrors) >= 0) - { - numUpdates++; + // prepare to parse next sentence + start_flag = false; + found_cr = false; + rx_count = 0; + // Our rxBuffer must look like this now: + // [0] = '$' + // ... = zero or more bytes of sentence payload + // [end_pos - 1] = '\r' + // [end_pos] = '\n' + // + // Prepare to consume the sentence from the buffer + + // Validate the checksum over the sentence + if (!NMEA_checksum(&gps_rx_buffer[1])) + { // Invalid checksum. May indicate dropped characters on Rx. + //PIOS_DEBUG_PinHigh(2); + ++numChecksumErrors; + //PIOS_DEBUG_PinLow(2); + } + else + { // Valid checksum, use this packet to update the GPS position + if (!NMEA_update_position(&gps_rx_buffer[1])) { + //PIOS_DEBUG_PinHigh(2); + ++numParsingErrors; + //PIOS_DEBUG_PinLow(2); + } + else + ++numUpdates; timeNowMs = xTaskGetTickCount() * portTICK_RATE_MS; timeOfLastUpdateMs = timeNowMs; timeOfLastCommandMs = timeNowMs; } } - - #else - // NMEA or SINGLE-SENTENCE GPS mode - - // This blocks the task until there is something on the buffer - while (PIOS_COM_ReceiveBufferUsed(gpsPort) > 0) - { - uint8_t c; - PIOS_COM_ReceiveBuffer(gpsPort, &c, 1, 0); - - // detect start while acquiring stream - if (!start_flag && (c == '$')) - { - start_flag = true; - found_cr = false; - rx_count = 0; - } - else - if (!start_flag) - continue; - - if (rx_count >= sizeof(gps_rx_buffer)) - { - // The buffer is already full and we haven't found a valid NMEA sentence. - // Flush the buffer and note the overflow event. - gpsRxOverflow++; - start_flag = false; - found_cr = false; - rx_count = 0; - } - else - { - gps_rx_buffer[rx_count] = c; - rx_count++; - } - - // look for ending '\r\n' sequence - if (!found_cr && (c == '\r') ) - found_cr = true; - else - if (found_cr && (c != '\n') ) - found_cr = false; // false end flag - else - if (found_cr && (c == '\n') ) - { - // The NMEA functions require a zero-terminated string - // As we detected \r\n, the string as for sure 2 bytes long, we will also strip the \r\n - gps_rx_buffer[rx_count-2] = 0; - - // prepare to parse next sentence - start_flag = false; - found_cr = false; - rx_count = 0; - // Our rxBuffer must look like this now: - // [0] = '$' - // ... = zero or more bytes of sentence payload - // [end_pos - 1] = '\r' - // [end_pos] = '\n' - // - // Prepare to consume the sentence from the buffer - - // Validate the checksum over the sentence - if (!NMEA_checksum(&gps_rx_buffer[1])) - { // Invalid checksum. May indicate dropped characters on Rx. - //PIOS_DEBUG_PinHigh(2); - ++numChecksumErrors; - //PIOS_DEBUG_PinLow(2); - } - else - { // Valid checksum, use this packet to update the GPS position - if (!NMEA_update_position(&gps_rx_buffer[1])) { - //PIOS_DEBUG_PinHigh(2); - ++numParsingErrors; - //PIOS_DEBUG_PinLow(2); - } - else - ++numUpdates; - - timeNowMs = xTaskGetTickCount() * portTICK_RATE_MS; - timeOfLastUpdateMs = timeNowMs; - timeOfLastCommandMs = timeNowMs; - } - } - } - #endif + } // Check for GPS timeout timeNowMs = xTaskGetTickCount() * portTICK_RATE_MS; @@ -305,30 +273,6 @@ static void gpsTask(void *parameters) GPSPositionSet(&GpsData); AlarmsSet(SYSTEMALARMS_ALARM_GPS, SYSTEMALARMS_ALARM_ERROR); - if ((timeNowMs - timeOfLastCommandMs) >= GPS_COMMAND_RESEND_TIMEOUT_MS) - { // resend the command .. just incase the gps has only just been plugged in or the gps did not get our last command - timeOfLastCommandMs = timeNowMs; - - #ifdef ENABLE_GPS_BINARY_GTOP - GTOP_BIN_init(); - // switch to binary mode - PIOS_COM_SendStringNonBlocking(gpsPort,"$PGCMD,21,1*6F\r\n"); - #endif - - #ifdef ENABLE_GPS_ONESENTENCE_GTOP - // switch to single sentence mode - PIOS_COM_SendStringNonBlocking(gpsPort,"$PGCMD,21,2*6C\r\n"); - #endif - - #ifdef ENABLE_GPS_NMEA - // switch to NMEA mode - PIOS_COM_SendStringNonBlocking(gpsPort,"$PGCMD,21,3*6D\r\n"); - #endif - - #ifdef DISABLE_GPS_TRESHOLD - PIOS_COM_SendStringNonBlocking(gpsPort,"$PMTK397,0*23\r\n"); - #endif - } } else { // we appear to be receiving GPS sentences OK, we've had an update @@ -354,8 +298,6 @@ static void gpsTask(void *parameters) AlarmsSet(SYSTEMALARMS_ALARM_GPS, SYSTEMALARMS_ALARM_CRITICAL); } - // Block task until next update - vTaskDelay(xDelay); } } @@ -417,7 +359,47 @@ static void setHomeLocation(GPSPositionData * gpsData) } #endif -// **************** +/** + * Update the GPS settings, called on startup. + * FIXME: This should be in the GPSSettings object. But objects have + * too much overhead yet. Also the GPS has no any specific settings + * like protocol, etc. Thus the HwSettings object which contains the + * GPS port speed is used for now. + */ +static void updateSettings() +{ + if (gpsPort) { + + // Retrieve settings + uint8_t speed; + HwSettingsGPSSpeedGet(&speed); + + // Set port speed + switch (speed) { + case HWSETTINGS_GPSSPEED_2400: + PIOS_COM_ChangeBaud(gpsPort, 2400); + break; + case HWSETTINGS_GPSSPEED_4800: + PIOS_COM_ChangeBaud(gpsPort, 4800); + break; + case HWSETTINGS_GPSSPEED_9600: + PIOS_COM_ChangeBaud(gpsPort, 9600); + break; + case HWSETTINGS_GPSSPEED_19200: + PIOS_COM_ChangeBaud(gpsPort, 19200); + break; + case HWSETTINGS_GPSSPEED_38400: + PIOS_COM_ChangeBaud(gpsPort, 38400); + break; + case HWSETTINGS_GPSSPEED_57600: + PIOS_COM_ChangeBaud(gpsPort, 57600); + break; + case HWSETTINGS_GPSSPEED_115200: + PIOS_COM_ChangeBaud(gpsPort, 115200); + break; + } + } +} /** * @} diff --git a/flight/Modules/GPS/GTOP_BIN.c b/flight/Modules/GPS/GTOP_BIN.c deleted file mode 100644 index 7bd2964d9..000000000 --- a/flight/Modules/GPS/GTOP_BIN.c +++ /dev/null @@ -1,262 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotModules OpenPilot Modules - * @{ - * @addtogroup GSPModule GPS Module - * @brief Process GPS information - * @{ - * - * @file GTOP_BIN.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief GPS module, handles GPS and NMEA stream - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "openpilot.h" -#include "pios.h" -#include "GTOP_BIN.h" -#include "gpsposition.h" -#include "gpstime.h" -#include "gpssatellites.h" - -#include // memmove - -#ifdef ENABLE_GPS_BINARY_GTOP - -// ************ -// the structure of the binary packet - -typedef struct -{ - uint32_t utc_time; - - int32_t latitude; - uint8_t ns_indicator; - - int32_t longitude; - uint8_t ew_indicator; - - uint8_t fix_quality; - - uint8_t satellites_used; - - uint16_t hdop; - - int32_t msl_altitude; - - int32_t geoidal_seperation; - - uint8_t fix_type; - - int32_t course_over_ground; - - int32_t speed_over_ground; - - uint8_t day; - uint8_t month; - uint16_t year; -} __attribute__((__packed__)) t_gps_bin_packet_data; - -typedef struct -{ - uint16_t header; - t_gps_bin_packet_data data; - uint8_t asterisk; - uint8_t checksum; - uint16_t end_word; -} __attribute__((__packed__)) t_gps_bin_packet; - -// ************ - -// buffer that holds the incoming binary packet -static uint8_t gps_rx_buffer[sizeof(t_gps_bin_packet)] __attribute__ ((aligned(4))); - -// number of bytes currently in the rx buffer -static int16_t gps_rx_buffer_wr = 0; - -// ************ -// endian swapping functions - -static uint16_t swap2Bytes(uint16_t data) -{ - return (((data >> 8) & 0x00ff) | - ((data << 8) & 0xff00)); -} - -static uint32_t swap4Bytes(uint32_t data) -{ - return (((data >> 24) & 0x000000ff) | - ((data >> 8) & 0x0000ff00) | - ((data << 8) & 0x00ff0000) | - ((data << 24) & 0xff000000)); -} - -// ************ -/** - * Parses a complete binary packet and update the GPSPosition and GPSTime UAVObjects - * - * param[in] .. b = a new received byte from the GPS - * - * return '0' if we have found a valid binary packet - * return <0 if any errors were encountered with the packet or no packet found - */ - -int GTOP_BIN_update_position(uint8_t b, volatile uint32_t *chksum_errors, volatile uint32_t *parsing_errors) -{ - if (gps_rx_buffer_wr >= sizeof(gps_rx_buffer)) - { // make room for the new byte .. this will actually never get executed, just here as a safe guard really - memmove(gps_rx_buffer, gps_rx_buffer + 1, sizeof(gps_rx_buffer) - 1); - gps_rx_buffer_wr = sizeof(gps_rx_buffer) - 1; - } - - // add the new byte into the buffer - gps_rx_buffer[gps_rx_buffer_wr++] = b; - - int16_t i = 0; - - while (gps_rx_buffer_wr > 0) - { - t_gps_bin_packet *rx_packet = (t_gps_bin_packet *)(gps_rx_buffer + i); - - // scan for the start of a binary packet (the header bytes) - while (gps_rx_buffer_wr - i >= sizeof(rx_packet->header)) - { - if (rx_packet->header == 0x2404) - break; // found a valid header marker - rx_packet = (t_gps_bin_packet *)(gps_rx_buffer + ++i); - } - - // remove unwanted bytes before the start of the packet header - if (i > 0) - { - gps_rx_buffer_wr -= i; - if (gps_rx_buffer_wr > 0) - memmove(gps_rx_buffer, gps_rx_buffer + i, gps_rx_buffer_wr); - i = 0; - } - - if (gps_rx_buffer_wr < sizeof(t_gps_bin_packet)) - break; // not yet enough bytes for a complete binary packet - - // we have enough bytes for a complete binary packet - - // check to see if certain parameters in the binary packet are valid - if (rx_packet->header != 0x2404 || - rx_packet->end_word != 0x0A0D || - rx_packet->asterisk != 0x2A || - (rx_packet->data.ns_indicator != 1 && rx_packet->data.ns_indicator != 2) || - (rx_packet->data.ew_indicator != 1 && rx_packet->data.ew_indicator != 2) || - (rx_packet->data.fix_quality > 2) || - (rx_packet->data.fix_type < 1 || rx_packet->data.fix_type > 3) ) - { // invalid packet - if (parsing_errors) *parsing_errors++; - i++; - continue; - } - - { // check the checksum is valid - uint8_t *p = (uint8_t *)&rx_packet->data; - uint8_t checksum = 0; - for (int i = 0; i < sizeof(t_gps_bin_packet_data); i++) - checksum ^= *p++; - - if (checksum != rx_packet->checksum) - { // checksum error - if (chksum_errors) *chksum_errors++; - i++; - continue; - } - } - - // we now have a valid complete binary packet, update the GpsData and GpsTime objects - - // correct the endian order of the parameters - rx_packet->data.utc_time = swap4Bytes(rx_packet->data.utc_time); - rx_packet->data.latitude = swap4Bytes(rx_packet->data.latitude); - rx_packet->data.longitude = swap4Bytes(rx_packet->data.longitude); - rx_packet->data.hdop = swap2Bytes(rx_packet->data.hdop); - rx_packet->data.msl_altitude = swap4Bytes(rx_packet->data.msl_altitude); - rx_packet->data.geoidal_seperation = swap4Bytes(rx_packet->data.geoidal_seperation); - rx_packet->data.course_over_ground = swap4Bytes(rx_packet->data.course_over_ground); - rx_packet->data.speed_over_ground = swap4Bytes(rx_packet->data.speed_over_ground); - rx_packet->data.year = swap2Bytes(rx_packet->data.year); - - // set the gps time object - GPSTimeData GpsTime; -// GPSTimeGet(&GpsTime); - uint32_t utc_time = rx_packet->data.utc_time / 1000; - GpsTime.Second = utc_time % 100; // seconds - GpsTime.Minute = (utc_time / 100) % 100; // minutes - GpsTime.Hour = utc_time / 10000; // hours - GpsTime.Day = rx_packet->data.day; // day - GpsTime.Month = rx_packet->data.month; // month - GpsTime.Year = rx_packet->data.year; // year - GPSTimeSet(&GpsTime); - - // set the gps position object - GPSPositionData GpsData; -// GPSPositionGet(&GpsData); - switch (rx_packet->data.fix_type) - { - case 1: GpsData.Status = GPSPOSITION_STATUS_NOFIX; break; - case 2: GpsData.Status = GPSPOSITION_STATUS_FIX2D; break; - case 3: GpsData.Status = GPSPOSITION_STATUS_FIX3D; break; - default: GpsData.Status = GPSPOSITION_STATUS_NOGPS; break; - } - GpsData.Latitude = rx_packet->data.latitude * (rx_packet->data.ns_indicator == 1 ? +1 : -1) * 10; // degrees * 10e6 - GpsData.Longitude = rx_packet->data.longitude * (rx_packet->data.ew_indicator == 1 ? +1 : -1) * 10; // degrees * 10e6 - GpsData.Altitude = (float)rx_packet->data.msl_altitude / 1000; // meters - GpsData.GeoidSeparation = (float)rx_packet->data.geoidal_seperation / 1000; // meters - GpsData.Heading = (float)rx_packet->data.course_over_ground / 1000; // degrees - GpsData.Groundspeed = (float)rx_packet->data.speed_over_ground / 3600; // m/s - GpsData.Satellites = rx_packet->data.satellites_used; // - GpsData.PDOP = 99.99; // not available in binary mode - GpsData.HDOP = (float)rx_packet->data.hdop / 100; // - GpsData.VDOP = 99.99; // not available in binary mode - GPSPositionSet(&GpsData); - - // set the number of satellites -// GPSSatellitesData SattelliteData; -//// GPSSatellitesGet(&SattelliteData); -// memset(&SattelliteData, 0, sizeof(SattelliteData)); -// SattelliteData.SatsInView = rx_packet->data.satellites_used; // -// GPSSatellitesSet(&SattelliteData); - - // remove the spent binary packet from the buffer - gps_rx_buffer_wr -= sizeof(t_gps_bin_packet); - if (gps_rx_buffer_wr > 0) - memmove(gps_rx_buffer, gps_rx_buffer + sizeof(t_gps_bin_packet), gps_rx_buffer_wr); - - return 0; // found a valid packet - } - - return -1; // no valid packet found -} - -// ************ - -void GTOP_BIN_init(void) -{ - gps_rx_buffer_wr = 0; -} - -// ************ - -#endif // ENABLE_GPS_BINARY_GTOP - diff --git a/flight/Modules/GPS/NMEA.c b/flight/Modules/GPS/NMEA.c index 3dfd98d40..4f78b27a4 100644 --- a/flight/Modules/GPS/NMEA.c +++ b/flight/Modules/GPS/NMEA.c @@ -40,8 +40,6 @@ -#if defined(ENABLE_GPS_NMEA) || defined(ENABLE_GPS_ONESENTENCE_GTOP) - // Debugging #ifdef ENABLE_DEBUG_MSG //#define DEBUG_MSG_IN ///< define to display the incoming NMEA messages @@ -54,7 +52,6 @@ //#define NMEA_DEBUG_GSA ///< define to enable debug of GSA messages //#define NMEA_DEBUG_GSV ///< define to enable debug of GSV messages //#define NMEA_DEBUG_ZDA ///< define to enable debug of ZDA messages -//#define NMEA_DEBUG_PGTOP ///< define to enable debug of PGTOP messages #define DEBUG_MSG(format, ...) PIOS_COM_SendFormattedString(DEBUG_PORT, format, ## __VA_ARGS__) #else #define DEBUG_MSG(format, ...) @@ -69,56 +66,49 @@ struct nmea_parser { uint32_t cnt; }; - #ifdef ENABLE_GPS_NMEA - static bool nmeaProcessGPGGA(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam); - static bool nmeaProcessGPRMC(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam); - static bool nmeaProcessGPVTG(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam); - static bool nmeaProcessGPGSA(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam); - static bool nmeaProcessGPZDA(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam); - static bool nmeaProcessGPGSV(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam); - #endif +static bool nmeaProcessGPGGA(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam); +static bool nmeaProcessGPRMC(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam); +static bool nmeaProcessGPVTG(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam); +static bool nmeaProcessGPGSA(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam); +#if !defined(PIOS_GPS_MINIMAL) + static bool nmeaProcessGPZDA(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam); + static bool nmeaProcessGPGSV(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam); +#endif //PIOS_GPS_MINIMAL - static bool nmeaProcessPGTOP(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam); - static struct nmea_parser nmea_parsers[] = { - - #ifdef ENABLE_GPS_NMEA - { - .prefix = "GPGGA", - .handler = nmeaProcessGPGGA, - .cnt = 0, - }, - { - .prefix = "GPVTG", - .handler = nmeaProcessGPVTG, - .cnt = 0, - }, - { - .prefix = "GPGSA", - .handler = nmeaProcessGPGSA, - .cnt = 0, - }, - { - .prefix = "GPRMC", - .handler = nmeaProcessGPRMC, - .cnt = 0, - }, - { - .prefix = "GPZDA", - .handler = nmeaProcessGPZDA, - .cnt = 0, - }, - { - .prefix = "GPGSV", - .handler = nmeaProcessGPGSV, - .cnt = 0, - }, - #endif - { - .prefix = "PGTOP", - .handler = nmeaProcessPGTOP, - .cnt = 0, - }, +static struct nmea_parser nmea_parsers[] = { + { + .prefix = "GPGGA", + .handler = nmeaProcessGPGGA, + .cnt = 0, + }, + { + .prefix = "GPVTG", + .handler = nmeaProcessGPVTG, + .cnt = 0, + }, + { + .prefix = "GPGSA", + .handler = nmeaProcessGPGSA, + .cnt = 0, + }, + { + .prefix = "GPRMC", + .handler = nmeaProcessGPRMC, + .cnt = 0, + }, +#if !defined(PIOS_GPS_MINIMAL) + { + .prefix = "GPZDA", + .handler = nmeaProcessGPZDA, + .cnt = 0, + }, + { + .prefix = "GPGSV", + .handler = nmeaProcessGPGSV, + .cnt = 0, + }, +#endif //PIOS_GPS_MINIMAL }; static struct nmea_parser *NMEA_find_parser_by_prefix(const char *prefix) @@ -229,7 +219,6 @@ static float NMEA_real_to_float(char *nmea_real) return (((float)whole) + fract * pow(10, -fract_units)); } -#ifdef ENABLE_GPS_NMEA /* * Parse a field in the format: * DD[D]MM.mmmm[mm] @@ -287,7 +276,6 @@ static bool NMEA_latlon_to_fixed_point(int32_t * latlon, char *nmea_latlon, bool return true; } -#endif // ENABLE_GPS_NMEA /** @@ -376,7 +364,6 @@ bool NMEA_update_position(char *nmea_sentence) return true; } -#ifdef ENABLE_GPS_NMEA /** * Parse an NMEA GPGGA sentence and update the given UAVObject @@ -445,6 +432,7 @@ static bool nmeaProcessGPRMC(GPSPositionData * GpsData, bool* gpsDataUpdated, ch *gpsDataUpdated = true; +#if !defined(PIOS_GPS_MINIMAL) GPSTimeData gpst; GPSTimeGet(&gpst); @@ -453,6 +441,7 @@ static bool nmeaProcessGPRMC(GPSPositionData * GpsData, bool* gpsDataUpdated, ch gpst.Second = (int)hms % 100; gpst.Minute = (((int)hms - gpst.Second) / 100) % 100; gpst.Hour = (int)hms / 10000; +#endif //PIOS_GPS_MINIMAL // get latitude [DDMM.mmmmm] [N|S] if (!NMEA_latlon_to_fixed_point(&GpsData->Latitude, param[3], param[4][0] == 'S')) { @@ -470,6 +459,7 @@ static bool nmeaProcessGPRMC(GPSPositionData * GpsData, bool* gpsDataUpdated, ch // get True course GpsData->Heading = NMEA_real_to_float(param[8]); +#if !defined(PIOS_GPS_MINIMAL) // get Date of fix // TODO: Should really not use a float here to be safe float date = NMEA_real_to_float(param[9]); @@ -478,6 +468,7 @@ static bool nmeaProcessGPRMC(GPSPositionData * GpsData, bool* gpsDataUpdated, ch gpst.Day = (int)(date / 10000); gpst.Year += 2000; GPSTimeSet(&gpst); +#endif //PIOS_GPS_MINIMAL return true; } @@ -505,6 +496,7 @@ static bool nmeaProcessGPVTG(GPSPositionData * GpsData, bool* gpsDataUpdated, ch return true; } +#if !defined(PIOS_GPS_MINIMAL) /** * Parse an NMEA GPZDA sentence and update the @ref GPSTime object * \param[in] A pointer to a GPSPosition UAVObject to be updated (unused). @@ -627,6 +619,7 @@ static bool nmeaProcessGPGSV(GPSPositionData * GpsData, bool* gpsDataUpdated, ch return true; } +#endif //PIOS_GPS_MINIMAL /** * Parse an NMEA GPGSA sentence and update the given UAVObject @@ -675,83 +668,3 @@ static bool nmeaProcessGPGSA(GPSPositionData * GpsData, bool* gpsDataUpdated, ch return true; } -#endif // ENABLE_GPS_NMEA - -/** - * Parse an NMEA PGTOP sentence and update the given UAVObject - * \param[in] A pointer to a GPSPosition UAVObject to be updated. - * \param[in] An NMEA sentence with a valid checksum - */ -static bool nmeaProcessPGTOP(GPSPositionData * GpsData, bool* gpsDataUpdated, char* param[], uint8_t nbParam) -{ - if (nbParam != 17) - return false; - - GPSTimeData gpst; - GPSTimeGet(&gpst); - - *gpsDataUpdated = true; - - // get UTC time [hhmmss.sss] - float hms = NMEA_real_to_float(param[1]); - gpst.Second = (int)hms % 100; - gpst.Minute = (((int)hms - gpst.Second) / 100) % 100; - gpst.Hour = (int)hms / 10000; - - // get latitude decimal degrees - GpsData->Latitude = NMEA_real_to_float(param[2])*1e7; - if (param[3][0] == 'S') - GpsData->Latitude = -GpsData->Latitude; - - - // get longitude decimal degrees - GpsData->Longitude = NMEA_real_to_float(param[4])*1e7; - if (param[5][0] == 'W') - GpsData->Longitude = -GpsData->Longitude; - - // get number of satellites used in GPS solution - GpsData->Satellites = atoi(param[7]); - - // next field: HDOP - GpsData->HDOP = NMEA_real_to_float(param[8]); - - // get altitude (in meters mm.m) - GpsData->Altitude = NMEA_real_to_float(param[9]); - - // next field: geoid separation - GpsData->GeoidSeparation = NMEA_real_to_float(param[10]); - - // Mode: 1=Fix not available, 2=2D, 3=3D - switch (atoi(param[11])) { - case 1: - GpsData->Status = GPSPOSITION_STATUS_NOFIX; - break; - case 2: - GpsData->Status = GPSPOSITION_STATUS_FIX2D; - break; - case 3: - GpsData->Status = GPSPOSITION_STATUS_FIX3D; - break; - default: - /* Unhandled */ - return false; - break; - } - - // get course over ground in degrees [ddd.dd] - GpsData->Heading = NMEA_real_to_float(param[12]); - - // get speed in km/h - GpsData->Groundspeed = NMEA_real_to_float(param[13]); - // to m/s - GpsData->Groundspeed /= 3.6; - - gpst.Day = atoi(param[14]); - gpst.Month = atoi(param[15]); - gpst.Year = atoi(param[16]); - GPSTimeSet(&gpst); - - return true; -} - -#endif // #if defined(ENABLE_GPS_NMEA) || defined(ENABLE_GPS_ONESENTENCE_GTOP) diff --git a/flight/Modules/GPS/inc/GPS.h b/flight/Modules/GPS/inc/GPS.h index 1ae683c9a..86a92d285 100644 --- a/flight/Modules/GPS/inc/GPS.h +++ b/flight/Modules/GPS/inc/GPS.h @@ -34,8 +34,6 @@ #ifndef GPS_H #define GPS_H -#include "gps_mode.h" - int32_t GPSInitialize(void); #endif // GPS_H diff --git a/flight/Modules/GPS/inc/NMEA.h b/flight/Modules/GPS/inc/NMEA.h index 5c1b13f8b..6ff6b1195 100644 --- a/flight/Modules/GPS/inc/NMEA.h +++ b/flight/Modules/GPS/inc/NMEA.h @@ -33,11 +33,8 @@ #include #include -#include "gps_mode.h" -#if defined(ENABLE_GPS_NMEA) || defined(ENABLE_GPS_ONESENTENCE_GTOP) - extern bool NMEA_update_position(char *nmea_sentence); - extern bool NMEA_checksum(char *nmea_sentence); -#endif +extern bool NMEA_update_position(char *nmea_sentence); +extern bool NMEA_checksum(char *nmea_sentence); #endif /* NMEA_H */ diff --git a/flight/Modules/GPS/inc/gps_mode.h b/flight/Modules/GPS/inc/gps_mode.h deleted file mode 100644 index 43e5b0398..000000000 --- a/flight/Modules/GPS/inc/gps_mode.h +++ /dev/null @@ -1,58 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup OpenPilotModules OpenPilot Modules - * @{ - * @addtogroup GSPModule GPS Module - * @brief Process GPS information - * @{ - * - * @file gps_mode.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Include file of the GPS module. - * As with all modules only the initialize function is exposed all other - * interactions with the module take place through the event queue and - * objects. - * @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 GPS_MODE_H -#define GPS_MODE_H - -// **************** -// you MUST have one of these uncommented - and ONLY one - -//#define ENABLE_GPS_BINARY_GTOP // uncomment this if we are using GTOP BINARY mode -//#define ENABLE_GPS_ONESENTENCE_GTOP // uncomment this if we are using GTOP SINGLE SENTENCE mode -#define ENABLE_GPS_NMEA // uncomment this if we are using NMEA mode - -// **************** -// make sure they have defined a protocol to use - -#if !defined(ENABLE_GPS_BINARY_GTOP) && !defined(ENABLE_GPS_ONESENTENCE_GTOP) && !defined(ENABLE_GPS_NMEA) - #error YOU MUST SELECT THE DESIRED GPS PROTOCOL IN gps_mode.h! -#endif - -// **************** - -#endif - -/** - * @} - * @} - */ diff --git a/flight/Modules/Guidance/guidance.c b/flight/Modules/Guidance/guidance.c index 348210675..b90303928 100644 --- a/flight/Modules/Guidance/guidance.c +++ b/flight/Modules/Guidance/guidance.c @@ -97,6 +97,12 @@ int32_t GuidanceStart() */ int32_t GuidanceInitialize() { + + GuidanceSettingsInitialize(); + PositionDesiredInitialize(); + NedAccelInitialize(); + VelocityDesiredInitialize(); + // Create object queue queue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(UAVObjEvent)); diff --git a/flight/Modules/ManualControl/inc/manualcontrol.h b/flight/Modules/ManualControl/inc/manualcontrol.h index 5cca1a623..1215ca27d 100644 --- a/flight/Modules/ManualControl/inc/manualcontrol.h +++ b/flight/Modules/ManualControl/inc/manualcontrol.h @@ -105,4 +105,11 @@ int32_t ManualControlInitialize(); ( (int)MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_POSITIONHOLD == (int) FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD) \ ) +#define assumptions_channelcount ( \ +( (int)MANUALCONTROLCOMMAND_CHANNEL_NUMELEM == (int)MANUALCONTROLSETTINGS_CHANNELGROUPS_NUMELEM ) && \ +( (int)MANUALCONTROLCOMMAND_CHANNEL_NUMELEM == (int)MANUALCONTROLSETTINGS_CHANNELNUMBER_NUMELEM ) && \ +( (int)MANUALCONTROLCOMMAND_CHANNEL_NUMELEM == (int)MANUALCONTROLSETTINGS_CHANNELMIN_NUMELEM ) && \ +( (int)MANUALCONTROLCOMMAND_CHANNEL_NUMELEM == (int)MANUALCONTROLSETTINGS_CHANNELMAX_NUMELEM ) && \ +( (int)MANUALCONTROLCOMMAND_CHANNEL_NUMELEM == (int)MANUALCONTROLSETTINGS_CHANNELNEUTRAL_NUMELEM ) ) + #endif // MANUALCONTROL_H diff --git a/flight/Modules/ManualControl/manualcontrol.c b/flight/Modules/ManualControl/manualcontrol.c index 19b6bc293..19b99148c 100644 --- a/flight/Modules/ManualControl/manualcontrol.c +++ b/flight/Modules/ManualControl/manualcontrol.c @@ -43,6 +43,7 @@ #include "flighttelemetrystats.h" #include "flightstatus.h" #include "accessorydesired.h" +#include "receiveractivity.h" // Private constants #if defined(PIOS_MANUAL_STACK_SIZE) @@ -80,6 +81,7 @@ static void updateActuatorDesired(ManualControlCommandData * cmd); static void updateStabilizationDesired(ManualControlCommandData * cmd, ManualControlSettingsData * settings); static void processFlightMode(ManualControlSettingsData * settings, float flightMode); static void processArm(ManualControlCommandData * cmd, ManualControlSettingsData * settings); +static void setArmedIfChanged(uint8_t val); static void manualControlTask(void *parameters); static float scaleChannel(int16_t value, int16_t max, int16_t min, int16_t neutral); @@ -87,20 +89,30 @@ 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 assumptions (assumptions1 && assumptions3 && assumptions5 && assumptions7 && assumptions8 && assumptions_flightmode) +#define RCVR_ACTIVITY_MONITOR_CHANNELS_PER_GROUP 12 +#define RCVR_ACTIVITY_MONITOR_MIN_RANGE 10 +struct rcvr_activity_fsm { + ManualControlSettingsChannelGroupsOptions group; + uint16_t prev[RCVR_ACTIVITY_MONITOR_CHANNELS_PER_GROUP]; + uint8_t sample_count; +}; +static struct rcvr_activity_fsm activity_fsm; + +static void resetRcvrActivity(struct rcvr_activity_fsm * fsm); +static bool updateRcvrActivity(struct rcvr_activity_fsm * fsm); + +#define assumptions (assumptions1 && assumptions3 && assumptions5 && assumptions7 && assumptions8 && assumptions_flightmode && assumptions_channelcount) /** - * Module initialization + * Module starting */ int32_t ManualControlStart() { - /* Check the assumptions about uavobject enum's are correct */ - if(!assumptions) - return -1; // 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; } @@ -110,6 +122,17 @@ int32_t ManualControlStart() int32_t ManualControlInitialize() { + /* Check the assumptions about uavobject enum's are correct */ + if(!assumptions) + return -1; + + AccessoryDesiredInitialize(); + ManualControlCommandInitialize(); + FlightStatusInitialize(); + StabilizationDesiredInitialize(); + ReceiverActivityInitialize(); + ManualControlSettingsInitialize(); + return 0; } MODULE_INITCALL(ManualControlInitialize, ManualControlStart) @@ -138,10 +161,14 @@ static void manualControlTask(void *parameters) flightStatus.Armed = FLIGHTSTATUS_ARMED_DISARMED; armState = ARM_STATE_DISARMED; + /* Initialize the RcvrActivty FSM */ + portTickType lastActivityTime = xTaskGetTickCount(); + resetRcvrActivity(&activity_fsm); + // Main task loop lastSysTime = xTaskGetTickCount(); while (1) { - float scaledChannel[MANUALCONTROLCOMMAND_CHANNEL_NUMELEM]; + float scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_NUMELEM]; // Wait until next update vTaskDelayUntil(&lastSysTime, UPDATE_PERIOD_MS / portTICK_RATE_MS); @@ -150,48 +177,90 @@ static void manualControlTask(void *parameters) // Read settings ManualControlSettingsGet(&settings); - if (ManualControlCommandReadOnly(&cmd)) { + /* Update channel activity monitor */ + if (flightStatus.Armed == ARM_STATE_DISARMED) { + if (updateRcvrActivity(&activity_fsm)) { + /* Reset the aging timer because activity was detected */ + lastActivityTime = lastSysTime; + } + } + if (timeDifferenceMs(lastActivityTime, lastSysTime) > 5000) { + resetRcvrActivity(&activity_fsm); + lastActivityTime = lastSysTime; + } + + if (ManualControlCommandReadOnly()) { FlightTelemetryStatsData flightTelemStats; FlightTelemetryStatsGet(&flightTelemStats); if(flightTelemStats.Status != FLIGHTTELEMETRYSTATS_STATUS_CONNECTED) { /* trying to fly via GCS and lost connection. fall back to transmitter */ UAVObjMetadata metadata; - UAVObjGetMetadata(&cmd, &metadata); + ManualControlCommandGetMetadata(&metadata); metadata.access = ACCESS_READWRITE; - UAVObjSetMetadata(&cmd, &metadata); + ManualControlCommandSetMetadata(&metadata); } } - if (!ManualControlCommandReadOnly(&cmd)) { + if (!ManualControlCommandReadOnly()) { + bool valid_input_detected = true; + // Read channel values in us - for (int n = 0; n < MANUALCONTROLCOMMAND_CHANNEL_NUMELEM; ++n) { - 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); + for (uint8_t n = 0; + n < MANUALCONTROLSETTINGS_CHANNELGROUPS_NUMELEM && n < MANUALCONTROLCOMMAND_CHANNEL_NUMELEM; + ++n) { + extern uint32_t pios_rcvr_group_map[]; + + if (settings.ChannelGroups[n] >= MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE) { + cmd.Channel[n] = PIOS_RCVR_INVALID; } else { - cmd.Channel[n] = -1; + cmd.Channel[n] = PIOS_RCVR_Read(pios_rcvr_group_map[settings.ChannelGroups[n]], + settings.ChannelNumber[n]); } - scaledChannel[n] = scaleChannel(cmd.Channel[n], settings.ChannelMax[n], settings.ChannelMin[n], settings.ChannelNeutral[n]); + + // If a channel has timed out this is not valid data and we shouldn't update anything + // until we decide to go to failsafe + if(cmd.Channel[n] == PIOS_RCVR_TIMEOUT) + valid_input_detected = false; + else + scaledChannel[n] = scaleChannel(cmd.Channel[n], settings.ChannelMax[n], settings.ChannelMin[n], settings.ChannelNeutral[n]); } // Check settings, if error raise alarm - if (settings.Roll >= MANUALCONTROLSETTINGS_ROLL_NONE || - settings.Pitch >= MANUALCONTROLSETTINGS_PITCH_NONE || - settings.Yaw >= MANUALCONTROLSETTINGS_YAW_NONE || - settings.Throttle >= MANUALCONTROLSETTINGS_THROTTLE_NONE || - settings.FlightMode >= MANUALCONTROLSETTINGS_FLIGHTMODE_NONE) { + if (settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_ROLL] >= MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE || + settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_PITCH] >= MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE || + settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_YAW] >= MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE || + settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_THROTTLE] >= MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE || + settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_FLIGHTMODE] >= MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE || + // Check all channel mappings are valid + cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_ROLL] == (uint16_t) PIOS_RCVR_INVALID || + cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_PITCH] == (uint16_t) PIOS_RCVR_INVALID || + cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_YAW] == (uint16_t) PIOS_RCVR_INVALID || + cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_THROTTLE] == (uint16_t) PIOS_RCVR_INVALID || + cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_FLIGHTMODE] == (uint16_t) PIOS_RCVR_INVALID || + // Check the driver is exists + cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_ROLL] == (uint16_t) PIOS_RCVR_NODRIVER || + cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_PITCH] == (uint16_t) PIOS_RCVR_NODRIVER || + cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_YAW] == (uint16_t) PIOS_RCVR_NODRIVER || + cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_THROTTLE] == (uint16_t) PIOS_RCVR_NODRIVER || + cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_FLIGHTMODE] == (uint16_t) PIOS_RCVR_NODRIVER) { + AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_CRITICAL); cmd.Connected = MANUALCONTROLCOMMAND_CONNECTED_FALSE; ManualControlCommandSet(&cmd); + + // Need to do this here since we don't process armed status. Since this shouldn't happen in flight (changed config) + // immediately disarm + setArmedIfChanged(FLIGHTSTATUS_ARMED_DISARMED); + continue; } // decide if we have valid manual input or not - bool valid_input_detected = validInputRange(settings.ChannelMin[settings.Throttle], settings.ChannelMax[settings.Throttle], cmd.Channel[settings.Throttle]) && - validInputRange(settings.ChannelMin[settings.Roll], settings.ChannelMax[settings.Roll], cmd.Channel[settings.Roll]) && - validInputRange(settings.ChannelMin[settings.Yaw], settings.ChannelMax[settings.Yaw], cmd.Channel[settings.Yaw]) && - validInputRange(settings.ChannelMin[settings.Pitch], settings.ChannelMax[settings.Pitch], cmd.Channel[settings.Pitch]); + valid_input_detected &= validInputRange(settings.ChannelMin[MANUALCONTROLSETTINGS_CHANNELGROUPS_THROTTLE], settings.ChannelMax[MANUALCONTROLSETTINGS_CHANNELGROUPS_THROTTLE], cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_THROTTLE]) && + validInputRange(settings.ChannelMin[MANUALCONTROLSETTINGS_CHANNELGROUPS_ROLL], settings.ChannelMax[MANUALCONTROLSETTINGS_CHANNELGROUPS_ROLL], cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_ROLL]) && + validInputRange(settings.ChannelMin[MANUALCONTROLSETTINGS_CHANNELGROUPS_YAW], settings.ChannelMax[MANUALCONTROLSETTINGS_CHANNELGROUPS_YAW], cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_YAW]) && + validInputRange(settings.ChannelMin[MANUALCONTROLSETTINGS_CHANNELGROUPS_PITCH], settings.ChannelMax[MANUALCONTROLSETTINGS_CHANNELGROUPS_PITCH], cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_PITCH]); // Implement hysteresis loop on connection status if (valid_input_detected && (++connected_count > 10)) { @@ -209,55 +278,88 @@ static void manualControlTask(void *parameters) cmd.Roll = 0; cmd.Yaw = 0; cmd.Pitch = 0; + cmd.Collective = 0; //cmd.FlightMode = MANUALCONTROLCOMMAND_FLIGHTMODE_AUTO; // don't do until AUTO implemented and functioning // Important: Throttle < 0 will reset Stabilization coefficients among other things. Either change this, // or leave throttle at IDLE speed or above when going into AUTO-failsafe. AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_WARNING); - ManualControlCommandSet(&cmd); - } else { - AlarmsClear(SYSTEMALARMS_ALARM_MANUALCONTROL); - - // Scale channels to -1 -> +1 range - cmd.Roll = scaledChannel[settings.Roll]; - cmd.Pitch = scaledChannel[settings.Pitch]; - cmd.Yaw = scaledChannel[settings.Yaw]; - cmd.Throttle = scaledChannel[settings.Throttle]; - flightMode = scaledChannel[settings.FlightMode]; - + AccessoryDesiredData accessory; // Set Accessory 0 - if(settings.Accessory0 != MANUALCONTROLSETTINGS_ACCESSORY0_NONE) { - accessory.AccessoryVal = scaledChannel[settings.Accessory0]; + if (settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_ACCESSORY0] != + MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE) { + accessory.AccessoryVal = 0; if(AccessoryDesiredInstSet(0, &accessory) != 0) AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_WARNING); } // Set Accessory 1 - if(settings.Accessory1 != MANUALCONTROLSETTINGS_ACCESSORY1_NONE) { - accessory.AccessoryVal = scaledChannel[settings.Accessory1]; + if (settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_ACCESSORY1] != + MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE) { + accessory.AccessoryVal = 0; if(AccessoryDesiredInstSet(1, &accessory) != 0) AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_WARNING); } - // Set Accsesory 2 - if(settings.Accessory2 != MANUALCONTROLSETTINGS_ACCESSORY2_NONE) { - accessory.AccessoryVal = scaledChannel[settings.Accessory2]; + // Set Accessory 2 + if (settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_ACCESSORY2] != + MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE) { + accessory.AccessoryVal = 0; + if(AccessoryDesiredInstSet(2, &accessory) != 0) + AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_WARNING); + } + + } else { + AlarmsClear(SYSTEMALARMS_ALARM_MANUALCONTROL); + + // Scale channels to -1 -> +1 range + cmd.Roll = scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_ROLL]; + cmd.Pitch = scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_PITCH]; + cmd.Yaw = scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_YAW]; + cmd.Throttle = scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_THROTTLE]; + flightMode = scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_FLIGHTMODE]; + + if(cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_COLLECTIVE] != PIOS_RCVR_INVALID && + cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_COLLECTIVE] != PIOS_RCVR_NODRIVER && + cmd.Channel[MANUALCONTROLSETTINGS_CHANNELGROUPS_COLLECTIVE] != PIOS_RCVR_TIMEOUT) + cmd.Collective = scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_COLLECTIVE]; + + AccessoryDesiredData accessory; + // Set Accessory 0 + if (settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_ACCESSORY0] != + MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE) { + accessory.AccessoryVal = scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_ACCESSORY0]; + if(AccessoryDesiredInstSet(0, &accessory) != 0) + AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_WARNING); + } + // Set Accessory 1 + if (settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_ACCESSORY1] != + MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE) { + accessory.AccessoryVal = scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_ACCESSORY1]; + if(AccessoryDesiredInstSet(1, &accessory) != 0) + AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_WARNING); + } + // Set Accessory 2 + if (settings.ChannelGroups[MANUALCONTROLSETTINGS_CHANNELGROUPS_ACCESSORY2] != + MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE) { + accessory.AccessoryVal = scaledChannel[MANUALCONTROLSETTINGS_CHANNELGROUPS_ACCESSORY2]; if(AccessoryDesiredInstSet(2, &accessory) != 0) AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_WARNING); } processFlightMode(&settings, flightMode); - processArm(&cmd, &settings); - - // Update cmd object - ManualControlCommandSet(&cmd); } + // Process arming outside conditional so system will disarm when disconnected + processArm(&cmd, &settings); + + // Update cmd object + ManualControlCommandSet(&cmd); + } else { ManualControlCommandGet(&cmd); /* Under GCS control */ } - FlightStatusGet(&flightStatus); // Depending on the mode update the Stabilization or Actuator objects @@ -279,6 +381,145 @@ static void manualControlTask(void *parameters) } } +static void resetRcvrActivity(struct rcvr_activity_fsm * fsm) +{ + ReceiverActivityData data; + bool updated = false; + + /* Clear all channel activity flags */ + ReceiverActivityGet(&data); + if (data.ActiveGroup != RECEIVERACTIVITY_ACTIVEGROUP_NONE && + data.ActiveChannel != 255) { + data.ActiveGroup = RECEIVERACTIVITY_ACTIVEGROUP_NONE; + data.ActiveChannel = 255; + updated = true; + } + if (updated) { + ReceiverActivitySet(&data); + } + + /* Reset the FSM state */ + fsm->group = 0; + fsm->sample_count = 0; +} + +static void updateRcvrActivitySample(uint32_t rcvr_id, uint16_t samples[], uint8_t max_channels) { + for (uint8_t channel = 1; channel <= max_channels; channel++) { + // Subtract 1 because channels are 1 indexed + samples[channel - 1] = PIOS_RCVR_Read(rcvr_id, channel); + } +} + +static bool updateRcvrActivityCompare(uint32_t rcvr_id, struct rcvr_activity_fsm * fsm) +{ + bool activity_updated = false; + + /* Compare the current value to the previous sampled value */ + for (uint8_t channel = 1; + channel <= RCVR_ACTIVITY_MONITOR_CHANNELS_PER_GROUP; + channel++) { + uint16_t delta; + uint16_t prev = fsm->prev[channel - 1]; // Subtract 1 because channels are 1 indexed + uint16_t curr = PIOS_RCVR_Read(rcvr_id, channel); + if (curr > prev) { + delta = curr - prev; + } else { + delta = prev - curr; + } + + if (delta > RCVR_ACTIVITY_MONITOR_MIN_RANGE) { + /* Mark this channel as active */ + ReceiverActivityActiveGroupOptions group; + + /* Don't assume manualcontrolsettings and receiveractivity are in the same order. */ + switch (fsm->group) { + case MANUALCONTROLSETTINGS_CHANNELGROUPS_PWM: + group = RECEIVERACTIVITY_ACTIVEGROUP_PWM; + break; + case MANUALCONTROLSETTINGS_CHANNELGROUPS_PPM: + group = RECEIVERACTIVITY_ACTIVEGROUP_PPM; + break; + case MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT: + group = RECEIVERACTIVITY_ACTIVEGROUP_DSMMAINPORT; + break; + case MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMFLEXIPORT: + group = RECEIVERACTIVITY_ACTIVEGROUP_DSMFLEXIPORT; + break; + case MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS: + group = RECEIVERACTIVITY_ACTIVEGROUP_SBUS; + break; + case MANUALCONTROLSETTINGS_CHANNELGROUPS_GCS: + group = RECEIVERACTIVITY_ACTIVEGROUP_GCS; + break; + default: + PIOS_Assert(0); + break; + } + + ReceiverActivityActiveGroupSet((uint8_t*)&group); + ReceiverActivityActiveChannelSet(&channel); + activity_updated = true; + } + } + return (activity_updated); +} + +static bool updateRcvrActivity(struct rcvr_activity_fsm * fsm) +{ + bool activity_updated = false; + + if (fsm->group >= MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE) { + /* We're out of range, reset things */ + resetRcvrActivity(fsm); + } + + extern uint32_t pios_rcvr_group_map[]; + if (!pios_rcvr_group_map[fsm->group]) { + /* Unbound group, skip it */ + goto group_completed; + } + + if (fsm->sample_count == 0) { + /* Take a sample of each channel in this group */ + updateRcvrActivitySample(pios_rcvr_group_map[fsm->group], + fsm->prev, + NELEMENTS(fsm->prev)); + fsm->sample_count++; + return (false); + } + + /* Compare with previous sample */ + activity_updated = updateRcvrActivityCompare(pios_rcvr_group_map[fsm->group], fsm); + +group_completed: + /* Reset the sample counter */ + fsm->sample_count = 0; + + /* Find the next active group, but limit search so we can't loop forever here */ + for (uint8_t i = 0; i < MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE; i++) { + /* Move to the next group */ + fsm->group++; + if (fsm->group >= MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE) { + /* Wrap back to the first group */ + fsm->group = 0; + } + if (pios_rcvr_group_map[fsm->group]) { + /* + * Found an active group, take a sample here to avoid an + * extra 20ms delay in the main thread so we can speed up + * this algorithm. + */ + updateRcvrActivitySample(pios_rcvr_group_map[fsm->group], + fsm->prev, + NELEMENTS(fsm->prev)); + fsm->sample_count++; + break; + } + } + + return (activity_updated); +} + static void updateActuatorDesired(ManualControlCommandData * cmd) { ActuatorDesiredData actuator; @@ -440,7 +681,7 @@ static void processArm(ManualControlCommandData * cmd, ManualControlSettingsData } else { // Not really needed since this function not called when disconnected if (cmd->Connected == MANUALCONTROLCOMMAND_CONNECTED_FALSE) - return; + lowThrottle = true; // The throttle is not low, in case we where arming or disarming, abort if (!lowThrottle) { @@ -584,4 +825,3 @@ bool validInputRange(int16_t min, int16_t max, uint16_t value) * @} * @} */ - diff --git a/flight/Modules/Stabilization/stabilization.c b/flight/Modules/Stabilization/stabilization.c index 9d3a538d0..ffc3c53be 100644 --- a/flight/Modules/Stabilization/stabilization.c +++ b/flight/Modules/Stabilization/stabilization.c @@ -40,8 +40,6 @@ #include "attitudeactual.h" #include "attituderaw.h" #include "flightstatus.h" -#include "systemsettings.h" -#include "ahrssettings.h" #include "manualcontrol.h" // Just to get a macro #include "CoordinateConversions.h" @@ -115,6 +113,11 @@ int32_t StabilizationStart() int32_t StabilizationInitialize() { // Initialize variables + StabilizationSettingsInitialize(); + ActuatorDesiredInitialize(); +#if defined(DIAGNOSTICS) + RateDesiredInitialize(); +#endif // Create object queue queue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(UAVObjEvent)); @@ -147,7 +150,6 @@ static void stabilizationTask(void* parameters) RateDesiredData rateDesired; AttitudeActualData attitudeActual; AttitudeRawData attitudeRaw; - SystemSettingsData systemSettings; FlightStatusData flightStatus; SettingsUpdatedCb((UAVObjEvent *) NULL); @@ -175,8 +177,10 @@ static void stabilizationTask(void* parameters) StabilizationDesiredGet(&stabDesired); AttitudeActualGet(&attitudeActual); AttitudeRawGet(&attitudeRaw); + +#if defined(DIAGNOSTICS) RateDesiredGet(&rateDesired); - SystemSettingsGet(&systemSettings); +#endif #if defined(PIOS_QUATERNION_STABILIZATION) // Quaternion calculation of error in each axis. Uses more memory. @@ -231,6 +235,9 @@ static void stabilizationTask(void* parameters) { case STABILIZATIONDESIRED_STABILIZATIONMODE_RATE: rateDesiredAxis[i] = attitudeDesiredAxis[i]; + + // Zero attitude and axis lock accumulators + pids[PID_ROLL + i].iAccumulator = 0; axis_lock_accum[i] = 0; break; @@ -245,11 +252,20 @@ static void stabilizationTask(void* parameters) rateDesiredAxis[i] = attitudeDesiredAxis[i] + weak_leveling; + // Zero attitude and axis lock accumulators + pids[PID_ROLL + i].iAccumulator = 0; axis_lock_accum[i] = 0; break; } case STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE: rateDesiredAxis[i] = ApplyPid(&pids[PID_ROLL + i], local_error[i]); + + if(rateDesiredAxis[i] > settings.MaximumRate[i]) + rateDesiredAxis[i] = settings.MaximumRate[i]; + else if(rateDesiredAxis[i] < -settings.MaximumRate[i]) + rateDesiredAxis[i] = -settings.MaximumRate[i]; + + axis_lock_accum[i] = 0; break; @@ -268,21 +284,24 @@ static void stabilizationTask(void* parameters) rateDesiredAxis[i] = ApplyPid(&pids[PID_ROLL + i], axis_lock_accum[i]); } + + if(rateDesiredAxis[i] > settings.MaximumRate[i]) + rateDesiredAxis[i] = settings.MaximumRate[i]; + else if(rateDesiredAxis[i] < -settings.MaximumRate[i]) + rateDesiredAxis[i] = -settings.MaximumRate[i]; + break; } } uint8_t shouldUpdate = 1; +#if defined(DIAGNOSTICS) RateDesiredSet(&rateDesired); +#endif ActuatorDesiredGet(&actuatorDesired); //Calculate desired command for(int8_t ct=0; ct< MAX_AXES; 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: @@ -300,14 +319,20 @@ static void stabilizationTask(void* parameters) case ROLL: actuatorDesiredAxis[ct] = bound(attitudeDesiredAxis[ct]); shouldUpdate = 1; + pids[PID_RATE_ROLL].iAccumulator = 0; + pids[PID_ROLL].iAccumulator = 0; break; case PITCH: actuatorDesiredAxis[ct] = bound(attitudeDesiredAxis[ct]); shouldUpdate = 1; + pids[PID_RATE_PITCH].iAccumulator = 0; + pids[PID_PITCH].iAccumulator = 0; break; case YAW: actuatorDesiredAxis[ct] = bound(attitudeDesiredAxis[ct]); shouldUpdate = 1; + pids[PID_RATE_YAW].iAccumulator = 0; + pids[PID_YAW].iAccumulator = 0; break; } break; diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index f555d227f..b3da26870 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -43,10 +43,11 @@ #include "objectpersistence.h" #include "flightstatus.h" #include "systemstats.h" +#include "systemsettings.h" #include "i2cstats.h" +#include "taskinfo.h" #include "watchdogstatus.h" #include "taskmonitor.h" -#include "pios_config.h" // Private constants @@ -73,16 +74,18 @@ static uint32_t idleCounter; static uint32_t idleCounterClear; static xTaskHandle systemTaskHandle; -static int32_t stackOverflow; +static bool stackOverflow; +static bool mallocFailed; // Private functions static void objectUpdatedCb(UAVObjEvent * ev); static void updateStats(); -static void updateI2Cstats(); -static void updateWDGstats(); static void updateSystemAlarms(); static void systemTask(void *parameters); - +#if defined(DIAGNOSTICS) +static void updateI2Cstats(); +static void updateWDGstats(); +#endif /** * Create the module task. * \returns 0 on success or -1 if initialization failed @@ -90,7 +93,8 @@ static void systemTask(void *parameters); int32_t SystemModStart(void) { // Initialize vars - stackOverflow = 0; + stackOverflow = false; + mallocFailed = false; // Create system task xTaskCreate(systemTask, (signed char *)"System", STACK_SIZE_BYTES/4, NULL, TASK_PRIORITY, &systemTaskHandle); // Register task @@ -106,6 +110,17 @@ int32_t SystemModStart(void) int32_t SystemModInitialize(void) { + // Must registers objects here for system thread because ObjectManager started in OpenPilotInit + SystemSettingsInitialize(); + SystemStatsInitialize(); + FlightStatusInitialize(); + ObjectPersistenceInitialize(); +#if defined(DIAGNOSTICS) + TaskInfoInitialize(); + I2CStatsInitialize(); + WatchdogStatusInitialize(); +#endif + SystemModStart(); return 0; @@ -137,9 +152,10 @@ static void systemTask(void *parameters) // Update the system alarms updateSystemAlarms(); +#if defined(DIAGNOSTICS) updateI2Cstats(); updateWDGstats(); - +#endif // Update the task status object TaskMonitorUpdateAll(); @@ -230,6 +246,11 @@ static void objectUpdatedCb(UAVObjEvent * ev) || objper.Selection == OBJECTPERSISTENCE_SELECTION_ALLOBJECTS) { retval = UAVObjDeleteMetaobjects(); } + } else if (objper.Operation == OBJECTPERSISTENCE_OPERATION_FULLERASE) { + retval = -1; +#if defined(PIOS_INCLUDE_FLASH_SECTOR_SETTINGS) + retval = PIOS_FLASHFS_Format(); +#endif } if(retval == 0) { objper.Operation = OBJECTPERSISTENCE_OPERATION_COMPLETED; @@ -241,9 +262,7 @@ static void objectUpdatedCb(UAVObjEvent * ev) /** * Called periodically to update the I2C statistics */ -#if defined(ARCH_POSIX) || defined(ARCH_WIN32) -static void updateI2Cstats() {} //Posix and win32 don't have I2C -#else +#if defined(DIAGNOSTICS) static void updateI2Cstats() { #if defined(PIOS_INCLUDE_I2C) @@ -263,7 +282,6 @@ static void updateI2Cstats() I2CStatsSet(&i2cStats); #endif } -#endif static void updateWDGstats() { @@ -272,6 +290,8 @@ static void updateWDGstats() watchdogStatus.ActiveFlags = PIOS_WDG_GetActiveFlags(); WatchdogStatusSet(&watchdogStatus); } +#endif + /** * Called periodically to update the system stats @@ -369,25 +389,24 @@ static void updateSystemAlarms() EventStats evStats; SystemStatsGet(&stats); - // Check heap - if (stats.HeapRemaining < HEAP_LIMIT_CRITICAL) { - AlarmsSet(SYSTEMALARMS_ALARM_OUTOFMEMORY, SYSTEMALARMS_ALARM_CRITICAL); - } else if (stats.HeapRemaining < HEAP_LIMIT_WARNING) { - AlarmsSet(SYSTEMALARMS_ALARM_OUTOFMEMORY, SYSTEMALARMS_ALARM_WARNING); - } else { - AlarmsClear(SYSTEMALARMS_ALARM_OUTOFMEMORY); - } - + // Check heap, IRQ stack and malloc failures + if ( mallocFailed + || (stats.HeapRemaining < HEAP_LIMIT_CRITICAL) #if !defined(ARCH_POSIX) && !defined(ARCH_WIN32) && defined(CHECK_IRQ_STACK) - // Check IRQ stack - if (stats.IRQStackRemaining < IRQSTACK_LIMIT_CRITICAL) { + || (stats.IRQStackRemaining < IRQSTACK_LIMIT_CRITICAL) +#endif + ) { AlarmsSet(SYSTEMALARMS_ALARM_OUTOFMEMORY, SYSTEMALARMS_ALARM_CRITICAL); - } else if (stats.IRQStackRemaining < IRQSTACK_LIMIT_WARNING) { + } else if ( + (stats.HeapRemaining < HEAP_LIMIT_WARNING) +#if !defined(ARCH_POSIX) && !defined(ARCH_WIN32) && defined(CHECK_IRQ_STACK) + || (stats.IRQStackRemaining < IRQSTACK_LIMIT_WARNING) +#endif + ) { AlarmsSet(SYSTEMALARMS_ALARM_OUTOFMEMORY, SYSTEMALARMS_ALARM_WARNING); } else { AlarmsClear(SYSTEMALARMS_ALARM_OUTOFMEMORY); } -#endif // Check CPU load if (stats.CPULoad > CPULOAD_LIMIT_CRITICAL) { @@ -399,7 +418,7 @@ static void updateSystemAlarms() } // Check for stack overflow - if (stackOverflow == 1) { + if (stackOverflow) { AlarmsSet(SYSTEMALARMS_ALARM_STACKOVERFLOW, SYSTEMALARMS_ALARM_CRITICAL); } else { AlarmsClear(SYSTEMALARMS_ALARM_STACKOVERFLOW); @@ -443,9 +462,29 @@ void vApplicationIdleHook(void) /** * Called by the RTOS when a stack overflow is detected. */ +#define DEBUG_STACK_OVERFLOW 0 void vApplicationStackOverflowHook(xTaskHandle * pxTask, signed portCHAR * pcTaskName) { - stackOverflow = 1; + stackOverflow = true; +#if DEBUG_STACK_OVERFLOW + static volatile bool wait_here = true; + while(wait_here); + wait_here = true; +#endif +} + +/** + * Called by the RTOS when a malloc call fails. + */ +#define DEBUG_MALLOC_FAILURES 0 +void vApplicationMallocFailedHook(void) +{ + mallocFailed = true; +#if DEBUG_MALLOC_FAILURES + static volatile bool wait_here = true; + while(wait_here); + wait_here = true; +#endif } /** diff --git a/flight/Modules/Telemetry/telemetry.c b/flight/Modules/Telemetry/telemetry.c index 06581fe1a..e0f8b2d5f 100644 --- a/flight/Modules/Telemetry/telemetry.c +++ b/flight/Modules/Telemetry/telemetry.c @@ -34,7 +34,7 @@ #include "telemetry.h" #include "flighttelemetrystats.h" #include "gcstelemetrystats.h" -#include "telemetrysettings.h" +#include "hwsettings.h" // Private constants #define MAX_QUEUE_SIZE TELEM_QUEUE_SIZE @@ -65,8 +65,8 @@ static xTaskHandle telemetryTxTaskHandle; static xTaskHandle telemetryRxTaskHandle; static uint32_t txErrors; static uint32_t txRetries; -static TelemetrySettingsData settings; static uint32_t timeOfLastObjectUpdate; +static UAVTalkConnection uavTalkCon; // Private functions static void telemetryTxTask(void *parameters); @@ -88,7 +88,12 @@ static void updateSettings(); */ int32_t TelemetryStart(void) { - + // Process all registered objects and connect queue for updates + UAVObjIterate(®isterObject); + + // Listen to objects of interest + GCSTelemetryStatsConnectQueue(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); @@ -110,7 +115,8 @@ int32_t TelemetryStart(void) */ int32_t TelemetryInitialize(void) { - UAVObjEvent ev; + FlightTelemetryStatsInitialize(); + GCSTelemetryStatsInitialize(); // Initialize vars timeOfLastObjectUpdate = 0; @@ -120,26 +126,22 @@ int32_t TelemetryInitialize(void) #if defined(PIOS_TELEM_PRIORITY_QUEUE) priorityQueue = xQueueCreate(MAX_QUEUE_SIZE, sizeof(UAVObjEvent)); #endif - - // Get telemetry settings object + + // Update telemetry settings + telemetryPort = PIOS_COM_TELEM_RF; + HwSettingsInitialize(); updateSettings(); - + // Initialise UAVTalk - UAVTalkInitialize(&transmitData); - - // Process all registered objects and connect queue for updates - UAVObjIterate(®isterObject); - + uavTalkCon = UAVTalkInitialize(&transmitData,256); + // Create periodic event that will be used to update the telemetry stats txErrors = 0; txRetries = 0; + UAVObjEvent ev; memset(&ev, 0, sizeof(UAVObjEvent)); EventPeriodicQueueCreate(&ev, priorityQueue, STATS_UPDATE_PERIOD_MS); - // Listen to objects of interest - GCSTelemetryStatsConnectQueue(priorityQueue); - TelemetrySettingsConnectQueue(priorityQueue); - return 0; } @@ -221,8 +223,6 @@ static void processObjEvent(UAVObjEvent * ev) updateTelemetryStats(); } else if (ev->obj == GCSTelemetryStatsHandle()) { gcsTelemetryStatsUpdated(); - } else if (ev->obj == TelemetrySettingsHandle()) { - updateSettings(); } else { // Only process event if connected to GCS or if object FlightTelemetryStats is updated FlightTelemetryStatsGet(&flightStats); @@ -235,7 +235,7 @@ static void processObjEvent(UAVObjEvent * ev) if (ev->event == EV_UPDATED || ev->event == EV_UPDATED_MANUAL) { // Send update to GCS (with retries) while (retries < MAX_RETRIES && success == -1) { - success = UAVTalkSendObject(ev->obj, ev->instId, metadata.telemetryAcked, REQ_TIMEOUT_MS); // call blocks until ack is received or timeout + success = UAVTalkSendObject(uavTalkCon, ev->obj, ev->instId, metadata.telemetryAcked, REQ_TIMEOUT_MS); // call blocks until ack is received or timeout ++retries; } // Update stats @@ -246,7 +246,7 @@ static void processObjEvent(UAVObjEvent * ev) } else if (ev->event == EV_UPDATE_REQ) { // Request object update from GCS (with retries) while (retries < MAX_RETRIES && success == -1) { - success = UAVTalkSendObjectRequest(ev->obj, ev->instId, REQ_TIMEOUT_MS); // call blocks until update is received or timeout + success = UAVTalkSendObjectRequest(uavTalkCon, ev->obj, ev->instId, REQ_TIMEOUT_MS); // call blocks until update is received or timeout ++retries; } // Update stats @@ -326,7 +326,7 @@ static void telemetryRxTask(void *parameters) bytes_to_process = PIOS_COM_ReceiveBuffer(inputPort, serial_data, sizeof(serial_data), 500); if (bytes_to_process > 0) { for (uint8_t i = 0; i < bytes_to_process; i++) { - UAVTalkProcessInputStream(serial_data[i]); + UAVTalkProcessInputStream(uavTalkCon,serial_data[i]); } } } else { @@ -426,8 +426,8 @@ static void updateTelemetryStats() uint32_t timeNow; // Get stats - UAVTalkGetStats(&utalkStats); - UAVTalkResetStats(); + UAVTalkGetStats(uavTalkCon, &utalkStats); + UAVTalkResetStats(uavTalkCon); // Get object data FlightTelemetryStatsGet(&flightStats); @@ -504,27 +504,45 @@ static void updateTelemetryStats() } /** - * Update the telemetry settings, called on startup and - * each time the settings object is updated + * Update the telemetry settings, called on startup. + * FIXME: This should be in the TelemetrySettings object. But objects + * have too much overhead yet. Also the telemetry has no any specific + * settings, etc. Thus the HwSettings object which contains the + * telemetry port speed is used for now. */ static void updateSettings() { - // Set port - telemetryPort = PIOS_COM_TELEM_RF; + if (telemetryPort) { - // Retrieve settings - TelemetrySettingsGet(&settings); + // Retrieve settings + uint8_t speed; + HwSettingsTelemetrySpeedGet(&speed); - if (telemetryPort) { - // Set port speed - if (settings.Speed == TELEMETRYSETTINGS_SPEED_2400) PIOS_COM_ChangeBaud(telemetryPort, 2400); - else if (settings.Speed == TELEMETRYSETTINGS_SPEED_4800) PIOS_COM_ChangeBaud(telemetryPort, 4800); - else if (settings.Speed == TELEMETRYSETTINGS_SPEED_9600) PIOS_COM_ChangeBaud(telemetryPort, 9600); - else if (settings.Speed == TELEMETRYSETTINGS_SPEED_19200) PIOS_COM_ChangeBaud(telemetryPort, 19200); - else if (settings.Speed == TELEMETRYSETTINGS_SPEED_38400) PIOS_COM_ChangeBaud(telemetryPort, 38400); - else if (settings.Speed == TELEMETRYSETTINGS_SPEED_57600) PIOS_COM_ChangeBaud(telemetryPort, 57600); - else if (settings.Speed == TELEMETRYSETTINGS_SPEED_115200) PIOS_COM_ChangeBaud(telemetryPort, 115200); - } + // Set port speed + switch (speed) { + case HWSETTINGS_TELEMETRYSPEED_2400: + PIOS_COM_ChangeBaud(telemetryPort, 2400); + break; + case HWSETTINGS_TELEMETRYSPEED_4800: + PIOS_COM_ChangeBaud(telemetryPort, 4800); + break; + case HWSETTINGS_TELEMETRYSPEED_9600: + PIOS_COM_ChangeBaud(telemetryPort, 9600); + break; + case HWSETTINGS_TELEMETRYSPEED_19200: + PIOS_COM_ChangeBaud(telemetryPort, 19200); + break; + case HWSETTINGS_TELEMETRYSPEED_38400: + PIOS_COM_ChangeBaud(telemetryPort, 38400); + break; + case HWSETTINGS_TELEMETRYSPEED_57600: + PIOS_COM_ChangeBaud(telemetryPort, 57600); + break; + case HWSETTINGS_TELEMETRYSPEED_115200: + PIOS_COM_ChangeBaud(telemetryPort, 115200); + break; + } + } } /** diff --git a/flight/OpenPilot/Makefile b/flight/OpenPilot/Makefile index 60f9d6d30..ddb298157 100644 --- a/flight/OpenPilot/Makefile +++ b/flight/OpenPilot/Makefile @@ -37,6 +37,9 @@ OUTDIR := $(TOP)/build/$(TARGET) # Set to YES to compile for debugging DEBUG ?= YES +# Include objects that are just nice information to show +DIAGNOSTICS ?= YES + # Set to YES to use the Servo output pins for debugging via scope or logic analyser ENABLE_DEBUG_PINS ?= NO @@ -55,13 +58,16 @@ endif FLASH_TOOL = OPENOCD + # List of modules to include -MODULES = Actuator Telemetry GPS ManualControl Altitude AHRSComms Stabilization Guidance FirmwareIAP +OPTMODULES = CameraStab GPS +MODULES = Actuator ManualControl Altitude AHRSComms Stabilization Guidance FirmwareIAP PYMODULES = FlightPlan #MODULES = Telemetry Example #MODULES = Telemetry MK/MKSerial #MODULES = Telemetry #MODULES += Osd/OsdEtStd +MODULES += Telemetry # Paths OPSYSTEM = ./System @@ -125,6 +131,7 @@ PYSRC += ${foreach MOD, ${PYMODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} SRC += $(PYSRC) ## MODULES +SRC += ${foreach MOD, ${OPTMODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} SRC += ${foreach MOD, ${MODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} ## OPENPILOT CORE: SRC += ${OPMODULEDIR}/System/systemmod.c @@ -135,7 +142,6 @@ SRC += $(OPSYSTEM)/taskmonitor.c SRC += $(OPUAVTALK)/uavtalk.c SRC += $(OPUAVOBJ)/uavobjectmanager.c SRC += $(OPUAVOBJ)/eventdispatcher.c -SRC += $(OPUAVOBJ)/uavobjectsinit_linker.c else ## TESTCODE SRC += $(OPTESTS)/test_common.c @@ -163,8 +169,9 @@ SRC += $(PIOSSTM32F10X)/pios_i2c.c SRC += $(PIOSSTM32F10X)/pios_spi.c SRC += $(PIOSSTM32F10X)/pios_ppm.c SRC += $(PIOSSTM32F10X)/pios_pwm.c -SRC += $(PIOSSTM32F10X)/pios_spektrum.c +SRC += $(PIOSSTM32F10X)/pios_dsm.c SRC += $(PIOSSTM32F10X)/pios_sbus.c +SRC += $(PIOSSTM32F10X)/pios_tim.c SRC += $(PIOSSTM32F10X)/pios_debug.c SRC += $(PIOSSTM32F10X)/pios_gpio.c SRC += $(PIOSSTM32F10X)/pios_exti.c @@ -307,7 +314,7 @@ EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/ARM_CM3 EXTRAINCDIRS += $(AHRSBOOTLOADERINC) EXTRAINCDIRS += $(PYMITEINC) -EXTRAINCDIRS += ${foreach MOD, ${MODULES} ${PYMODULES}, $(OPMODULEDIR)/${MOD}/inc} ${OPMODULEDIR}/System/inc +EXTRAINCDIRS += ${foreach MOD, ${OPTMODULES} ${MODULES} ${PYMODULES}, $(OPMODULEDIR)/${MOD}/inc} ${OPMODULEDIR}/System/inc # List any extra directories to look for library files here. @@ -385,9 +392,14 @@ CSTANDARD = -std=gnu99 # Flags for C and C++ (arm-elf-gcc/arm-elf-g++) ifeq ($(DEBUG),YES) -CFLAGS = -g$(DEBUGF) -DDEBUG +CFLAGS = -DDEBUG endif +ifeq ($(DIAGNOSTICS),YES) +CFLAGS = -DDIAGNOSTICS +endif + +CFLAGS += -g$(DEBUGF) CFLAGS += -O$(OPT) CFLAGS += -mcpu=$(MCU) CFLAGS += $(CDEFS) @@ -469,9 +481,6 @@ endif endif # Generate intermediate code -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 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) @@ -512,7 +521,7 @@ $(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin $(eval $(call OPFW_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BOARD_TYPE),$(BOARD_REVISION))) # Add jtag targets (program and wipe) -$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE))) +$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE),$(OPENOCD_CONFIG))) .PHONY: elf lss sym hex bin bino opfw elf: $(OUTDIR)/$(TARGET).elf @@ -579,4 +588,4 @@ else endif # Listing of phony targets. -.PHONY : all build clean clean_list gencode install +.PHONY : all build clean clean_list install diff --git a/flight/OpenPilot/Makefile.posix b/flight/OpenPilot/Makefile.posix index cfcdbf55f..4a947ae8d 100644 --- a/flight/OpenPilot/Makefile.posix +++ b/flight/OpenPilot/Makefile.posix @@ -27,6 +27,9 @@ # Set to YES to compile for debugging DEBUG ?= YES +# Include objects that are just nice information to show +DIAGNOSTICS ?= YES + # Set to YES to use the Servo output pins for debugging via scope or logic analyser ENABLE_DEBUG_PINS ?= NO @@ -53,10 +56,12 @@ FLASH_TOOL = OPENOCD USE_THUMB_MODE = YES # List of modules to include -MODULES = Telemetry Actuator Stabilization Guidance ManualControl FlightPlan GPS +OPTMODULES = CameraStab GPS +MODULES = Telemetry Actuator Stabilization Guidance ManualControl #MODULES = Telemetry ManualControl Actuator Attitude Stabilization #MODULES = Telemetry Example #MODULES = Telemetry MK/MKSerial +PYMODULES = FlightPlan #MODULES += Osd/OsdEtStd @@ -121,6 +126,7 @@ UAVOBJPYTHONSYNTHDIR = $(OUTDIR)/../uavobject-synthetics/python # use file-extension c for "c-only"-files MODNAMES = $(notdir ${MODULES}) +MODNAMES += $(notdir ${OPTMODULES}) ifndef TESTAPP @@ -129,10 +135,13 @@ SRC += $(OUTDIR)/pmlib_img.c SRC += $(OUTDIR)/pmlib_nat.c SRC += $(OUTDIR)/pmlibusr_img.c SRC += $(OUTDIR)/pmlibusr_nat.c -SRC += $(wildcard ${PYMITEVM}/*.c) -SRC += $(wildcard ${PYMITEPLAT}/*.c) +PYSRC += $(wildcard ${PYMITEVM}/*.c) +PYSRC += $(wildcard ${PYMITEPLAT}/*.c) +PYSRC += ${foreach MOD, ${PYMODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} +SRC += $(PYSRC) ## MODULES +SRC += ${foreach MOD, ${OPTMODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} SRC += ${foreach MOD, ${MODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} SRC += ${OUTDIR}/InitMods.c ## OPENPILOT CORE: @@ -228,7 +237,7 @@ EXTRAINCDIRS += $(APPLIBDIR) EXTRAINCDIRS += $(RTOSSRCDIR)/portable/GCC/Posix EXTRAINCDIRS += $(PYMITEINC) -EXTRAINCDIRS += ${foreach MOD, ${MODULES}, $(OPMODULEDIR)/${MOD}/inc} ${OPMODULEDIR}/System/inc +EXTRAINCDIRS += ${foreach MOD, ${PYMODULES} ${OPTMODULES} ${MODULES}, $(OPMODULEDIR)/${MOD}/inc} ${OPMODULEDIR}/System/inc # List any extra directories to look for library files here. @@ -306,6 +315,10 @@ ifeq ($(DEBUG),YES) CFLAGS = -g$(DEBUGF) -DDEBUG endif +ifeq ($(DIAGNOSTICS),YES) +CFLAGS = -DDIAGNOSTICS +endif + CFLAGS += $(CFLAGS_UAVOBJECTS) CFLAGS += -DARCH_POSIX CFLAGS += -O$(OPT) @@ -436,9 +449,6 @@ else quote = endif -# Generate intermediate code -gencode: ${OUTDIR}/InitMods.c ${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h - # Generate code for module initialization ${OUTDIR}/InitMods.c: Makefile.posix @echo ${MSG_MODINIT} @@ -453,9 +463,9 @@ ${OUTDIR}/InitMods.c: Makefile.posix @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) - @echo ${MSG_PYMITEINIT} - @$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -s --memspace=flash -o $(OUTDIR)/pmlib_img.c --native-file=$(OUTDIR)/pmlib_nat.c $(PYMITELIB)/list.py $(PYMITELIB)/dict.py $(PYMITELIB)/__bi.py $(PYMITELIB)/sys.py $(PYMITELIB)/string.py $(wildcard $(FLIGHTPLANLIB)/*.py) $(wildcard $(UAVOBJPYTHONSYNTHDIR)/*.py) +${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, $@) + @$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -s --memspace=flash -o $(OUTDIR)/pmlib_img.c --native-file=$(OUTDIR)/pmlib_nat.c $(PYMITELIB)/list.py $(PYMITELIB)/dict.py $(PYMITELIB)/__bi.py $(PYMITELIB)/sys.py $(PYMITELIB)/string.py $(wildcard $(FLIGHTPLANLIB)/*.py) @$(PYTHON) $(PYMITETOOLS)/pmGenPmFeatures.py $(PYMITEPLAT)/pmfeatures.py > $(OUTDIR)/pmfeatures.h @$(PYTHON) $(PYMITETOOLS)/pmImgCreator.py -f $(PYMITEPLAT)/pmfeatures.py -c -u -o $(OUTDIR)/pmlibusr_img.c --native-file=$(OUTDIR)/pmlibusr_nat.c $(FLIGHTPLANS)/test.py @@ -651,5 +661,5 @@ endif # Listing of phony targets. .PHONY : all begin finish end sizebefore sizeafter gccversion \ -build elf hex bin lss sym clean clean_list program gencode +build elf hex bin lss sym clean clean_list program diff --git a/flight/OpenPilot/System/alarms.c b/flight/OpenPilot/System/alarms.c index e899be779..e61c7c1ea 100644 --- a/flight/OpenPilot/System/alarms.c +++ b/flight/OpenPilot/System/alarms.c @@ -41,14 +41,12 @@ static xSemaphoreHandle lock; static int32_t hasSeverity(SystemAlarmsAlarmOptions severity); /** - * Initialize the alarms library + * Initialize the alarms library */ int32_t AlarmsInitialize(void) { + SystemAlarmsInitialize(); lock = xSemaphoreCreateRecursiveMutex(); - //do not change the default states of the alarms, let the init code generated by the uavobjectgenerator handle that - //AlarmsClearAll(); - //AlarmsDefaultAll(); return 0; } @@ -56,7 +54,7 @@ int32_t AlarmsInitialize(void) * Set an alarm * @param alarm The system alarm to be modified * @param severity The alarm severity - * @return 0 if success, -1 if an error + * @return 0 if success, -1 if an error */ int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity) { @@ -151,7 +149,7 @@ void AlarmsClearAll() /** * Check if there are any alarms with the given or higher severity - * @return 0 if no alarms are found, 1 if at least one alarm is found + * @return 0 if no alarms are found, 1 if at least one alarm is found */ int32_t AlarmsHasWarnings() { @@ -208,5 +206,5 @@ static int32_t hasSeverity(SystemAlarmsAlarmOptions severity) /** * @} * @} - */ + */ diff --git a/flight/OpenPilot/System/inc/FreeRTOSConfig.h b/flight/OpenPilot/System/inc/FreeRTOSConfig.h index 75a14ea13..4b37f7e44 100644 --- a/flight/OpenPilot/System/inc/FreeRTOSConfig.h +++ b/flight/OpenPilot/System/inc/FreeRTOSConfig.h @@ -26,6 +26,7 @@ #define configUSE_PREEMPTION 1 #define configUSE_IDLE_HOOK 1 #define configUSE_TICK_HOOK 0 +#define configUSE_MALLOC_FAILED_HOOK 1 #define configCPU_CLOCK_HZ ( ( unsigned long ) 72000000 ) #define configTICK_RATE_HZ ( ( portTickType ) 1000 ) #define configMAX_PRIORITIES ( ( unsigned portBASE_TYPE ) 5 ) @@ -39,7 +40,7 @@ #define configUSE_RECURSIVE_MUTEXES 1 #define configUSE_COUNTING_SEMAPHORES 0 #define configUSE_ALTERNATIVE_API 0 -#define configCHECK_FOR_STACK_OVERFLOW 2 +//#define configCHECK_FOR_STACK_OVERFLOW 2 #define configQUEUE_REGISTRY_SIZE 10 /* Co-routine definitions. */ @@ -72,7 +73,9 @@ NVIC value of 255. */ #define configLIBRARY_KERNEL_INTERRUPT_PRIORITY 15 /* Enable run time stats collection */ -#if defined(DEBUG) +#if defined(DIAGNOSTICS) +#define configCHECK_FOR_STACK_OVERFLOW 2 + #define configGENERATE_RUN_TIME_STATS 1 #define INCLUDE_uxTaskGetRunTime 1 #define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS()\ @@ -81,6 +84,8 @@ do {\ (*(unsigned long *)0xe0001000) |= 1; /* DWT_CTRL |= DWT_CYCCNT_ENA */\ } while(0) #define portGET_RUN_TIME_COUNTER_VALUE() (*(unsigned long *)0xe0001004)/* DWT_CYCCNT */ +#else +#define configCHECK_FOR_STACK_OVERFLOW 1 #endif #if !defined(ARCH_POSIX) && !defined(ARCH_WIN32) diff --git a/flight/OpenPilot/System/inc/pios_config.h b/flight/OpenPilot/System/inc/pios_config.h index 4d561382e..81699215b 100644 --- a/flight/OpenPilot/System/inc/pios_config.h +++ b/flight/OpenPilot/System/inc/pios_config.h @@ -44,10 +44,10 @@ #define PIOS_INCLUDE_RCVR -#define PIOS_INCLUDE_SPEKTRUM +#define PIOS_INCLUDE_DSM //#define PIOS_INCLUDE_SBUS #define PIOS_INCLUDE_PWM -//#define PIOS_INCLUDE_PPM +#define PIOS_INCLUDE_PPM #define PIOS_INCLUDE_TELEMETRY_RF @@ -60,6 +60,7 @@ //#define PIOS_INCLUDE_HCSR04 #define PIOS_INCLUDE_OPAHRS #define PIOS_INCLUDE_COM +#define PIOS_INCLUDE_GPS #define PIOS_INCLUDE_SDCARD #define PIOS_INCLUDE_SETTINGS #define PIOS_INCLUDE_FREERTOS @@ -77,12 +78,6 @@ /* Enable a priority queue in telemetry */ #define PIOS_TELEM_PRIORITY_QUEUE -/* COM Module */ -#define GPS_BAUDRATE 19200 -#define TELEM_BAUDRATE 19200 -#define AUXUART_ENABLED 0 -#define AUXUART_BAUDRATE 19200 - /* Alarm Thresholds */ #define HEAP_LIMIT_WARNING 4000 #define HEAP_LIMIT_CRITICAL 1000 @@ -97,6 +92,8 @@ /* GPS options */ #define PIOS_GPS_SETS_HOMELOCATION +/* PIOS Initcall infrastructure */ +#define PIOS_INCLUDE_INITCALL #endif /* PIOS_CONFIG_H */ /** diff --git a/flight/OpenPilot/System/inc/pios_config_posix.h b/flight/OpenPilot/System/inc/pios_config_posix.h index 4b779cc49..1148a497c 100644 --- a/flight/OpenPilot/System/inc/pios_config_posix.h +++ b/flight/OpenPilot/System/inc/pios_config_posix.h @@ -36,6 +36,7 @@ #define PIOS_INCLUDE_SDCARD #define PIOS_INCLUDE_FREERTOS #define PIOS_INCLUDE_COM +#define PIOS_INCLUDE_GPS #define PIOS_INCLUDE_IRQ #define PIOS_INCLUDE_TELEMETRY_RF #define PIOS_INCLUDE_UDP @@ -49,18 +50,28 @@ #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 - #define TELEM_QUEUE_SIZE 20 #define PIOS_TELEM_STACK_SIZE 2048 +/* 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 + /* Stabilization options */ #define PIOS_QUATERNION_STABILIZATION +/* 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 + /* GPS options */ #define PIOS_GPS_SETS_HOMELOCATION diff --git a/flight/OpenPilot/System/openpilot.c b/flight/OpenPilot/System/openpilot.c index 81a8f17b1..c90f5fd81 100644 --- a/flight/OpenPilot/System/openpilot.c +++ b/flight/OpenPilot/System/openpilot.c @@ -143,11 +143,11 @@ static void TaskTesting(void *pvParameters) PIOS_COM_SendFormattedStringNonBlocking(COM_DEBUG_USART, "%u\r", PIOS_BMP085_GetPressure()); */ -#if defined(PIOS_INCLUDE_SPEKTRUM) - PIOS_COM_SendFormattedStringNonBlocking(COM_DEBUG_USART, "%u,%u,%u,%u,%u,%u,%u,%u\r", PIOS_SPEKTRUM_Get(0), PIOS_SPEKTRUM_Get(1), PIOS_SPEKTRUM_Get(2), PIOS_SPEKTRUM_Get(3), PIOS_SPEKTRUM_Get(4), PIOS_SPEKTRUM_Get(5), PIOS_SPEKTRUM_Get(6), PIOS_SPEKTRUM_Get(7)); +#if defined(PIOS_INCLUDE_DSM) + PIOS_COM_SendFormattedStringNonBlocking(COM_DEBUG_USART, "%u,%u,%u,%u,%u,%u,%u,%u\r", PIOS_DSM_Get(0), PIOS_DSM_Get(1), PIOS_DSM_Get(2), PIOS_DSM_Get(3), PIOS_DSM_Get(4), PIOS_DSM_Get(5), PIOS_DSM_Get(6), PIOS_DSM_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)); + 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)); diff --git a/flight/OpenPilot/System/pios_board.c b/flight/OpenPilot/System/pios_board.c index 822b7a8ae..03a75a30c 100644 --- a/flight/OpenPilot/System/pios_board.c +++ b/flight/OpenPilot/System/pios_board.c @@ -30,7 +30,8 @@ #include #include #include -#include "manualcontrolsettings.h" +#include +#include //#define I2C_DEBUG_PIN 0 //#define USART_GPS_DEBUG_PIN 1 @@ -301,6 +302,89 @@ void PIOS_ADC_handler() { PIOS_ADC_DMA_Handler(); } +#include "pios_tim_priv.h" + +static const TIM_TimeBaseInitTypeDef tim_4_8_time_base = { + .TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1, + .TIM_ClockDivision = TIM_CKD_DIV1, + .TIM_CounterMode = TIM_CounterMode_Up, + .TIM_Period = ((1000000 / PIOS_SERVO_UPDATE_HZ) - 1), + .TIM_RepetitionCounter = 0x0000, +}; + +static const struct pios_tim_clock_cfg tim_4_cfg = { + .timer = TIM4, + .time_base_init = &tim_4_8_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM4_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const struct pios_tim_clock_cfg tim_8_cfg = { + .timer = TIM8, + .time_base_init = &tim_4_8_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM8_CC_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const TIM_TimeBaseInitTypeDef tim_1_3_5_time_base = { + .TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1, + .TIM_ClockDivision = TIM_CKD_DIV1, + .TIM_CounterMode = TIM_CounterMode_Up, + .TIM_Period = 0xFFFF, + .TIM_RepetitionCounter = 0x0000, +}; + +static const struct pios_tim_clock_cfg tim_1_cfg = { + .timer = TIM1, + .time_base_init = &tim_1_3_5_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM1_CC_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const struct pios_tim_clock_cfg tim_3_cfg = { + .timer = TIM3, + .time_base_init = &tim_1_3_5_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM3_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const struct pios_tim_clock_cfg tim_5_cfg = { + .timer = TIM5, + .time_base_init = &tim_1_3_5_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM5_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + #if defined(PIOS_INCLUDE_USART) #include "pios_usart_priv.h" @@ -454,13 +538,13 @@ void PIOS_RTC_IRQ_Handler (void) #endif -#if defined(PIOS_INCLUDE_SPEKTRUM) +#if defined(PIOS_INCLUDE_DSM) /* - * SPEKTRUM USART + * Spektrum/JR DSM USART */ -#include +#include -static const struct pios_usart_cfg pios_usart_spektrum_cfg = { +static const struct pios_usart_cfg pios_usart_dsm_cfg = { .regs = USART1, .init = { .USART_BaudRate = 115200, @@ -496,8 +580,7 @@ static const struct pios_usart_cfg pios_usart_spektrum_cfg = { }, }; -#include -static const struct pios_spektrum_cfg pios_spektrum_cfg = { +static const struct pios_dsm_cfg pios_dsm_cfg = { .bind = { .gpio = GPIOA, .init = { @@ -506,10 +589,9 @@ static const struct pios_spektrum_cfg pios_spektrum_cfg = { .GPIO_Mode = GPIO_Mode_Out_PP, }, }, - .remap = 0, }; -#endif /* PIOS_COM_SPEKTRUM */ +#endif /* PIOS_COM_DSM */ #if defined(PIOS_INCLUDE_SBUS) #error PIOS_INCLUDE_SBUS not implemented @@ -535,65 +617,106 @@ static const struct pios_spektrum_cfg pios_spektrum_cfg = { * Pios servo configuration structures */ #include -static const struct pios_servo_channel pios_servo_channels[] = { +static const struct pios_tim_channel pios_tim_servoport_all_pins[] = { { .timer = TIM4, - .port = GPIOB, - .channel = TIM_Channel_1, - .pin = GPIO_Pin_6, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_6, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, }, { .timer = TIM4, - .port = GPIOB, - .channel = TIM_Channel_2, - .pin = GPIO_Pin_7, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_7, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, }, { .timer = TIM4, - .port = GPIOB, - .channel = TIM_Channel_3, - .pin = GPIO_Pin_8, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_8, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, }, { .timer = TIM4, - .port = GPIOB, - .channel = TIM_Channel_4, - .pin = GPIO_Pin_9, + .timer_chan = TIM_Channel_4, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_9, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, }, { .timer = TIM8, - .port = GPIOC, - .channel = TIM_Channel_1, - .pin = GPIO_Pin_6, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_6, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, }, { .timer = TIM8, - .port = GPIOC, - .channel = TIM_Channel_2, - .pin = GPIO_Pin_7, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_7, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, }, { .timer = TIM8, - .port = GPIOC, - .channel = TIM_Channel_3, - .pin = GPIO_Pin_8, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_8, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, }, { .timer = TIM8, - .port = GPIOC, - .channel = TIM_Channel_4, - .pin = GPIO_Pin_9, + .timer_chan = TIM_Channel_4, + .pin = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_9, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, }, }; const struct pios_servo_cfg pios_servo_cfg = { - .tim_base_init = { - .TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1, - .TIM_ClockDivision = TIM_CKD_DIV1, - .TIM_CounterMode = TIM_CounterMode_Up, - .TIM_Period = ((1000000 / PIOS_SERVO_UPDATE_HZ) - 1), - .TIM_RepetitionCounter = 0x0000, - }, .tim_oc_init = { .TIM_OCMode = TIM_OCMode_PWM1, .TIM_OutputState = TIM_OutputState_Enable, @@ -604,127 +727,127 @@ const struct pios_servo_cfg pios_servo_cfg = { .TIM_OCIdleState = TIM_OCIdleState_Reset, .TIM_OCNIdleState = TIM_OCNIdleState_Reset, }, - .gpio_init = { - .GPIO_Mode = GPIO_Mode_AF_PP, - .GPIO_Speed = GPIO_Speed_2MHz, - }, - .remap = 0, - .channels = pios_servo_channels, - .num_channels = NELEMENTS(pios_servo_channels), + .channels = pios_tim_servoport_all_pins, + .num_channels = NELEMENTS(pios_tim_servoport_all_pins), }; /* * PWM Inputs */ -#if defined(PIOS_INCLUDE_PWM) +#if defined(PIOS_INCLUDE_PWM) || defined(PIOS_INCLUDE_PPM) #include -static const struct pios_pwm_channel pios_pwm_channels[] = { +static const struct pios_tim_channel pios_tim_rcvrport_all_channels[] = { { .timer = TIM1, - .port = GPIOA, - .ccr = TIM_IT_CC2, - .channel = TIM_Channel_2, - .pin = GPIO_Pin_9, - }, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_9, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, { .timer = TIM1, - .port = GPIOA, - .ccr = TIM_IT_CC3, - .channel = TIM_Channel_3, - .pin = GPIO_Pin_10, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, }, { .timer = TIM5, - .port = GPIOA, - .ccr = TIM_IT_CC1, - .channel = TIM_Channel_1, - .pin = GPIO_Pin_0 + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_0, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, }, { .timer = TIM1, - .port = GPIOA, - .ccr = TIM_IT_CC1, - .channel = TIM_Channel_1, - .pin = GPIO_Pin_8, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_8, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, }, { .timer = TIM3, - .port = GPIOB, - .ccr = TIM_IT_CC4, - .channel = TIM_Channel_4, - .pin = GPIO_Pin_1, + .timer_chan = TIM_Channel_4, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_1, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, }, { .timer = TIM3, - .port = GPIOB, - .ccr = TIM_IT_CC3, - .channel = TIM_Channel_3, - .pin = GPIO_Pin_0, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_0, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, }, { .timer = TIM3, - .port = GPIOB, - .ccr = TIM_IT_CC1, - .channel = TIM_Channel_1, - .pin = GPIO_Pin_4, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_4, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + .remap = GPIO_PartialRemap_TIM3, }, { .timer = TIM3, - .port = GPIOB, - .ccr = TIM_IT_CC2, - .channel = TIM_Channel_2, - .pin = GPIO_Pin_5, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_5, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + .remap = GPIO_PartialRemap_TIM3, }, }; -void TIM1_CC_IRQHandler(); -void TIM3_IRQHandler(); -void TIM5_IRQHandler(); -void TIM1_CC_IRQHandler() __attribute__ ((alias ("PIOS_TIM1_CC_irq_handler"))); -void TIM3_IRQHandler() __attribute__ ((alias ("PIOS_TIM3_irq_handler"))); -void TIM5_IRQHandler() __attribute__ ((alias ("PIOS_TIM5_irq_handler"))); const struct pios_pwm_cfg pios_pwm_cfg = { - .tim_base_init = { - .TIM_Prescaler = (PIOS_MASTER_CLOCK / 1000000) - 1, - .TIM_ClockDivision = TIM_CKD_DIV1, - .TIM_CounterMode = TIM_CounterMode_Up, - .TIM_Period = 0xFFFF, - .TIM_RepetitionCounter = 0x0000, - }, .tim_ic_init = { .TIM_ICPolarity = TIM_ICPolarity_Rising, .TIM_ICSelection = TIM_ICSelection_DirectTI, .TIM_ICPrescaler = TIM_ICPSC_DIV1, .TIM_ICFilter = 0x0, }, - .gpio_init = { - .GPIO_Mode = GPIO_Mode_IPD, - .GPIO_Speed = GPIO_Speed_2MHz, - }, - .remap = GPIO_PartialRemap_TIM3, - .irq = { - .init = { - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .channels = pios_pwm_channels, - .num_channels = NELEMENTS(pios_pwm_channels), + .channels = pios_tim_rcvrport_all_channels, + .num_channels = NELEMENTS(pios_tim_rcvrport_all_channels), }; -void PIOS_TIM1_CC_irq_handler() -{ - PIOS_PWM_irq_handler(TIM1); -} -void PIOS_TIM3_irq_handler() -{ - PIOS_PWM_irq_handler(TIM3); -} -void PIOS_TIM5_irq_handler() -{ - PIOS_PWM_irq_handler(TIM5); -} #endif /* @@ -732,42 +855,7 @@ void PIOS_TIM5_irq_handler() */ #if defined(PIOS_INCLUDE_PPM) #include -void TIM6_IRQHandler(); -void TIM6_IRQHandler() __attribute__ ((alias ("PIOS_TIM6_irq_handler"))); -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, - .TIM_CounterMode = TIM_CounterMode_Up, - .TIM_Period = ((1000000 / 25) - 1), /* 25 Hz */ - .TIM_RepetitionCounter = 0x0000, - }, - .irq = { - .init = { - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .timer = TIM6, - .ccr = TIM_IT_Update, -}; - -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"))); 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, - .TIM_CounterMode = TIM_CounterMode_Up, - .TIM_Period = 0xFFFF, - .TIM_RepetitionCounter = 0x0000, - }, .tim_ic_init = { .TIM_ICPolarity = TIM_ICPolarity_Rising, .TIM_ICSelection = TIM_ICSelection_DirectTI, @@ -775,30 +863,11 @@ static const struct pios_ppm_cfg pios_ppm_cfg = { .TIM_ICFilter = 0x0, .TIM_Channel = TIM_Channel_2, }, - .gpio_init = { - .GPIO_Mode = GPIO_Mode_IPD, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Pin = GPIO_Pin_9, - }, - .remap = 0, - .irq = { - .init = { - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - .NVIC_IRQChannel = TIM1_CC_IRQn, - }, - }, - .timer = TIM1, - .port = GPIOA, - .ccr = TIM_IT_CC2, + /* Use only the first channel for ppm */ + .channels = &pios_tim_rcvrport_all_channels[0], + .num_channels = 1, }; -void PIOS_TIM1_CC_irq_handler(void) -{ - PIOS_PPM_irq_handler(); -} - #endif //PPM #if defined(PIOS_INCLUDE_I2C) @@ -964,8 +1033,12 @@ static const struct stm32_gpio pios_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; +/* One slot per selectable receiver group. + * eg. PWM, PPM, GCS, DSMMAINPORT, DSMFLEXIPORT, SBUS + * NOTE: No slot in this map for NONE. + */ +uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE]; + #endif /* PIOS_INCLUDE_RCVR */ #if defined(PIOS_INCLUDE_USB_HID) @@ -989,7 +1062,7 @@ uint32_t pios_com_telem_rf_id; uint32_t pios_com_telem_usb_id; uint32_t pios_com_gps_id; uint32_t pios_com_aux_id; -uint32_t pios_com_spektrum_id; +uint32_t pios_com_dsm_id; #include "ahrs_spi_comm.h" @@ -1003,8 +1076,9 @@ void PIOS_Board_Init(void) { /* Remap AFIO pin */ //GPIO_PinRemapConfig( GPIO_Remap_SWJ_NoJTRST, ENABLE); - /* Debug services */ - PIOS_DEBUG_Init(); +#ifdef PIOS_DEBUG_ENABLE_DEBUG_PINS + PIOS_DEBUG_Init(&pios_tim_servo_all_channels, NELEMENTS(pios_tim_servo_all_channels)); +#endif /* PIOS_DEBUG_ENABLE_DEBUG_PINS */ /* Delay system */ PIOS_DELAY_Init(); @@ -1023,7 +1097,8 @@ void PIOS_Board_Init(void) { /* Initialize UAVObject libraries */ EventDispatcherInitialize(); UAVObjInitialize(); - UAVObjectsInitializeAll(); + + HwSettingsInitialize(); #if defined(PIOS_INCLUDE_RTC) /* Initialize the real-time clock and its associated tick */ @@ -1036,6 +1111,14 @@ void PIOS_Board_Init(void) { /* Initialize the task monitor library */ TaskMonitorInitialize(); + /* Set up pulse timers */ + PIOS_TIM_InitClock(&tim_1_cfg); + PIOS_TIM_InitClock(&tim_3_cfg); + PIOS_TIM_InitClock(&tim_5_cfg); + + PIOS_TIM_InitClock(&tim_4_cfg); + PIOS_TIM_InitClock(&tim_8_cfg); + /* Prepare the AHRS Comms upper layer protocol */ AhrsInitComms(); @@ -1047,126 +1130,150 @@ void PIOS_Board_Init(void) { /* Bind the AHRS comms layer to the AHRS SPI link */ AhrsConnect(pios_spi_ahrs_id); - /* Initialize the PiOS library */ -#if defined(PIOS_INCLUDE_COM) + /* Configure the main IO port */ + uint8_t hwsettings_op_mainport; + HwSettingsOP_MainPortGet(&hwsettings_op_mainport); + + switch (hwsettings_op_mainport) { + case HWSETTINGS_OP_MAINPORT_DISABLED: + break; + case HWSETTINGS_OP_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_cfg)) { - PIOS_Assert(0); - } + { + uint32_t pios_usart_telem_rf_id; + if (PIOS_USART_Init(&pios_usart_telem_rf_id, &pios_usart_telem_cfg)) { + PIOS_Assert(0); + } - uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RF_RX_BUF_LEN); - uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RF_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_usart_com_driver, pios_usart_telem_rf_id, - rx_buffer, PIOS_COM_TELEM_RF_RX_BUF_LEN, - tx_buffer, PIOS_COM_TELEM_RF_TX_BUF_LEN)) { - PIOS_Assert(0); + uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RF_RX_BUF_LEN); + uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_TELEM_RF_TX_BUF_LEN); + PIOS_Assert(rx_buffer); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_telem_rf_id, &pios_usart_com_driver, pios_usart_telem_rf_id, + rx_buffer, PIOS_COM_TELEM_RF_RX_BUF_LEN, + tx_buffer, PIOS_COM_TELEM_RF_TX_BUF_LEN)) { + 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_Assert(0); - } - uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_GPS_RX_BUF_LEN); - PIOS_Assert(rx_buffer); - if (PIOS_COM_Init(&pios_com_gps_id, &pios_usart_com_driver, pios_usart_gps_id, - rx_buffer, PIOS_COM_GPS_RX_BUF_LEN, - NULL, 0)) { - PIOS_Assert(0); - } + break; } -#endif /* PIOS_INCLUDE_GPS */ -#endif - PIOS_Servo_Init(); + /* Configure the flexi port */ + uint8_t hwsettings_op_flexiport; + HwSettingsOP_FlexiPortGet(&hwsettings_op_flexiport); + + switch (hwsettings_op_flexiport) { + case HWSETTINGS_OP_FLEXIPORT_DISABLED: + break; + case HWSETTINGS_OP_FLEXIPORT_GPS: +#if defined(PIOS_INCLUDE_GPS) + { + uint32_t pios_usart_gps_id; + if (PIOS_USART_Init(&pios_usart_gps_id, &pios_usart_gps_cfg)) { + PIOS_Assert(0); + } + uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_GPS_RX_BUF_LEN); + PIOS_Assert(rx_buffer); + if (PIOS_COM_Init(&pios_com_gps_id, &pios_usart_com_driver, pios_usart_gps_id, + rx_buffer, PIOS_COM_GPS_RX_BUF_LEN, + NULL, 0)) { + PIOS_Assert(0); + } + } +#endif /* PIOS_INCLUDE_GPS */ + break; + } + +#ifndef PIOS_DEBUG_ENABLE_DEBUG_PINS + PIOS_Servo_Init(&pios_servo_cfg); +#endif /* PIOS_DEBUG_ENABLE_DEBUG_PINS */ + PIOS_ADC_Init(); PIOS_GPIO_Init(); - /* Configure the selected receiver */ - uint8_t manualcontrolsettings_inputmode; - ManualControlSettingsInputModeGet(&manualcontrolsettings_inputmode); + /* Configure the rcvr port */ + uint8_t hwsettings_rcvrport; + HwSettingsOP_RcvrPortGet(&hwsettings_rcvrport); - switch (manualcontrolsettings_inputmode) { - case MANUALCONTROLSETTINGS_INPUTMODE_PWM: + + switch (hwsettings_rcvrport) { + case HWSETTINGS_OP_RCVRPORT_DISABLED: + break; + case HWSETTINGS_OP_RCVRPORT_DEBUG: + /* Not supported yet */ + break; + case HWSETTINGS_OP_RCVRPORT_DSM2: + case HWSETTINGS_OP_RCVRPORT_DSMX10BIT: + case HWSETTINGS_OP_RCVRPORT_DSMX11BIT: +#if defined(PIOS_INCLUDE_DSM) + { + enum pios_dsm_proto proto; + switch (hwsettings_rcvrport) { + case HWSETTINGS_OP_RCVRPORT_DSM2: + proto = PIOS_DSM_PROTO_DSM2; + break; + case HWSETTINGS_OP_RCVRPORT_DSMX10BIT: + proto = PIOS_DSM_PROTO_DSMX10BIT; + break; + case HWSETTINGS_OP_RCVRPORT_DSMX11BIT: + proto = PIOS_DSM_PROTO_DSMX11BIT; + break; + default: + PIOS_Assert(0); + break; + } + + uint32_t pios_usart_dsm_id; + if (PIOS_USART_Init(&pios_usart_dsm_id, &pios_usart_dsm_cfg)) { + PIOS_Assert(0); + } + + uint32_t pios_dsm_id; + if (PIOS_DSM_Init(&pios_dsm_id, + &pios_dsm_cfg, + &pios_usart_com_driver, + pios_usart_dsm_id, + proto, 0)) { + PIOS_Assert(0); + } + + uint32_t pios_dsm_rcvr_id; + if (PIOS_RCVR_Init(&pios_dsm_rcvr_id, &pios_dsm_rcvr_driver, pios_dsm_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT] = pios_dsm_rcvr_id; + } +#endif + break; + case HWSETTINGS_OP_RCVRPORT_PWM: #if defined(PIOS_INCLUDE_PWM) -#if (PIOS_PWM_NUM_INPUTS > PIOS_RCVR_MAX_CHANNELS) -#error More receiver inputs than available devices -#endif - PIOS_PWM_Init(); + { + uint32_t pios_pwm_id; + PIOS_PWM_Init(&pios_pwm_id, &pios_pwm_cfg); + uint32_t pios_pwm_rcvr_id; - if (PIOS_RCVR_Init(&pios_pwm_rcvr_id, &pios_pwm_rcvr_driver, 0)) { - PIOS_Assert(0); + if (PIOS_RCVR_Init(&pios_pwm_rcvr_id, &pios_pwm_rcvr_driver, pios_pwm_id)) { + 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: + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PWM] = pios_pwm_rcvr_id; + } +#endif /* PIOS_INCLUDE_PWM */ + break; + case HWSETTINGS_OP_RCVRPORT_PPM: #if defined(PIOS_INCLUDE_PPM) -#if (PIOS_PPM_NUM_INPUTS > PIOS_RCVR_MAX_CHANNELS) -#error More receiver inputs than available devices -#endif - PIOS_PPM_Init(); + { + uint32_t pios_ppm_id; + PIOS_PPM_Init(&pios_ppm_id, &pios_ppm_cfg); + 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++; + if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id)) { + PIOS_Assert(0); } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PPM] = pios_ppm_rcvr_id; + } #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 - { - 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_id; - if (PIOS_SPEKTRUM_Init(&pios_spektrum_id, &pios_spektrum_cfg, &pios_usart_com_driver, pios_usart_spektrum_id, false)) { - 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; + break; } #if defined(PIOS_INCLUDE_USB_HID) diff --git a/flight/OpenPilot/System/pios_board_posix.c b/flight/OpenPilot/System/pios_board_posix.c index 2480d0730..bb1f7d5b2 100644 --- a/flight/OpenPilot/System/pios_board_posix.c +++ b/flight/OpenPilot/System/pios_board_posix.c @@ -29,10 +29,24 @@ #include #include +#include "hwsettings.h" +#include "attituderaw.h" +#include "attitudeactual.h" +#include "positionactual.h" +#include "velocityactual.h" +#include "manualcontrolsettings.h" + +#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; +/* One slot per selectable receiver group. + * eg. PWM, PPM, GCS, DSMMAINPORT, DSMFLEXIPORT, SBUS + * NOTE: No slot in this map for NONE. + */ +uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE]; + +#endif /* PIOS_INCLUDE_RCVR */ + void Stack_Change() { } @@ -66,6 +80,7 @@ const struct pios_udp_cfg pios_udp_aux_cfg = { #define PIOS_COM_TELEM_RF_RX_BUF_LEN 192 #define PIOS_COM_TELEM_RF_TX_BUF_LEN 192 +#define PIOS_COM_GPS_RX_BUF_LEN 96 /* * Board specific number of devices. @@ -154,7 +169,7 @@ void PIOS_Board_Init(void) { #if defined(PIOS_INCLUDE_GPS) { uint32_t pios_udp_gps_id; - if (PIOS_USART_Init(&pios_udp_gps_id, &pios_udp_gps_cfg)) { + if (PIOS_UDP_Init(&pios_udp_gps_id, &pios_udp_gps_cfg)) { PIOS_Assert(0); } uint8_t * rx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_GPS_RX_BUF_LEN); @@ -168,6 +183,12 @@ void PIOS_Board_Init(void) { #endif /* PIOS_INCLUDE_GPS */ #endif + // Initialize these here as posix has no AHRSComms + AttitudeRawInitialize(); + AttitudeActualInitialize(); + VelocityActualInitialize(); + PositionActualInitialize(); + HwSettingsInitialize(); } diff --git a/flight/OpenPilot/System/taskmonitor.c b/flight/OpenPilot/System/taskmonitor.c index d7fa3fde4..dcd08945c 100644 --- a/flight/OpenPilot/System/taskmonitor.c +++ b/flight/OpenPilot/System/taskmonitor.c @@ -46,7 +46,10 @@ int32_t TaskMonitorInitialize(void) { lock = xSemaphoreCreateRecursiveMutex(); memset(handles, 0, sizeof(xTaskHandle)*TASKINFO_RUNNING_NUMELEM); + lastMonitorTime = 0; +#if defined(DIAGNOSTICS) lastMonitorTime = portGET_RUN_TIME_COUNTER_VALUE(); +#endif return 0; } @@ -91,6 +94,7 @@ int32_t TaskMonitorRemove(TaskInfoRunningElem task) */ void TaskMonitorUpdateAll(void) { +#if defined(DIAGNOSTICS) TaskInfoData data; int n; @@ -142,4 +146,5 @@ void TaskMonitorUpdateAll(void) // Done xSemaphoreGiveRecursive(lock); +#endif } diff --git a/flight/OpenPilot/UAVObjects.inc b/flight/OpenPilot/UAVObjects.inc index 3eb2fa571..8d5c5409f 100644 --- a/flight/OpenPilot/UAVObjects.inc +++ b/flight/OpenPilot/UAVObjects.inc @@ -64,11 +64,14 @@ UAVOBJSRCFILENAMES += systemalarms UAVOBJSRCFILENAMES += systemsettings UAVOBJSRCFILENAMES += systemstats UAVOBJSRCFILENAMES += taskinfo -UAVOBJSRCFILENAMES += telemetrysettings UAVOBJSRCFILENAMES += velocityactual UAVOBJSRCFILENAMES += velocitydesired UAVOBJSRCFILENAMES += watchdogstatus UAVOBJSRCFILENAMES += flightstatus +UAVOBJSRCFILENAMES += hwsettings +UAVOBJSRCFILENAMES += receiveractivity +UAVOBJSRCFILENAMES += cameradesired +UAVOBJSRCFILENAMES += camerastabsettings UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(UAVOBJSYNTHDIR)/$(UAVOBJSRCFILE).c ) UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) ) diff --git a/flight/PiOS.posix/inc/pios_initcall.h b/flight/PiOS.posix/inc/pios_initcall.h index deb6e0eb6..f88081c33 100644 --- a/flight/PiOS.posix/inc/pios_initcall.h +++ b/flight/PiOS.posix/inc/pios_initcall.h @@ -51,7 +51,6 @@ 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 { \ diff --git a/flight/PiOS.posix/inc/pios_rcvr.h b/flight/PiOS.posix/inc/pios_rcvr.h index a32160894..ab493cd35 100644 --- a/flight/PiOS.posix/inc/pios_rcvr.h +++ b/flight/PiOS.posix/inc/pios_rcvr.h @@ -31,21 +31,24 @@ #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); + 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); +/*! Define error codes for PIOS_RCVR_Get */ +enum PIOS_RCVR_errors { + /*! Indicates that a failsafe condition or missing receiver detected for that channel */ + PIOS_RCVR_TIMEOUT = 0, + /*! Channel is invalid for this driver (usually out of range supported) */ + PIOS_RCVR_INVALID = -1, + /*! Indicates that the driver for this channel has not been initialized */ + PIOS_RCVR_NODRIVER = -2 +}; + #endif /* PIOS_RCVR_H */ /** diff --git a/flight/PiOS.posix/posix/pios_debug.c b/flight/PiOS.posix/posix/pios_debug.c index f79f2e730..5956a9d04 100644 --- a/flight/PiOS.posix/posix/pios_debug.c +++ b/flight/PiOS.posix/posix/pios_debug.c @@ -79,8 +79,15 @@ void PIOS_DEBUG_Panic(const char *msg) PIOS_COM_SendFormattedStringNonBlocking(PIOS_COM_DEBUG, "\r%s @0x%x\r", msg, lr); #endif - // Stay put - while (1) ; + // tell the user whats going on on commandline too + fprintf(stderr,"CRITICAL ERROR: %s\n",msg); + + // this helps debugging: causing a div by zero allows a backtrace + // and/or ends execution + int b = 0; + int a = (2/b); + b=a; + } /** diff --git a/flight/PiOS.posix/posix/pios_rcvr.c b/flight/PiOS.posix/posix/pios_rcvr.c index 652730547..719cb9769 100644 --- a/flight/PiOS.posix/posix/pios_rcvr.c +++ b/flight/PiOS.posix/posix/pios_rcvr.c @@ -21,32 +21,39 @@ static bool PIOS_RCVR_validate(struct pios_rcvr_dev * rcvr_dev) } #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); -} +//static struct pios_rcvr_dev * PIOS_RCVR_alloc(void) +//{ +// struct pios_rcvr_dev * rcvr_dev; +// +// rcvr_dev = (struct pios_rcvr_dev *)pvPortMalloc(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) +static uint32_t PIOS_RCVR_alloc(void) { struct pios_rcvr_dev * rcvr_dev; if (pios_rcvr_num_devs >= PIOS_RCVR_MAX_DEVS) { - return (NULL); + return (PIOS_RCVR_MAX_DEVS+1); } rcvr_dev = &pios_rcvr_devs[pios_rcvr_num_devs++]; rcvr_dev->magic = PIOS_RCVR_DEV_MAGIC; - return (rcvr_dev); + return (pios_rcvr_num_devs); } +static struct pios_rcvr_dev * PIOS_RCVR_find_dev(uint32_t rcvr_dev_id) +{ + if (!rcvr_dev_id) return NULL; + if (rcvr_dev_id>pios_rcvr_num_devs+1) return NULL; + return &pios_rcvr_devs[rcvr_dev_id-1]; +} + #endif /** @@ -56,35 +63,53 @@ static struct pios_rcvr_dev * PIOS_RCVR_alloc(void) * \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) +int32_t PIOS_RCVR_Init(uint32_t * rcvr_id, const struct pios_rcvr_driver * driver, uint32_t lower_id) { PIOS_DEBUG_Assert(rcvr_id); PIOS_DEBUG_Assert(driver); + uint32_t rcvr_dev_id; struct pios_rcvr_dev * rcvr_dev; - rcvr_dev = (struct pios_rcvr_dev *) PIOS_RCVR_alloc(); + rcvr_dev_id = PIOS_RCVR_alloc(); + rcvr_dev = PIOS_RCVR_find_dev(rcvr_dev_id); if (!rcvr_dev) goto out_fail; rcvr_dev->driver = driver; rcvr_dev->lower_id = lower_id; - - *rcvr_id = pios_rcvr_num_devs - 1; - + *rcvr_id = rcvr_dev_id; return(0); out_fail: return(-1); } +/** + * @brief Reads an input channel from the appropriate driver + * @param[in] rcvr_id driver to read from + * @param[in] channel channel to read + * @returns Unitless input value + * @retval PIOS_RCVR_TIMEOUT indicates a failsafe or timeout from that channel + * @retval PIOS_RCVR_INVALID invalid channel for this driver (usually out of range supported) + * @retval PIOS_RCVR_NODRIVER driver was not initialized + */ int32_t PIOS_RCVR_Read(uint32_t rcvr_id, uint8_t channel) { - struct pios_rcvr_dev * rcvr_dev = &pios_rcvr_devs[rcvr_id]; + // Publicly facing API uses channel 1 for first channel + if(channel == 0) + return PIOS_RCVR_INVALID; + else + channel--; + + if (rcvr_id == 0) + return PIOS_RCVR_NODRIVER; + + struct pios_rcvr_dev * rcvr_dev = PIOS_RCVR_find_dev(rcvr_id); if (!PIOS_RCVR_validate(rcvr_dev)) { /* Undefined RCVR port for this board (see pios_board.c) */ - PIOS_DEBUG_Assert(0); + PIOS_Assert(0); } PIOS_DEBUG_Assert(rcvr_dev->driver->read); diff --git a/flight/PiOS.posix/posix/pios_udp.c b/flight/PiOS.posix/posix/pios_udp.c index 39077b455..5ccbae767 100644 --- a/flight/PiOS.posix/posix/pios_udp.c +++ b/flight/PiOS.posix/posix/pios_udp.c @@ -64,6 +64,7 @@ static pios_udp_dev * find_udp_dev_by_id (uint8_t udp) { if (udp >= pios_udp_num_devices) { /* Undefined UDP port for this board (see pios_board.c) */ + PIOS_Assert(0); return NULL; } @@ -154,6 +155,8 @@ int32_t PIOS_UDP_Init(uint32_t * udp_id, const struct pios_udp_cfg * cfg) printf("udp dev %i - socket %i opened - result %i\n",pios_udp_num_devices-1,udp_dev->socket,res); + *udp_id = pios_udp_num_devices-1; + return res; } @@ -191,7 +194,7 @@ static void PIOS_UDP_TxStart(uint32_t udp_id, uint16_t tx_bytes_avail) length = (udp_dev->tx_out_cb)(udp_dev->tx_out_context, udp_dev->tx_buffer, PIOS_UDP_RX_BUFFER_SIZE, NULL, &tx_need_yield); rem = length; while (rem>0) { - len = sendto(udp_dev->socket, udp_dev->tx_buffer, length, 0, + len = sendto(udp_dev->socket, udp_dev->tx_buffer+length-rem, rem, 0, (struct sockaddr *) &udp_dev->client, sizeof(udp_dev->client)); if (len<=0) { diff --git a/flight/PiOS.win32/inc/pios_initcall.h b/flight/PiOS.win32/inc/pios_initcall.h index f370f27ee..bdb47cc8e 100644 --- a/flight/PiOS.win32/inc/pios_initcall.h +++ b/flight/PiOS.win32/inc/pios_initcall.h @@ -38,8 +38,7 @@ * and we cannot define a linker script for each of them atm */ -#define UAVOBJ_INITCALL(fn) -#define MODULE_INITCALL(ifn, iparam, sfn, sparam, flags) +#define MODULE_INITCALL(ifn, sfn) #define MODULE_TASKCREATE_ALL diff --git a/flight/PiOS/Boards/STM32103CB_CC_Rev1.h b/flight/PiOS/Boards/STM32103CB_CC_Rev1.h index 18e0da624..1a8a17c89 100644 --- a/flight/PiOS/Boards/STM32103CB_CC_Rev1.h +++ b/flight/PiOS/Boards/STM32103CB_CC_Rev1.h @@ -206,23 +206,32 @@ extern uint32_t pios_com_telem_usb_id; // PIOS_RCVR // See also pios_board.c //------------------------ -#define PIOS_RCVR_MAX_DEVS 1 +#define PIOS_RCVR_MAX_DEVS 3 #define PIOS_RCVR_MAX_CHANNELS 12 //------------------------- // Receiver PPM input //------------------------- +#define PIOS_PPM_MAX_DEVS 1 #define PIOS_PPM_NUM_INPUTS 12 //------------------------- // Receiver PWM input //------------------------- +#define PIOS_PWM_MAX_DEVS 1 #define PIOS_PWM_NUM_INPUTS 6 //------------------------- -// Receiver SPEKTRUM input +// Receiver DSM input //------------------------- -#define PIOS_SPEKTRUM_NUM_INPUTS 12 +#define PIOS_DSM_MAX_DEVS 2 +#define PIOS_DSM_NUM_INPUTS 12 + +//------------------------- +// Receiver S.Bus input +//------------------------- +#define PIOS_SBUS_MAX_DEVS 1 +#define PIOS_SBUS_NUM_INPUTS (16+2) //------------------------- // Servo outputs @@ -230,6 +239,11 @@ extern uint32_t pios_com_telem_usb_id; #define PIOS_SERVO_UPDATE_HZ 50 #define PIOS_SERVOS_INITIAL_POSITION 0 /* dont want to start motors, have no pulse till settings loaded */ +//-------------------------- +// Timer controller settings +//-------------------------- +#define PIOS_TIM_MAX_DEVS 3 + //------------------------- // GPIO //------------------------- diff --git a/flight/PiOS/Boards/STM3210E_OP.h b/flight/PiOS/Boards/STM3210E_OP.h index 3098ee259..c82bb8fe8 100644 --- a/flight/PiOS/Boards/STM3210E_OP.h +++ b/flight/PiOS/Boards/STM3210E_OP.h @@ -185,17 +185,26 @@ extern uint32_t pios_com_aux_id; //------------------------- // Receiver PPM input //------------------------- +#define PIOS_PPM_MAX_DEVS 1 #define PIOS_PPM_NUM_INPUTS 12 //------------------------- // Receiver PWM input //------------------------- +#define PIOS_PWM_MAX_DEVS 1 #define PIOS_PWM_NUM_INPUTS 8 //------------------------- -// Receiver SPEKTRUM input +// Receiver DSM input //------------------------- -#define PIOS_SPEKTRUM_NUM_INPUTS 12 +#define PIOS_DSM_MAX_DEVS 1 +#define PIOS_DSM_NUM_INPUTS 12 + +//------------------------- +// Receiver S.Bus input +//------------------------- +#define PIOS_SBUS_MAX_DEVS 0 +#define PIOS_SBUS_NUM_INPUTS (16+2) //------------------------- // Servo outputs @@ -203,6 +212,11 @@ extern uint32_t pios_com_aux_id; #define PIOS_SERVO_UPDATE_HZ 50 #define PIOS_SERVOS_INITIAL_POSITION 0 /* dont want to start motors, have no pulse till settings loaded */ +//-------------------------- +// Timer controller settings +//-------------------------- +#define PIOS_TIM_MAX_DEVS 3 + //------------------------- // ADC // PIOS_ADC_PinGet(0) = Temperature Sensor (On-board) diff --git a/flight/PiOS/Common/pios_com.c b/flight/PiOS/Common/pios_com.c index b7a9a67e5..e7fba8867 100644 --- a/flight/PiOS/Common/pios_com.c +++ b/flight/PiOS/Common/pios_com.c @@ -67,12 +67,12 @@ static bool PIOS_COM_validate(struct pios_com_dev * com_dev) return (com_dev && (com_dev->magic == PIOS_COM_DEV_MAGIC)); } -#if defined(PIOS_INCLUDE_FREERTOS) && 0 +#if defined(PIOS_INCLUDE_FREERTOS) static struct pios_com_dev * PIOS_COM_alloc(void) { struct pios_com_dev * com_dev; - com_dev = (struct pios_com_dev *)malloc(sizeof(*com_dev)); + com_dev = (struct pios_com_dev *)pvPortMalloc(sizeof(*com_dev)); if (!com_dev) return (NULL); com_dev->magic = PIOS_COM_DEV_MAGIC; diff --git a/flight/PiOS/Common/pios_flashfs_objlist.c b/flight/PiOS/Common/pios_flashfs_objlist.c index 08fe640c9..e02683657 100644 --- a/flight/PiOS/Common/pios_flashfs_objlist.c +++ b/flight/PiOS/Common/pios_flashfs_objlist.c @@ -56,12 +56,12 @@ struct fileHeader { } __attribute__((packed)); -#define OBJECT_TABLE_MAGIC 0x85FB3C35 -#define OBJ_MAGIC 0x3015AE71 +#define OBJECT_TABLE_MAGIC 0x85FB3D35 +#define OBJ_MAGIC 0x3015A371 #define OBJECT_TABLE_START 0x00000010 #define OBJECT_TABLE_END 0x00001000 #define SECTOR_SIZE 0x00001000 -#define MAX_BADMAGIC 4 +#define MAX_BADMAGIC 1000 /** * @brief Initialize the flash object setting FS @@ -72,7 +72,7 @@ int32_t PIOS_FLASHFS_Init() // Check for valid object table or create one uint32_t object_table_magic; - uint8_t magic_fail_count = 0; + uint32_t magic_fail_count = 0; bool magic_good = false; while(!magic_good) { @@ -85,7 +85,7 @@ int32_t PIOS_FLASHFS_Init() magic_fail_count = 0; magic_good = true; } else { - PIOS_DELAY_WaituS(100); + PIOS_DELAY_WaituS(1000); } } @@ -116,6 +116,19 @@ int32_t PIOS_FLASHFS_Init() return 0; } +/** + * @brief Erase the whole flash chip and create the file system + * @return 0 if successful, -1 if not + */ +int32_t PIOS_FLASHFS_Format() +{ + if(PIOS_Flash_W25X_EraseChip() != 0) + return -1; + if(PIOS_FLASHFS_ClearObjectTableHeader() != 0) + return -1; + return 0; +} + /** * @brief Erase the headers for all objects in the flash chip * @return 0 if successful, -1 if not diff --git a/flight/PiOS/Common/pios_gcsrcvr.c b/flight/PiOS/Common/pios_gcsrcvr.c new file mode 100644 index 000000000..18e6644a6 --- /dev/null +++ b/flight/PiOS/Common/pios_gcsrcvr.c @@ -0,0 +1,75 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_GCSRCVR GCS Receiver Input Functions + * @brief Code to read the channels within the GCS Receiver UAVObject + * @{ + * + * @file pios_gcsrcvr.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief GCS Input functions (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" + +#if defined(PIOS_INCLUDE_GCSRCVR) + +#include "pios_gcsrcvr_priv.h" + +static GCSReceiverData gcsreceiverdata; + +/* Provide a RCVR driver */ +static int32_t PIOS_GCSRCVR_Get(uint32_t rcvr_id, uint8_t channel); + +const struct pios_rcvr_driver pios_gcsrcvr_rcvr_driver = { + .read = PIOS_GCSRCVR_Get, +}; + +static void gcsreceiver_updated(UAVObjEvent * ev) +{ + if (ev->obj == GCSReceiverHandle()) { + GCSReceiverGet(&gcsreceiverdata); + } +} + +void PIOS_GCSRCVR_Init(void) +{ + /* Register uavobj callback */ + GCSReceiverConnectCallback (gcsreceiver_updated); +} + +static int32_t PIOS_GCSRCVR_Get(uint32_t rcvr_id, uint8_t channel) +{ + if (channel >= GCSRECEIVER_CHANNEL_NUMELEM) { + /* channel is out of range */ + return -1; + } + + return (gcsreceiverdata.Channel[channel]); +} + +#endif /* PIOS_INCLUDE_GCSRCVR */ + +/** + * @} + * @} + */ diff --git a/flight/PiOS/Common/pios_hcsr04.c b/flight/PiOS/Common/pios_hcsr04.c index 6db1bc401..cbdb31e7e 100644 --- a/flight/PiOS/Common/pios_hcsr04.c +++ b/flight/PiOS/Common/pios_hcsr04.c @@ -32,8 +32,8 @@ #include "pios.h" #if defined(PIOS_INCLUDE_HCSR04) -#if !(defined(PIOS_INCLUDE_SPEKTRUM) || defined(PIOS_INCLUDE_SBUS)) -#error Only supported with Spektrum or S.Bus interface! +#if !(defined(PIOS_INCLUDE_DSM) || defined(PIOS_INCLUDE_SBUS)) +#error Only supported with Spektrum/JR DSM or S.Bus interface! #endif /* Local Variables */ diff --git a/flight/PiOS/Common/pios_rcvr.c b/flight/PiOS/Common/pios_rcvr.c index 29acb2594..0f3988d7f 100644 --- a/flight/PiOS/Common/pios_rcvr.c +++ b/flight/PiOS/Common/pios_rcvr.c @@ -20,12 +20,12 @@ 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 +#if defined(PIOS_INCLUDE_FREERTOS) 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)); + rcvr_dev = (struct pios_rcvr_dev *)pvPortMalloc(sizeof(*rcvr_dev)); if (!rcvr_dev) return (NULL); rcvr_dev->magic = PIOS_RCVR_DEV_MAGIC; @@ -76,8 +76,26 @@ out_fail: return(-1); } +/** + * @brief Reads an input channel from the appropriate driver + * @param[in] rcvr_id driver to read from + * @param[in] channel channel to read + * @returns Unitless input value + * @retval PIOS_RCVR_TIMEOUT indicates a failsafe or timeout from that channel + * @retval PIOS_RCVR_INVALID invalid channel for this driver (usually out of range supported) + * @retval PIOS_RCVR_NODRIVER driver was not initialized + */ int32_t PIOS_RCVR_Read(uint32_t rcvr_id, uint8_t channel) { + // Publicly facing API uses channel 1 for first channel + if(channel == 0) + return PIOS_RCVR_INVALID; + else + channel--; + + if (rcvr_id == 0) + return PIOS_RCVR_NODRIVER; + struct pios_rcvr_dev * rcvr_dev = (struct pios_rcvr_dev *)rcvr_id; if (!PIOS_RCVR_validate(rcvr_dev)) { diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_tim.h b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_tim.h index 6529c0b0a..388d276e4 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_tim.h +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/inc/stm32f10x_tim.h @@ -1025,12 +1025,12 @@ typedef struct */ void TIM_DeInit(TIM_TypeDef* TIMx); -void TIM_TimeBaseInit(TIM_TypeDef* TIMx, TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct); -void TIM_OC1Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct); -void TIM_OC2Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct); -void TIM_OC3Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct); -void TIM_OC4Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct); -void TIM_ICInit(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct); +void TIM_TimeBaseInit(TIM_TypeDef* TIMx, const TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct); +void TIM_OC1Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_OC2Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_OC3Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_OC4Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct); +void TIM_ICInit(TIM_TypeDef* TIMx, const TIM_ICInitTypeDef* TIM_ICInitStruct); void TIM_PWMIConfig(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct); void TIM_BDTRConfig(TIM_TypeDef* TIMx, TIM_BDTRInitTypeDef *TIM_BDTRInitStruct); void TIM_TimeBaseStructInit(TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct); diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_tim.c b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_tim.c index 780105589..2f31c9a1a 100755 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_tim.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_tim.c @@ -221,7 +221,7 @@ void TIM_DeInit(TIM_TypeDef* TIMx) * structure that contains the configuration information for the specified TIM peripheral. * @retval None */ -void TIM_TimeBaseInit(TIM_TypeDef* TIMx, TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct) +void TIM_TimeBaseInit(TIM_TypeDef* TIMx, const TIM_TimeBaseInitTypeDef* TIM_TimeBaseInitStruct) { uint16_t tmpcr1 = 0; @@ -274,7 +274,7 @@ void TIM_TimeBaseInit(TIM_TypeDef* TIMx, TIM_TimeBaseInitTypeDef* TIM_TimeBaseIn * that contains the configuration information for the specified TIM peripheral. * @retval None */ -void TIM_OC1Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct) +void TIM_OC1Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct) { uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; @@ -357,7 +357,7 @@ void TIM_OC1Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct) * that contains the configuration information for the specified TIM peripheral. * @retval None */ -void TIM_OC2Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct) +void TIM_OC2Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct) { uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; @@ -439,7 +439,7 @@ void TIM_OC2Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct) * that contains the configuration information for the specified TIM peripheral. * @retval None */ -void TIM_OC3Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct) +void TIM_OC3Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct) { uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; @@ -518,7 +518,7 @@ void TIM_OC3Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct) * that contains the configuration information for the specified TIM peripheral. * @retval None */ -void TIM_OC4Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct) +void TIM_OC4Init(TIM_TypeDef* TIMx, const TIM_OCInitTypeDef* TIM_OCInitStruct) { uint16_t tmpccmrx = 0, tmpccer = 0, tmpcr2 = 0; @@ -582,7 +582,7 @@ void TIM_OC4Init(TIM_TypeDef* TIMx, TIM_OCInitTypeDef* TIM_OCInitStruct) * that contains the configuration information for the specified TIM peripheral. * @retval None */ -void TIM_ICInit(TIM_TypeDef* TIMx, TIM_ICInitTypeDef* TIM_ICInitStruct) +void TIM_ICInit(TIM_TypeDef* TIMx, const TIM_ICInitTypeDef* TIM_ICInitStruct) { /* Check the parameters */ assert_param(IS_TIM_CHANNEL(TIM_ICInitStruct->TIM_Channel)); diff --git a/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_BL_sections.ld b/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_BL_sections.ld index f818fff42..777e09aa6 100644 --- a/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_BL_sections.ld +++ b/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_BL_sections.ld @@ -18,16 +18,6 @@ SECTIONS *(.rodata .rodata* .gnu.linkonce.r.*) } > BL_FLASH - /* init sections */ - .initcalluavobj.init : - { - . = ALIGN(4); - __uavobj_initcall_start = .; - KEEP(*(.initcalluavobj.init)) - . = ALIGN(4); - __uavobj_initcall_end = .; - } > BL_FLASH - .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) diff --git a/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_sections.ld b/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_sections.ld index d2c4abb17..d3e9f797e 100644 --- a/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_sections.ld +++ b/flight/PiOS/STM32F10x/link_STM32103CB_CC_Rev1_sections.ld @@ -1,5 +1,5 @@ /* This is the size of the stack for all FreeRTOS IRQs */ -_irq_stack_size = 0x180; +_irq_stack_size = 0x1E6; /* This is the size of the stack for early init: life span is until scheduler starts */ _init_stack_size = 0x100; @@ -22,16 +22,6 @@ SECTIONS *(.rodata .rodata* .gnu.linkonce.r.*) } > FLASH - /* init sections */ - .initcalluavobj.init : - { - . = ALIGN(4); - __uavobj_initcall_start = .; - KEEP(*(.initcalluavobj.init)) - . = ALIGN(4); - __uavobj_initcall_end = .; - } >FLASH - /* module sections */ .initcallmodule.init : { diff --git a/flight/PiOS/STM32F10x/link_STM3210E_INS_BL_sections.ld b/flight/PiOS/STM32F10x/link_STM3210E_INS_BL_sections.ld index 1b3c11e34..3420c385e 100644 --- a/flight/PiOS/STM32F10x/link_STM3210E_INS_BL_sections.ld +++ b/flight/PiOS/STM32F10x/link_STM3210E_INS_BL_sections.ld @@ -207,16 +207,6 @@ SECTIONS } > BL_FLASH - /* init sections */ - .initcalluavobj.init : - { - . = ALIGN(4); - __uavobj_initcall_start = .; - KEEP(*(.initcalluavobj.init)) - . = ALIGN(4); - __uavobj_initcall_end = .; - } > BL_FLASH - /* the program code is stored in the .text section, which goes to Flash */ .text : { diff --git a/flight/PiOS/STM32F10x/link_STM3210E_INS_sections.ld b/flight/PiOS/STM32F10x/link_STM3210E_INS_sections.ld index ef25c9344..bcf498dd0 100644 --- a/flight/PiOS/STM32F10x/link_STM3210E_INS_sections.ld +++ b/flight/PiOS/STM32F10x/link_STM3210E_INS_sections.ld @@ -206,16 +206,6 @@ SECTIONS . = ALIGN(4); } > FLASH - - /* init sections */ - .initcalluavobj.init : - { - . = ALIGN(4); - __uavobj_initcall_start = .; - KEEP(*(.initcalluavobj.init)) - . = ALIGN(4); - __uavobj_initcall_end = .; - } > FLASH /* the program code is stored in the .text section, which goes to Flash */ .text : diff --git a/flight/PiOS/STM32F10x/link_STM3210E_OP_BL_sections.ld b/flight/PiOS/STM32F10x/link_STM3210E_OP_BL_sections.ld index 7716ccbf2..9cd7c8b4b 100644 --- a/flight/PiOS/STM32F10x/link_STM3210E_OP_BL_sections.ld +++ b/flight/PiOS/STM32F10x/link_STM3210E_OP_BL_sections.ld @@ -179,17 +179,6 @@ SECTIONS . = ALIGN(4); } > BL_FLASH - - /* init sections */ - .initcalluavobj.init : - { - . = ALIGN(4); - __uavobj_initcall_start = .; - KEEP(*(.initcalluavobj.init)) - . = ALIGN(4); - __uavobj_initcall_end = .; - } > BL_FLASH - /* the program code is stored in the .text section, which goes to Flash */ .text : { diff --git a/flight/PiOS/STM32F10x/link_STM3210E_OP_sections.ld b/flight/PiOS/STM32F10x/link_STM3210E_OP_sections.ld index 87a65d7c1..066fa01ee 100644 --- a/flight/PiOS/STM32F10x/link_STM3210E_OP_sections.ld +++ b/flight/PiOS/STM32F10x/link_STM3210E_OP_sections.ld @@ -1,7 +1,7 @@ /* This is the size of the stack for early init and for all FreeRTOS IRQs */ -_irq_stack_size = 0x400; +_irq_stack_size = 0x800; /* This is the size of the stack for early init: life span is until scheduler starts */ -_init_stack_size = 0x400; +_init_stack_size = 0x800; /* Check valid alignment for VTOR */ ASSERT(ORIGIN(FLASH) == ALIGN(ORIGIN(FLASH), 0x80), "Start of memory region flash not aligned for startup vector table"); @@ -181,17 +181,6 @@ SECTIONS *(.flashtext) /* Startup code */ . = ALIGN(4); } >FLASH - - - /* init sections */ - .initcalluavobj.init : - { - . = ALIGN(4); - __uavobj_initcall_start = .; - KEEP(*(.initcalluavobj.init)) - . = ALIGN(4); - __uavobj_initcall_end = .; - } >FLASH /* module sections */ .initcallmodule.init : diff --git a/flight/PiOS/STM32F10x/pios_debug.c b/flight/PiOS/STM32F10x/pios_debug.c index ca4f67dc5..18ea0071b 100644 --- a/flight/PiOS/STM32F10x/pios_debug.c +++ b/flight/PiOS/STM32F10x/pios_debug.c @@ -34,39 +34,41 @@ // Global variables const char *PIOS_DEBUG_AssertMsg = "ASSERT FAILED"; -#include -extern const struct pios_servo_channel pios_servo_channels[]; -#define PIOS_SERVO_GPIO_PORT_1TO4 pios_servo_channels[0].port -#define PIOS_SERVO_GPIO_PORT_5TO8 pios_servo_channels[4].port -#define PIOS_SERVO_GPIO_PIN_1 pios_servo_channels[0].pin -#define PIOS_SERVO_GPIO_PIN_2 pios_servo_channels[1].pin -#define PIOS_SERVO_GPIO_PIN_3 pios_servo_channels[2].pin -#define PIOS_SERVO_GPIO_PIN_4 pios_servo_channels[3].pin -#define PIOS_SERVO_GPIO_PIN_5 pios_servo_channels[4].pin -#define PIOS_SERVO_GPIO_PIN_6 pios_servo_channels[5].pin -#define PIOS_SERVO_GPIO_PIN_7 pios_servo_channels[6].pin -#define PIOS_SERVO_GPIO_PIN_8 pios_servo_channels[7].pin -/* Private Function Prototypes */ +#ifdef PIOS_ENABLE_DEBUG_PINS +static const struct pios_tim_channel * debug_channels; +static uint8_t debug_num_channels; +#endif /* PIOS_ENABLE_DEBUG_PINS */ /** * Initialise Debug-features */ -void PIOS_DEBUG_Init(void) +void PIOS_DEBUG_Init(const struct pios_tim_channel * channels, uint8_t num_channels) { #ifdef PIOS_ENABLE_DEBUG_PINS - // Initialise Servo pins as standard output pins - GPIO_InitTypeDef GPIO_InitStructure; - GPIO_StructInit(&GPIO_InitStructure); - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; - GPIO_InitStructure.GPIO_Pin = PIOS_SERVO_GPIO_PIN_1 | PIOS_SERVO_GPIO_PIN_2 | PIOS_SERVO_GPIO_PIN_3 | PIOS_SERVO_GPIO_PIN_4; - GPIO_Init(PIOS_SERVO_GPIO_PORT_1TO4, &GPIO_InitStructure); - GPIO_InitStructure.GPIO_Pin = PIOS_SERVO_GPIO_PIN_5 | PIOS_SERVO_GPIO_PIN_6 | PIOS_SERVO_GPIO_PIN_7 | PIOS_SERVO_GPIO_PIN_8; - GPIO_Init(PIOS_SERVO_GPIO_PORT_5TO8, &GPIO_InitStructure); + PIOS_Assert(channels); + PIOS_Assert(num_channels); - // Drive all pins low - PIOS_SERVO_GPIO_PORT_1TO4->BRR = PIOS_SERVO_GPIO_PIN_1 | PIOS_SERVO_GPIO_PIN_2 | PIOS_SERVO_GPIO_PIN_3 | PIOS_SERVO_GPIO_PIN_4; - PIOS_SERVO_GPIO_PORT_5TO8->BRR = PIOS_SERVO_GPIO_PIN_5 | PIOS_SERVO_GPIO_PIN_6 | PIOS_SERVO_GPIO_PIN_7 | PIOS_SERVO_GPIO_PIN_8; + /* Store away the GPIOs we've been given */ + debug_channels = channels; + debug_num_channels = num_channels; + + /* Configure the GPIOs we've been given */ + for (uint8_t i = 0; i < num_channels; i++) { + const struct pios_tim_channel * chan = &channels[i]; + + // Initialise pins as standard output pins + GPIO_InitTypeDef GPIO_InitStructure; + GPIO_StructInit(&GPIO_InitStructure); + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP; + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; + GPIO_InitStructure.GPIO_Pin = chan->init->GPIO_Pin; + + /* Initialize the GPIO */ + GPIO_Init(chan->init->port, &GPIO_InitStructure); + + /* Set the pin low */ + GPIO_WriteBit(chan->init->port, chan->init->GPIO_Pin, Bit_RESET); + } #endif // PIOS_ENABLE_DEBUG_PINS } @@ -74,14 +76,17 @@ void PIOS_DEBUG_Init(void) * Set debug-pin high * \param pin 0 for S1 output */ -void PIOS_DEBUG_PinHigh(uint8_t Pin) +void PIOS_DEBUG_PinHigh(uint8_t pin) { #ifdef PIOS_ENABLE_DEBUG_PINS - if (Pin < 4) { - PIOS_SERVO_GPIO_PORT_1TO4->BSRR = (PIOS_SERVO_GPIO_PIN_1 << Pin); - } else if (Pin <= 7) { - PIOS_SERVO_GPIO_PORT_5TO8->BSRR = (PIOS_SERVO_GPIO_PIN_5 << (Pin - 4)); + if (!debug_channels || pin >= debug_num_channels) { + return; } + + const struct pios_tim_channel * chan = &debug_channels[pin]; + + GPIO_WriteBit(chan->init->port, chan->init->GPIO_Pin, Bit_Set); + #endif // PIOS_ENABLE_DEBUG_PINS } @@ -89,14 +94,17 @@ void PIOS_DEBUG_PinHigh(uint8_t Pin) * Set debug-pin low * \param pin 0 for S1 output */ -void PIOS_DEBUG_PinLow(uint8_t Pin) +void PIOS_DEBUG_PinLow(uint8_t pin) { #ifdef PIOS_ENABLE_DEBUG_PINS - if (Pin < 4) { - PIOS_SERVO_GPIO_PORT_1TO4->BRR = (PIOS_SERVO_GPIO_PIN_1 << Pin); - } else if (Pin <= 7) { - PIOS_SERVO_GPIO_PORT_5TO8->BRR = (PIOS_SERVO_GPIO_PIN_5 << (Pin - 4)); + if (!debug_channels || pin >= debug_num_channels) { + return; } + + const struct pios_tim_channel * chan = &debug_channels[pin]; + + GPIO_WriteBit(chan->init->port, chan->init->GPIO_Pin, Bit_RESET); + #endif // PIOS_ENABLE_DEBUG_PINS } @@ -104,11 +112,22 @@ void PIOS_DEBUG_PinLow(uint8_t Pin) void PIOS_DEBUG_PinValue8Bit(uint8_t value) { #ifdef PIOS_ENABLE_DEBUG_PINS + if (!debug_channels) { + return; + } + uint32_t bsrr_l = ( ((~value)&0x0F)<<(16+6) ) | ((value & 0x0F)<<6); uint32_t bsrr_h = ( ((~value)&0xF0)<<(16+6-4) ) | ((value & 0xF0)<<(6-4)); + PIOS_IRQ_Disable(); - PIOS_SERVO_GPIO_PORT_1TO4->BSRR = bsrr_l; - PIOS_SERVO_GPIO_PORT_5TO8->BSRR = bsrr_h; + + /* + * This is sketchy since it assumes a particular ordering + * and bitwise layout of the channels provided to the debug code. + */ + debug_channels[0].init.port->BSRR = bsrr_l; + debug_channels[4].init.port->BSRR = bsrr_h; + PIOS_IRQ_Enable(); #endif // PIOS_ENABLE_DEBUG_PINS } @@ -116,8 +135,16 @@ void PIOS_DEBUG_PinValue8Bit(uint8_t value) void PIOS_DEBUG_PinValue4BitL(uint8_t value) { #ifdef PIOS_ENABLE_DEBUG_PINS + if (!debug_channels) { + return; + } + + /* + * This is sketchy since it assumes a particular ordering + * and bitwise layout of the channels provided to the debug code. + */ uint32_t bsrr_l = ((~(value & 0x0F)<<(16+6))) | ((value & 0x0F)<<6); - PIOS_SERVO_GPIO_PORT_1TO4->BSRR = bsrr_l; + debug_channels[0].init.port->BSRR = bsrr_l; #endif // PIOS_ENABLE_DEBUG_PINS } diff --git a/flight/PiOS/STM32F10x/pios_dsm.c b/flight/PiOS/STM32F10x/pios_dsm.c new file mode 100644 index 000000000..cb838b56b --- /dev/null +++ b/flight/PiOS/STM32F10x/pios_dsm.c @@ -0,0 +1,407 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_DSM Spektrum/JR DSMx satellite receiver functions + * @brief Code to bind and read Spektrum/JR DSMx satellite receiver serial stream + * @{ + * + * @file pios_dsm.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. + * @brief Code bind and read Spektrum/JR DSMx satellite receiver serial stream + * @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_dsm_priv.h" + +#if defined(PIOS_INCLUDE_DSM) + +/* Forward Declarations */ +static int32_t PIOS_DSM_Get(uint32_t rcvr_id, uint8_t channel); +static uint16_t PIOS_DSM_RxInCallback(uint32_t context, + uint8_t *buf, + uint16_t buf_len, + uint16_t *headroom, + bool *need_yield); +static void PIOS_DSM_Supervisor(uint32_t dsm_id); + +/* Local Variables */ +const struct pios_rcvr_driver pios_dsm_rcvr_driver = { + .read = PIOS_DSM_Get, +}; + +enum pios_dsm_dev_magic { + PIOS_DSM_DEV_MAGIC = 0x44534d78, +}; + +struct pios_dsm_state { + uint16_t channel_data[PIOS_DSM_NUM_INPUTS]; + uint8_t received_data[DSM_FRAME_LENGTH]; + uint8_t receive_timer; + uint8_t failsafe_timer; + uint8_t frame_found; + uint8_t byte_count; +#ifdef DSM_LOST_FRAME_COUNTER + uint8_t frames_lost_last; + uint16_t frames_lost; +#endif +}; + +struct pios_dsm_dev { + enum pios_dsm_dev_magic magic; + const struct pios_dsm_cfg *cfg; + enum pios_dsm_proto proto; + struct pios_dsm_state state; +}; + +/* Allocate DSM device descriptor */ +#if defined(PIOS_INCLUDE_FREERTOS) +static struct pios_dsm_dev *PIOS_DSM_Alloc(void) +{ + struct pios_dsm_dev *dsm_dev; + + dsm_dev = (struct pios_dsm_dev *)pvPortMalloc(sizeof(*dsm_dev)); + if (!dsm_dev) + return NULL; + + dsm_dev->magic = PIOS_DSM_DEV_MAGIC; + return dsm_dev; +} +#else +static struct pios_dsm_dev pios_dsm_devs[PIOS_DSM_MAX_DEVS]; +static uint8_t pios_dsm_num_devs; +static struct pios_dsm_dev *PIOS_DSM_Alloc(void) +{ + struct pios_dsm_dev *dsm_dev; + + if (pios_dsm_num_devs >= PIOS_DSM_MAX_DEVS) + return NULL; + + dsm_dev = &pios_dsm_devs[pios_dsm_num_devs++]; + dsm_dev->magic = PIOS_DSM_DEV_MAGIC; + + return dsm_dev; +} +#endif + +/* Validate DSM device descriptor */ +static bool PIOS_DSM_Validate(struct pios_dsm_dev *dsm_dev) +{ + return (dsm_dev->magic == PIOS_DSM_DEV_MAGIC); +} + +/* Try to bind DSMx satellite using specified number of pulses */ +static void PIOS_DSM_Bind(struct pios_dsm_dev *dsm_dev, uint8_t bind) +{ + const struct pios_dsm_cfg *cfg = dsm_dev->cfg; + + GPIO_InitTypeDef GPIO_InitStructure; + GPIO_InitStructure.GPIO_Pin = cfg->bind.init.GPIO_Pin; + GPIO_InitStructure.GPIO_Speed = cfg->bind.init.GPIO_Speed; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPU; + + /* just to limit bind pulses */ + if (bind > 10) + bind = 10; + + 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 up to 140ms, guess bind window is around 20-140ms after power up */ + PIOS_DELAY_WaitmS(60); + + for (int i = 0; i < bind ; 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 */ + GPIO_Init(cfg->bind.gpio, &GPIO_InitStructure); +} + +/* Reset channels in case of lost signal or explicit failsafe receiver flag */ +static void PIOS_DSM_ResetChannels(struct pios_dsm_dev *dsm_dev) +{ + struct pios_dsm_state *state = &(dsm_dev->state); + for (int i = 0; i < PIOS_DSM_NUM_INPUTS; i++) { + state->channel_data[i] = PIOS_RCVR_TIMEOUT; + } +} + +/* Reset DSM receiver state */ +static void PIOS_DSM_ResetState(struct pios_dsm_dev *dsm_dev) +{ + struct pios_dsm_state *state = &(dsm_dev->state); + state->receive_timer = 0; + state->failsafe_timer = 0; + state->frame_found = 0; +#ifdef DSM_LOST_FRAME_COUNTER + state->frames_lost_last = 0; + state->frames_lost = 0; +#endif + PIOS_DSM_ResetChannels(dsm_dev); +} + +/** + * Check and unroll complete frame data. + * \output 0 frame data accepted + * \output -1 frame error found + */ +static int PIOS_DSM_UnrollChannels(struct pios_dsm_dev *dsm_dev) +{ + struct pios_dsm_state *state = &(dsm_dev->state); + uint8_t resolution; + +#ifdef DSM_LOST_FRAME_COUNTER + /* increment the lost frame counter */ + uint8_t frames_lost = state->received_data[0]; + state->frames_lost += (frames_lost - state->frames_lost_last); + state->frames_lost_last = frames_lost; +#endif + + /* check the frame type assuming master satellite stream */ + uint8_t type = state->received_data[1]; + switch (type) { + case 0x01: + case 0x02: + case 0x12: + /* DSM2, DSMJ stream */ + if (dsm_dev->proto == PIOS_DSM_PROTO_DSM2) { + /* DSM2/DSMJ resolution is known from the header */ + resolution = (type & DSM_DSM2_RES_MASK) ? 11 : 10; + } else { + /* DSMX resolution should explicitly be selected */ + goto stream_error; + } + break; + case 0xA2: + case 0xB2: + /* DSMX stream */ + if (dsm_dev->proto == PIOS_DSM_PROTO_DSMX10BIT) { + resolution = 10; + } else if (dsm_dev->proto == PIOS_DSM_PROTO_DSMX11BIT) { + resolution = 11; + } else { + /* DSMX resolution should explicitly be selected */ + goto stream_error; + } + break; + default: + /* unknown yet data stream */ + goto stream_error; + } + + /* unroll channels */ + uint8_t *s = &(state->received_data[2]); + uint16_t mask = (resolution == 10) ? 0x03ff : 0x07ff; + + for (int i = 0; i < DSM_CHANNELS_PER_FRAME; i++) { + uint16_t word = ((uint16_t)s[0] << 8) | s[1]; + s += 2; + + /* skip empty channel slot */ + if (word == 0xffff) + continue; + + /* minimal data validation */ + if ((i > 0) && (word & DSM_2ND_FRAME_MASK)) { + /* invalid frame data, ignore rest of the frame */ + goto stream_error; + } + + /* extract and save the channel value */ + uint8_t channel_num = (word >> resolution) & 0x0f; + if (channel_num < PIOS_DSM_NUM_INPUTS) + state->channel_data[channel_num] = (word & mask); + } + +#ifdef DSM_LOST_FRAME_COUNTER + /* put lost frames counter into the last channel for debugging */ + state->channel_data[PIOS_DSM_NUM_INPUTS-1] = state->frames_lost; +#endif + + /* all channels processed */ + return 0; + +stream_error: + /* either DSM2 selected with DSMX stream found, or vice-versa */ + return -1; +} + +/* Update decoder state processing input byte from the DSMx stream */ +static void PIOS_DSM_UpdateState(struct pios_dsm_dev *dsm_dev, uint8_t byte) +{ + struct pios_dsm_state *state = &(dsm_dev->state); + if (state->frame_found) { + /* receiving the data frame */ + if (state->byte_count < DSM_FRAME_LENGTH) { + /* store next byte */ + state->received_data[state->byte_count++] = byte; + if (state->byte_count == DSM_FRAME_LENGTH) { + /* full frame received - process and wait for new one */ + if (!PIOS_DSM_UnrollChannels(dsm_dev)) + /* data looking good */ + state->failsafe_timer = 0; + + /* prepare for the next frame */ + state->frame_found = 0; + } + } + } +} + +/* Initialise DSM receiver interface */ +int32_t PIOS_DSM_Init(uint32_t *dsm_id, + const struct pios_dsm_cfg *cfg, + const struct pios_com_driver *driver, + uint32_t lower_id, + enum pios_dsm_proto proto, + uint8_t bind) +{ + PIOS_DEBUG_Assert(dsm_id); + PIOS_DEBUG_Assert(cfg); + PIOS_DEBUG_Assert(driver); + + struct pios_dsm_dev *dsm_dev; + + dsm_dev = (struct pios_dsm_dev *)PIOS_DSM_Alloc(); + if (!dsm_dev) + return -1; + + /* Bind the configuration to the device instance */ + dsm_dev->cfg = cfg; + dsm_dev->proto = proto; + + /* Bind the receiver if requested */ + if (bind) + PIOS_DSM_Bind(dsm_dev, bind); + + PIOS_DSM_ResetState(dsm_dev); + + *dsm_id = (uint32_t)dsm_dev; + + /* Set comm driver callback */ + (driver->bind_rx_cb)(lower_id, PIOS_DSM_RxInCallback, *dsm_id); + + if (!PIOS_RTC_RegisterTickCallback(PIOS_DSM_Supervisor, *dsm_id)) { + PIOS_DEBUG_Assert(0); + } + + return 0; +} + +/* Comm byte received callback */ +static uint16_t PIOS_DSM_RxInCallback(uint32_t context, + uint8_t *buf, + uint16_t buf_len, + uint16_t *headroom, + bool *need_yield) +{ + struct pios_dsm_dev *dsm_dev = (struct pios_dsm_dev *)context; + + bool valid = PIOS_DSM_Validate(dsm_dev); + PIOS_Assert(valid); + + /* process byte(s) and clear receive timer */ + for (uint8_t i = 0; i < buf_len; i++) { + PIOS_DSM_UpdateState(dsm_dev, buf[i]); + dsm_dev->state.receive_timer = 0; + } + + /* Always signal that we can accept another byte */ + if (headroom) + *headroom = DSM_FRAME_LENGTH; + + /* We never need a yield */ + *need_yield = false; + + /* Always indicate that all bytes were consumed */ + return buf_len; +} + +/** + * Get the value of an input channel + * \param[in] channel Number of the channel desired (zero based) + * \output PIOS_RCVR_INVALID channel not available + * \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver + * \output >0 channel value + */ +static int32_t PIOS_DSM_Get(uint32_t rcvr_id, uint8_t channel) +{ + struct pios_dsm_dev *dsm_dev = (struct pios_dsm_dev *)rcvr_id; + + if (!PIOS_DSM_Validate(dsm_dev)) + return PIOS_RCVR_INVALID; + + /* return error if channel is not available */ + if (channel >= PIOS_DSM_NUM_INPUTS) + return PIOS_RCVR_INVALID; + + /* may also be PIOS_RCVR_TIMEOUT set by other function */ + return dsm_dev->state.channel_data[channel]; +} + +/** + * Input data supervisor is called periodically and provides + * two functions: frame syncing and failsafe triggering. + * + * DSM frames come at 11ms or 22ms rate at 115200bps. + * RTC timer is running at 625Hz (1.6ms). So with divider 5 it gives + * 8ms pause between frames which is good for both DSM frame 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_DSM_Supervisor(uint32_t dsm_id) +{ + struct pios_dsm_dev *dsm_dev = (struct pios_dsm_dev *)dsm_id; + + bool valid = PIOS_DSM_Validate(dsm_dev); + PIOS_Assert(valid); + + struct pios_dsm_state *state = &(dsm_dev->state); + + /* waiting for new frame if no bytes were received in 8ms */ + if (++state->receive_timer > 4) { + state->frame_found = 1; + state->byte_count = 0; + state->receive_timer = 0; + } + + /* activate failsafe if no frames have arrived in 102.4ms */ + if (++state->failsafe_timer > 64) { + PIOS_DSM_ResetChannels(dsm_dev); + state->failsafe_timer = 0; + } +} + +#endif /* PIOS_INCLUDE_DSM */ + +/** + * @} + * @} + */ diff --git a/flight/PiOS/STM32F10x/pios_i2c.c b/flight/PiOS/STM32F10x/pios_i2c.c index 0d47fd117..6e623d597 100644 --- a/flight/PiOS/STM32F10x/pios_i2c.c +++ b/flight/PiOS/STM32F10x/pios_i2c.c @@ -823,12 +823,12 @@ static bool PIOS_I2C_validate(struct pios_i2c_adapter * i2c_adapter) return (i2c_adapter->magic == PIOS_I2C_DEV_MAGIC); } -#if defined(PIOS_INCLUDE_FREERTOS) && 0 -static struct pios_i2c_dev * PIOS_I2C_alloc(void) +#if defined(PIOS_INCLUDE_FREERTOS) +static struct pios_i2c_adapter * PIOS_I2C_alloc(void) { - struct pios_i2c_dev * i2c_adapter; + struct pios_i2c_adapter * i2c_adapter; - i2c_adapter = (struct pios_i2c_adapter *)malloc(sizeof(*i2c_adapter)); + i2c_adapter = (struct pios_i2c_adapter *)pvPortMalloc(sizeof(*i2c_adapter)); if (!i2c_adapter) return(NULL); i2c_adapter->magic = PIOS_I2C_DEV_MAGIC; diff --git a/flight/PiOS/STM32F10x/pios_ppm.c b/flight/PiOS/STM32F10x/pios_ppm.c index fe7421a17..aea1016d3 100644 --- a/flight/PiOS/STM32F10x/pios_ppm.c +++ b/flight/PiOS/STM32F10x/pios_ppm.c @@ -47,108 +47,139 @@ const struct pios_rcvr_driver pios_ppm_rcvr_driver = { #define PIOS_PPM_IN_MIN_SYNC_PULSE_US 3800 // microseconds #define PIOS_PPM_IN_MIN_CHANNEL_PULSE_US 750 // microseconds #define PIOS_PPM_IN_MAX_CHANNEL_PULSE_US 2250 // microseconds -#define PIOS_PPM_INPUT_INVALID 0 /* Local Variables */ static TIM_ICInitTypeDef TIM_ICInitStructure; -static uint8_t PulseIndex; -static uint32_t PreviousTime; -static uint32_t CurrentTime; -static uint32_t DeltaTime; -static uint32_t CaptureValue[PIOS_PPM_IN_MAX_NUM_CHANNELS]; -static uint32_t CaptureValueNewFrame[PIOS_PPM_IN_MAX_NUM_CHANNELS]; -static uint32_t LargeCounter; -static int8_t NumChannels; -static int8_t NumChannelsPrevFrame; -static uint8_t NumChannelCounter; - -static uint8_t supv_timer = 0; -static bool Tracking; -static bool Fresh; static void PIOS_PPM_Supervisor(uint32_t ppm_id); -void PIOS_PPM_Init(void) +enum pios_ppm_dev_magic { + PIOS_PPM_DEV_MAGIC = 0xee014d8b, +}; + +struct pios_ppm_dev { + enum pios_ppm_dev_magic magic; + const struct pios_ppm_cfg * cfg; + + uint8_t PulseIndex; + uint32_t PreviousTime; + uint32_t CurrentTime; + uint32_t DeltaTime; + uint32_t CaptureValue[PIOS_PPM_IN_MAX_NUM_CHANNELS]; + uint32_t CaptureValueNewFrame[PIOS_PPM_IN_MAX_NUM_CHANNELS]; + uint32_t LargeCounter; + int8_t NumChannels; + int8_t NumChannelsPrevFrame; + uint8_t NumChannelCounter; + + uint8_t supv_timer; + bool Tracking; + bool Fresh; +}; + +static bool PIOS_PPM_validate(struct pios_ppm_dev * ppm_dev) { - /* Flush counter variables */ - int32_t i; + return (ppm_dev->magic == PIOS_PPM_DEV_MAGIC); +} - PulseIndex = 0; - PreviousTime = 0; - CurrentTime = 0; - DeltaTime = 0; - LargeCounter = 0; - NumChannels = -1; - NumChannelsPrevFrame = -1; - NumChannelCounter = 0; - Tracking = FALSE; - Fresh = FALSE; +#if defined(PIOS_INCLUDE_FREERTOS) +static struct pios_ppm_dev * PIOS_PPM_alloc(void) +{ + struct pios_ppm_dev * ppm_dev; - for (i = 0; i < PIOS_PPM_IN_MAX_NUM_CHANNELS; i++) { - CaptureValue[i] = 0; - CaptureValueNewFrame[i] = 0; + ppm_dev = (struct pios_ppm_dev *)pvPortMalloc(sizeof(*ppm_dev)); + if (!ppm_dev) return(NULL); + + ppm_dev->magic = PIOS_PPM_DEV_MAGIC; + return(ppm_dev); +} +#else +static struct pios_ppm_dev pios_ppm_devs[PIOS_PPM_MAX_DEVS]; +static uint8_t pios_ppm_num_devs; +static struct pios_ppm_dev * PIOS_PPM_alloc(void) +{ + struct pios_ppm_dev * ppm_dev; + + if (pios_ppm_num_devs >= PIOS_PPM_MAX_DEVS) { + return (NULL); } - NVIC_InitTypeDef NVIC_InitStructure = pios_ppm_cfg.irq.init; + ppm_dev = &pios_ppm_devs[pios_ppm_num_devs++]; + ppm_dev->magic = PIOS_PPM_DEV_MAGIC; - /* Enable appropriate clock to timer module */ - switch((int32_t) pios_ppm_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; + return (ppm_dev); +} #endif + +static void PIOS_PPM_tim_overflow_cb (uint32_t id, uint32_t context, uint8_t channel, uint16_t count); +static void PIOS_PPM_tim_edge_cb (uint32_t id, uint32_t context, uint8_t channel, uint16_t count); +const static struct pios_tim_callbacks tim_callbacks = { + .overflow = PIOS_PPM_tim_overflow_cb, + .edge = PIOS_PPM_tim_edge_cb, +}; + +extern int32_t PIOS_PPM_Init(uint32_t * ppm_id, const struct pios_ppm_cfg * cfg) +{ + PIOS_DEBUG_Assert(ppm_id); + PIOS_DEBUG_Assert(cfg); + + struct pios_ppm_dev * ppm_dev; + + ppm_dev = (struct pios_ppm_dev *) PIOS_PPM_alloc(); + if (!ppm_dev) goto out_fail; + + /* Bind the configuration to the device instance */ + ppm_dev->cfg = cfg; + + /* Set up the state variables */ + ppm_dev->PulseIndex = 0; + ppm_dev->PreviousTime = 0; + ppm_dev->CurrentTime = 0; + ppm_dev->DeltaTime = 0; + ppm_dev->LargeCounter = 0; + ppm_dev->NumChannels = -1; + ppm_dev->NumChannelsPrevFrame = -1; + ppm_dev->NumChannelCounter = 0; + ppm_dev->Tracking = FALSE; + ppm_dev->Fresh = FALSE; + + for (uint8_t i = 0; i < PIOS_PPM_IN_MAX_NUM_CHANNELS; i++) { + /* Flush counter variables */ + ppm_dev->CaptureValue[i] = 0; + ppm_dev->CaptureValueNewFrame[i] = 0; + } - /* Enable timer interrupts */ - NVIC_Init(&NVIC_InitStructure); - /* Configure input pins */ - GPIO_InitTypeDef GPIO_InitStructure = pios_ppm_cfg.gpio_init; - GPIO_Init(pios_ppm_cfg.port, &GPIO_InitStructure); + uint32_t tim_id; + if (PIOS_TIM_InitChannels(&tim_id, cfg->channels, cfg->num_channels, &tim_callbacks, (uint32_t)ppm_dev)) { + return -1; + } - /* Configure timer for input capture */ - TIM_ICInitStructure = pios_ppm_cfg.tim_ic_init; - TIM_ICInit(pios_ppm_cfg.timer, &TIM_ICInitStructure); + /* Configure the channels to be in capture/compare mode */ + for (uint8_t i = 0; i < cfg->num_channels; i++) { + const struct pios_tim_channel * chan = &cfg->channels[i]; - /* Configure timer clocks */ - TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure = pios_ppm_cfg.tim_base_init; - TIM_InternalClockConfig(pios_ppm_cfg.timer); - TIM_TimeBaseInit(pios_ppm_cfg.timer, &TIM_TimeBaseStructure); + /* Configure timer for input capture */ + TIM_ICInitTypeDef TIM_ICInitStructure = cfg->tim_ic_init; + TIM_ICInitStructure.TIM_Channel = chan->timer_chan; + TIM_ICInit(chan->timer, &TIM_ICInitStructure); - /* Enable the Capture Compare Interrupt Request */ - TIM_ITConfig(pios_ppm_cfg.timer, pios_ppm_cfg.ccr | TIM_IT_Update, ENABLE); - - /* Enable timers */ - TIM_Cmd(pios_ppm_cfg.timer, ENABLE); + /* Enable the Capture Compare Interrupt Request */ + switch (chan->timer_chan) { + case TIM_Channel_1: + TIM_ITConfig(chan->timer, TIM_IT_CC1 | TIM_IT_Update, ENABLE); + break; + case TIM_Channel_2: + TIM_ITConfig(chan->timer, TIM_IT_CC2 | TIM_IT_Update, ENABLE); + break; + case TIM_Channel_3: + TIM_ITConfig(chan->timer, TIM_IT_CC3 | TIM_IT_Update, ENABLE); + break; + case TIM_Channel_4: + TIM_ITConfig(chan->timer, TIM_IT_CC4 | TIM_IT_Update, ENABLE); + break; + } + } /* Setup local variable which stays in this scope */ /* Doing this here and using a local variable saves doing it in the ISR */ @@ -156,9 +187,16 @@ void PIOS_PPM_Init(void) TIM_ICInitStructure.TIM_ICPrescaler = TIM_ICPSC_DIV1; TIM_ICInitStructure.TIM_ICFilter = 0x0; - if (!PIOS_RTC_RegisterTickCallback(PIOS_PPM_Supervisor, 0)) { + if (!PIOS_RTC_RegisterTickCallback(PIOS_PPM_Supervisor, (uint32_t)ppm_dev)) { PIOS_DEBUG_Assert(0); } + + *ppm_id = (uint32_t)ppm_dev; + + return(0); + +out_fail: + return(-1); } /** @@ -169,142 +207,146 @@ void PIOS_PPM_Init(void) */ static int32_t PIOS_PPM_Get(uint32_t rcvr_id, uint8_t channel) { - /* Return error if channel not available */ - if (channel >= PIOS_PPM_IN_MAX_NUM_CHANNELS) { - return -1; + struct pios_ppm_dev * ppm_dev = (struct pios_ppm_dev *)rcvr_id; + + if (!PIOS_PPM_validate(ppm_dev)) { + /* Invalid device specified */ + return PIOS_RCVR_INVALID; } - return CaptureValue[channel]; + + if (channel >= PIOS_PPM_IN_MAX_NUM_CHANNELS) { + /* Channel out of range */ + return PIOS_RCVR_INVALID; + } + return ppm_dev->CaptureValue[channel]; } -/** -* Handle TIMx global interrupt request -* Some work and testing still needed, need to detect start of frame and decode pulses -* -*/ -void PIOS_PPM_irq_handler(void) +static void PIOS_PPM_tim_overflow_cb (uint32_t tim_id, uint32_t context, uint8_t channel, uint16_t count) { - /* Timer Overflow Interrupt - * The time between timer overflows must be greater than the PPM - * frame period. If a full frame has not decoded in the between timer - * overflows then capture values should be cleared. - */ + struct pios_ppm_dev * ppm_dev = (struct pios_ppm_dev *)context; - if (TIM_GetITStatus(pios_ppm_cfg.timer, TIM_IT_Update) == SET) { - /* Clear TIMx overflow interrupt pending bit */ - TIM_ClearITPendingBit(pios_ppm_cfg.timer, TIM_IT_Update); - - /* If sharing a timer with a servo output the ARR register will - be set according to the PWM period. When timer reaches the - ARR value a timer overflow interrupt will fire. We use the - interrupt accumulate a 32-bit timer. */ - LargeCounter = LargeCounter + pios_ppm_cfg.timer->ARR; + if (!PIOS_PPM_validate(ppm_dev)) { + /* Invalid device specified */ + return; } - /* Signal edge interrupt */ - if (TIM_GetITStatus(pios_ppm_cfg.timer, pios_ppm_cfg.ccr) == SET) { - PreviousTime = CurrentTime; + ppm_dev->LargeCounter += count; - switch((int32_t) pios_ppm_cfg.ccr) { - case (int32_t)TIM_IT_CC1: - CurrentTime = TIM_GetCapture1(pios_ppm_cfg.timer); - break; - case (int32_t)TIM_IT_CC2: - CurrentTime = TIM_GetCapture2(pios_ppm_cfg.timer); - break; - case (int32_t)TIM_IT_CC3: - CurrentTime = TIM_GetCapture3(pios_ppm_cfg.timer); - break; - case (int32_t)TIM_IT_CC4: - CurrentTime = TIM_GetCapture4(pios_ppm_cfg.timer); - break; + return; +} + + +static void PIOS_PPM_tim_edge_cb (uint32_t tim_id, uint32_t context, uint8_t chan_idx, uint16_t count) +{ + /* Recover our device context */ + struct pios_ppm_dev * ppm_dev = (struct pios_ppm_dev *)context; + + if (!PIOS_PPM_validate(ppm_dev)) { + /* Invalid device specified */ + return; + } + + if (chan_idx >= ppm_dev->cfg->num_channels) { + /* Channel out of range */ + return; + } + + /* Shift the last measurement out */ + ppm_dev->PreviousTime = ppm_dev->CurrentTime; + + /* Grab the new count */ + ppm_dev->CurrentTime = count; + + /* Convert to 32-bit timer result */ + ppm_dev->CurrentTime += ppm_dev->LargeCounter; + + /* Capture computation */ + ppm_dev->DeltaTime = ppm_dev->CurrentTime - ppm_dev->PreviousTime; + + ppm_dev->PreviousTime = ppm_dev->CurrentTime; + + /* Sync pulse detection */ + if (ppm_dev->DeltaTime > PIOS_PPM_IN_MIN_SYNC_PULSE_US) { + if (ppm_dev->PulseIndex == ppm_dev->NumChannelsPrevFrame + && ppm_dev->PulseIndex >= PIOS_PPM_IN_MIN_NUM_CHANNELS + && ppm_dev->PulseIndex <= PIOS_PPM_IN_MAX_NUM_CHANNELS) + { + /* If we see n simultaneous frames of the same + number of channels we save it as our frame size */ + if (ppm_dev->NumChannelCounter < PIOS_PPM_STABLE_CHANNEL_COUNT) + ppm_dev->NumChannelCounter++; + else + ppm_dev->NumChannels = ppm_dev->PulseIndex; + } else { + ppm_dev->NumChannelCounter = 0; } - /* Clear TIMx Capture compare interrupt pending bit */ - TIM_ClearITPendingBit(pios_ppm_cfg.timer, pios_ppm_cfg.ccr); - - /* Convert to 32-bit timer result */ - CurrentTime = CurrentTime + LargeCounter; - - /* Capture computation */ - DeltaTime = CurrentTime - PreviousTime; - - PreviousTime = CurrentTime; - - /* Sync pulse detection */ - if (DeltaTime > PIOS_PPM_IN_MIN_SYNC_PULSE_US) { - if (PulseIndex == NumChannelsPrevFrame - && PulseIndex >= PIOS_PPM_IN_MIN_NUM_CHANNELS - && PulseIndex <= PIOS_PPM_IN_MAX_NUM_CHANNELS) - { - /* If we see n simultaneous frames of the same - number of channels we save it as our frame size */ - if (NumChannelCounter < PIOS_PPM_STABLE_CHANNEL_COUNT) - NumChannelCounter++; - else - NumChannels = PulseIndex; - } else { - NumChannelCounter = 0; + /* Check if the last frame was well formed */ + if (ppm_dev->PulseIndex == ppm_dev->NumChannels && ppm_dev->Tracking) { + /* The last frame was well formed */ + for (uint32_t i = 0; i < ppm_dev->NumChannels; i++) { + ppm_dev->CaptureValue[i] = ppm_dev->CaptureValueNewFrame[i]; } - - /* Check if the last frame was well formed */ - if (PulseIndex == NumChannels && Tracking) { - /* The last frame was well formed */ - for (uint32_t i = 0; i < NumChannels; i++) { - CaptureValue[i] = CaptureValueNewFrame[i]; - } - for (uint32_t i = NumChannels; - i < PIOS_PPM_IN_MAX_NUM_CHANNELS; i++) { - CaptureValue[i] = PIOS_PPM_INPUT_INVALID; - } + for (uint32_t i = ppm_dev->NumChannels; + i < PIOS_PPM_IN_MAX_NUM_CHANNELS; i++) { + ppm_dev->CaptureValue[i] = PIOS_RCVR_TIMEOUT; } + } - Fresh = TRUE; - Tracking = TRUE; - NumChannelsPrevFrame = PulseIndex; - PulseIndex = 0; + ppm_dev->Fresh = TRUE; + ppm_dev->Tracking = TRUE; + ppm_dev->NumChannelsPrevFrame = ppm_dev->PulseIndex; + ppm_dev->PulseIndex = 0; - /* We rely on the supervisor to set CaptureValue to invalid - if no valid frame is found otherwise we ride over it */ + /* We rely on the supervisor to set CaptureValue to invalid + if no valid frame is found otherwise we ride over it */ - } else if (Tracking) { - /* Valid pulse duration 0.75 to 2.5 ms*/ - if (DeltaTime > PIOS_PPM_IN_MIN_CHANNEL_PULSE_US - && DeltaTime < PIOS_PPM_IN_MAX_CHANNEL_PULSE_US - && PulseIndex < PIOS_PPM_IN_MAX_NUM_CHANNELS) { - - CaptureValueNewFrame[PulseIndex] = DeltaTime; - PulseIndex++; - } else { - /* Not a valid pulse duration */ - Tracking = FALSE; - for (uint32_t i = 0; i < PIOS_PPM_IN_MAX_NUM_CHANNELS ; i++) { - CaptureValueNewFrame[i] = PIOS_PPM_INPUT_INVALID; - } + } else if (ppm_dev->Tracking) { + /* Valid pulse duration 0.75 to 2.5 ms*/ + if (ppm_dev->DeltaTime > PIOS_PPM_IN_MIN_CHANNEL_PULSE_US + && ppm_dev->DeltaTime < PIOS_PPM_IN_MAX_CHANNEL_PULSE_US + && ppm_dev->PulseIndex < PIOS_PPM_IN_MAX_NUM_CHANNELS) { + + ppm_dev->CaptureValueNewFrame[ppm_dev->PulseIndex] = ppm_dev->DeltaTime; + ppm_dev->PulseIndex++; + } else { + /* Not a valid pulse duration */ + ppm_dev->Tracking = FALSE; + for (uint32_t i = 0; i < PIOS_PPM_IN_MAX_NUM_CHANNELS ; i++) { + ppm_dev->CaptureValueNewFrame[i] = PIOS_RCVR_TIMEOUT; } } } } static void PIOS_PPM_Supervisor(uint32_t ppm_id) { + /* Recover our device context */ + struct pios_ppm_dev * ppm_dev = (struct pios_ppm_dev *)ppm_id; + + if (!PIOS_PPM_validate(ppm_dev)) { + /* Invalid device specified */ + return; + } + /* * RTC runs at 625Hz so divide down the base rate so * that this loop runs at 25Hz. */ - if(++supv_timer < 25) { + if(++(ppm_dev->supv_timer) < 25) { return; } - supv_timer = 0; + ppm_dev->supv_timer = 0; - if (!Fresh) { - Tracking = FALSE; + if (!ppm_dev->Fresh) { + ppm_dev->Tracking = FALSE; for (int32_t i = 0; i < PIOS_PPM_IN_MAX_NUM_CHANNELS ; i++) { - CaptureValue[i] = PIOS_PPM_INPUT_INVALID; - CaptureValueNewFrame[i] = PIOS_PPM_INPUT_INVALID; + ppm_dev->CaptureValue[i] = PIOS_RCVR_TIMEOUT; + ppm_dev->CaptureValueNewFrame[i] = PIOS_RCVR_TIMEOUT; } } - Fresh = FALSE; + ppm_dev->Fresh = FALSE; } #endif diff --git a/flight/PiOS/STM32F10x/pios_pwm.c b/flight/PiOS/STM32F10x/pios_pwm.c index 433c272bb..4e7c98b14 100644 --- a/flight/PiOS/STM32F10x/pios_pwm.c +++ b/flight/PiOS/STM32F10x/pios_pwm.c @@ -42,96 +42,131 @@ const struct pios_rcvr_driver pios_pwm_rcvr_driver = { }; /* 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]; +/* 100 ms timeout without updates on channels */ +const static uint32_t PWM_SUPERVISOR_TIMEOUT = 100000; -static uint32_t CapCounter[PIOS_PWM_NUM_INPUTS]; +enum pios_pwm_dev_magic { + PIOS_PWM_DEV_MAGIC = 0xab30293c, +}; + +struct pios_pwm_dev { + enum pios_pwm_dev_magic magic; + const struct pios_pwm_cfg * cfg; + + uint8_t CaptureState[PIOS_PWM_NUM_INPUTS]; + uint16_t RiseValue[PIOS_PWM_NUM_INPUTS]; + uint16_t FallValue[PIOS_PWM_NUM_INPUTS]; + uint32_t CaptureValue[PIOS_PWM_NUM_INPUTS]; + uint32_t CapCounter[PIOS_PWM_NUM_INPUTS]; + uint32_t us_since_update[PIOS_PWM_NUM_INPUTS]; +}; + +static bool PIOS_PWM_validate(struct pios_pwm_dev * pwm_dev) +{ + return (pwm_dev->magic == PIOS_PWM_DEV_MAGIC); +} + +#if defined(PIOS_INCLUDE_FREERTOS) +static struct pios_pwm_dev * PIOS_PWM_alloc(void) +{ + struct pios_pwm_dev * pwm_dev; + + pwm_dev = (struct pios_pwm_dev *)pvPortMalloc(sizeof(*pwm_dev)); + if (!pwm_dev) return(NULL); + + pwm_dev->magic = PIOS_PWM_DEV_MAGIC; + return(pwm_dev); +} +#else +static struct pios_pwm_dev pios_pwm_devs[PIOS_PWM_MAX_DEVS]; +static uint8_t pios_pwm_num_devs; +static struct pios_pwm_dev * PIOS_PWM_alloc(void) +{ + struct pios_pwm_dev * pwm_dev; + + if (pios_pwm_num_devs >= PIOS_PWM_MAX_DEVS) { + return (NULL); + } + + pwm_dev = &pios_pwm_devs[pios_pwm_num_devs++]; + pwm_dev->magic = PIOS_PWM_DEV_MAGIC; + + return (pwm_dev); +} +#endif + +static void PIOS_PWM_tim_overflow_cb (uint32_t id, uint32_t context, uint8_t channel, uint16_t count); +static void PIOS_PWM_tim_edge_cb (uint32_t id, uint32_t context, uint8_t channel, uint16_t count); +const static struct pios_tim_callbacks tim_callbacks = { + .overflow = PIOS_PWM_tim_overflow_cb, + .edge = PIOS_PWM_tim_edge_cb, +}; /** * Initialises all the pins */ -void PIOS_PWM_Init(void) +int32_t PIOS_PWM_Init(uint32_t * pwm_id, const struct pios_pwm_cfg * cfg) { - for (uint8_t i = 0; i < pios_pwm_cfg.num_channels; i++) { - /* Flush counter variables */ - CaptureState[i] = 0; - RiseValue[i] = 0; - FallValue[i] = 0; - CaptureValue[i] = 0; - - NVIC_InitTypeDef NVIC_InitStructure = pios_pwm_cfg.irq.init; - GPIO_InitTypeDef GPIO_InitStructure = pios_pwm_cfg.gpio_init; - TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure = pios_pwm_cfg.tim_base_init; - TIM_ICInitTypeDef TIM_ICInitStructure = pios_pwm_cfg.tim_ic_init; - - struct pios_pwm_channel channel = pios_pwm_cfg.channels[i]; - - /* Enable appropriate clock to timer module */ - switch((int32_t) channel.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 - } - NVIC_Init(&NVIC_InitStructure); + PIOS_DEBUG_Assert(pwm_id); + PIOS_DEBUG_Assert(cfg); + + struct pios_pwm_dev * pwm_dev; + + pwm_dev = (struct pios_pwm_dev *) PIOS_PWM_alloc(); + if (!pwm_dev) goto out_fail; + + /* Bind the configuration to the device instance */ + pwm_dev->cfg = cfg; + + for (uint8_t i = 0; i < PIOS_PWM_NUM_INPUTS; i++) { + /* Flush counter variables */ + pwm_dev->CaptureState[i] = 0; + pwm_dev->RiseValue[i] = 0; + pwm_dev->FallValue[i] = 0; + pwm_dev->CaptureValue[i] = PIOS_RCVR_TIMEOUT; + } + + uint32_t tim_id; + if (PIOS_TIM_InitChannels(&tim_id, cfg->channels, cfg->num_channels, &tim_callbacks, (uint32_t)pwm_dev)) { + return -1; + } + + /* Configure the channels to be in capture/compare mode */ + for (uint8_t i = 0; i < cfg->num_channels; i++) { + const struct pios_tim_channel * chan = &cfg->channels[i]; - /* Enable GPIO */ - GPIO_InitStructure.GPIO_Pin = channel.pin; - GPIO_Init(channel.port, &GPIO_InitStructure); - /* Configure timer for input capture */ - TIM_ICInitStructure.TIM_Channel = channel.channel; - TIM_ICInit(channel.timer, &TIM_ICInitStructure); - - /* Configure timer clocks */ - TIM_InternalClockConfig(channel.timer); - if(channel.timer->PSC != ((PIOS_MASTER_CLOCK / 1000000) - 1)) - TIM_TimeBaseInit(channel.timer, &TIM_TimeBaseStructure); + TIM_ICInitTypeDef TIM_ICInitStructure = cfg->tim_ic_init; + TIM_ICInitStructure.TIM_Channel = chan->timer_chan; + TIM_ICInit(chan->timer, &TIM_ICInitStructure); /* Enable the Capture Compare Interrupt Request */ - TIM_ITConfig(channel.timer, channel.ccr, ENABLE); + switch (chan->timer_chan) { + case TIM_Channel_1: + TIM_ITConfig(chan->timer, TIM_IT_CC1, ENABLE); + break; + case TIM_Channel_2: + TIM_ITConfig(chan->timer, TIM_IT_CC2, ENABLE); + break; + case TIM_Channel_3: + TIM_ITConfig(chan->timer, TIM_IT_CC3, ENABLE); + break; + case TIM_Channel_4: + TIM_ITConfig(chan->timer, TIM_IT_CC4, ENABLE); + break; + } + + // Need the update event for that timer to detect timeouts + TIM_ITConfig(chan->timer, TIM_IT_Update, ENABLE); - /* Enable timers */ - TIM_Cmd(channel.timer, ENABLE); } - if(pios_pwm_cfg.remap) { - /* Warning, I don't think this will work for multiple remaps at once */ - GPIO_PinRemapConfig(pios_pwm_cfg.remap, ENABLE); - } + *pwm_id = (uint32_t) pwm_dev; + + return (0); + +out_fail: + return (-1); } /** @@ -142,75 +177,101 @@ void PIOS_PWM_Init(void) */ 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) { - return -1; + struct pios_pwm_dev * pwm_dev = (struct pios_pwm_dev *)rcvr_id; + + if (!PIOS_PWM_validate(pwm_dev)) { + /* Invalid device specified */ + return PIOS_RCVR_INVALID; } - return CaptureValue[channel]; + + if (channel >= PIOS_PWM_NUM_INPUTS) { + /* Channel out of range */ + return PIOS_RCVR_INVALID; + } + return pwm_dev->CaptureValue[channel]; } -void PIOS_PWM_irq_handler(TIM_TypeDef * timer) +static void PIOS_PWM_tim_overflow_cb (uint32_t tim_id, uint32_t context, uint8_t channel, uint16_t count) { - uint16_t val = 0; - for(uint8_t i = 0; i < pios_pwm_cfg.num_channels; i++) { - struct pios_pwm_channel channel = pios_pwm_cfg.channels[i]; - if ((channel.timer == timer) && (TIM_GetITStatus(channel.timer, channel.ccr) == SET)) { - - TIM_ClearITPendingBit(channel.timer, channel.ccr); - - switch(channel.channel) { - case TIM_Channel_1: - val = TIM_GetCapture1(channel.timer); - break; - case TIM_Channel_2: - val = TIM_GetCapture2(channel.timer); - break; - case TIM_Channel_3: - val = TIM_GetCapture3(channel.timer); - break; - case TIM_Channel_4: - val = TIM_GetCapture4(channel.timer); - break; - } - - if (CaptureState[i] == 0) { - RiseValue[i] = val; - } else { - FallValue[i] = val; - } - - // flip state machine and capture value here - /* Simple rise or fall state machine */ - TIM_ICInitTypeDef TIM_ICInitStructure = pios_pwm_cfg.tim_ic_init; - if (CaptureState[i] == 0) { - /* Switch states */ - CaptureState[i] = 1; - - /* Switch polarity of input capture */ - TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Falling; - TIM_ICInitStructure.TIM_Channel = channel.channel; - TIM_ICInit(channel.timer, &TIM_ICInitStructure); - } else { - /* Capture computation */ - if (FallValue[i] > RiseValue[i]) { - CaptureValue[i] = (FallValue[i] - RiseValue[i]); - } else { - CaptureValue[i] = ((channel.timer->ARR - RiseValue[i]) + FallValue[i]); - } - - /* Switch states */ - CaptureState[i] = 0; - - /* Increase supervisor counter */ - CapCounter[i]++; - - /* Switch polarity of input capture */ - TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Rising; - TIM_ICInitStructure.TIM_Channel = channel.channel; - TIM_ICInit(channel.timer, &TIM_ICInitStructure); - } - } + struct pios_pwm_dev * pwm_dev = (struct pios_pwm_dev *)context; + + if (!PIOS_PWM_validate(pwm_dev)) { + /* Invalid device specified */ + return; } + + if (channel >= pwm_dev->cfg->num_channels) { + /* Channel out of range */ + return; + } + + pwm_dev->us_since_update[channel] += count; + if(pwm_dev->us_since_update[channel] >= PWM_SUPERVISOR_TIMEOUT) { + pwm_dev->CaptureState[channel] = 0; + pwm_dev->RiseValue[channel] = 0; + pwm_dev->FallValue[channel] = 0; + pwm_dev->CaptureValue[channel] = PIOS_RCVR_TIMEOUT; + pwm_dev->us_since_update[channel] = 0; + } + + return; +} + +static void PIOS_PWM_tim_edge_cb (uint32_t tim_id, uint32_t context, uint8_t chan_idx, uint16_t count) +{ + /* Recover our device context */ + struct pios_pwm_dev * pwm_dev = (struct pios_pwm_dev *)context; + + if (!PIOS_PWM_validate(pwm_dev)) { + /* Invalid device specified */ + return; + } + + if (chan_idx >= pwm_dev->cfg->num_channels) { + /* Channel out of range */ + return; + } + + const struct pios_tim_channel * chan = &pwm_dev->cfg->channels[chan_idx]; + + if (pwm_dev->CaptureState[chan_idx] == 0) { + pwm_dev->RiseValue[chan_idx] = count; + pwm_dev->us_since_update[chan_idx] = 0; + } else { + pwm_dev->FallValue[chan_idx] = count; + } + + // flip state machine and capture value here + /* Simple rise or fall state machine */ + TIM_ICInitTypeDef TIM_ICInitStructure = pwm_dev->cfg->tim_ic_init; + if (pwm_dev->CaptureState[chan_idx] == 0) { + /* Switch states */ + pwm_dev->CaptureState[chan_idx] = 1; + + /* Switch polarity of input capture */ + TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Falling; + TIM_ICInitStructure.TIM_Channel = chan->timer_chan; + TIM_ICInit(chan->timer, &TIM_ICInitStructure); + } else { + /* Capture computation */ + if (pwm_dev->FallValue[chan_idx] > pwm_dev->RiseValue[chan_idx]) { + pwm_dev->CaptureValue[chan_idx] = (pwm_dev->FallValue[chan_idx] - pwm_dev->RiseValue[chan_idx]); + } else { + pwm_dev->CaptureValue[chan_idx] = ((chan->timer->ARR - pwm_dev->RiseValue[chan_idx]) + pwm_dev->FallValue[chan_idx]); + } + + /* Switch states */ + pwm_dev->CaptureState[chan_idx] = 0; + + /* Increase supervisor counter */ + pwm_dev->CapCounter[chan_idx]++; + + /* Switch polarity of input capture */ + TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Rising; + TIM_ICInitStructure.TIM_Channel = chan->timer_chan; + TIM_ICInit(chan->timer, &TIM_ICInitStructure); + } + } #endif diff --git a/flight/PiOS/STM32F10x/pios_sbus.c b/flight/PiOS/STM32F10x/pios_sbus.c index a80fe8fe3..53730b16b 100644 --- a/flight/PiOS/STM32F10x/pios_sbus.c +++ b/flight/PiOS/STM32F10x/pios_sbus.c @@ -2,13 +2,13 @@ ****************************************************************************** * @addtogroup PIOS PIOS Core hardware abstraction layer * @{ - * @addtogroup PIOS_SBUS Futaba S.Bus receiver functions - * @brief Code to read Futaba S.Bus input + * @addtogroup PIOS_SBus Futaba S.Bus receiver functions + * @brief Code to read Futaba S.Bus receiver serial stream * @{ * * @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) + * @brief Code to read Futaba S.Bus receiver serial stream * @see The GNU Public License (GPL) Version 3 * *****************************************************************************/ @@ -34,52 +34,168 @@ #if defined(PIOS_INCLUDE_SBUS) -/* Global Variables */ +/* Forward Declarations */ +static int32_t PIOS_SBus_Get(uint32_t rcvr_id, uint8_t channel); +static uint16_t PIOS_SBus_RxInCallback(uint32_t context, + uint8_t *buf, + uint16_t buf_len, + uint16_t *headroom, + bool *need_yield); +static void PIOS_SBus_Supervisor(uint32_t sbus_id); -/* 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; +const struct pios_rcvr_driver pios_sbus_rcvr_driver = { + .read = PIOS_SBus_Get, +}; -static void PIOS_SBUS_Supervisor(uint32_t sbus_id); +enum pios_sbus_dev_magic { + PIOS_SBUS_DEV_MAGIC = 0x53427573, +}; -/** - * 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) +struct pios_sbus_state { + uint16_t channel_data[PIOS_SBUS_NUM_INPUTS]; + uint8_t received_data[SBUS_FRAME_LENGTH - 2]; + uint8_t receive_timer; + uint8_t failsafe_timer; + uint8_t frame_found; + uint8_t byte_count; +}; + +struct pios_sbus_dev { + enum pios_sbus_dev_magic magic; + const struct pios_sbus_cfg *cfg; + struct pios_sbus_state state; +}; + +/* Allocate S.Bus device descriptor */ +#if defined(PIOS_INCLUDE_FREERTOS) +static struct pios_sbus_dev *PIOS_SBus_Alloc(void) { - for (int i = 0; i < SBUS_NUMBER_OF_CHANNELS; i++) { - channel_data[i] = 0; + struct pios_sbus_dev *sbus_dev; + + sbus_dev = (struct pios_sbus_dev *)pvPortMalloc(sizeof(*sbus_dev)); + if (!sbus_dev) return(NULL); + + sbus_dev->magic = PIOS_SBUS_DEV_MAGIC; + return(sbus_dev); +} +#else +static struct pios_sbus_dev pios_sbus_devs[PIOS_SBUS_MAX_DEVS]; +static uint8_t pios_sbus_num_devs; +static struct pios_sbus_dev *PIOS_SBus_Alloc(void) +{ + struct pios_sbus_dev *sbus_dev; + + if (pios_sbus_num_devs >= PIOS_SBUS_MAX_DEVS) { + return (NULL); + } + + sbus_dev = &pios_sbus_devs[pios_sbus_num_devs++]; + sbus_dev->magic = PIOS_SBUS_DEV_MAGIC; + + return (sbus_dev); +} +#endif + +/* Validate S.Bus device descriptor */ +static bool PIOS_SBus_Validate(struct pios_sbus_dev *sbus_dev) +{ + return (sbus_dev->magic == PIOS_SBUS_DEV_MAGIC); +} + +/* Reset channels in case of lost signal or explicit failsafe receiver flag */ +static void PIOS_SBus_ResetChannels(struct pios_sbus_state *state) +{ + for (int i = 0; i < PIOS_SBUS_NUM_INPUTS; i++) { + state->channel_data[i] = PIOS_RCVR_TIMEOUT; } } -/** - * 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) +/* Reset S.Bus receiver state */ +static void PIOS_SBus_ResetState(struct pios_sbus_state *state) { - uint8_t *s = received_data; - uint16_t *d = channel_data; + state->receive_timer = 0; + state->failsafe_timer = 0; + state->frame_found = 0; + PIOS_SBus_ResetChannels(state); +} -#if (SBUS_NUMBER_OF_CHANNELS != 8) -#error Current S.Bus code unrolls only first 8 channels -#endif +/* Initialise S.Bus receiver interface */ +int32_t PIOS_SBus_Init(uint32_t *sbus_id, + const struct pios_sbus_cfg *cfg, + const struct pios_com_driver *driver, + uint32_t lower_id) +{ + PIOS_DEBUG_Assert(sbus_id); + PIOS_DEBUG_Assert(cfg); + PIOS_DEBUG_Assert(driver); -#define F(v,s) ((v) >> s) & 0x7ff + struct pios_sbus_dev *sbus_dev; + + sbus_dev = (struct pios_sbus_dev *)PIOS_SBus_Alloc(); + if (!sbus_dev) goto out_fail; + + /* Bind the configuration to the device instance */ + sbus_dev->cfg = cfg; + + PIOS_SBus_ResetState(&(sbus_dev->state)); + + *sbus_id = (uint32_t)sbus_dev; + + /* 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); + + /* Set comm driver callback */ + (driver->bind_rx_cb)(lower_id, PIOS_SBus_RxInCallback, *sbus_id); + + if (!PIOS_RTC_RegisterTickCallback(PIOS_SBus_Supervisor, *sbus_id)) { + PIOS_DEBUG_Assert(0); + } + + return 0; + +out_fail: + return -1; +} + +/** + * Get the value of an input channel + * \param[in] channel Number of the channel desired (zero based) + * \output PIOS_RCVR_INVALID channel not available + * \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver + * \output >0 channel value + */ +static int32_t PIOS_SBus_Get(uint32_t rcvr_id, uint8_t channel) +{ + struct pios_sbus_dev *sbus_dev = (struct pios_sbus_dev *)rcvr_id; + + if (!PIOS_SBus_Validate(sbus_dev)) + return PIOS_RCVR_INVALID; + + /* return error if channel is not available */ + if (channel >= PIOS_SBUS_NUM_INPUTS) { + return PIOS_RCVR_INVALID; + } + + return sbus_dev->state.channel_data[channel]; +} + +/** + * Compute channel_data[] from received_data[]. + * For efficiency it unrolls first 8 channels without loops and does the + * same for other 8 channels. Also 2 discrete channels will be set. + */ +static void PIOS_SBus_UnrollChannels(struct pios_sbus_state *state) +{ + uint8_t *s = state->received_data; + uint16_t *d = state->channel_data; + +#define F(v,s) (((v) >> (s)) & 0x7ff) + + /* unroll channels 1-8 */ *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); @@ -88,134 +204,135 @@ static void unroll_channels(void) *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); + + /* unroll channels 9-16 */ + *d++ = F(s[11] | s[12] << 8, 0); + *d++ = F(s[12] | s[13] << 8, 3); + *d++ = F(s[13] | s[14] << 8 | s[15] << 16, 6); + *d++ = F(s[15] | s[16] << 8, 1); + *d++ = F(s[16] | s[17] << 8, 4); + *d++ = F(s[17] | s[18] << 8 | s[19] << 16, 7); + *d++ = F(s[19] | s[20] << 8, 2); + *d++ = F(s[20] | s[21] << 8, 5); + + /* unroll discrete channels 17 and 18 */ + *d++ = (s[22] & SBUS_FLAG_DC1) ? SBUS_VALUE_MAX : SBUS_VALUE_MIN; + *d++ = (s[22] & SBUS_FLAG_DC2) ? SBUS_VALUE_MAX : SBUS_VALUE_MIN; } -/** - * process_byte() function processes incoming byte from S.Bus stream - */ -static void process_byte(uint8_t b) +/* Update decoder state processing input byte from the S.Bus stream */ +static void PIOS_SBus_UpdateState(struct pios_sbus_state *state, uint8_t b) { - static uint8_t byte_count; + /* should not process any data until new frame is found */ + if (!state->frame_found) + return; - 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; + if (state->byte_count == 0) { + if (b != SBUS_SOF_BYTE) { + /* discard the whole frame if the 1st byte is not correct */ + state->frame_found = 0; } 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; + /* do not store the SOF byte */ + state->byte_count++; } + return; + } + + /* do not store last frame byte as well */ + if (state->byte_count < SBUS_FRAME_LENGTH - 1) { + /* store next byte */ + state->received_data[state->byte_count - 1] = b; + state->byte_count++; + } else { + if (b == SBUS_EOF_BYTE) { + /* full frame received */ + uint8_t flags = state->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 */ + PIOS_SBus_ResetChannels(state); + } else { + /* data looking good */ + PIOS_SBus_UnrollChannels(state); + state->failsafe_timer = 0; + } + } else { + /* discard whole frame */ + } + + /* prepare for the next frame */ + state->frame_found = 0; } } -static uint16_t PIOS_SBUS_RxInCallback(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, bool * need_yield) +/* Comm byte received callback */ +static uint16_t PIOS_SBus_RxInCallback(uint32_t context, + uint8_t *buf, + uint16_t buf_len, + uint16_t *headroom, + bool *need_yield) { + struct pios_sbus_dev *sbus_dev = (struct pios_sbus_dev *)context; + + bool valid = PIOS_SBus_Validate(sbus_dev); + PIOS_Assert(valid); + + struct pios_sbus_state *state = &(sbus_dev->state); + /* process byte(s) and clear receive timer */ for (uint8_t i = 0; i < buf_len; i++) { - process_byte(buf[i]); - receive_timer = 0; + PIOS_SBus_UpdateState(state, buf[i]); + state->receive_timer = 0; } /* Always signal that we can accept another byte */ - if (headroom) { + if (headroom) *headroom = SBUS_FRAME_LENGTH; - } /* We never need a yield */ *need_yield = false; /* Always indicate that all bytes were consumed */ - return (buf_len); -} - -/** - * Initialise S.Bus receiver interface - */ -int32_t PIOS_SBUS_Init(uint32_t * sbus_id, const struct pios_sbus_cfg *cfg, const struct pios_com_driver * driver, uint32_t lower_id) -{ - /* 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); - - (driver->bind_rx_cb)(lower_id, PIOS_SBUS_RxInCallback, 0); - - if (!PIOS_RTC_RegisterTickCallback(PIOS_SBUS_Supervisor, 0)) { - PIOS_Assert(0); - } - - return (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]; + return buf_len; } /** * 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. + * 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 frame 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) +static void PIOS_SBus_Supervisor(uint32_t sbus_id) { + struct pios_sbus_dev *sbus_dev = (struct pios_sbus_dev *)sbus_id; + + bool valid = PIOS_SBus_Validate(sbus_dev); + PIOS_Assert(valid); + + struct pios_sbus_state *state = &(sbus_dev->state); + /* waiting for new frame if no bytes were received in 3.2ms */ - if (++receive_timer > 2) { - receive_timer = 0; - frame_found = 0; + if (++state->receive_timer > 2) { + state->frame_found = 1; + state->byte_count = 0; + state->receive_timer = 0; } /* activate failsafe if no frames have arrived in 102.4ms */ - if (++failsafe_timer > 64) { - reset_channels(); - failsafe_timer = 0; + if (++state->failsafe_timer > 64) { + PIOS_SBus_ResetChannels(state); + state->failsafe_timer = 0; } } -#endif +#endif /* PIOS_INCLUDE_SBUS */ /** * @} diff --git a/flight/PiOS/STM32F10x/pios_servo.c b/flight/PiOS/STM32F10x/pios_servo.c index 229f371ce..cb7d98292 100644 --- a/flight/PiOS/STM32F10x/pios_servo.c +++ b/flight/PiOS/STM32F10x/pios_servo.c @@ -31,97 +31,55 @@ /* Project Includes */ #include "pios.h" #include "pios_servo_priv.h" +#include "pios_tim_priv.h" /* Private Function Prototypes */ +static const struct pios_servo_cfg * servo_cfg; + /** * Initialise Servos */ -void PIOS_Servo_Init(void) +int32_t PIOS_Servo_Init(const struct pios_servo_cfg * cfg) { -#ifndef PIOS_ENABLE_DEBUG_PINS -#if defined(PIOS_INCLUDE_SERVO) + uint32_t tim_id; + if (PIOS_TIM_InitChannels(&tim_id, cfg->channels, cfg->num_channels, NULL, 0)) { + return -1; + } + /* Store away the requested configuration */ + servo_cfg = cfg; - 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: - RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1, ENABLE); - break; - case (int32_t)TIM2: - RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE); - break; - case (int32_t)TIM3: - RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE); - break; - case (int32_t)TIM4: - RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM4, ENABLE); - break; - case (int32_t)TIM5: - RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM5, ENABLE); - break; - case (int32_t)TIM6: - RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM6, ENABLE); - break; - case (int32_t)TIM7: - RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM7, ENABLE); - break; - case (int32_t)TIM8: - RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM8, ENABLE); - break; - } - - /* 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; + /* Configure the channels to be in output compare mode */ + for (uint8_t i = 0; i < cfg->num_channels; i++) { + const struct pios_tim_channel * chan = &cfg->channels[i]; /* Set up for output compare function */ - switch(channel.channel) { + switch(chan->timer_chan) { case TIM_Channel_1: - TIM_OC1Init(channel.timer, &TIM_OCInitStructure); - TIM_OC1PreloadConfig(channel.timer, TIM_OCPreload_Enable); + TIM_OC1Init(chan->timer, &cfg->tim_oc_init); + TIM_OC1PreloadConfig(chan->timer, TIM_OCPreload_Enable); break; case TIM_Channel_2: - TIM_OC2Init(channel.timer, &TIM_OCInitStructure); - TIM_OC2PreloadConfig(channel.timer, TIM_OCPreload_Enable); + TIM_OC2Init(chan->timer, &cfg->tim_oc_init); + TIM_OC2PreloadConfig(chan->timer, TIM_OCPreload_Enable); break; case TIM_Channel_3: - TIM_OC3Init(channel.timer, &TIM_OCInitStructure); - TIM_OC3PreloadConfig(channel.timer, TIM_OCPreload_Enable); + TIM_OC3Init(chan->timer, &cfg->tim_oc_init); + TIM_OC3PreloadConfig(chan->timer, TIM_OCPreload_Enable); break; case TIM_Channel_4: - TIM_OC4Init(channel.timer, &TIM_OCInitStructure); - TIM_OC4PreloadConfig(channel.timer, TIM_OCPreload_Enable); + TIM_OC4Init(chan->timer, &cfg->tim_oc_init); + TIM_OC4PreloadConfig(chan->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_ARRPreloadConfig(chan->timer, ENABLE); + TIM_CtrlPWMOutputs(chan->timer, ENABLE); + TIM_Cmd(chan->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 + return 0; } /** @@ -131,31 +89,31 @@ void PIOS_Servo_Init(void) */ void PIOS_Servo_SetHz(uint16_t * speeds, uint8_t banks) { -#ifndef PIOS_ENABLE_DEBUG_PINS -#if defined(PIOS_INCLUDE_SERVO) - TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure = pios_servo_cfg.tim_base_init; + if (!servo_cfg) { + return; + } + + TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure = servo_cfg->tim_base_init; 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 < servo_cfg->num_channels) && (set < banks); i++) { bool new = true; - struct pios_servo_channel channel = pios_servo_cfg.channels[i]; + const struct pios_tim_channel * chan = &servo_cfg->channels[i]; /* See if any previous channels use that same timer */ for(uint8_t j = 0; (j < i) && new; j++) - new &= channel.timer != pios_servo_cfg.channels[j].timer; + new &= chan->timer != servo_cfg->channels[j].timer; if(new) { TIM_TimeBaseStructure.TIM_Period = ((1000000 / speeds[set]) - 1); - TIM_TimeBaseInit(channel.timer, &TIM_TimeBaseStructure); + TIM_TimeBaseInit(chan->timer, &TIM_TimeBaseStructure); set++; } } -#endif // PIOS_INCLUDE_SERVO -#endif // PIOS_ENABLE_DEBUG_PINS } /** @@ -163,29 +121,27 @@ void PIOS_Servo_SetHz(uint16_t * speeds, uint8_t banks) * \param[in] Servo Servo number (0-7) * \param[in] Position Servo position in microseconds */ -void PIOS_Servo_Set(uint8_t Servo, uint16_t Position) +void PIOS_Servo_Set(uint8_t servo, uint16_t position) { -#ifndef PIOS_ENABLE_DEBUG_PINS -#if defined(PIOS_INCLUDE_SERVO) /* Make sure servo exists */ - if (Servo < pios_servo_cfg.num_channels && Servo >= 0) { - /* Update the position */ - - switch(pios_servo_cfg.channels[Servo].channel) { - case TIM_Channel_1: - TIM_SetCompare1(pios_servo_cfg.channels[Servo].timer, Position); - break; - case TIM_Channel_2: - TIM_SetCompare2(pios_servo_cfg.channels[Servo].timer, Position); - break; - case TIM_Channel_3: - TIM_SetCompare3(pios_servo_cfg.channels[Servo].timer, Position); - break; - case TIM_Channel_4: - TIM_SetCompare4(pios_servo_cfg.channels[Servo].timer, Position); - break; - } + if (!servo_cfg || servo >= servo_cfg->num_channels) { + return; + } + + /* Update the position */ + const struct pios_tim_channel * chan = &servo_cfg->channels[servo]; + switch(chan->timer_chan) { + case TIM_Channel_1: + TIM_SetCompare1(chan->timer, position); + break; + case TIM_Channel_2: + TIM_SetCompare2(chan->timer, position); + break; + case TIM_Channel_3: + TIM_SetCompare3(chan->timer, position); + break; + case TIM_Channel_4: + TIM_SetCompare4(chan->timer, position); + break; } -#endif // PIOS_INCLUDE_SERVO -#endif // PIOS_ENABLE_DEBUG_PINS } diff --git a/flight/PiOS/STM32F10x/pios_spektrum.c b/flight/PiOS/STM32F10x/pios_spektrum.c deleted file mode 100644 index 8b0f38c6b..000000000 --- a/flight/PiOS/STM32F10x/pios_spektrum.c +++ /dev/null @@ -1,264 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_SPEKTRUM Spektrum receiver functions - * @brief Code to read Spektrum input - * @{ - * - * @file pios_spektrum.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) (tk@midibox.org) - * @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_spektrum_priv.h" - -#if defined(PIOS_INCLUDE_SPEKTRUM) - -/** - * @Note Framesyncing: - * The code resets the watchdog timer whenever a single byte is received, so what watchdog code - * is never called if regularly getting bytes. - * RTC timer is running @625Hz, supervisor timer has divider 5 so frame sync comes every 1/125Hz=8ms. - * Good for both 11ms and 22ms framecycles - */ - -/* 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[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); -static int32_t PIOS_SPEKTRUM_Decode(uint8_t b); - -static uint16_t PIOS_SPEKTRUM_RxInCallback(uint32_t context, uint8_t * buf, uint16_t buf_len, uint16_t * headroom, bool * need_yield) -{ - /* process byte(s) and clear receive timer */ - for (uint8_t i = 0; i < buf_len; i++) { - PIOS_SPEKTRUM_Decode(buf[i]); - supv_timer = 0; - } - - /* Always signal that we can accept another byte */ - if (headroom) { - *headroom = 1; - } - - /* We never need a yield */ - *need_yield = false; - - /* Always indicate that all bytes were consumed */ - return (buf_len); -} - -/** -* Bind and Initialise Spektrum satellite receiver -*/ -int32_t PIOS_SPEKTRUM_Init(uint32_t * spektrum_id, const struct pios_spektrum_cfg *cfg, const struct pios_com_driver * driver, uint32_t lower_id, bool bind) -{ - // TODO: need setting flag for bind on next powerup - if (bind) { - PIOS_SPEKTRUM_Bind(cfg); - } - - (driver->bind_rx_cb)(lower_id, PIOS_SPEKTRUM_RxInCallback, 0); - - if (!PIOS_RTC_RegisterTickCallback(PIOS_SPEKTRUM_Supervisor, 0)) { - PIOS_DEBUG_Assert(0); - } - - return (0); -} - -/** -* Get the value of an input channel -* \param[in] Channel Number of the channel desired -* \output -1 Channel not available -* \output >0 Channel value -*/ -static int32_t PIOS_SPEKTRUM_Get(uint32_t rcvr_id, uint8_t channel) -{ - /* Return error if channel not available */ - if (channel >= PIOS_SPEKTRUM_NUM_INPUTS) { - return -1; - } - return CaptureValue[channel]; -} - -/** -* Spektrum bind function -* \output true Successful bind -* \output false Bind failed -*/ -static bool PIOS_SPEKTRUM_Bind(const struct pios_spektrum_cfg * cfg) -{ -#define BIND_PULSES 5 - - 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 true; -} - -/** -* Decodes a byte -* \param[in] b byte which should be spektrum decoded -* \return 0 if no error -* \return -1 if USART not available -* \return -2 if buffer full (retry) -* \note Applications shouldn't call these functions directly -*/ -static int32_t PIOS_SPEKTRUM_Decode(uint8_t b) -{ - static uint16_t channel = 0; /*, sync_word = 0;*/ - uint8_t channeln = 0, frame = 0; - uint16_t data = 0; - byte_array[bytecount] = b; - bytecount++; - if (sync == 0) { - //sync_word = (prev_byte << 8) + b; -#if 0 - /* maybe create object to show this data */ - if(bytecount==1) - { - /* record losscounter into channel8 */ - CaptureValueTemp[7]=b; - /* instant write */ - CaptureValue[7]=b; - } -#endif - /* Known sync bytes, 0x01, 0x02, 0x12 */ - if (bytecount == 2) { - if (b == 0x01) { - datalength=0; // 10bit - //frames=1; - sync = 1; - bytecount = 2; - } - else if(b == 0x02) { - datalength=0; // 10bit - //frames=2; - sync = 1; - bytecount = 2; - } - else if(b == 0x12) { - datalength=1; // 11bit - //frames=2; - sync = 1; - bytecount = 2; - } - else - { - bytecount = 0; - } - } - } else { - if ((bytecount % 2) == 0) { - channel = (prev_byte << 8) + b; - frame = channel >> 15; - channeln = (channel >> (10+datalength)) & 0x0F; - data = channel & (0x03FF+(0x0400*datalength)); - if(channeln==0 && data<10) // discard frame if throttle misbehaves - { - frame_error=1; - } - if (channeln < PIOS_SPEKTRUM_NUM_INPUTS && !frame_error) - CaptureValueTemp[channeln] = data; - } - } - if (bytecount == 16) { - //PIOS_COM_SendBufferNonBlocking(PIOS_COM_TELEM_RF,byte_array,16); //00 2c 58 84 b0 dc ff - bytecount = 0; - sync = 0; - sync_of = 0; - if (!frame_error) - { - for(int i=0;i 5) { - /* sync between frames */ - sync = 0; - bytecount = 0; - prev_byte = 0xFF; - frame_error = 0; - sync_of++; - /* watchdog activated after 100ms silence */ - if (sync_of > 12) { - /* signal lost */ - sync_of = 0; - for (int i = 0; i < PIOS_SPEKTRUM_NUM_INPUTS; i++) { - CaptureValue[i] = 0; - CaptureValueTemp[i] = 0; - } - } - supv_timer = 0; - } -} - -#endif - -/** - * @} - * @} - */ diff --git a/flight/PiOS/STM32F10x/pios_spi.c b/flight/PiOS/STM32F10x/pios_spi.c index 74a14afc0..a5e57335f 100644 --- a/flight/PiOS/STM32F10x/pios_spi.c +++ b/flight/PiOS/STM32F10x/pios_spi.c @@ -46,10 +46,10 @@ static bool PIOS_SPI_validate(struct pios_spi_dev * com_dev) return(true); } -#if defined(PIOS_INCLUDE_FREERTOS) && 0 +#if defined(PIOS_INCLUDE_FREERTOS) static struct pios_spi_dev * PIOS_SPI_alloc(void) { - return (malloc(sizeof(struct pios_spi_dev))); + return (pvPortMalloc(sizeof(struct pios_spi_dev))); } #else static struct pios_spi_dev pios_spi_devs[PIOS_SPI_MAX_DEVS]; diff --git a/flight/PiOS/STM32F10x/pios_tim.c b/flight/PiOS/STM32F10x/pios_tim.c new file mode 100644 index 000000000..dcdd07670 --- /dev/null +++ b/flight/PiOS/STM32F10x/pios_tim.c @@ -0,0 +1,427 @@ +#include "pios.h" + +#include "pios_tim.h" +#include "pios_tim_priv.h" + +enum pios_tim_dev_magic { + PIOS_TIM_DEV_MAGIC = 0x87654098, +}; + +struct pios_tim_dev { + enum pios_tim_dev_magic magic; + + const struct pios_tim_channel * channels; + uint8_t num_channels; + + const struct pios_tim_callbacks * callbacks; + uint32_t context; +}; + +#if 0 +static bool PIOS_TIM_validate(struct pios_tim_dev * tim_dev) +{ + return (tim_dev->magic == PIOS_TIM_DEV_MAGIC); +} +#endif + +#if defined(PIOS_INCLUDE_FREERTOS) && 0 +static struct pios_tim_dev * PIOS_TIM_alloc(void) +{ + struct pios_tim_dev * tim_dev; + + tim_dev = (struct pios_tim_dev *)malloc(sizeof(*tim_dev)); + if (!tim_dev) return(NULL); + + tim_dev->magic = PIOS_TIM_DEV_MAGIC; + return(tim_dev); +} +#else +static struct pios_tim_dev pios_tim_devs[PIOS_TIM_MAX_DEVS]; +static uint8_t pios_tim_num_devs; +static struct pios_tim_dev * PIOS_TIM_alloc(void) +{ + struct pios_tim_dev * tim_dev; + + if (pios_tim_num_devs >= PIOS_TIM_MAX_DEVS) { + return (NULL); + } + + tim_dev = &pios_tim_devs[pios_tim_num_devs++]; + tim_dev->magic = PIOS_TIM_DEV_MAGIC; + + return (tim_dev); +} +#endif + + + + +int32_t PIOS_TIM_InitClock(const struct pios_tim_clock_cfg * cfg) +{ + PIOS_DEBUG_Assert(cfg); + + /* Enable appropriate clock to timer module */ + switch((uint32_t) cfg->timer) { + case (uint32_t)TIM1: + RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM1, ENABLE); + break; + case (uint32_t)TIM2: + RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE); + break; + case (uint32_t)TIM3: + RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE); + break; + case (uint32_t)TIM4: + RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM4, ENABLE); + break; +#ifdef STM32F10X_HD + case (uint32_t)TIM5: + RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM5, ENABLE); + break; + case (uint32_t)TIM6: + RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM6, ENABLE); + break; + case (uint32_t)TIM7: + RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM7, ENABLE); + break; + case (uint32_t)TIM8: + RCC_APB2PeriphClockCmd(RCC_APB2Periph_TIM8, ENABLE); + break; +#endif + } + + /* Configure the dividers for this timer */ + TIM_TimeBaseInit(cfg->timer, cfg->time_base_init); + + /* Configure internal timer clocks */ + TIM_InternalClockConfig(cfg->timer); + + /* Enable timers */ + TIM_Cmd(cfg->timer, ENABLE); + + /* Enable Interrupts */ + NVIC_Init(&cfg->irq.init); + + return 0; +} + +int32_t PIOS_TIM_InitChannels(uint32_t * tim_id, const struct pios_tim_channel * channels, uint8_t num_channels, const struct pios_tim_callbacks * callbacks, uint32_t context) +{ + PIOS_Assert(channels); + PIOS_Assert(num_channels); + + struct pios_tim_dev * tim_dev; + tim_dev = (struct pios_tim_dev *) PIOS_TIM_alloc(); + if (!tim_dev) goto out_fail; + + /* Bind the configuration to the device instance */ + tim_dev->channels = channels; + tim_dev->num_channels = num_channels; + tim_dev->callbacks = callbacks; + tim_dev->context = context; + + /* Configure the pins */ + for (uint8_t i = 0; i < num_channels; i++) { + const struct pios_tim_channel * chan = &(channels[i]); + + /* Enable the peripheral clock for the GPIO */ + switch ((uint32_t)chan->pin.gpio) { + case (uint32_t) GPIOA: + RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE); + break; + case (uint32_t) GPIOB: + RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE); + break; + case (uint32_t) GPIOC: + RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE); + break; + default: + PIOS_Assert(0); + break; + } + GPIO_Init(chan->pin.gpio, &chan->pin.init); + + if (chan->remap) { + GPIO_PinRemapConfig(chan->remap, ENABLE); + } + } + + *tim_id = (uint32_t)tim_dev; + + return(0); + +out_fail: + return(-1); +} + +static void PIOS_TIM_generic_irq_handler(TIM_TypeDef * timer) +{ + /* Iterate over all registered clients of the TIM layer to find channels on this timer */ + for (uint8_t i = 0; i < pios_tim_num_devs; i++) { + const struct pios_tim_dev * tim_dev = &pios_tim_devs[i]; + + if (!tim_dev->channels || tim_dev->num_channels == 0) { + /* No channels to process on this client */ + continue; + } + + /* Check for an overflow event on this timer */ + bool overflow_event; + uint16_t overflow_count; + if (TIM_GetITStatus(timer, TIM_IT_Update) == SET) { + TIM_ClearITPendingBit(timer, TIM_IT_Update); + overflow_count = timer->ARR; + overflow_event = true; + } else { + overflow_count = 0; + overflow_event = false; + } + + for (uint8_t j = 0; j < tim_dev->num_channels; j++) { + const struct pios_tim_channel * chan = &tim_dev->channels[j]; + + if (chan->timer != timer) { + /* channel is not on this timer */ + continue; + } + + /* Figure out which interrupt bit we should be looking at */ + uint16_t timer_it; + switch (chan->timer_chan) { + case TIM_Channel_1: + timer_it = TIM_IT_CC1; + break; + case TIM_Channel_2: + timer_it = TIM_IT_CC2; + break; + case TIM_Channel_3: + timer_it = TIM_IT_CC3; + break; + case TIM_Channel_4: + timer_it = TIM_IT_CC4; + break; + default: + PIOS_Assert(0); + break; + } + + bool edge_event; + uint16_t edge_count; + if (TIM_GetITStatus(chan->timer, timer_it) == SET) { + TIM_ClearITPendingBit(chan->timer, timer_it); + + /* Read the current counter */ + switch(chan->timer_chan) { + case TIM_Channel_1: + edge_count = TIM_GetCapture1(chan->timer); + break; + case TIM_Channel_2: + edge_count = TIM_GetCapture2(chan->timer); + break; + case TIM_Channel_3: + edge_count = TIM_GetCapture3(chan->timer); + break; + case TIM_Channel_4: + edge_count = TIM_GetCapture4(chan->timer); + break; + default: + PIOS_Assert(0); + break; + } + edge_event = true; + } else { + edge_event = false; + edge_count = 0; + } + + if (!tim_dev->callbacks) { + /* No callbacks registered, we're done with this channel */ + continue; + } + + /* Generate the appropriate callbacks */ + if (overflow_event & edge_event) { + /* + * When both edge and overflow happen in the same interrupt, we + * need a heuristic to determine the order of the edge and overflow + * events so that the callbacks happen in the right order. If we + * get the order wrong, our pulse width calculations could be off by up + * to ARR ticks. That could be bad. + * + * Heuristic: If the edge_count is < 16 ticks above zero then we assume the + * edge happened just after the overflow. + */ + + if (edge_count < 16) { + /* Call the overflow callback first */ + if (tim_dev->callbacks->overflow) { + (*tim_dev->callbacks->overflow)((uint32_t)tim_dev, + tim_dev->context, + j, + overflow_count); + } + /* Call the edge callback second */ + if (tim_dev->callbacks->edge) { + (*tim_dev->callbacks->edge)((uint32_t)tim_dev, + tim_dev->context, + j, + edge_count); + } + } else { + /* Call the edge callback first */ + if (tim_dev->callbacks->edge) { + (*tim_dev->callbacks->edge)((uint32_t)tim_dev, + tim_dev->context, + j, + edge_count); + } + /* Call the overflow callback second */ + if (tim_dev->callbacks->overflow) { + (*tim_dev->callbacks->overflow)((uint32_t)tim_dev, + tim_dev->context, + j, + overflow_count); + } + } + } else if (overflow_event && tim_dev->callbacks->overflow) { + (*tim_dev->callbacks->overflow)((uint32_t)tim_dev, + tim_dev->context, + j, + overflow_count); + } else if (edge_event && tim_dev->callbacks->edge) { + (*tim_dev->callbacks->edge)((uint32_t)tim_dev, + tim_dev->context, + j, + edge_count); + } + } + } +} +#if 0 + uint16_t val = 0; + for(uint8_t i = 0; i < pios_pwm_cfg.num_channels; i++) { + struct pios_pwm_channel channel = pios_pwm_cfg.channels[i]; + if ((channel.timer == timer) && (TIM_GetITStatus(channel.timer, channel.ccr) == SET)) { + + TIM_ClearITPendingBit(channel.timer, channel.ccr); + + switch(channel.channel) { + case TIM_Channel_1: + val = TIM_GetCapture1(channel.timer); + break; + case TIM_Channel_2: + val = TIM_GetCapture2(channel.timer); + break; + case TIM_Channel_3: + val = TIM_GetCapture3(channel.timer); + break; + case TIM_Channel_4: + val = TIM_GetCapture4(channel.timer); + break; + } + + if (CaptureState[i] == 0) { + RiseValue[i] = val; + } else { + FallValue[i] = val; + } + + // flip state machine and capture value here + /* Simple rise or fall state machine */ + TIM_ICInitTypeDef TIM_ICInitStructure = pios_pwm_cfg.tim_ic_init; + if (CaptureState[i] == 0) { + /* Switch states */ + CaptureState[i] = 1; + + /* Switch polarity of input capture */ + TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Falling; + TIM_ICInitStructure.TIM_Channel = channel.channel; + TIM_ICInit(channel.timer, &TIM_ICInitStructure); + } else { + /* Capture computation */ + if (FallValue[i] > RiseValue[i]) { + CaptureValue[i] = (FallValue[i] - RiseValue[i]); + } else { + CaptureValue[i] = ((channel.timer->ARR - RiseValue[i]) + FallValue[i]); + } + + /* Switch states */ + CaptureState[i] = 0; + + /* Increase supervisor counter */ + CapCounter[i]++; + + /* Switch polarity of input capture */ + TIM_ICInitStructure.TIM_ICPolarity = TIM_ICPolarity_Rising; + TIM_ICInitStructure.TIM_Channel = channel.channel; + TIM_ICInit(channel.timer, &TIM_ICInitStructure); + } + } + } +#endif + +/* Bind Interrupt Handlers + * + * Map all valid TIM IRQs to the common interrupt handler + * and give it enough context to properly demux the various timers + */ +void TIM1_UP_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_1_UP_irq_handler"))); +static void PIOS_TIM_1_UP_irq_handler (void) +{ + PIOS_TIM_generic_irq_handler (TIM1); +} + +void TIM1_CC_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_1_CC_irq_handler"))); +static void PIOS_TIM_1_CC_irq_handler (void) +{ + PIOS_TIM_generic_irq_handler (TIM1); +} + +void TIM2_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_2_irq_handler"))); +static void PIOS_TIM_2_irq_handler (void) +{ + PIOS_TIM_generic_irq_handler (TIM2); +} + +void TIM3_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_3_irq_handler"))); +static void PIOS_TIM_3_irq_handler (void) +{ + PIOS_TIM_generic_irq_handler (TIM3); +} + +void TIM4_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_4_irq_handler"))); +static void PIOS_TIM_4_irq_handler (void) +{ + PIOS_TIM_generic_irq_handler (TIM4); +} + +void TIM5_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_5_irq_handler"))); +static void PIOS_TIM_5_irq_handler (void) +{ + PIOS_TIM_generic_irq_handler (TIM5); +} + +void TIM6_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_6_irq_handler"))); +static void PIOS_TIM_6_irq_handler (void) +{ + PIOS_TIM_generic_irq_handler (TIM6); +} + +void TIM7_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_7_irq_handler"))); +static void PIOS_TIM_7_irq_handler (void) +{ + PIOS_TIM_generic_irq_handler (TIM7); +} + +void TIM8_UP_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_8_UP_irq_handler"))); +static void PIOS_TIM_8_UP_irq_handler (void) +{ + PIOS_TIM_generic_irq_handler (TIM8); +} + +void TIM8_CC_IRQHandler(void) __attribute__ ((alias ("PIOS_TIM_8_CC_irq_handler"))); +static void PIOS_TIM_8_CC_irq_handler (void) +{ + PIOS_TIM_generic_irq_handler (TIM8); +} + diff --git a/flight/PiOS/STM32F10x/pios_usart.c b/flight/PiOS/STM32F10x/pios_usart.c index 8582344b5..68a9265ee 100644 --- a/flight/PiOS/STM32F10x/pios_usart.c +++ b/flight/PiOS/STM32F10x/pios_usart.c @@ -70,12 +70,12 @@ static bool PIOS_USART_validate(struct pios_usart_dev * usart_dev) return (usart_dev->magic == PIOS_USART_DEV_MAGIC); } -#if defined(PIOS_INCLUDE_FREERTOS) && 0 +#if defined(PIOS_INCLUDE_FREERTOS) static struct pios_usart_dev * PIOS_USART_alloc(void) { struct pios_usart_dev * usart_dev; - usart_dev = (struct pios_usart_dev *)malloc(sizeof(*usart_dev)); + usart_dev = (struct pios_usart_dev *)pvPortMalloc(sizeof(*usart_dev)); if (!usart_dev) return(NULL); usart_dev->magic = PIOS_USART_DEV_MAGIC; diff --git a/flight/PiOS/STM32F10x/pios_usb_hid.c b/flight/PiOS/STM32F10x/pios_usb_hid.c index 0ebca1320..8644dd517 100644 --- a/flight/PiOS/STM32F10x/pios_usb_hid.c +++ b/flight/PiOS/STM32F10x/pios_usb_hid.c @@ -75,12 +75,12 @@ static bool PIOS_USB_HID_validate(struct pios_usb_hid_dev * usb_hid_dev) return (usb_hid_dev->magic == PIOS_USB_HID_DEV_MAGIC); } -#if defined(PIOS_INCLUDE_FREERTOS) && 0 +#if defined(PIOS_INCLUDE_FREERTOS) static struct pios_usb_hid_dev * PIOS_USB_HID_alloc(void) { struct pios_usb_hid_dev * usb_hid_dev; - usb_hid_dev = (struct pios_usb_hid_dev *)malloc(sizeof(*usb_hid_dev)); + usb_hid_dev = (struct pios_usb_hid_dev *)pvPortMalloc(sizeof(*usb_hid_dev)); if (!usb_hid_dev) return(NULL); usb_hid_dev->magic = PIOS_USB_HID_DEV_MAGIC; diff --git a/flight/PiOS/inc/pios_debug.h b/flight/PiOS/inc/pios_debug.h index e663d224e..4dc5f5b3e 100644 --- a/flight/PiOS/inc/pios_debug.h +++ b/flight/PiOS/inc/pios_debug.h @@ -33,7 +33,9 @@ extern const char *PIOS_DEBUG_AssertMsg; -void PIOS_DEBUG_Init(void); +#include + +void PIOS_DEBUG_Init(const struct pios_tim_channel * channels, uint8_t num_channels); void PIOS_DEBUG_PinHigh(uint8_t pin); void PIOS_DEBUG_PinLow(uint8_t pin); void PIOS_DEBUG_PinValue8Bit(uint8_t value); diff --git a/flight/PiOS/inc/pios_spektrum.h b/flight/PiOS/inc/pios_dsm.h similarity index 78% rename from flight/PiOS/inc/pios_spektrum.h rename to flight/PiOS/inc/pios_dsm.h index 765d2c8a5..4bd9ed481 100644 --- a/flight/PiOS/inc/pios_spektrum.h +++ b/flight/PiOS/inc/pios_dsm.h @@ -2,13 +2,12 @@ ****************************************************************************** * @addtogroup PIOS PIOS Core hardware abstraction layer * @{ - * @addtogroup PIOS_SPEKTRUM Spektrum receiver functions + * @addtogroup PIOS_DSM Spektrum/JR DSMx satellite receiver functions * @{ * - * @file pios_spektrum.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * Parts by Thorsten Klose (tk@midibox.org) - * @brief Spektrum satellite functions header. + * @file pios_dsm.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. + * @brief Spektrum/JR DSMx satellite receiver functions header. * @see The GNU Public License (GPL) Version 3 * *****************************************************************************/ @@ -28,16 +27,16 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#ifndef PIOS_SPEKTRUM_H -#define PIOS_SPEKTRUM_H +#ifndef PIOS_DSM_H +#define PIOS_DSM_H /* Global Types */ /* Public Functions */ -#endif /* PIOS_SPEKTRUM_H */ +#endif /* PIOS_DSM_H */ /** - * @} - * @} - */ + * @} + * @} + */ diff --git a/flight/PiOS/inc/pios_dsm_priv.h b/flight/PiOS/inc/pios_dsm_priv.h new file mode 100644 index 000000000..480273e39 --- /dev/null +++ b/flight/PiOS/inc/pios_dsm_priv.h @@ -0,0 +1,138 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_DSM Spektrum/JR DSMx satellite receiver functions + * @brief PIOS interface to bind and read Spektrum/JR DSMx satellite receiver + * @{ + * + * @file pios_dsm_priv.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. + * @brief Spektrum/JR DSMx satellite receiver private structures. + * @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_DSM_PRIV_H +#define PIOS_DSM_PRIV_H + +#include +#include +#include + +/* + * Currently known DSMx (DSM2, DSMJ, DSMX) satellite serial port settings: + * 115200bps serial stream, 8 bits, no parity, 1 stop bit + * size of each frame: 16 bytes + * data resolution: 10 or 11 bits + * number of frames: 1 or 2 + * frame period: 11ms or 22ms + * + * Currently known DSMx frame structure: + * 2 bytes - depend on protocol version: + * for DSM2/DSMJ: + * 1 byte - lost frame counter (8 bit) + * 1 byte - data format (for master receiver bound with 3 or 5 pulses), + * or unknown (for slave receiver bound with 4 or 6 pulses, + * some sources call it also the lost frame counter) + * for DSMX: + * 1 byte - unknown data (does not look like lost frame counter) + * 1 byte - unknown data, has been seen only 0xB2 so far + + * 14 bytes - up to 7 channels (16 bit word per channel) with encoded channel + * number, channel value, the "2nd frame in a sequence" flag. + * Unused channels have FF FF instead of data bytes. + * + * Data format identification: + * - for DSM2/DSMJ: [0 0 0 R 0 0 N1 N0] + * where + * R is data resolution (0 - 10 bits, 1 - 11 bits), + * N1..N0 is the number of frames required to receive all channel + * data (01 or 10 are known to the moment, which means 1 or 2 frames). + * Three values for the transmitter information byte have been seen + * thus far: 0x01, 0x02, 0x12. + * - for DSMX this byte contains just 0xB2 or 0xA2 value for any resolution. + * It is not known at the moment how to find the exact resolution from the + * DSMX data stream. The frame number (1 or 2) and 10/11 bit resolution were + * found in different data streams. So it is safer at the moment to ask user + * explicitly choose the resolution. + * Also some weird throttle channel (0) behavior was found in some streams + * from DX8 transmitter (all zeroes). Thus DSMX needs special processing. + * + * Channel data are: + * - for 10 bit: [F 0 C3 C2 C1 C0 D9 D8 D7 D6 D5 D4 D3 D2 D1 D0] + * - for 11 bit: [F C3 C2 C1 C0 D10 D9 D8 D7 D6 D5 D4 D3 D2 D1 D0] + * where + * F is normally 0 but set to 1 for the first channel of the 2nd frame, + * C3 to C0 is the channel number, 4 bit, zero-based, in any order, + * Dx..D0 - channel data (10 or 11 bits) + * + * DSM2 protocol bug: in some cases in 2-frame format some bytes of the + * frame can contain invalid values from the previous frame. They usually + * are the last 5 bytes and can be equal to FF or other data from last + * frame. There is no explicit workaround currently known. + * + * Binding: the number of pulses within bind window after power up defines + * if this receiver is a master (provides receiver capabilities info to + * the transmitter to choose data format) or slave (does not respond to + * the transmitter which falls back to the old DSM mode in that case). + * Currently known are 3(4) pulses for low resolution (10 bit) DSM2 mode, + * 5(6) pulses for high resolution (11 bit) DSM2 mode, and also 7(8) and + * 9(10) pulses for DSMX modes. Thus only 3, 5, 7 or 9 pulses should be + * used for stand-alone satellite receiver to be bound correctly as the + * master. + */ + +#define DSM_CHANNELS_PER_FRAME 7 +#define DSM_FRAME_LENGTH (1+1+DSM_CHANNELS_PER_FRAME*2) +#define DSM_DSM2_RES_MASK 0x0010 +#define DSM_2ND_FRAME_MASK 0x8000 + +/* + * Include lost frame counter and provide it as a last channel value + * for debugging. Currently is not used by the receiver layer. + */ +//#define DSM_LOST_FRAME_COUNTER + +/* DSM protocol variations */ +enum pios_dsm_proto { + PIOS_DSM_PROTO_DSM2, + PIOS_DSM_PROTO_DSMX10BIT, + PIOS_DSM_PROTO_DSMX11BIT, +}; + +/* DSM receiver instance configuration */ +struct pios_dsm_cfg { + struct stm32_gpio bind; +}; + +extern const struct pios_rcvr_driver pios_dsm_rcvr_driver; + +extern int32_t PIOS_DSM_Init(uint32_t *dsm_id, + const struct pios_dsm_cfg *cfg, + const struct pios_com_driver *driver, + uint32_t lower_id, + enum pios_dsm_proto proto, + uint8_t bind); + +#endif /* PIOS_DSM_PRIV_H */ + +/** + * @} + * @} + */ diff --git a/flight/PiOS/inc/pios_flashfs_objlist.h b/flight/PiOS/inc/pios_flashfs_objlist.h index 945df4068..f5c22d973 100644 --- a/flight/PiOS/inc/pios_flashfs_objlist.h +++ b/flight/PiOS/inc/pios_flashfs_objlist.h @@ -32,6 +32,7 @@ #include "uavobjectmanager.h" int32_t PIOS_FLASHFS_Init(); +int32_t PIOS_FLASHFS_Format(); int32_t PIOS_FLASHFS_ObjSave(UAVObjHandle obj, uint16_t instId, uint8_t * data); int32_t PIOS_FLASHFS_ObjLoad(UAVObjHandle obj, uint16_t instId, uint8_t * data); -int32_t PIOS_FLASHFS_ObjDelete(UAVObjHandle obj, uint16_t instId); \ No newline at end of file +int32_t PIOS_FLASHFS_ObjDelete(UAVObjHandle obj, uint16_t instId); diff --git a/flight/PiOS/inc/pios_spektrum_priv.h b/flight/PiOS/inc/pios_gcsrcvr_priv.h similarity index 63% rename from flight/PiOS/inc/pios_spektrum_priv.h rename to flight/PiOS/inc/pios_gcsrcvr_priv.h index 2d31a8027..9a828cb95 100644 --- a/flight/PiOS/inc/pios_spektrum_priv.h +++ b/flight/PiOS/inc/pios_gcsrcvr_priv.h @@ -2,13 +2,13 @@ ****************************************************************************** * @addtogroup PIOS PIOS Core hardware abstraction layer * @{ - * @addtogroup PIOS_SPEKTRUM SPEKTRUM Functions - * @brief PIOS interface to read and write from spektrum port + * @addtogroup PIOS_GCSRCVR GCS Receiver Functions + * @brief PIOS interface to read from GCS receiver port * @{ * - * @file pios_spektrum_priv.h + * @file pios_gcsrcvr_priv.h * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Servo private structures. + * @brief GCS receiver private functions * @see The GNU Public License (GPL) Version 3 * *****************************************************************************/ @@ -28,23 +28,18 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#ifndef PIOS_SPEKTRUM_PRIV_H -#define PIOS_SPEKTRUM_PRIV_H +#ifndef PIOS_GCSRCVR_PRIV_H +#define PIOS_GCSRCVR_PRIV_H #include -#include -#include -struct pios_spektrum_cfg { - struct stm32_gpio bind; - uint32_t remap; /* GPIO_Remap_* */ -}; +#include "gcsreceiver.h" -extern const struct pios_rcvr_driver pios_spektrum_rcvr_driver; +extern const struct pios_rcvr_driver pios_gcsrcvr_rcvr_driver; -extern int32_t PIOS_SPEKTRUM_Init(uint32_t * spektrum_id, const struct pios_spektrum_cfg *cfg, const struct pios_com_driver * driver, uint32_t lower_id, bool bind); +extern void PIOS_GCSRCVR_Init(void); -#endif /* PIOS_PWM_PRIV_H */ +#endif /* PIOS_GCSRCVR_PRIV_H */ /** * @} diff --git a/flight/PiOS/inc/pios_initcall.h b/flight/PiOS/inc/pios_initcall.h index 68b9ef077..e242989c0 100644 --- a/flight/PiOS/inc/pios_initcall.h +++ b/flight/PiOS/inc/pios_initcall.h @@ -67,7 +67,6 @@ extern initmodule_t __module_initcall_start[], __module_initcall_end[]; 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++) \ diff --git a/flight/PiOS/inc/pios_ppm_priv.h b/flight/PiOS/inc/pios_ppm_priv.h index fd863fc50..0facab9d5 100644 --- a/flight/PiOS/inc/pios_ppm_priv.h +++ b/flight/PiOS/inc/pios_ppm_priv.h @@ -35,24 +35,14 @@ #include struct pios_ppm_cfg { - TIM_TimeBaseInitTypeDef tim_base_init; TIM_ICInitTypeDef tim_ic_init; - GPIO_InitTypeDef gpio_init; - uint32_t remap; /* GPIO_Remap_* */ - struct stm32_irq irq; - TIM_TypeDef * timer; - GPIO_TypeDef * port; - uint16_t ccr; + const struct pios_tim_channel * channels; + uint8_t num_channels; }; -extern void PIOS_PPM_irq_handler(); - -extern uint8_t pios_ppm_num_channels; -extern const struct pios_ppm_cfg pios_ppm_cfg; - extern const struct pios_rcvr_driver pios_ppm_rcvr_driver; -extern void PIOS_PPM_Init(void); +extern int32_t PIOS_PPM_Init(uint32_t * ppm_id, const struct pios_ppm_cfg * cfg); #endif /* PIOS_PPM_PRIV_H */ diff --git a/flight/PiOS/inc/pios_pwm_priv.h b/flight/PiOS/inc/pios_pwm_priv.h index 23d7d4818..fe11b3d60 100644 --- a/flight/PiOS/inc/pios_pwm_priv.h +++ b/flight/PiOS/inc/pios_pwm_priv.h @@ -34,32 +34,17 @@ #include #include -struct pios_pwm_channel { - TIM_TypeDef * timer; - GPIO_TypeDef * port; - uint16_t ccr; - uint8_t channel; - uint16_t pin; -}; +#include struct pios_pwm_cfg { - TIM_TimeBaseInitTypeDef tim_base_init; TIM_ICInitTypeDef tim_ic_init; - GPIO_InitTypeDef gpio_init; - uint32_t remap; /* GPIO_Remap_* */ - struct stm32_irq irq; - const struct pios_pwm_channel *const channels; + const struct pios_tim_channel * channels; uint8_t num_channels; }; -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); +extern int32_t PIOS_PWM_Init(uint32_t * pwm_id, const struct pios_pwm_cfg * cfg); #endif /* PIOS_PWM_PRIV_H */ diff --git a/flight/PiOS/inc/pios_rcvr.h b/flight/PiOS/inc/pios_rcvr.h index dfec004f5..ab493cd35 100644 --- a/flight/PiOS/inc/pios_rcvr.h +++ b/flight/PiOS/inc/pios_rcvr.h @@ -31,13 +31,6 @@ #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); @@ -46,6 +39,16 @@ struct pios_rcvr_driver { /* Public Functions */ extern int32_t PIOS_RCVR_Read(uint32_t rcvr_id, uint8_t channel); +/*! Define error codes for PIOS_RCVR_Get */ +enum PIOS_RCVR_errors { + /*! Indicates that a failsafe condition or missing receiver detected for that channel */ + PIOS_RCVR_TIMEOUT = 0, + /*! Channel is invalid for this driver (usually out of range supported) */ + PIOS_RCVR_INVALID = -1, + /*! Indicates that the driver for this channel has not been initialized */ + PIOS_RCVR_NODRIVER = -2 +}; + #endif /* PIOS_RCVR_H */ /** diff --git a/flight/PiOS/inc/pios_sbus.h b/flight/PiOS/inc/pios_sbus.h index 868fedd70..fd8580f2e 100644 --- a/flight/PiOS/inc/pios_sbus.h +++ b/flight/PiOS/inc/pios_sbus.h @@ -2,7 +2,7 @@ ****************************************************************************** * @addtogroup PIOS PIOS Core hardware abstraction layer * @{ - * @addtogroup PIOS_SBUS Futaba S.Bus receiver functions + * @addtogroup PIOS_SBus Futaba S.Bus receiver functions * @{ * * @file pios_sbus.h diff --git a/flight/PiOS/inc/pios_sbus_priv.h b/flight/PiOS/inc/pios_sbus_priv.h index 4e46b2089..127db9a46 100644 --- a/flight/PiOS/inc/pios_sbus_priv.h +++ b/flight/PiOS/inc/pios_sbus_priv.h @@ -2,7 +2,7 @@ ****************************************************************************** * @addtogroup PIOS PIOS Core hardware abstraction layer * @{ - * @addtogroup PIOS_SBUS S.Bus Functions + * @addtogroup PIOS_SBus S.Bus Functions * @brief PIOS interface to read and write from Futaba S.Bus port * @{ * @@ -44,8 +44,8 @@ * 1 byte - 0x0f (start of frame byte) * 22 bytes - channel data (11 bit/channel, 16 channels, LSB first) * 1 byte - bit flags: - * 0x01 - digital channel 1, - * 0x02 - digital channel 2, + * 0x01 - discrete channel 1, + * 0x02 - discrete channel 2, * 0x04 - lost frame flag, * 0x08 - failsafe flag, * 0xf0 - reserved @@ -54,16 +54,22 @@ #define SBUS_FRAME_LENGTH (1+22+1+1) #define SBUS_SOF_BYTE 0x0f #define SBUS_EOF_BYTE 0x00 -#define SBUS_FLAG_DG1 0x01 -#define SBUS_FLAG_DG2 0x02 +#define SBUS_FLAG_DC1 0x01 +#define SBUS_FLAG_DC2 0x02 #define SBUS_FLAG_FL 0x04 #define SBUS_FLAG_FS 0x08 /* - * S.Bus protocol provides up to 16 analog and 2 digital channels. - * Only 8 channels are currently supported by the OpenPilot. + * S.Bus protocol provides 16 proportional and 2 discrete channels. + * Do not change unless driver code is updated accordingly. */ -#define SBUS_NUMBER_OF_CHANNELS 8 +#if (PIOS_SBUS_NUM_INPUTS != (16+2)) +#error "S.Bus protocol provides 16 proportional and 2 discrete channels" +#endif + +/* Discrete channels represented as bits, provide values for them */ +#define SBUS_VALUE_MIN 352 +#define SBUS_VALUE_MAX 1696 /* * S.Bus configuration programmable invertor @@ -77,7 +83,10 @@ struct pios_sbus_cfg { extern const struct pios_rcvr_driver pios_sbus_rcvr_driver; -extern int32_t PIOS_SBUS_Init(uint32_t * sbus_id, const struct pios_sbus_cfg *cfg, const struct pios_com_driver * driver, uint32_t lower_id); +extern int32_t PIOS_SBus_Init(uint32_t *sbus_id, + const struct pios_sbus_cfg *cfg, + const struct pios_com_driver *driver, + uint32_t lower_id); #endif /* PIOS_SBUS_PRIV_H */ diff --git a/flight/PiOS/inc/pios_servo.h b/flight/PiOS/inc/pios_servo.h index 2d621cb25..043d656df 100644 --- a/flight/PiOS/inc/pios_servo.h +++ b/flight/PiOS/inc/pios_servo.h @@ -31,7 +31,6 @@ #define PIOS_SERVO_H /* Public Functions */ -extern void PIOS_Servo_Init(void); extern void PIOS_Servo_SetHz(uint16_t * update_rates, uint8_t channels); extern void PIOS_Servo_Set(uint8_t Servo, uint16_t Position); diff --git a/flight/PiOS/inc/pios_servo_priv.h b/flight/PiOS/inc/pios_servo_priv.h index a1136c46d..f5ed86e25 100644 --- a/flight/PiOS/inc/pios_servo_priv.h +++ b/flight/PiOS/inc/pios_servo_priv.h @@ -33,25 +33,18 @@ #include #include - -struct pios_servo_channel { - TIM_TypeDef * timer; - GPIO_TypeDef * port; - uint8_t channel; - uint16_t pin; -}; +#include struct pios_servo_cfg { TIM_TimeBaseInitTypeDef tim_base_init; TIM_OCInitTypeDef tim_oc_init; GPIO_InitTypeDef gpio_init; uint32_t remap; - const struct pios_servo_channel *const channels; + const struct pios_tim_channel * channels; uint8_t num_channels; }; - -extern const struct pios_servo_cfg pios_servo_cfg; +extern int32_t PIOS_Servo_Init(const struct pios_servo_cfg * cfg); #endif /* PIOS_SERVO_PRIV_H */ diff --git a/flight/PiOS/inc/pios_tim.h b/flight/PiOS/inc/pios_tim.h new file mode 100644 index 000000000..0bad07f41 --- /dev/null +++ b/flight/PiOS/inc/pios_tim.h @@ -0,0 +1,4 @@ +#ifndef PIOS_TIM_H +#define PIOS_TIM_H + +#endif /* PIOS_TIM_H */ diff --git a/flight/PiOS/inc/pios_tim_priv.h b/flight/PiOS/inc/pios_tim_priv.h new file mode 100644 index 000000000..7f05719f8 --- /dev/null +++ b/flight/PiOS/inc/pios_tim_priv.h @@ -0,0 +1,28 @@ +#ifndef PIOS_TIM_PRIV_H +#define PIOS_TIM_PRIV_H + +#include + +struct pios_tim_clock_cfg { + TIM_TypeDef * timer; + const TIM_TimeBaseInitTypeDef * time_base_init; + struct stm32_irq irq; +}; + +struct pios_tim_channel { + TIM_TypeDef * timer; + uint8_t timer_chan; + + struct stm32_gpio pin; + uint32_t remap; +}; + +struct pios_tim_callbacks { + void (*overflow)(uint32_t tim_id, uint32_t context, uint8_t chan_idx, uint16_t count); + void (*edge)(uint32_t tim_id, uint32_t context, uint8_t chan_idx, uint16_t count); +}; + +extern int32_t PIOS_TIM_InitClock(const struct pios_tim_clock_cfg * cfg); +extern int32_t PIOS_TIM_InitChannels(uint32_t * tim_id, const struct pios_tim_channel * channels, uint8_t num_channels, const struct pios_tim_callbacks * callbacks, uint32_t context); + +#endif /* PIOS_TIM_PRIV_H */ diff --git a/flight/PiOS/pios.h b/flight/PiOS/pios.h index a675f93b1..58d869517 100644 --- a/flight/PiOS/pios.h +++ b/flight/PiOS/pios.h @@ -59,7 +59,9 @@ #endif /* Generic initcall infrastructure */ +#if defined(PIOS_INCLUDE_INITCALL) #include "pios_initcall.h" +#endif /* PIOS Board Specific Device Configuration */ #include "pios_board.h" @@ -79,7 +81,7 @@ #include #include #include -#include +#include #include #include #include diff --git a/flight/PipXtreme/Makefile b/flight/PipXtreme/Makefile index 9a70ac417..8a939d411 100644 --- a/flight/PipXtreme/Makefile +++ b/flight/PipXtreme/Makefile @@ -394,7 +394,7 @@ $(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin $(eval $(call OPFW_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BOARD_TYPE),$(BOARD_REVISION))) # Add jtag targets (program and wipe) -$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE))) +$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE),$(OPENOCD_CONFIG))) .PHONY: elf lss sym hex bin bino opfw elf: $(OUTDIR)/$(TARGET).elf diff --git a/flight/Project/OpenOCD/stm32f1x.cfg b/flight/Project/OpenOCD/stm32f1x.cfg new file mode 100644 index 000000000..9047b5aff --- /dev/null +++ b/flight/Project/OpenOCD/stm32f1x.cfg @@ -0,0 +1,75 @@ +# script for stm32 + +if { [info exists CHIPNAME] } { + set _CHIPNAME $CHIPNAME +} else { + set _CHIPNAME stm32 +} + +if { [info exists ENDIAN] } { + set _ENDIAN $ENDIAN +} else { + set _ENDIAN little +} + +# Work-area is a space in RAM used for flash programming +# By default use 16kB +if { [info exists WORKAREASIZE] } { + set _WORKAREASIZE $WORKAREASIZE +} else { + set _WORKAREASIZE 0x4000 +} + +# JTAG speed should be <= F_CPU/6. F_CPU after reset is 8MHz, so use F_JTAG = 1MHz +adapter_khz 1000 + +adapter_nsrst_delay 100 +jtag_ntrst_delay 100 + +#jtag scan chain +if { [info exists CPUTAPID ] } { + set _CPUTAPID $CPUTAPID +} else { + # See STM Document RM0008 + # Section 26.6.3 + set _CPUTAPID 0x3ba00477 +} +jtag newtap $_CHIPNAME cpu -irlen 4 -ircapture 0x1 -irmask 0xf -expected-id $_CPUTAPID + +if { [info exists BSTAPID ] } { + # FIXME this never gets used to override defaults... + set _BSTAPID $BSTAPID +} else { + # See STM Document RM0008 + # Section 29.6.2 + # Low density devices, Rev A + set _BSTAPID1 0x06412041 + # Medium density devices, Rev A + set _BSTAPID2 0x06410041 + # Medium density devices, Rev B and Rev Z + set _BSTAPID3 0x16410041 + set _BSTAPID4 0x06420041 + # High density devices, Rev A + set _BSTAPID5 0x06414041 + # Connectivity line devices, Rev A and Rev Z + set _BSTAPID6 0x06418041 + # XL line devices, Rev A + set _BSTAPID7 0x06430041 +} +jtag newtap $_CHIPNAME bs -irlen 5 -expected-id $_BSTAPID1 \ + -expected-id $_BSTAPID2 -expected-id $_BSTAPID3 \ + -expected-id $_BSTAPID4 -expected-id $_BSTAPID5 \ + -expected-id $_BSTAPID6 -expected-id $_BSTAPID7 + +set _TARGETNAME $_CHIPNAME.cpu +target create $_TARGETNAME cortex_m3 -endian $_ENDIAN -chain-position $_TARGETNAME -rtos auto + +$_TARGETNAME configure -work-area-phys 0x20000000 -work-area-size $_WORKAREASIZE -work-area-backup 0 + +# flash size will be probed +set _FLASHNAME $_CHIPNAME.flash +flash bank $_FLASHNAME stm32f1x 0x08000000 0 0 0 $_TARGETNAME + +# if srst is not fitted use SYSRESETREQ to +# perform a soft reset +cortex_m3 reset_config sysresetreq diff --git a/flight/Project/OpenOCD/stm32f2x.cfg b/flight/Project/OpenOCD/stm32f2x.cfg new file mode 100644 index 000000000..b5cea55e5 --- /dev/null +++ b/flight/Project/OpenOCD/stm32f2x.cfg @@ -0,0 +1,61 @@ +# script for stm32f2xxx + +if { [info exists CHIPNAME] } { + set _CHIPNAME $CHIPNAME +} else { + set _CHIPNAME stm32f2xxx +} + +if { [info exists ENDIAN] } { + set _ENDIAN $ENDIAN +} else { + set _ENDIAN little +} + +# Work-area is a space in RAM used for flash programming +# By default use 64kB +if { [info exists WORKAREASIZE] } { + set _WORKAREASIZE $WORKAREASIZE +} else { + set _WORKAREASIZE 0x10000 +} + +# JTAG speed should be <= F_CPU/6. F_CPU after reset is 8MHz, so use F_JTAG = 1MHz +# +# Since we may be running of an RC oscilator, we crank down the speed a +# bit more to be on the safe side. Perhaps superstition, but if are +# running off a crystal, we can run closer to the limit. Note +# that there can be a pretty wide band where things are more or less stable. +jtag_khz 1000 + +jtag_nsrst_delay 100 +jtag_ntrst_delay 100 + +#jtag scan chain +if { [info exists CPUTAPID ] } { + set _CPUTAPID $CPUTAPID +} else { + # See STM Document RM0033 + # Section 32.6.3 - corresponds to Cortex-M3 r2p0 + set _CPUTAPID 0x4ba00477 +} +jtag newtap $_CHIPNAME cpu -irlen 4 -ircapture 0x1 -irmask 0xf -expected-id $_CPUTAPID + +if { [info exists BSTAPID ] } { + set _BSTAPID $BSTAPID +} else { + # See STM Document RM0033 + # Section 32.6.2 + # + set _BSTAPID 0x06411041 +} +jtag newtap $_CHIPNAME bs -irlen 5 -expected-id $_BSTAPID + +set _TARGETNAME $_CHIPNAME.cpu +target create $_TARGETNAME cortex_m3 -endian $_ENDIAN -chain-position $_TARGETNAME -rtos auto + +$_TARGETNAME configure -work-area-phys 0x20000000 -work-area-size $_WORKAREASIZE -work-area-backup 0 + +set _FLASHNAME $_CHIPNAME.flash +flash bank $_FLASHNAME stm32f2x 0 0 0 0 $_TARGETNAME + diff --git a/flight/Project/OpenPilotOSX/OpenPilotOSX.xcodeproj/project.pbxproj b/flight/Project/OpenPilotOSX/OpenPilotOSX.xcodeproj/project.pbxproj index 3a0fc1dfa..ed4340a11 100644 --- a/flight/Project/OpenPilotOSX/OpenPilotOSX.xcodeproj/project.pbxproj +++ b/flight/Project/OpenPilotOSX/OpenPilotOSX.xcodeproj/project.pbxproj @@ -85,11 +85,20 @@ 6549E0D21279B3C800C5476F /* fifo_buffer.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = fifo_buffer.c; sourceTree = ""; }; 6549E0D31279B3CF00C5476F /* fifo_buffer.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = fifo_buffer.h; sourceTree = ""; }; 655268BC121FBD2900410C6E /* ahrscalibration.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = ahrscalibration.xml; sourceTree = ""; }; + 655B1A8E13B2FC0900B0E48D /* camerastabsettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = camerastabsettings.xml; sourceTree = ""; }; 656268C612DC1923007B0A0F /* nedaccel.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = nedaccel.xml; sourceTree = ""; }; 6562BE1713CCAD0600C823E8 /* pios_rcvr.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_rcvr.c; sourceTree = ""; }; 65632DF51251650300469B77 /* pios_board.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_board.h; sourceTree = ""; }; 65632DF61251650300469B77 /* STM32103CB_AHRS.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = STM32103CB_AHRS.h; sourceTree = ""; }; 65632DF71251650300469B77 /* STM3210E_OP.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = STM3210E_OP.h; sourceTree = ""; }; + 65643CAB1413322000A32F59 /* pios_rcvr_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_rcvr_priv.h; sourceTree = ""; }; + 65643CAC1413322000A32F59 /* pios_rcvr.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_rcvr.h; sourceTree = ""; }; + 65643CAD1413322000A32F59 /* pios_rtc_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_rtc_priv.h; sourceTree = ""; }; + 65643CAE1413322000A32F59 /* pios_sbus_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_sbus_priv.h; sourceTree = ""; }; + 65643CAF1413322000A32F59 /* pios_sbus.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_sbus.h; sourceTree = ""; }; + 65643CB01413322000A32F59 /* pios_dsm_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_dsm_priv.h; sourceTree = ""; }; + 65643CB91413456D00A32F59 /* pios_tim.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_tim.c; sourceTree = ""; }; + 65643CBA141350C200A32F59 /* pios_sbus.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = pios_sbus.c; sourceTree = ""; }; 6572CB1613D0F2B200FC2972 /* link_STM32103CB_CC_Rev1_memory.ld */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; name = link_STM32103CB_CC_Rev1_memory.ld; path = ../../PiOS/STM32F10x/link_STM32103CB_CC_Rev1_memory.ld; sourceTree = SOURCE_ROOT; }; 6572CB1713D0F2B200FC2972 /* link_STM32103CB_CC_Rev1_sections.ld */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text; name = link_STM32103CB_CC_Rev1_sections.ld; path = ../../PiOS/STM32F10x/link_STM32103CB_CC_Rev1_sections.ld; sourceTree = SOURCE_ROOT; }; 657CEEAD121DB6C8007A1FBE /* homelocation.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = homelocation.xml; sourceTree = ""; }; @@ -2647,7 +2656,6 @@ 65C35E5612EFB2F3004811C2 /* attitudeactual.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = attitudeactual.xml; sourceTree = ""; }; 65C35E5812EFB2F3004811C2 /* attituderaw.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = attituderaw.xml; sourceTree = ""; }; 65C35E5912EFB2F3004811C2 /* baroaltitude.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = baroaltitude.xml; sourceTree = ""; }; - 65C35E5A12EFB2F3004811C2 /* batterysettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = batterysettings.xml; sourceTree = ""; }; 65C35E5C12EFB2F3004811C2 /* flightbatterystate.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = flightbatterystate.xml; sourceTree = ""; }; 65C35E5D12EFB2F3004811C2 /* flightplancontrol.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = flightplancontrol.xml; sourceTree = ""; }; 65C35E5E12EFB2F3004811C2 /* flightplansettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = flightplansettings.xml; sourceTree = ""; }; @@ -2680,7 +2688,6 @@ 65C35E7912EFB2F3004811C2 /* watchdogstatus.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = watchdogstatus.xml; sourceTree = ""; }; 65C35E9E12F0A834004811C2 /* uavobjecttemplate.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = uavobjecttemplate.c; sourceTree = ""; }; 65C35E9F12F0A834004811C2 /* uavobjectsinittemplate.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = uavobjectsinittemplate.c; sourceTree = ""; }; - 65C35EA012F0A834004811C2 /* uavobjectsinit_cc.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = uavobjectsinit_cc.c; sourceTree = ""; }; 65C35EA112F0A834004811C2 /* uavobjectmanager.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = uavobjectmanager.c; sourceTree = ""; }; 65C35EA312F0A834004811C2 /* eventdispatcher.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = eventdispatcher.h; sourceTree = ""; }; 65C35EA412F0A834004811C2 /* uavobjectmanager.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = uavobjectmanager.h; sourceTree = ""; }; @@ -2690,9 +2697,13 @@ 65C35EA812F0A834004811C2 /* eventdispatcher.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = eventdispatcher.c; sourceTree = ""; }; 65C35F6612F0DC2D004811C2 /* attitude.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = attitude.c; sourceTree = ""; }; 65C35F6812F0DC2D004811C2 /* attitude.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = attitude.h; sourceTree = ""; }; + 65C9903C13A871B90082BD60 /* camerastab.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = camerastab.c; sourceTree = ""; }; + 65C9903E13A871B90082BD60 /* camerastab.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = camerastab.h; sourceTree = ""; }; 65D2CA841248F9A400B1E7D6 /* mixersettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = mixersettings.xml; sourceTree = ""; }; 65D2CA851248F9A400B1E7D6 /* mixerstatus.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = mixerstatus.xml; sourceTree = ""; }; + 65DEA79113F2143B00095B06 /* cameradesired.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = cameradesired.xml; sourceTree = ""; }; 65E410AE12F65AEA00725888 /* attitudesettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = attitudesettings.xml; sourceTree = ""; }; + 65E6D80713E3A4D0002A557A /* hwsettings.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = hwsettings.xml; sourceTree = ""; }; 65E6DF7112E02E8E00058553 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = ""; }; 65E6DF7312E02E8E00058553 /* alarms.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = alarms.c; sourceTree = ""; }; 65E6DF7412E02E8E00058553 /* coptercontrol.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = coptercontrol.c; sourceTree = ""; }; @@ -2785,7 +2796,7 @@ 65E8F04911EFF25C00BBF654 /* pios_pwm.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_pwm.h; path = ../../PiOS/inc/pios_pwm.h; sourceTree = SOURCE_ROOT; }; 65E8F04A11EFF25C00BBF654 /* pios_sdcard.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_sdcard.h; path = ../../PiOS/inc/pios_sdcard.h; sourceTree = SOURCE_ROOT; }; 65E8F04B11EFF25C00BBF654 /* pios_servo.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_servo.h; path = ../../PiOS/inc/pios_servo.h; sourceTree = SOURCE_ROOT; }; - 65E8F04C11EFF25C00BBF654 /* pios_spektrum.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_spektrum.h; path = ../../PiOS/inc/pios_spektrum.h; sourceTree = SOURCE_ROOT; }; + 65E8F04C11EFF25C00BBF654 /* pios_dsm.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_dsm.h; path = ../../PiOS/inc/pios_dsm.h; sourceTree = SOURCE_ROOT; }; 65E8F04D11EFF25C00BBF654 /* pios_spi.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_spi.h; path = ../../PiOS/inc/pios_spi.h; sourceTree = SOURCE_ROOT; }; 65E8F04E11EFF25C00BBF654 /* pios_spi_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_spi_priv.h; path = ../../PiOS/inc/pios_spi_priv.h; sourceTree = SOURCE_ROOT; }; 65E8F04F11EFF25C00BBF654 /* pios_stm32.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; name = pios_stm32.h; path = ../../PiOS/inc/pios_stm32.h; sourceTree = SOURCE_ROOT; }; @@ -2914,7 +2925,7 @@ 65E8F0E411EFF25C00BBF654 /* pios_ppm.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_ppm.c; path = ../../PiOS/STM32F10x/pios_ppm.c; sourceTree = SOURCE_ROOT; }; 65E8F0E511EFF25C00BBF654 /* pios_pwm.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_pwm.c; path = ../../PiOS/STM32F10x/pios_pwm.c; sourceTree = SOURCE_ROOT; }; 65E8F0E611EFF25C00BBF654 /* pios_servo.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_servo.c; path = ../../PiOS/STM32F10x/pios_servo.c; sourceTree = SOURCE_ROOT; }; - 65E8F0E711EFF25C00BBF654 /* pios_spektrum.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_spektrum.c; path = ../../PiOS/STM32F10x/pios_spektrum.c; sourceTree = SOURCE_ROOT; }; + 65E8F0E711EFF25C00BBF654 /* pios_dsm.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_dsm.c; path = ../../PiOS/STM32F10x/pios_dsm.c; sourceTree = SOURCE_ROOT; }; 65E8F0E811EFF25C00BBF654 /* pios_spi.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_spi.c; path = ../../PiOS/STM32F10x/pios_spi.c; sourceTree = SOURCE_ROOT; }; 65E8F0E911EFF25C00BBF654 /* pios_sys.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_sys.c; path = ../../PiOS/STM32F10x/pios_sys.c; sourceTree = SOURCE_ROOT; }; 65E8F0EA11EFF25C00BBF654 /* pios_usart.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = pios_usart.c; path = ../../PiOS/STM32F10x/pios_usart.c; sourceTree = SOURCE_ROOT; }; @@ -3128,6 +3139,7 @@ 65F93D0712EE09290047DB36 /* uavtalk_comms.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = uavtalk_comms.c; sourceTree = ""; }; 65F93D0812EE09290047DB36 /* watchdog.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = watchdog.c; sourceTree = ""; }; 65FAA03F133B669400F6F5CD /* GTOP_BIN.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; path = GTOP_BIN.c; sourceTree = ""; }; + 65FAB8CF147FFD76000FF8B2 /* receiveractivity.xml */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = text.xml; path = receiveractivity.xml; sourceTree = ""; }; 65FBE14412E7C98100176B5A /* pios_servo_priv.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = pios_servo_priv.h; sourceTree = ""; }; 65FC66AA123F30F100B04F74 /* ahrs_timer.c */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.c; name = ahrs_timer.c; path = ../../AHRS/ahrs_timer.c; sourceTree = SOURCE_ROOT; }; 65FC66AB123F312A00B04F74 /* ahrs_timer.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ahrs_timer.h; sourceTree = ""; }; @@ -3208,6 +3220,7 @@ 650D8E2812DFE16400D05CC9 /* Altitude */, 65C35F6512F0DC2D004811C2 /* Attitude */, 650D8E2E12DFE16400D05CC9 /* Battery */, + 65C9903B13A871B90082BD60 /* CameraStab */, 650D8E3212DFE16400D05CC9 /* Example */, 650D8E3B12DFE16400D05CC9 /* FirmwareIAP */, 650D8E3F12DFE16400D05CC9 /* FlightPlan */, @@ -3517,7 +3530,6 @@ children = ( 65C35E9E12F0A834004811C2 /* uavobjecttemplate.c */, 65C35E9F12F0A834004811C2 /* uavobjectsinittemplate.c */, - 65C35EA012F0A834004811C2 /* uavobjectsinit_cc.c */, 65C35EA112F0A834004811C2 /* uavobjectmanager.c */, 65C35EA212F0A834004811C2 /* inc */, 65C35EA812F0A834004811C2 /* eventdispatcher.c */, @@ -7433,7 +7445,7 @@ 65C35E5812EFB2F3004811C2 /* attituderaw.xml */, 65E410AE12F65AEA00725888 /* attitudesettings.xml */, 65C35E5912EFB2F3004811C2 /* baroaltitude.xml */, - 65C35E5A12EFB2F3004811C2 /* batterysettings.xml */, + 655B1A8E13B2FC0900B0E48D /* camerastabsettings.xml */, 652C8568132B632A00BFCC70 /* firmwareiapobj.xml */, 65C35E5C12EFB2F3004811C2 /* flightbatterystate.xml */, 65C35E5D12EFB2F3004811C2 /* flightplancontrol.xml */, @@ -7447,6 +7459,7 @@ 65C35E6412EFB2F3004811C2 /* gpstime.xml */, 65C35E6512EFB2F3004811C2 /* guidancesettings.xml */, 65C35E6612EFB2F3004811C2 /* homelocation.xml */, + 65E6D80713E3A4D0002A557A /* hwsettings.xml */, 65C35E6712EFB2F3004811C2 /* i2cstats.xml */, 65C35E6812EFB2F3004811C2 /* manualcontrolcommand.xml */, 65C35E6912EFB2F3004811C2 /* manualcontrolsettings.xml */, @@ -7457,6 +7470,7 @@ 65C35E6E12EFB2F3004811C2 /* positionactual.xml */, 65C35E6F12EFB2F3004811C2 /* positiondesired.xml */, 65C35E7012EFB2F3004811C2 /* ratedesired.xml */, + 65FAB8CF147FFD76000FF8B2 /* receiveractivity.xml */, 652C856A132B6EA600BFCC70 /* sonaraltitude.xml */, 6536D47B1307962C0042A298 /* stabilizationdesired.xml */, 65C35E7112EFB2F3004811C2 /* stabilizationsettings.xml */, @@ -7468,6 +7482,7 @@ 65C35E7712EFB2F3004811C2 /* velocityactual.xml */, 65C35E7812EFB2F3004811C2 /* velocitydesired.xml */, 65C35E7912EFB2F3004811C2 /* watchdogstatus.xml */, + 65DEA79113F2143B00095B06 /* cameradesired.xml */, ); path = uavobjectdefinition; sourceTree = ""; @@ -7501,6 +7516,23 @@ path = inc; sourceTree = ""; }; + 65C9903B13A871B90082BD60 /* CameraStab */ = { + isa = PBXGroup; + children = ( + 65C9903C13A871B90082BD60 /* camerastab.c */, + 65C9903D13A871B90082BD60 /* inc */, + ); + path = CameraStab; + sourceTree = ""; + }; + 65C9903D13A871B90082BD60 /* inc */ = { + isa = PBXGroup; + children = ( + 65C9903E13A871B90082BD60 /* camerastab.h */, + ); + path = inc; + sourceTree = ""; + }; 65E6DF7012E02E8E00058553 /* CopterControl */ = { isa = PBXGroup; children = ( @@ -7700,11 +7732,17 @@ 65E8F04811EFF25C00BBF654 /* pios_ppm.h */, 65E8F04911EFF25C00BBF654 /* pios_pwm.h */, 657FF86A12EA8BFB00801617 /* pios_pwm_priv.h */, + 65643CAC1413322000A32F59 /* pios_rcvr.h */, + 65643CAB1413322000A32F59 /* pios_rcvr_priv.h */, 6589A9E2131DF1C7006BD67C /* pios_rtc.h */, + 65643CAD1413322000A32F59 /* pios_rtc_priv.h */, + 65643CAE1413322000A32F59 /* pios_sbus_priv.h */, + 65643CAF1413322000A32F59 /* pios_sbus.h */, 65E8F04A11EFF25C00BBF654 /* pios_sdcard.h */, 65E8F04B11EFF25C00BBF654 /* pios_servo.h */, 65FBE14412E7C98100176B5A /* pios_servo_priv.h */, - 65E8F04C11EFF25C00BBF654 /* pios_spektrum.h */, + 65E8F04C11EFF25C00BBF654 /* pios_dsm.h */, + 65643CB01413322000A32F59 /* pios_dsm_priv.h */, 65E8F04D11EFF25C00BBF654 /* pios_spi.h */, 65E8F04E11EFF25C00BBF654 /* pios_spi_priv.h */, 65E8F04F11EFF25C00BBF654 /* pios_stm32.h */, @@ -7728,6 +7766,8 @@ 65E8F05811EFF25C00BBF654 /* STM32F10x */ = { isa = PBXGroup; children = ( + 6572CB1613D0F2B200FC2972 /* link_STM32103CB_CC_Rev1_memory.ld */, + 6572CB1713D0F2B200FC2972 /* link_STM32103CB_CC_Rev1_sections.ld */, 65E8F05911EFF25C00BBF654 /* Libraries */, 65E8F0D811EFF25C00BBF654 /* link_stm32f10x_HD.ld */, 65E8F0DB11EFF25C00BBF654 /* link_stm32f10x_MD.ld */, @@ -7742,10 +7782,12 @@ 65E8F0E411EFF25C00BBF654 /* pios_ppm.c */, 65E8F0E511EFF25C00BBF654 /* pios_pwm.c */, 6589A9DB131DEE76006BD67C /* pios_rtc.c */, + 65643CBA141350C200A32F59 /* pios_sbus.c */, 65E8F0E611EFF25C00BBF654 /* pios_servo.c */, - 65E8F0E711EFF25C00BBF654 /* pios_spektrum.c */, + 65E8F0E711EFF25C00BBF654 /* pios_dsm.c */, 65E8F0E811EFF25C00BBF654 /* pios_spi.c */, 65E8F0E911EFF25C00BBF654 /* pios_sys.c */, + 65643CB91413456D00A32F59 /* pios_tim.c */, 65E8F0EA11EFF25C00BBF654 /* pios_usart.c */, 65E8F0ED11EFF25C00BBF654 /* pios_usb_hid.c */, 651CF9E5120B5D8300EEFD70 /* pios_usb_hid_desc.c */, @@ -7763,8 +7805,6 @@ 65E8F05911EFF25C00BBF654 /* Libraries */ = { isa = PBXGroup; children = ( - 6572CB1613D0F2B200FC2972 /* link_STM32103CB_CC_Rev1_memory.ld */, - 6572CB1713D0F2B200FC2972 /* link_STM32103CB_CC_Rev1_sections.ld */, 65E8F05A11EFF25C00BBF654 /* CMSIS */, 65E8F06B11EFF25C00BBF654 /* dosfs */, 65E8F07111EFF25C00BBF654 /* FreeRTOS */, diff --git a/flight/Project/versionblob.py b/flight/Project/versionblob.py deleted file mode 100755 index 82440a746..000000000 --- a/flight/Project/versionblob.py +++ /dev/null @@ -1,99 +0,0 @@ -#!/usr/bin/env python - -# Generate a version blob for -# the OpenPilot firmware. -# -# By E. Lafargue (c) 2011 E. Lafargue & the OpenPilot team -# Licence: GPLv3 -# -### -# Usage: -# versionblob.py --append --firmware= --boardid= -# -# append: if present, then append blob to firmware file directly, otherwise create "blob.bin" -# firmware: the filename of the firmware binary -# boardid: as a string, the board code, for example "0401" for CC board version 1. -# should match the codes in firmware description files. -# -# We have 100 bytes for the whole description. -# -# Only the first 40 are visible on the FirmwareIAP uavobject, the remaining -# 60 are ok to use for packaging and will be saved in the flash -# -# Structure is: -# 4 bytes: header: "OpFw" -# 4 bytes: GIT commit tag (short version of SHA1) -# 4 bytes: Unix timestamp of compile time -# 2 bytes: target platform. Should follow same rule as BOARD_TYPE and BOARD_REVISION in board define files. -# 26 bytes: commit tag if it is there, otherwise branch name. Zero-padded -# ---- 40 bytes limit --- -# 20 bytes: SHA1 sum of the firmware. -# 40 bytes: free for now. - -import binascii -import os -from time import time -import argparse - -# Do the argument parsing: -parser = argparse.ArgumentParser(description='Generate firmware desciption blob') -parser.add_argument('--append', action='store_true') -parser.add_argument('--firmware', help='name of firmware binary file' , required=True) -parser.add_argument('--boardid', help='ID of board model, for example 0401 for CopterControl', required=True) -args = parser.parse_args() -print args - -if args.append == True: - print 'Appending description blob directly to ' + args.firmware - filename = args.firmware - file = open(filename,"ab") -else: - filename = 'blob.bin' - file = open(filename,"wb") - - -# Write the magic value: -file.write("OpFw") -# Get the short commit tag of the current git repository. -# Strip it to 8 characters for a 4 byte (int32) value. -# We have no full guarantee of unicity, but it is good enough -# with the rest of the information in the structure. -hs= os.popen('git rev-parse --short=8 HEAD').read().strip() -print "Version: " + hs -hb=binascii.a2b_hex(hs) -file.write(hb) -# Then the Unix time into a 32 bit integer: -print "Date: " + hex(int(time())).lstrip('0x') -hb = binascii.a2b_hex(hex(int(time())).lstrip('0x')) -file.write(hb) - -# Then write board type and board revision -hb = binascii.a2b_hex(args.boardid) -file.write(hb) - -# Last: a user-friendly description if it exists in GIT, otherwise -# just "unreleased" -hs = os.popen('git describe --exact-match').read() -if len(hs) == 0 : - print "Unreleased: get branch name instead" - hs = os.popen('git branch --contains HEAD').read() - -file.write(hs[0:26]) -file.write("\0"*(26-len(hs))) - -## Now we are at the 40 bytes mark. - -## Add the 20 byte SHA1 hash of the firmware: -import hashlib -sha1 = hashlib.sha1() -with open('build/coptercontrol/CopterControl.bin','rb') as f: - for chunk in iter(lambda: f.read(8192), ''): - sha1.update(chunk) -file.write(sha1.digest()) - -# Pad will null bytes: -file.write('\0'*40) - - -file.close() - diff --git a/flight/UAVObjects/inc/uavobjectsinit.h b/flight/UAVObjects/inc/uavobjectsinittemplate.h similarity index 93% rename from flight/UAVObjects/inc/uavobjectsinit.h rename to flight/UAVObjects/inc/uavobjectsinittemplate.h index ec946ba92..ec11c47ad 100644 --- a/flight/UAVObjects/inc/uavobjectsinit.h +++ b/flight/UAVObjects/inc/uavobjectsinittemplate.h @@ -29,4 +29,6 @@ void UAVObjectsInitializeAll(); +#define UAVOBJECTS_LARGEST $(SIZECALCULATION) + #endif // UAVOBJECTSINIT_H diff --git a/flight/UAVObjects/inc/uavobjecttemplate.h b/flight/UAVObjects/inc/uavobjecttemplate.h index 9564d05d2..f106dd8ba 100644 --- a/flight/UAVObjects/inc/uavobjecttemplate.h +++ b/flight/UAVObjects/inc/uavobjecttemplate.h @@ -67,7 +67,7 @@ #define $(NAME)InstUpdated(instId) UAVObjUpdated($(NAME)Handle(), instId) #define $(NAME)GetMetadata(dataOut) UAVObjGetMetadata($(NAME)Handle(), dataOut) #define $(NAME)SetMetadata(dataIn) UAVObjSetMetadata($(NAME)Handle(), dataIn) -#define $(NAME)ReadOnly(dataIn) UAVObjReadOnly($(NAME)Handle()) +#define $(NAME)ReadOnly() UAVObjReadOnly($(NAME)Handle()) // Object data typedef struct { diff --git a/flight/UAVObjects/uavobjectsinittemplate.c b/flight/UAVObjects/uavobjectsinittemplate.c index 75a104d18..97a1525a4 100644 --- a/flight/UAVObjects/uavobjectsinittemplate.c +++ b/flight/UAVObjects/uavobjectsinittemplate.c @@ -36,5 +36,7 @@ $(OBJINC) */ void UAVObjectsInitializeAll() { +return; +// This function is no longer used anyway $(OBJINIT) } diff --git a/flight/UAVObjects/uavobjecttemplate.c b/flight/UAVObjects/uavobjecttemplate.c index 9dd45b09f..6d572dbcb 100644 --- a/flight/UAVObjects/uavobjecttemplate.c +++ b/flight/UAVObjects/uavobjecttemplate.c @@ -40,15 +40,19 @@ #include "$(NAMELC).h" // Private variables -static UAVObjHandle handle; +static UAVObjHandle handle = NULL; /** * Initialize object. * \return 0 Success - * \return -1 Failure + * \return -1 Failure to initialize or -2 for already initialized */ int32_t $(NAME)Initialize(void) { + // Don't set the handle to null if already registered + if(UAVObjGetByID($(NAMEUC)_OBJID) != NULL) + return -2; + // Register object with the object manager handle = UAVObjRegister($(NAMEUC)_OBJID, $(NAMEUC)_NAME, $(NAMEUC)_METANAME, 0, $(NAMEUC)_ISSINGLEINST, $(NAMEUC)_ISSETTINGS, $(NAMEUC)_NUMBYTES, &$(NAME)SetDefaults); @@ -64,8 +68,6 @@ int32_t $(NAME)Initialize(void) } } -UAVOBJ_INITCALL($(NAME)Initialize); - /** * Initialize object fields and metadata with the default values. * If a default value is not specified the object fields diff --git a/flight/UAVTalk/inc/uavtalk.h b/flight/UAVTalk/inc/uavtalk.h index 7a257620d..71114ce74 100644 --- a/flight/UAVTalk/inc/uavtalk.h +++ b/flight/UAVTalk/inc/uavtalk.h @@ -29,10 +29,6 @@ #ifndef UAVTALK_H #define UAVTALK_H -// Public constants -#define UAVTALK_WAITFOREVER -1 -#define UAVTALK_NOWAIT 0 - // Public types typedef int32_t (*UAVTalkOutputStream)(uint8_t* data, int32_t length); @@ -47,14 +43,17 @@ typedef struct { uint32_t rxErrors; } UAVTalkStats; +typedef void* UAVTalkConnection; + // Public functions -int32_t UAVTalkInitialize(UAVTalkOutputStream outputStream); -int32_t UAVTalkSetOutputStream(UAVTalkOutputStream outputStream); -int32_t UAVTalkSendObject(UAVObjHandle obj, uint16_t instId, uint8_t acked, int32_t timeoutMs); -int32_t UAVTalkSendObjectRequest(UAVObjHandle obj, uint16_t instId, int32_t timeoutMs); -int32_t UAVTalkProcessInputStream(uint8_t rxbyte); -void UAVTalkGetStats(UAVTalkStats* stats); -void UAVTalkResetStats(); +UAVTalkConnection UAVTalkInitialize(UAVTalkOutputStream outputStream, uint32_t maxPacketSize); +int32_t UAVTalkSetOutputStream(UAVTalkConnection connection, UAVTalkOutputStream outputStream); +UAVTalkOutputStream UAVTalkGetOutputStream(UAVTalkConnection connection); +int32_t UAVTalkSendObject(UAVTalkConnection connection, UAVObjHandle obj, uint16_t instId, uint8_t acked, int32_t timeoutMs); +int32_t UAVTalkSendObjectRequest(UAVTalkConnection connection, UAVObjHandle obj, uint16_t instId, int32_t timeoutMs); +int32_t UAVTalkProcessInputStream(UAVTalkConnection connection, uint8_t rxbyte); +void UAVTalkGetStats(UAVTalkConnection connection, UAVTalkStats *stats); +void UAVTalkResetStats(UAVTalkConnection connection); #endif // UAVTALK_H /** diff --git a/flight/UAVTalk/inc/uavtalk_priv.h b/flight/UAVTalk/inc/uavtalk_priv.h new file mode 100644 index 000000000..77863a6a8 --- /dev/null +++ b/flight/UAVTalk/inc/uavtalk_priv.h @@ -0,0 +1,112 @@ +/** + ****************************************************************************** + * @addtogroup OpenPilotSystem OpenPilot System + * @{ + * @addtogroup OpenPilotLibraries OpenPilot System Libraries + * @{ + * @file uavtalk.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Private include file of the UAVTalk library + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef UAVTALK_PRIV_H +#define UAVTALK_PRIV_H + +#include "uavobjectsinit.h" + +// Private types and constants +typedef struct { + uint8_t sync; + uint8_t type; + uint16_t size; + uint32_t objId; +} uavtalk_min_header; +#define UAVTALK_MIN_HEADER_LENGTH sizeof(uavtalk_min_header) + +typedef struct { + uint8_t sync; + uint8_t type; + uint16_t size; + uint32_t objId; + uint16_t instId; +} uavtalk_max_header; +#define UAVTALK_MAX_HEADER_LENGTH sizeof(uavtalk_max_header) + +typedef uint8_t uavtalk_checksum; +#define UAVTALK_CHECKSUM_LENGTH sizeof(uavtalk_checksum) +#define UAVTALK_MAX_PAYLOAD_LENGTH (UAVOBJECTS_LARGEST + 1) +#define UAVTALK_MIN_PACKET_LENGTH UAVTALK_MAX_HEADER_LENGTH + UAVTALK_CHECKSUM_LENGTH +#define UAVTALK_MAX_PACKET_LENGTH UAVTALK_MIN_PACKET_LENGTH + UAVTALK_MAX_PAYLOAD_LENGTH + +typedef enum {UAVTALK_STATE_SYNC, UAVTALK_STATE_TYPE, UAVTALK_STATE_SIZE, UAVTALK_STATE_OBJID, UAVTALK_STATE_INSTID, UAVTALK_STATE_DATA, UAVTALK_STATE_CS} UAVTalkRxState; + +typedef struct { + UAVObjHandle obj; + uint8_t type; + uint16_t packet_size; + uint32_t objId; + uint16_t instId; + uint32_t length; + uint8_t instanceLength; + uint8_t cs; + int32_t rxCount; + UAVTalkRxState state; + uint16_t rxPacketLength; +} UAVTalkInputProcessor; + +typedef struct { + uint8_t canari; + UAVTalkOutputStream outStream; + xSemaphoreHandle lock; + xSemaphoreHandle transLock; + xSemaphoreHandle respSema; + UAVObjHandle respObj; + uint16_t respInstId; + UAVTalkStats stats; + UAVTalkInputProcessor iproc; + uint8_t *rxBuffer; + uint32_t txSize; + uint8_t *txBuffer; +} UAVTalkConnectionData; + +#define UAVTALK_CANARI 0xCA +#define UAVTALK_WAITFOREVER -1 +#define UAVTALK_NOWAIT 0 +#define UAVTALK_SYNC_VAL 0x3C +#define UAVTALK_TYPE_MASK 0xF8 +#define UAVTALK_TYPE_VER 0x20 +#define UAVTALK_TYPE_OBJ (UAVTALK_TYPE_VER | 0x00) +#define UAVTALK_TYPE_OBJ_REQ (UAVTALK_TYPE_VER | 0x01) +#define UAVTALK_TYPE_OBJ_ACK (UAVTALK_TYPE_VER | 0x02) +#define UAVTALK_TYPE_ACK (UAVTALK_TYPE_VER | 0x03) +#define UAVTALK_TYPE_NACK (UAVTALK_TYPE_VER | 0x04) + +//macros +#define CHECKCONHANDLE(handle,variable,failcommand) \ + variable = (UAVTalkConnectionData*) handle; \ + if (variable == NULL || variable->canari != UAVTALK_CANARI) { \ + failcommand; \ + } + +#endif // UAVTALK__PRIV_H +/** + * @} + * @} + */ diff --git a/flight/UAVTalk/uavtalk.c b/flight/UAVTalk/uavtalk.c index 48ad03f53..900dc24b3 100644 --- a/flight/UAVTalk/uavtalk.c +++ b/flight/UAVTalk/uavtalk.c @@ -30,113 +30,145 @@ */ #include "openpilot.h" +#include "uavtalk_priv.h" -// Private constants -#define SYNC_VAL 0x3C -#define TYPE_MASK 0xF8 -#define TYPE_VER 0x20 -#define TYPE_OBJ (TYPE_VER | 0x00) -#define TYPE_OBJ_REQ (TYPE_VER | 0x01) -#define TYPE_OBJ_ACK (TYPE_VER | 0x02) -#define TYPE_ACK (TYPE_VER | 0x03) -#define TYPE_NACK (TYPE_VER | 0x04) - -#define MIN_HEADER_LENGTH 8 // sync(1), type (1), size (2), object ID (4) -#define MAX_HEADER_LENGTH 10 // sync(1), type (1), size (2), object ID (4), instance ID (2, not used in single objects) - -#define CHECKSUM_LENGTH 1 - -#define MAX_PAYLOAD_LENGTH 256 - -#define MAX_PACKET_LENGTH (MAX_HEADER_LENGTH + MAX_PAYLOAD_LENGTH + CHECKSUM_LENGTH) - - -// Private types -typedef enum {STATE_SYNC, STATE_TYPE, STATE_SIZE, STATE_OBJID, STATE_INSTID, STATE_DATA, STATE_CS} RxState; - -// Private variables -static UAVTalkOutputStream outStream; -static xSemaphoreHandle lock; -static xSemaphoreHandle transLock; -static xSemaphoreHandle respSema; -static UAVObjHandle respObj; -static uint16_t respInstId; -static uint8_t rxBuffer[MAX_PACKET_LENGTH]; -static uint8_t txBuffer[MAX_PACKET_LENGTH]; -static UAVTalkStats stats; // Private functions -static int32_t objectTransaction(UAVObjHandle objectId, uint16_t instId, uint8_t type, int32_t timeout); -static int32_t sendObject(UAVObjHandle obj, uint16_t instId, uint8_t type); -static int32_t sendSingleObject(UAVObjHandle obj, uint16_t instId, uint8_t type); -static int32_t sendNack(uint32_t objId); -static int32_t receiveObject(uint8_t type, uint32_t objId, uint16_t instId, uint8_t* data, int32_t length); -static void updateAck(UAVObjHandle obj, uint16_t instId); +static int32_t objectTransaction(UAVTalkConnectionData *connection, UAVObjHandle objectId, uint16_t instId, uint8_t type, int32_t timeout); +static int32_t sendObject(UAVTalkConnectionData *connection, UAVObjHandle obj, uint16_t instId, uint8_t type); +static int32_t sendSingleObject(UAVTalkConnectionData *connection, UAVObjHandle obj, uint16_t instId, uint8_t type); +static int32_t sendNack(UAVTalkConnectionData *connection, uint32_t objId); +static int32_t receiveObject(UAVTalkConnectionData *connection, uint8_t type, uint32_t objId, uint16_t instId, uint8_t* data, int32_t length); +static void updateAck(UAVTalkConnectionData *connection, UAVObjHandle obj, uint16_t instId); /** * Initialize the UAVTalk library + * \param[in] connection UAVTalkConnection to be used * \param[in] outputStream Function pointer that is called to send a data buffer * \return 0 Success * \return -1 Failure */ -int32_t UAVTalkInitialize(UAVTalkOutputStream outputStream) +UAVTalkConnection UAVTalkInitialize(UAVTalkOutputStream outputStream, uint32_t maxPacketSize) { - outStream = outputStream; - lock = xSemaphoreCreateRecursiveMutex(); - transLock = xSemaphoreCreateRecursiveMutex(); - vSemaphoreCreateBinary(respSema); - xSemaphoreTake(respSema, 0); // reset to zero - UAVTalkResetStats(); + if (maxPacketSize<1) return 0; + // allocate object + UAVTalkConnectionData * connection = pvPortMalloc(sizeof(UAVTalkConnectionData)); + if (!connection) return 0; + connection->canari = UAVTALK_CANARI; + connection->iproc.rxPacketLength = 0; + connection->iproc.state = UAVTALK_STATE_SYNC; + connection->outStream = outputStream; + connection->lock = xSemaphoreCreateRecursiveMutex(); + connection->transLock = xSemaphoreCreateRecursiveMutex(); + connection->txSize = maxPacketSize; + // allocate buffers + connection->rxBuffer = pvPortMalloc(UAVTALK_MAX_PACKET_LENGTH); + if (!connection->rxBuffer) return 0; + connection->txBuffer = pvPortMalloc(UAVTALK_MAX_PACKET_LENGTH); + if (!connection->txBuffer) return 0; + vSemaphoreCreateBinary(connection->respSema); + xSemaphoreTake(connection->respSema, 0); // reset to zero + UAVTalkResetStats( (UAVTalkConnection) connection ); + return (UAVTalkConnection) connection; +} + +/** + * Set the communication output stream + * \param[in] connection UAVTalkConnection to be used + * \param[in] outputStream Function pointer that is called to send a data buffer + * \return 0 Success + * \return -1 Failure + */ +int32_t UAVTalkSetOutputStream(UAVTalkConnection connectionHandle, UAVTalkOutputStream outputStream) +{ + + UAVTalkConnectionData *connection; + CHECKCONHANDLE(connectionHandle,connection,return -1); + + // Lock + xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY); + + // set output stream + connection->outStream = outputStream; + + // Release lock + xSemaphoreGiveRecursive(connection->lock); + return 0; + +} + +/** + * Get current output stream + * \param[in] connection UAVTalkConnection to be used + * @return UAVTarlkOutputStream the output stream used + */ +UAVTalkOutputStream UAVTalkGetOutputStream(UAVTalkConnection connectionHandle) +{ + UAVTalkConnectionData *connection; + CHECKCONHANDLE(connectionHandle,connection,return NULL); + return connection->outStream; } /** * Get communication statistics counters + * \param[in] connection UAVTalkConnection to be used * @param[out] statsOut Statistics counters */ -void UAVTalkGetStats(UAVTalkStats* statsOut) +void UAVTalkGetStats(UAVTalkConnection connectionHandle, UAVTalkStats* statsOut) { + UAVTalkConnectionData *connection; + CHECKCONHANDLE(connectionHandle,connection,return ); + // Lock - xSemaphoreTakeRecursive(lock, portMAX_DELAY); + xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY); // Copy stats - memcpy(statsOut, &stats, sizeof(UAVTalkStats)); + memcpy(statsOut, &connection->stats, sizeof(UAVTalkStats)); // Release lock - xSemaphoreGiveRecursive(lock); + xSemaphoreGiveRecursive(connection->lock); } /** * Reset the statistics counters. + * \param[in] connection UAVTalkConnection to be used */ -void UAVTalkResetStats() +void UAVTalkResetStats(UAVTalkConnection connectionHandle) { + UAVTalkConnectionData *connection; + CHECKCONHANDLE(connectionHandle,connection,return); + // Lock - xSemaphoreTakeRecursive(lock, portMAX_DELAY); + xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY); // Clear stats - memset(&stats, 0, sizeof(UAVTalkStats)); + memset(&connection->stats, 0, sizeof(UAVTalkStats)); // Release lock - xSemaphoreGiveRecursive(lock); + xSemaphoreGiveRecursive(connection->lock); } /** * Request an update for the specified object, on success the object data would have been * updated by the GCS. + * \param[in] connection UAVTalkConnection to be used * \param[in] obj Object to update * \param[in] instId The instance ID or UAVOBJ_ALL_INSTANCES for all instances. * \param[in] timeout Time to wait for the response, when zero it will return immediately * \return 0 Success * \return -1 Failure */ -int32_t UAVTalkSendObjectRequest(UAVObjHandle obj, uint16_t instId, int32_t timeout) +int32_t UAVTalkSendObjectRequest(UAVTalkConnection connectionHandle, UAVObjHandle obj, uint16_t instId, int32_t timeout) { - return objectTransaction(obj, instId, TYPE_OBJ_REQ, timeout); + UAVTalkConnectionData *connection; + CHECKCONHANDLE(connectionHandle,connection,return -1); + return objectTransaction(connection, obj, instId, UAVTALK_TYPE_OBJ_REQ, timeout); } /** * Send the specified object through the telemetry link. + * \param[in] connection UAVTalkConnection to be used * \param[in] obj Object to send * \param[in] instId The instance ID or UAVOBJ_ALL_INSTANCES for all instances. * \param[in] acked Selects if an ack is required (1:ack required, 0: ack not required) @@ -144,69 +176,72 @@ int32_t UAVTalkSendObjectRequest(UAVObjHandle obj, uint16_t instId, int32_t time * \return 0 Success * \return -1 Failure */ -int32_t UAVTalkSendObject(UAVObjHandle obj, uint16_t instId, uint8_t acked, int32_t timeoutMs) +int32_t UAVTalkSendObject(UAVTalkConnection connectionHandle, UAVObjHandle obj, uint16_t instId, uint8_t acked, int32_t timeoutMs) { + UAVTalkConnectionData *connection; + CHECKCONHANDLE(connectionHandle,connection,return -1); // Send object if (acked == 1) { - return objectTransaction(obj, instId, TYPE_OBJ_ACK, timeoutMs); + return objectTransaction(connection, obj, instId, UAVTALK_TYPE_OBJ_ACK, timeoutMs); } else { - return objectTransaction(obj, instId, TYPE_OBJ, timeoutMs); + return objectTransaction(connection, obj, instId, UAVTALK_TYPE_OBJ, timeoutMs); } } /** * Execute the requested transaction on an object. + * \param[in] connection UAVTalkConnection to be used * \param[in] obj Object * \param[in] instId The instance ID of UAVOBJ_ALL_INSTANCES for all instances. * \param[in] type Transaction type - * TYPE_OBJ: send object, - * TYPE_OBJ_REQ: request object update - * TYPE_OBJ_ACK: send object with an ack + * UAVTALK_TYPE_OBJ: send object, + * UAVTALK_TYPE_OBJ_REQ: request object update + * UAVTALK_TYPE_OBJ_ACK: send object with an ack * \return 0 Success * \return -1 Failure */ -static int32_t objectTransaction(UAVObjHandle obj, uint16_t instId, uint8_t type, int32_t timeoutMs) +static int32_t objectTransaction(UAVTalkConnectionData *connection, UAVObjHandle obj, uint16_t instId, uint8_t type, int32_t timeoutMs) { int32_t respReceived; // Send object depending on if a response is needed - if (type == TYPE_OBJ_ACK || type == TYPE_OBJ_REQ) + if (type == UAVTALK_TYPE_OBJ_ACK || type == UAVTALK_TYPE_OBJ_REQ) { // Get transaction lock (will block if a transaction is pending) - xSemaphoreTakeRecursive(transLock, portMAX_DELAY); + xSemaphoreTakeRecursive(connection->transLock, portMAX_DELAY); // Send object - xSemaphoreTakeRecursive(lock, portMAX_DELAY); - respObj = obj; - respInstId = instId; - sendObject(obj, instId, type); - xSemaphoreGiveRecursive(lock); + xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY); + connection->respObj = obj; + connection->respInstId = instId; + sendObject(connection, obj, instId, type); + xSemaphoreGiveRecursive(connection->lock); // Wait for response (or timeout) - respReceived = xSemaphoreTake(respSema, timeoutMs/portTICK_RATE_MS); + respReceived = xSemaphoreTake(connection->respSema, timeoutMs/portTICK_RATE_MS); // Check if a response was received if (respReceived == pdFALSE) { // Cancel transaction - xSemaphoreTakeRecursive(lock, portMAX_DELAY); - xSemaphoreTake(respSema, 0); // non blocking call to make sure the value is reset to zero (binary sema) - respObj = 0; - xSemaphoreGiveRecursive(lock); - xSemaphoreGiveRecursive(transLock); + xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY); + xSemaphoreTake(connection->respSema, 0); // non blocking call to make sure the value is reset to zero (binary sema) + connection->respObj = 0; + xSemaphoreGiveRecursive(connection->lock); + xSemaphoreGiveRecursive(connection->transLock); return -1; } else { - xSemaphoreGiveRecursive(transLock); + xSemaphoreGiveRecursive(connection->transLock); return 0; } } - else if (type == TYPE_OBJ) + else if (type == UAVTALK_TYPE_OBJ) { - xSemaphoreTakeRecursive(lock, portMAX_DELAY); - sendObject(obj, instId, TYPE_OBJ); - xSemaphoreGiveRecursive(lock); + xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY); + sendObject(connection, obj, instId, UAVTALK_TYPE_OBJ); + xSemaphoreGiveRecursive(connection->lock); return 0; } else @@ -217,222 +252,220 @@ static int32_t objectTransaction(UAVObjHandle obj, uint16_t instId, uint8_t type /** * Process an byte from the telemetry stream. + * \param[in] connection UAVTalkConnection to be used * \param[in] rxbyte Received byte * \return 0 Success * \return -1 Failure */ -int32_t UAVTalkProcessInputStream(uint8_t rxbyte) +int32_t UAVTalkProcessInputStream(UAVTalkConnection connectionHandle, uint8_t rxbyte) { - static UAVObjHandle obj; - static uint8_t type; - static uint16_t packet_size; - static uint32_t objId; - static uint16_t instId; - static uint32_t length; - static uint8_t cs, csRx; - static int32_t rxCount; - static RxState state = STATE_SYNC; - static uint16_t rxPacketLength = 0; + UAVTalkConnectionData *connection; + CHECKCONHANDLE(connectionHandle,connection,return -1); + + UAVTalkInputProcessor *iproc = &connection->iproc; + ++connection->stats.rxBytes; - ++stats.rxBytes; - - if (rxPacketLength < 0xffff) - rxPacketLength++; // update packet byte count + if (iproc->rxPacketLength < 0xffff) + iproc->rxPacketLength++; // update packet byte count // Receive state machine - switch (state) + switch (iproc->state) { - case STATE_SYNC: - if (rxbyte != SYNC_VAL) + case UAVTALK_STATE_SYNC: + if (rxbyte != UAVTALK_SYNC_VAL) break; // Initialize and update the CRC - cs = PIOS_CRC_updateByte(0, rxbyte); + iproc->cs = PIOS_CRC_updateByte(0, rxbyte); - rxPacketLength = 1; + iproc->rxPacketLength = 1; - state = STATE_TYPE; + iproc->state = UAVTALK_STATE_TYPE; break; - case STATE_TYPE: + case UAVTALK_STATE_TYPE: // update the CRC - cs = PIOS_CRC_updateByte(cs, rxbyte); + iproc->cs = PIOS_CRC_updateByte(iproc->cs, rxbyte); - if ((rxbyte & TYPE_MASK) != TYPE_VER) + if ((rxbyte & UAVTALK_TYPE_MASK) != UAVTALK_TYPE_VER) { - state = STATE_SYNC; + iproc->state = UAVTALK_STATE_SYNC; break; } - type = rxbyte; + iproc->type = rxbyte; - packet_size = 0; + iproc->packet_size = 0; - state = STATE_SIZE; - rxCount = 0; + iproc->state = UAVTALK_STATE_SIZE; + iproc->rxCount = 0; break; - case STATE_SIZE: + case UAVTALK_STATE_SIZE: // update the CRC - cs = PIOS_CRC_updateByte(cs, rxbyte); + iproc->cs = PIOS_CRC_updateByte(iproc->cs, rxbyte); - if (rxCount == 0) + if (iproc->rxCount == 0) { - packet_size += rxbyte; - rxCount++; + iproc->packet_size += rxbyte; + iproc->rxCount++; break; } - packet_size += rxbyte << 8; + iproc->packet_size += rxbyte << 8; - if (packet_size < MIN_HEADER_LENGTH || packet_size > MAX_HEADER_LENGTH + MAX_PAYLOAD_LENGTH) + if (iproc->packet_size < UAVTALK_MIN_HEADER_LENGTH || iproc->packet_size > UAVTALK_MAX_HEADER_LENGTH + UAVTALK_MAX_PAYLOAD_LENGTH) { // incorrect packet size - state = STATE_SYNC; + iproc->state = UAVTALK_STATE_SYNC; break; } - rxCount = 0; - objId = 0; - state = STATE_OBJID; + iproc->rxCount = 0; + iproc->objId = 0; + iproc->state = UAVTALK_STATE_OBJID; break; - case STATE_OBJID: + case UAVTALK_STATE_OBJID: // update the CRC - cs = PIOS_CRC_updateByte(cs, rxbyte); + iproc->cs = PIOS_CRC_updateByte(iproc->cs, rxbyte); - objId += rxbyte << (8*(rxCount++)); + iproc->objId += rxbyte << (8*(iproc->rxCount++)); - if (rxCount < 4) + if (iproc->rxCount < 4) break; // Search for object, if not found reset state machine // except if we got a OBJ_REQ for an object which does not // exist, in which case we'll send a NACK - obj = UAVObjGetByID(objId); - if (obj == 0 && type != TYPE_OBJ_REQ) + iproc->obj = UAVObjGetByID(iproc->objId); + if (iproc->obj == 0 && iproc->type != UAVTALK_TYPE_OBJ_REQ) { - stats.rxErrors++; - state = STATE_SYNC; + connection->stats.rxErrors++; + iproc->state = UAVTALK_STATE_SYNC; break; } // Determine data length - if (type == TYPE_OBJ_REQ || type == TYPE_ACK || type == TYPE_NACK) - length = 0; + if (iproc->type == UAVTALK_TYPE_OBJ_REQ || iproc->type == UAVTALK_TYPE_ACK || iproc->type == UAVTALK_TYPE_NACK) + { + iproc->length = 0; + iproc->instanceLength = 0; + } else - length = UAVObjGetNumBytes(obj); + { + iproc->length = UAVObjGetNumBytes(iproc->obj); + iproc->instanceLength = (UAVObjIsSingleInstance(iproc->obj) ? 0 : 2); + } // Check length and determine next state - if (length >= MAX_PAYLOAD_LENGTH) + if (iproc->length >= UAVTALK_MAX_PAYLOAD_LENGTH) { - stats.rxErrors++; - state = STATE_SYNC; + connection->stats.rxErrors++; + iproc->state = UAVTALK_STATE_SYNC; break; } // Check the lengths match - if ((rxPacketLength + length) != packet_size) + if ((iproc->rxPacketLength + iproc->instanceLength + iproc->length) != iproc->packet_size) { // packet error - mismatched packet size - stats.rxErrors++; - state = STATE_SYNC; + connection->stats.rxErrors++; + iproc->state = UAVTALK_STATE_SYNC; break; } - instId = 0; - if (obj == 0) + iproc->instId = 0; + if (iproc->obj == 0) { // If this is a NACK, we skip to Checksum - state = STATE_CS; - rxCount = 0; + iproc->state = UAVTALK_STATE_CS; + iproc->rxCount = 0; } // Check if this is a single instance object (i.e. if the instance ID field is coming next) - else if (UAVObjIsSingleInstance(obj)) + else if (UAVObjIsSingleInstance(iproc->obj)) { // If there is a payload get it, otherwise receive checksum - if (length > 0) - state = STATE_DATA; + if (iproc->length > 0) + iproc->state = UAVTALK_STATE_DATA; else - state = STATE_CS; + iproc->state = UAVTALK_STATE_CS; - rxCount = 0; + iproc->rxCount = 0; } else { - state = STATE_INSTID; - rxCount = 0; + iproc->state = UAVTALK_STATE_INSTID; + iproc->rxCount = 0; } break; - case STATE_INSTID: + case UAVTALK_STATE_INSTID: // update the CRC - cs = PIOS_CRC_updateByte(cs, rxbyte); + iproc->cs = PIOS_CRC_updateByte(iproc->cs, rxbyte); - instId += rxbyte << (8*(rxCount++)); + iproc->instId += rxbyte << (8*(iproc->rxCount++)); - if (rxCount < 2) + if (iproc->rxCount < 2) break; - rxCount = 0; + iproc->rxCount = 0; // If there is a payload get it, otherwise receive checksum - if (length > 0) - state = STATE_DATA; + if (iproc->length > 0) + iproc->state = UAVTALK_STATE_DATA; else - state = STATE_CS; + iproc->state = UAVTALK_STATE_CS; break; - case STATE_DATA: + case UAVTALK_STATE_DATA: // update the CRC - cs = PIOS_CRC_updateByte(cs, rxbyte); + iproc->cs = PIOS_CRC_updateByte(iproc->cs, rxbyte); - rxBuffer[rxCount++] = rxbyte; - if (rxCount < length) + connection->rxBuffer[iproc->rxCount++] = rxbyte; + if (iproc->rxCount < iproc->length) break; - state = STATE_CS; - rxCount = 0; + iproc->state = UAVTALK_STATE_CS; + iproc->rxCount = 0; break; - case STATE_CS: + case UAVTALK_STATE_CS: // the CRC byte - csRx = rxbyte; - - if (csRx != cs) + if (rxbyte != iproc->cs) { // packet error - faulty CRC - stats.rxErrors++; - state = STATE_SYNC; + connection->stats.rxErrors++; + iproc->state = UAVTALK_STATE_SYNC; break; } - if (rxPacketLength != (packet_size + 1)) + if (iproc->rxPacketLength != (iproc->packet_size + 1)) { // packet error - mismatched packet size - stats.rxErrors++; - state = STATE_SYNC; + connection->stats.rxErrors++; + iproc->state = UAVTALK_STATE_SYNC; break; } - xSemaphoreTakeRecursive(lock, portMAX_DELAY); - receiveObject(type, objId, instId, rxBuffer, length); - stats.rxObjectBytes += length; - stats.rxObjects++; - xSemaphoreGiveRecursive(lock); + xSemaphoreTakeRecursive(connection->lock, portMAX_DELAY); + receiveObject(connection, iproc->type, iproc->objId, iproc->instId, connection->rxBuffer, iproc->length); + connection->stats.rxObjectBytes += iproc->length; + connection->stats.rxObjects++; + xSemaphoreGiveRecursive(connection->lock); - state = STATE_SYNC; + iproc->state = UAVTALK_STATE_SYNC; break; default: - stats.rxErrors++; - state = STATE_SYNC; + connection->stats.rxErrors++; + iproc->state = UAVTALK_STATE_SYNC; } // Done @@ -441,7 +474,8 @@ int32_t UAVTalkProcessInputStream(uint8_t rxbyte) /** * Receive an object. This function process objects received through the telemetry stream. - * \param[in] type Type of received message (TYPE_OBJ, TYPE_OBJ_REQ, TYPE_OBJ_ACK, TYPE_ACK, TYPE_NACK) + * \param[in] connection UAVTalkConnection to be used + * \param[in] type Type of received message (UAVTALK_TYPE_OBJ, UAVTALK_TYPE_OBJ_REQ, UAVTALK_TYPE_OBJ_ACK, UAVTALK_TYPE_ACK, UAVTALK_TYPE_NACK) * \param[in] objId ID of the object to work on * \param[in] instId The instance ID of UAVOBJ_ALL_INSTANCES for all instances. * \param[in] data Data buffer @@ -449,9 +483,9 @@ int32_t UAVTalkProcessInputStream(uint8_t rxbyte) * \return 0 Success * \return -1 Failure */ -static int32_t receiveObject(uint8_t type, uint32_t objId, uint16_t instId, uint8_t* data, int32_t length) +static int32_t receiveObject(UAVTalkConnectionData *connection, uint8_t type, uint32_t objId, uint16_t instId, uint8_t* data, int32_t length) { - static UAVObjHandle obj; + UAVObjHandle obj; int32_t ret = 0; // Get the handle to the Object. Will be zero @@ -460,21 +494,21 @@ static int32_t receiveObject(uint8_t type, uint32_t objId, uint16_t instId, uint // Process message type switch (type) { - case TYPE_OBJ: + case UAVTALK_TYPE_OBJ: // All instances, not allowed for OBJ messages if (instId != UAVOBJ_ALL_INSTANCES) { // Unpack object, if the instance does not exist it will be created! UAVObjUnpack(obj, instId, data); // Check if an ack is pending - updateAck(obj, instId); + updateAck(connection, obj, instId); } else { ret = -1; } break; - case TYPE_OBJ_ACK: + case UAVTALK_TYPE_OBJ_ACK: // All instances, not allowed for OBJ_ACK messages if (instId != UAVOBJ_ALL_INSTANCES) { @@ -482,7 +516,7 @@ static int32_t receiveObject(uint8_t type, uint32_t objId, uint16_t instId, uint if ( UAVObjUnpack(obj, instId, data) == 0 ) { // Transmit ACK - sendObject(obj, instId, TYPE_ACK); + sendObject(connection, obj, instId, UAVTALK_TYPE_ACK); } else { @@ -494,22 +528,22 @@ static int32_t receiveObject(uint8_t type, uint32_t objId, uint16_t instId, uint ret = -1; } break; - case TYPE_OBJ_REQ: + case UAVTALK_TYPE_OBJ_REQ: // Send requested object if message is of type OBJ_REQ if (obj == 0) - sendNack(objId); + sendNack(connection, objId); else - sendObject(obj, instId, TYPE_OBJ); + sendObject(connection, obj, instId, UAVTALK_TYPE_OBJ); break; - case TYPE_NACK: + case UAVTALK_TYPE_NACK: // Do nothing on flight side, let it time out. break; - case TYPE_ACK: + case UAVTALK_TYPE_ACK: // All instances, not allowed for ACK messages if (instId != UAVOBJ_ALL_INSTANCES) { // Check if an ack is pending - updateAck(obj, instId); + updateAck(connection, obj, instId); } else { @@ -525,25 +559,29 @@ static int32_t receiveObject(uint8_t type, uint32_t objId, uint16_t instId, uint /** * Check if an ack is pending on an object and give response semaphore + * \param[in] connection UAVTalkConnection to be used + * \param[in] obj Object + * \param[in] instId The instance ID of UAVOBJ_ALL_INSTANCES for all instances. */ -static void updateAck(UAVObjHandle obj, uint16_t instId) +static void updateAck(UAVTalkConnectionData *connection, UAVObjHandle obj, uint16_t instId) { - if (respObj == obj && (respInstId == instId || respInstId == UAVOBJ_ALL_INSTANCES)) + if (connection->respObj == obj && (connection->respInstId == instId || connection->respInstId == UAVOBJ_ALL_INSTANCES)) { - xSemaphoreGive(respSema); - respObj = 0; + xSemaphoreGive(connection->respSema); + connection->respObj = 0; } } /** * Send an object through the telemetry link. + * \param[in] connection UAVTalkConnection to be used * \param[in] obj Object handle to send * \param[in] instId The instance ID or UAVOBJ_ALL_INSTANCES for all instances * \param[in] type Transaction type * \return 0 Success * \return -1 Failure */ -static int32_t sendObject(UAVObjHandle obj, uint16_t instId, uint8_t type) +static int32_t sendObject(UAVTalkConnectionData *connection, UAVObjHandle obj, uint16_t instId, uint8_t type) { uint32_t numInst; uint32_t n; @@ -555,7 +593,7 @@ static int32_t sendObject(UAVObjHandle obj, uint16_t instId, uint8_t type) } // Process message type - if ( type == TYPE_OBJ || type == TYPE_OBJ_ACK ) + if ( type == UAVTALK_TYPE_OBJ || type == UAVTALK_TYPE_OBJ_ACK ) { if (instId == UAVOBJ_ALL_INSTANCES) { @@ -564,24 +602,24 @@ static int32_t sendObject(UAVObjHandle obj, uint16_t instId, uint8_t type) // Send all instances for (n = 0; n < numInst; ++n) { - sendSingleObject(obj, n, type); + sendSingleObject(connection, obj, n, type); } return 0; } else { - return sendSingleObject(obj, instId, type); + return sendSingleObject(connection, obj, instId, type); } } - else if (type == TYPE_OBJ_REQ) + else if (type == UAVTALK_TYPE_OBJ_REQ) { - return sendSingleObject(obj, instId, TYPE_OBJ_REQ); + return sendSingleObject(connection, obj, instId, UAVTALK_TYPE_OBJ_REQ); } - else if (type == TYPE_ACK) + else if (type == UAVTALK_TYPE_ACK) { if ( instId != UAVOBJ_ALL_INSTANCES ) { - return sendSingleObject(obj, instId, TYPE_ACK); + return sendSingleObject(connection, obj, instId, UAVTALK_TYPE_ACK); } else { @@ -596,13 +634,14 @@ static int32_t sendObject(UAVObjHandle obj, uint16_t instId, uint8_t type) /** * Send an object through the telemetry link. + * \param[in] connection UAVTalkConnection to be used * \param[in] obj Object handle to send * \param[in] instId The instance ID (can NOT be UAVOBJ_ALL_INSTANCES, use sendObject() instead) * \param[in] type Transaction type * \return 0 Success * \return -1 Failure */ -static int32_t sendSingleObject(UAVObjHandle obj, uint16_t instId, uint8_t type) +static int32_t sendSingleObject(UAVTalkConnectionData *connection, UAVObjHandle obj, uint16_t instId, uint8_t type) { int32_t length; int32_t dataOffset; @@ -610,13 +649,13 @@ static int32_t sendSingleObject(UAVObjHandle obj, uint16_t instId, uint8_t type) // Setup type and object id fields objId = UAVObjGetID(obj); - txBuffer[0] = SYNC_VAL; // sync byte - txBuffer[1] = type; + connection->txBuffer[0] = UAVTALK_SYNC_VAL; // sync byte + connection->txBuffer[1] = type; // data length inserted here below - txBuffer[4] = (uint8_t)(objId & 0xFF); - txBuffer[5] = (uint8_t)((objId >> 8) & 0xFF); - txBuffer[6] = (uint8_t)((objId >> 16) & 0xFF); - txBuffer[7] = (uint8_t)((objId >> 24) & 0xFF); + connection->txBuffer[4] = (uint8_t)(objId & 0xFF); + connection->txBuffer[5] = (uint8_t)((objId >> 8) & 0xFF); + connection->txBuffer[6] = (uint8_t)((objId >> 16) & 0xFF); + connection->txBuffer[7] = (uint8_t)((objId >> 24) & 0xFF); // Setup instance ID if one is required if (UAVObjIsSingleInstance(obj)) @@ -625,13 +664,13 @@ static int32_t sendSingleObject(UAVObjHandle obj, uint16_t instId, uint8_t type) } else { - txBuffer[8] = (uint8_t)(instId & 0xFF); - txBuffer[9] = (uint8_t)((instId >> 8) & 0xFF); + connection->txBuffer[8] = (uint8_t)(instId & 0xFF); + connection->txBuffer[9] = (uint8_t)((instId >> 8) & 0xFF); dataOffset = 10; } // Determine data length - if (type == TYPE_OBJ_REQ || type == TYPE_ACK) + if (type == UAVTALK_TYPE_OBJ_REQ || type == UAVTALK_TYPE_ACK) { length = 0; } @@ -641,7 +680,7 @@ static int32_t sendSingleObject(UAVObjHandle obj, uint16_t instId, uint8_t type) } // Check length - if (length >= MAX_PAYLOAD_LENGTH) + if (length >= UAVTALK_MAX_PAYLOAD_LENGTH) { return -1; } @@ -649,26 +688,34 @@ static int32_t sendSingleObject(UAVObjHandle obj, uint16_t instId, uint8_t type) // Copy data (if any) if (length > 0) { - if ( UAVObjPack(obj, instId, &txBuffer[dataOffset]) < 0 ) + if ( UAVObjPack(obj, instId, &connection->txBuffer[dataOffset]) < 0 ) { return -1; } } // Store the packet length - txBuffer[2] = (uint8_t)((dataOffset+length) & 0xFF); - txBuffer[3] = (uint8_t)(((dataOffset+length) >> 8) & 0xFF); + connection->txBuffer[2] = (uint8_t)((dataOffset+length) & 0xFF); + connection->txBuffer[3] = (uint8_t)(((dataOffset+length) >> 8) & 0xFF); // Calculate checksum - txBuffer[dataOffset+length] = PIOS_CRC_updateCRC(0, txBuffer, dataOffset+length); - - // Send buffer - if (outStream!=NULL) (*outStream)(txBuffer, dataOffset+length+CHECKSUM_LENGTH); + connection->txBuffer[dataOffset+length] = PIOS_CRC_updateCRC(0, connection->txBuffer, dataOffset+length); + + // Send buffer (partially if needed) + uint32_t sent=0; + while (sent < dataOffset+length+UAVTALK_CHECKSUM_LENGTH) { + uint32_t sending = dataOffset+length+UAVTALK_CHECKSUM_LENGTH - sent; + if ( sending > connection->txSize ) sending = connection->txSize; + if ( connection->outStream != NULL ) { + (*connection->outStream)(connection->txBuffer+sent, sending); + } + sent += sending; + } // Update stats - ++stats.txObjects; - stats.txBytes += dataOffset+length+CHECKSUM_LENGTH; - stats.txObjectBytes += length; + ++connection->stats.txObjects; + connection->stats.txBytes += dataOffset+length+UAVTALK_CHECKSUM_LENGTH; + connection->stats.txObjectBytes += length; // Done return 0; @@ -676,36 +723,37 @@ static int32_t sendSingleObject(UAVObjHandle obj, uint16_t instId, uint8_t type) /** * Send a NACK through the telemetry link. + * \param[in] connection UAVTalkConnection to be used * \param[in] objId Object ID to send a NACK for * \return 0 Success * \return -1 Failure */ -static int32_t sendNack(uint32_t objId) +static int32_t sendNack(UAVTalkConnectionData *connection, uint32_t objId) { int32_t dataOffset; - txBuffer[0] = SYNC_VAL; // sync byte - txBuffer[1] = TYPE_NACK; + connection->txBuffer[0] = UAVTALK_SYNC_VAL; // sync byte + connection->txBuffer[1] = UAVTALK_TYPE_NACK; // data length inserted here below - txBuffer[4] = (uint8_t)(objId & 0xFF); - txBuffer[5] = (uint8_t)((objId >> 8) & 0xFF); - txBuffer[6] = (uint8_t)((objId >> 16) & 0xFF); - txBuffer[7] = (uint8_t)((objId >> 24) & 0xFF); + connection->txBuffer[4] = (uint8_t)(objId & 0xFF); + connection->txBuffer[5] = (uint8_t)((objId >> 8) & 0xFF); + connection->txBuffer[6] = (uint8_t)((objId >> 16) & 0xFF); + connection->txBuffer[7] = (uint8_t)((objId >> 24) & 0xFF); dataOffset = 8; // Store the packet length - txBuffer[2] = (uint8_t)((dataOffset) & 0xFF); - txBuffer[3] = (uint8_t)(((dataOffset) >> 8) & 0xFF); + connection->txBuffer[2] = (uint8_t)((dataOffset) & 0xFF); + connection->txBuffer[3] = (uint8_t)(((dataOffset) >> 8) & 0xFF); // Calculate checksum - txBuffer[dataOffset] = PIOS_CRC_updateCRC(0, txBuffer, dataOffset); + connection->txBuffer[dataOffset] = PIOS_CRC_updateCRC(0, connection->txBuffer, dataOffset); // Send buffer - if (outStream!=NULL) (*outStream)(txBuffer, dataOffset+CHECKSUM_LENGTH); + if (connection->outStream!=NULL) (*connection->outStream)(connection->txBuffer, dataOffset+UAVTALK_CHECKSUM_LENGTH); // Update stats - stats.txBytes += dataOffset+CHECKSUM_LENGTH; + connection->stats.txBytes += dataOffset+UAVTALK_CHECKSUM_LENGTH; // Done return 0; diff --git a/ground/openpilotgcs/share/openpilotgcs/models/multi/ricoo/CC.PNG b/ground/openpilotgcs/share/openpilotgcs/models/multi/ricoo/CC.PNG new file mode 100644 index 000000000..467f34a97 Binary files /dev/null and b/ground/openpilotgcs/share/openpilotgcs/models/multi/ricoo/CC.PNG differ diff --git a/ground/openpilotgcs/share/openpilotgcs/models/multi/ricoo/TEXTURE.PNG b/ground/openpilotgcs/share/openpilotgcs/models/multi/ricoo/TEXTURE.PNG new file mode 100644 index 000000000..d6e63425a Binary files /dev/null and b/ground/openpilotgcs/share/openpilotgcs/models/multi/ricoo/TEXTURE.PNG differ diff --git a/ground/openpilotgcs/share/openpilotgcs/models/multi/ricoo/ricoo.3DS b/ground/openpilotgcs/share/openpilotgcs/models/multi/ricoo/ricoo.3DS new file mode 100644 index 000000000..226920061 Binary files /dev/null and b/ground/openpilotgcs/share/openpilotgcs/models/multi/ricoo/ricoo.3DS differ diff --git a/ground/openpilotgcs/share/openpilotgcs/models/multi/ricoo/ricoo.jpg b/ground/openpilotgcs/share/openpilotgcs/models/multi/ricoo/ricoo.jpg new file mode 100644 index 000000000..93df97866 Binary files /dev/null and b/ground/openpilotgcs/share/openpilotgcs/models/multi/ricoo/ricoo.jpg differ diff --git a/ground/openpilotgcs/share/openpilotgcs/sounds/Complete sound set.txt b/ground/openpilotgcs/share/openpilotgcs/sounds/Complete sound set.txt index e539e6d24..4361d3e8b 100644 --- a/ground/openpilotgcs/share/openpilotgcs/sounds/Complete sound set.txt +++ b/ground/openpilotgcs/share/openpilotgcs/sounds/Complete sound set.txt @@ -65,7 +65,8 @@ magic manual flight maxium meters -minimum +minimum +minus mode moved MPH diff --git a/ground/openpilotgcs/share/openpilotgcs/sounds/default/minus.wav b/ground/openpilotgcs/share/openpilotgcs/sounds/default/minus.wav new file mode 100644 index 000000000..385c1e55e Binary files /dev/null and b/ground/openpilotgcs/share/openpilotgcs/sounds/default/minus.wav differ diff --git a/ground/openpilotgcs/src/libs/glc_lib/3DWidget/.DS_Store b/ground/openpilotgcs/src/libs/glc_lib/3DWidget/.DS_Store deleted file mode 100644 index 5008ddfcf..000000000 Binary files a/ground/openpilotgcs/src/libs/glc_lib/3DWidget/.DS_Store and /dev/null differ diff --git a/ground/openpilotgcs/src/libs/utils/cachedsvgitem.cpp b/ground/openpilotgcs/src/libs/utils/cachedsvgitem.cpp new file mode 100644 index 000000000..2edef8ddf --- /dev/null +++ b/ground/openpilotgcs/src/libs/utils/cachedsvgitem.cpp @@ -0,0 +1,159 @@ +/** + ****************************************************************************** + * + * @file cachedsvgitem.h + * @author Dmytro Poplavskiy Copyright (C) 2011. + * @{ + * @brief OpenGL texture cached SVG item + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "cachedsvgitem.h" +#include +#include + +#ifndef GL_CLAMP_TO_EDGE +#define GL_CLAMP_TO_EDGE 0x812F +#endif + +CachedSvgItem::CachedSvgItem(QGraphicsItem * parent) : + QGraphicsSvgItem(parent), + m_context(0), + m_texture(0), + m_scale(1.0) +{ + setCacheMode(NoCache); +} + +CachedSvgItem::CachedSvgItem(const QString & fileName, QGraphicsItem * parent): + QGraphicsSvgItem(fileName, parent), + m_context(0), + m_texture(0), + m_scale(1.0) +{ + setCacheMode(NoCache); +} + +CachedSvgItem::~CachedSvgItem() +{ + if (m_context && m_texture) { + m_context->makeCurrent(); + glDeleteTextures(1, &m_texture); + } +} + +void CachedSvgItem::paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget) +{ + + if (painter->paintEngine()->type() != QPaintEngine::OpenGL && + painter->paintEngine()->type() != QPaintEngine::OpenGL2) { + //Fallback to direct painting + QGraphicsSvgItem::paint(painter, option, widget); + return; + } + + QRectF br = boundingRect(); + QTransform transform = painter->worldTransform(); + qreal sceneScale = transform.map(QLineF(0,0,1,0)).length(); + + bool stencilTestEnabled = glIsEnabled(GL_STENCIL_TEST); + bool scissorTestEnabled = glIsEnabled(GL_SCISSOR_TEST); + + painter->beginNativePainting(); + + if (stencilTestEnabled) + glEnable(GL_STENCIL_TEST); + if (scissorTestEnabled) + glEnable(GL_SCISSOR_TEST); + + bool dirty = false; + if (!m_texture) { + glGenTextures(1, &m_texture); + m_context = const_cast(QGLContext::currentContext()); + + dirty = true; + } + + if (!qFuzzyCompare(sceneScale, m_scale)) { + m_scale = sceneScale; + dirty = true; + } + + int textureWidth = (int(br.width()*m_scale) + 3) & ~3; + int textureHeight = (int(br.height()*m_scale) + 3) & ~3; + + if (dirty) { + //qDebug() << "re-render image"; + + QImage img(textureWidth, textureHeight, QImage::Format_ARGB32); + { + img.fill(Qt::transparent); + QPainter p; + p.begin(&img); + p.setRenderHints(painter->renderHints()); + p.translate(br.topLeft()); + p.scale(m_scale, m_scale); + QGraphicsSvgItem::paint(&p, option, 0); + p.end(); + + img = img.rgbSwapped(); + } + + glEnable(GL_TEXTURE_2D); + + glBindTexture(GL_TEXTURE_2D, m_texture); + glTexImage2D( + GL_TEXTURE_2D, + 0, + GL_RGBA, + textureWidth, + textureHeight, + 0, + GL_RGBA, + GL_UNSIGNED_BYTE, + img.bits()); + + glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR); + glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR); + glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE); + glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE); + + glDisable(GL_TEXTURE_2D); + + dirty = false; + } + + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + glEnable(GL_TEXTURE_2D); + + glBindTexture(GL_TEXTURE_2D, m_texture); + + //texture may be slightly large than svn image, ensure only used area is rendered + qreal tw = br.width()*m_scale/textureWidth; + qreal th = br.height()*m_scale/textureHeight; + + glBegin(GL_QUADS); + glTexCoord2d(0, 0 ); glVertex3d(br.left(), br.top(), -1); + glTexCoord2d(tw, 0 ); glVertex3d(br.right(), br.top(), -1); + glTexCoord2d(tw, th); glVertex3d(br.right(), br.bottom(), -1); + glTexCoord2d(0, th); glVertex3d(br.left(), br.bottom(), -1); + glEnd(); + glDisable(GL_TEXTURE_2D); + + painter->endNativePainting(); +} diff --git a/ground/openpilotgcs/src/libs/utils/cachedsvgitem.h b/ground/openpilotgcs/src/libs/utils/cachedsvgitem.h new file mode 100644 index 000000000..747ef391c --- /dev/null +++ b/ground/openpilotgcs/src/libs/utils/cachedsvgitem.h @@ -0,0 +1,54 @@ +/** + ****************************************************************************** + * + * @file cachedsvgitem.h + * @author Dmytro Poplavskiy Copyright (C) 2011. + * @{ + * @brief OpenGL texture cached SVG item + *****************************************************************************/ +/* + * 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 CACHEDSVGITEM_H +#define CACHEDSVGITEM_H + +#include +#include + +#include "utils_global.h" + +class QGLContext; + +//Cache Svg item as GL Texture. +//Texture is regenerated each time item is scaled +//but it's reused during rotation, unlike DeviceCoordinateCache mode +class QTCREATOR_UTILS_EXPORT CachedSvgItem: public QGraphicsSvgItem +{ + Q_OBJECT +public: + CachedSvgItem(QGraphicsItem * parent = 0); + CachedSvgItem(const QString & fileName, QGraphicsItem * parent = 0); + ~CachedSvgItem(); + + void paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget); + +private: + QGLContext *m_context; + GLuint m_texture; + qreal m_scale; +}; + +#endif diff --git a/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.cpp b/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.cpp index faf2c911e..c412a475c 100644 --- a/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.cpp +++ b/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.cpp @@ -65,7 +65,7 @@ MyTabbedStackWidget::MyTabbedStackWidget(QWidget *parent, bool isVertical, bool m_stackWidget->setContentsMargins(0, 0, 0, 0); setLayout(toplevelLayout); - connect(m_listWidget, SIGNAL(currentRowChanged(int)), this, SLOT(showWidget(int))); + connect(m_listWidget, SIGNAL(currentRowChanged(int)), this, SLOT(showWidget(int)),Qt::QueuedConnection); } void MyTabbedStackWidget::insertTab(const int index, QWidget *tab, const QIcon &icon, const QString &label) @@ -97,9 +97,19 @@ void MyTabbedStackWidget::setCurrentIndex(int index) void MyTabbedStackWidget::showWidget(int index) { - emit currentAboutToShow(index); - m_stackWidget->setCurrentIndex(index); - emit currentChanged(index); + if(m_stackWidget->currentIndex()==index) + return; + bool proceed=false; + emit currentAboutToShow(index,&proceed); + if(proceed) + { + m_stackWidget->setCurrentIndex(index); + emit currentChanged(index); + } + else + { + m_listWidget->setCurrentRow(m_stackWidget->currentIndex(),QItemSelectionModel::ClearAndSelect); + } } void MyTabbedStackWidget::insertCornerWidget(int index, QWidget *widget) diff --git a/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.h b/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.h index 428ed8646..f32524ce5 100644 --- a/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.h +++ b/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.h @@ -51,9 +51,10 @@ public: void insertCornerWidget(int index, QWidget *widget); int cornerWidgetCount() { return m_cornerWidgetCount; } + QWidget * currentWidget(){return m_stackWidget->currentWidget();} signals: - void currentAboutToShow(int index); + void currentAboutToShow(int index,bool * proceed); void currentChanged(int index); public slots: diff --git a/ground/openpilotgcs/src/libs/utils/utils.pro b/ground/openpilotgcs/src/libs/utils/utils.pro index 804f7c813..003497b4d 100644 --- a/ground/openpilotgcs/src/libs/utils/utils.pro +++ b/ground/openpilotgcs/src/libs/utils/utils.pro @@ -3,7 +3,9 @@ TARGET = Utils QT += gui \ network \ - xml + xml \ + svg \ + opengl DEFINES += QTCREATOR_UTILS_LIB @@ -48,7 +50,8 @@ SOURCES += reloadpromptutils.cpp \ homelocationutil.cpp \ mytabbedstackwidget.cpp \ mytabwidget.cpp \ - mylistwidget.cpp + mylistwidget.cpp \ + cachedsvgitem.cpp SOURCES += xmlconfig.cpp win32 { @@ -102,7 +105,8 @@ HEADERS += utils_global.h \ homelocationutil.h \ mytabbedstackwidget.h \ mytabwidget.h \ - mylistwidget.h + mylistwidget.h \ + cachedsvgitem.h HEADERS += xmlconfig.h FORMS += filewizardpage.ui \ diff --git a/ground/openpilotgcs/src/plugins/config/Config.pluginspec b/ground/openpilotgcs/src/plugins/config/Config.pluginspec index 0a9da6e94..83013fd28 100644 --- a/ground/openpilotgcs/src/plugins/config/Config.pluginspec +++ b/ground/openpilotgcs/src/plugins/config/Config.pluginspec @@ -9,5 +9,6 @@ + diff --git a/ground/openpilotgcs/src/plugins/config/airframe.ui b/ground/openpilotgcs/src/plugins/config/airframe.ui index fd039a906..343581f3c 100644 --- a/ground/openpilotgcs/src/plugins/config/airframe.ui +++ b/ground/openpilotgcs/src/plugins/config/airframe.ui @@ -172,7 +172,7 @@ - Output channel asignmets + Output channel assignments diff --git a/ground/openpilotgcs/src/plugins/config/camerastabilization.ui b/ground/openpilotgcs/src/plugins/config/camerastabilization.ui new file mode 100644 index 000000000..76ff38fcb --- /dev/null +++ b/ground/openpilotgcs/src/plugins/config/camerastabilization.ui @@ -0,0 +1,328 @@ + + + CameraStabilizationWidget + + + + 0 + 0 + 720 + 567 + + + + Form + + + + + + Enable CameraStabilization module + + + + + + + After enabling the module, you must power cycle before using and configuring. + + + + + + + Qt::Horizontal + + + + + + + Channel Ranges (number of degrees full range) + + + + + + + + Pitch + + + + + + + Yaw + + + + + + + Roll + + + + + + + 180 + + + + + + + 180 + + + + + + + 180 + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Qt::Horizontal + + + + 212 + 20 + + + + + + + + + + + Channel Mapping (select output channel or none to disable) + + + + + + + + Roll + + + + + + + + None + + + + + + + + + None + + + + + + + + Pitch + + + + + + + + None + + + + + + + + Yaw + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Qt::Horizontal + + + + 212 + 20 + + + + + + + + + + + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + QFrame::StyledPanel + + + QFrame::Raised + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 0 + 0 + + + + + 32 + 32 + + + + + true + + + + + + + + :/core/images/helpicon.svg:/core/images/helpicon.svg + + + + 32 + 32 + + + + Ctrl+S + + + false + + + true + + + + + + + Save settings to the board (RAM only). + +This does not save the calibration settings, this is done using the +specific calibration button on top of the screen. + + + Apply + + + + + + + Send settings to the board, and save to the non-volatile memory. + + + Save + + + false + + + + + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui b/ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui index a4a8586e5..929c9053d 100644 --- a/ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui +++ b/ground/openpilotgcs/src/plugins/config/cc_hw_settings.ui @@ -1,283 +1,307 @@ - - - CC_HW_Widget - - - - 0 - 0 - 517 - 487 - - - - Form - - - - - - QFrame::StyledPanel - - - QFrame::Raised - - - - - - - - - - - :/configgadget/images/coptercontrol.svg - - - true - - - - - - - - - - - - - MainPort - - - Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft - - - - - - - - - - - - - - FlexiPort - - - Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Receiver type - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - - - - - - - Telemetry speed: - - - - - - - Select the speed here. - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - - 75 - true - - - - - - - Qt::AutoText - - - true - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - 75 - true - - - - Changes on this page only take effect after board reset or power cycle - - - true - - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 0 - 0 - - - - - 32 - 32 - - - - - 32 - 32 - - - - - - - - :/core/images/helpicon.svg:/core/images/helpicon.svg - - - - 32 - 32 - - - - true - - - - - - - Send to OpenPilot but don't write in SD. -Beware of not locking yourself out! - - - true - - - - - - Apply - - - false - - - - - - - Applies and Saves all settings to SD. -Beware of not locking yourself out! - - - false - - - - - - Save - - - - - - - - - - - - - - - - + + + CC_HW_Widget + + + + 0 + 0 + 517 + 487 + + + + Form + + + + + + QFrame::StyledPanel + + + QFrame::Raised + + + + + + + + + + + :/configgadget/images/coptercontrol.svg + + + true + + + + + + + + + + + + + MainPort + + + Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft + + + + + + + + + + + + + + FlexiPort + + + Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + RcvrPort + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + + + + + + + + + Telemetry speed: + + + + + + + + 55 + 0 + + + + GPS speed: + + + + + + + Select the speed here. + + + + + + + Select the speed here. + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + 75 + true + + + + + + + Qt::AutoText + + + true + + + + + + + + 75 + true + + + + Changes on this page only take effect after board reset or power cycle + + + true + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 0 + 0 + + + + + 32 + 32 + + + + + 32 + 32 + + + + + + + + :/core/images/helpicon.svg:/core/images/helpicon.svg + + + + 32 + 32 + + + + true + + + + + + + Send to OpenPilot but don't write in SD. +Beware of not locking yourself out! + + + true + + + + + + Apply + + + false + + + + + + + Applies and Saves all settings to SD. +Beware of not locking yourself out! + + + false + + + + + + Save + + + + + + + + + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/config/ccpm.ui b/ground/openpilotgcs/src/plugins/config/ccpm.ui index 12d501f60..77e33e8ca 100644 --- a/ground/openpilotgcs/src/plugins/config/ccpm.ui +++ b/ground/openpilotgcs/src/plugins/config/ccpm.ui @@ -70,7 +70,7 @@ - 2 + 0 @@ -880,7 +880,7 @@ - + Link Roll/Pitch @@ -890,7 +890,7 @@ - + Link Cyclic/Collective @@ -900,80 +900,6 @@ - - - - QLayout::SetNoConstraint - - - - - true - - - - 0 - 0 - - - - - 80 - 0 - - - - - 80 - 16777215 - - - - - 11 - - - - Qt::LeftToRight - - - Collective Ch - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - true - - - - - - - true - - - - 0 - 0 - - - - - 90 - 0 - - - - - 100 - 16777215 - - - - - - diff --git a/ground/openpilotgcs/src/plugins/config/config.pro b/ground/openpilotgcs/src/plugins/config/config.pro index 79ddea046..091a7d45c 100644 --- a/ground/openpilotgcs/src/plugins/config/config.pro +++ b/ground/openpilotgcs/src/plugins/config/config.pro @@ -1,18 +1,15 @@ TEMPLATE = lib TARGET = Config QT += svg - include(../../openpilotgcsplugin.pri) include(../../libs/utils/utils.pri) include(../../plugins/uavtalk/uavtalk.pri) include(../../plugins/coreplugin/coreplugin.pri) include(../../plugins/uavobjects/uavobjects.pri) include(../../plugins/uavobjectutil/uavobjectutil.pri) - +include(../../plugins/uavsettingsimportexport/uavsettingsimportexport.pri) INCLUDEPATH += ../../libs/eigen - OTHER_FILES += Config.pluginspec - HEADERS += configplugin.h \ configgadgetconfiguration.h \ configgadgetwidget.h \ @@ -37,8 +34,10 @@ HEADERS += configplugin.h \ calibration.h \ defaultattitudewidget.h \ smartsavebutton.h \ - defaulthwsettingswidget.h - + defaulthwsettingswidget.h \ + inputchannelform.h \ + configcamerastabilizationwidget.h \ + outputchannelform.h SOURCES += configplugin.cpp \ configgadgetconfiguration.cpp \ configgadgetwidget.cpp \ @@ -65,10 +64,11 @@ SOURCES += configplugin.cpp \ alignment-calibration.cpp \ defaultattitudewidget.cpp \ smartsavebutton.cpp \ - defaulthwsettingswidget.cpp - -FORMS += \ - airframe.ui \ + defaulthwsettingswidget.cpp \ + inputchannelform.cpp \ + configcamerastabilizationwidget.cpp \ + outputchannelform.cpp +FORMS += airframe.ui \ cc_hw_settings.ui \ pro_hw_settings.ui \ ahrs.ui \ @@ -78,6 +78,8 @@ FORMS += \ output.ui \ ccattitude.ui \ defaultattitude.ui \ - defaulthwsettings.ui - + defaulthwsettings.ui \ + inputchannelform.ui \ + camerastabilization.ui \ + outputchannelform.ui RESOURCES += configgadget.qrc diff --git a/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp b/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp index e5adf27f1..1d0f723d0 100644 --- a/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp +++ b/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file configtelemetrywidget.h - * @author E. Lafargue & The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup ConfigPlugin Config Plugin @@ -25,6 +25,7 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ #include "config_cc_hw_widget.h" +#include "hwsettings.h" #include #include @@ -40,10 +41,11 @@ ConfigCCHWWidget::ConfigCCHWWidget(QWidget *parent) : ConfigTaskWidget(parent) m_telemetry = new Ui_CC_HW_Widget(); m_telemetry->setupUi(this); setupButtons(m_telemetry->saveTelemetryToRAM,m_telemetry->saveTelemetryToSD); - addUAVObjectToWidgetRelation("TelemetrySettings","Speed",m_telemetry->telemetrySpeed); addUAVObjectToWidgetRelation("HwSettings","CC_FlexiPort",m_telemetry->cbFlexi); addUAVObjectToWidgetRelation("HwSettings","CC_MainPort",m_telemetry->cbTele); - addUAVObjectToWidgetRelation("ManualControlSettings","InputMode",m_telemetry->receiverType); + addUAVObjectToWidgetRelation("HwSettings","CC_RcvrPort",m_telemetry->cbRcvr); + addUAVObjectToWidgetRelation("HwSettings","TelemetrySpeed",m_telemetry->telemetrySpeed); + addUAVObjectToWidgetRelation("HwSettings","GPSSpeed",m_telemetry->gpsSpeed); connect(m_telemetry->cchwHelp,SIGNAL(clicked()),this,SLOT(openHelp())); enableControls(false); populateWidgets(); @@ -62,26 +64,13 @@ void ConfigCCHWWidget::refreshValues() void ConfigCCHWWidget::widgetsContentsChanged() { ConfigTaskWidget::widgetsContentsChanged(); - enableControls(false); - if((m_telemetry->cbFlexi->currentText()==m_telemetry->cbTele->currentText()) && m_telemetry->cbTele->currentText()!="Disabled") + + if (((m_telemetry->cbTele->currentIndex() == HwSettings::CC_MAINPORT_TELEMETRY) && (m_telemetry->cbFlexi->currentIndex() == HwSettings::CC_FLEXIPORT_TELEMETRY)) || + ((m_telemetry->cbTele->currentIndex() == HwSettings::CC_MAINPORT_GPS) && (m_telemetry->cbFlexi->currentIndex() == HwSettings::CC_FLEXIPORT_GPS)) || + ((m_telemetry->cbTele->currentIndex() == HwSettings::CC_MAINPORT_COMAUX) && (m_telemetry->cbFlexi->currentIndex() == HwSettings::CC_FLEXIPORT_COMAUX))) { - m_telemetry->problems->setText("Warning: you have configured the MainPort and the FlexiPort for the same function, this is currently not suported"); - } - else if((m_telemetry->cbTele->currentText()=="Spektrum" ||m_telemetry->cbFlexi->currentText()=="Spektrum") && m_telemetry->receiverType->currentText()!="Spektrum") - { - m_telemetry->problems->setText("Warning: you have a port configured as 'Spektrum' however that is not your selected receiver type"); - } - else if(m_telemetry->cbTele->currentText()=="S.Bus" && m_telemetry->receiverType->currentText()!="S.Bus") - { - m_telemetry->problems->setText("Warning: you have a port configured as 'S.Bus' however that is not your selected receiver type"); - } - else if(m_telemetry->cbTele->currentText()!="S.Bus" && m_telemetry->receiverType->currentText()=="S.Bus") - { - m_telemetry->problems->setText("Warning: you have selected 'S.Bus' as your receiver type however you have no port configured for that protocol"); - } - else if((m_telemetry->cbTele->currentText()!="Spektrum" && m_telemetry->cbFlexi->currentText()!="Spektrum") && m_telemetry->receiverType->currentText()=="Spektrum") - { - m_telemetry->problems->setText("Warning: you have selected 'Spektrum' as your receiver type however you have no port configured for that protocol"); + enableControls(false); + m_telemetry->problems->setText(tr("Warning: you have configured both MainPort and FlexiPort for the same function, this currently is not supported")); } else { @@ -99,4 +88,3 @@ void ConfigCCHWWidget::openHelp() * @} * @} */ - diff --git a/ground/openpilotgcs/src/plugins/config/config_pro_hw_widget.cpp b/ground/openpilotgcs/src/plugins/config/config_pro_hw_widget.cpp index b3f562acd..f81ba32ee 100644 --- a/ground/openpilotgcs/src/plugins/config/config_pro_hw_widget.cpp +++ b/ground/openpilotgcs/src/plugins/config/config_pro_hw_widget.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file configtelemetrywidget.h - * @author E. Lafargue & The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup ConfigPlugin Config Plugin @@ -40,7 +40,7 @@ ConfigProHWWidget::ConfigProHWWidget(QWidget *parent) : ConfigTaskWidget(parent) m_telemetry->setupUi(this); setupButtons(m_telemetry->saveTelemetryToRAM,m_telemetry->saveTelemetryToSD); - addUAVObjectToWidgetRelation("TelemetrySettings","Speed",m_telemetry->telemetrySpeed); + addUAVObjectToWidgetRelation("HwSettings","TelemetrySpeed",m_telemetry->telemetrySpeed); enableControls(false); populateWidgets(); refreshWidgetsValues(); diff --git a/ground/openpilotgcs/src/plugins/config/configairframewidget.cpp b/ground/openpilotgcs/src/plugins/config/configairframewidget.cpp index dcf743915..9f118532e 100644 --- a/ground/openpilotgcs/src/plugins/config/configairframewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configairframewidget.cpp @@ -36,6 +36,10 @@ #include #include #include +#include "systemsettings.h" +#include "mixersettings.h" +#include "actuatorsettings.h" +#include /** Helper delegate for the custom mixer editor table. @@ -92,26 +96,7 @@ ConfigAirframeWidget::ConfigAirframeWidget(QWidget *parent) : ConfigTaskWidget(p m_aircraft->setupUi(this); setupButtons(m_aircraft->saveAircraftToRAM,m_aircraft->saveAircraftToSD); - addWidget(m_aircraft->customMixerTable); - addWidget(m_aircraft->customThrottle2Curve); - addWidget(m_aircraft->customThrottle1Curve); - addWidget(m_aircraft->multiThrottleCurve); - addWidget(m_aircraft->fixedWingThrottle); - addWidget(m_aircraft->fixedWingType); - addWidget(m_aircraft->feedForwardSlider); - addWidget(m_aircraft->accelTime); - addWidget(m_aircraft->decelTime); - addWidget(m_aircraft->maxAccelSlider); - addWidget(m_aircraft->multirotorFrameType); - addWidget(m_aircraft->multiMotor1); - addWidget(m_aircraft->multiMotor2); - addWidget(m_aircraft->multiMotor3); - addWidget(m_aircraft->multiMotor4); - addWidget(m_aircraft->multiMotor5); - addWidget(m_aircraft->multiMotor6); - addWidget(m_aircraft->multiMotor7); - addWidget(m_aircraft->multiMotor8); - addWidget(m_aircraft->triYawChannel); + addUAVObject("SystemSettings"); addUAVObject("MixerSettings"); addUAVObject("ActuatorSettings"); @@ -120,10 +105,13 @@ ConfigAirframeWidget::ConfigAirframeWidget(QWidget *parent) : ConfigTaskWidget(p ffTuningInProgress = false; ffTuningPhase = false; - mixerTypes << "Mixer1Type" << "Mixer2Type" << "Mixer3Type" - << "Mixer4Type" << "Mixer5Type" << "Mixer6Type" << "Mixer7Type" << "Mixer8Type"; - mixerVectors << "Mixer1Vector" << "Mixer2Vector" << "Mixer3Vector" - << "Mixer4Vector" << "Mixer5Vector" << "Mixer6Vector" << "Mixer7Vector" << "Mixer8Vector"; + QStringList channels; + channels << "None"; + for (int i = 0; i < ActuatorSettings::CHANNELADDR_NUMELEM; i++) { + mixerTypes << QString("Mixer%1Type").arg(i+1); + mixerVectors << QString("Mixer%1Vector").arg(i+1); + channels << QString("Channel%1").arg(i+1); + } QStringList airframeTypes; airframeTypes << "Fixed Wing" << "Multirotor" << "Helicopter" << "Custom"; @@ -139,11 +127,6 @@ ConfigAirframeWidget::ConfigAirframeWidget(QWidget *parent) : ConfigTaskWidget(p << "Octo Coax X" << "Hexacopter Y6" << "Tricopter Y"; m_aircraft->multirotorFrameType->addItems(multiRotorTypes); - - - QStringList channels; - channels << "None" << "Channel1" << "Channel2" << "Channel3" << - "Channel4" << "Channel5" << "Channel6" << "Channel7" << "Channel8"; // Now load all the channel assignements for fixed wing m_aircraft->fwElevator1Channel->addItems(channels); m_aircraft->fwElevator2Channel->addItems(channels); @@ -217,7 +200,7 @@ ConfigAirframeWidget::ConfigAirframeWidget(QWidget *parent) : ConfigTaskWidget(p // Connect the help button connect(m_aircraft->airframeHelp, SIGNAL(clicked()), this, SLOT(openHelp())); - + addToDirtyMonitor(); } ConfigAirframeWidget::~ConfigAirframeWidget() @@ -462,6 +445,9 @@ void ConfigAirframeWidget::updateCustomThrottle2CurveValue(QList list, d */ void ConfigAirframeWidget::refreshWidgetsValues() { + if(!allObjectsUpdated()) + return; + bool dirty=isDirty(); // Get the Airframe type from the system settings: UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("SystemSettings"))); Q_ASSERT(obj); @@ -913,6 +899,7 @@ void ConfigAirframeWidget::refreshWidgetsValues() } updateCustomAirframeUI(); + setDirty(dirty); } /** @@ -921,6 +908,7 @@ void ConfigAirframeWidget::refreshWidgetsValues() */ void ConfigAirframeWidget::setupAirframeUI(QString frameType) { + bool dirty=isDirty(); if (frameType == "FixedWing" || frameType == "Elevator aileron rudder") { // Setup the UI m_aircraft->aircraftType->setCurrentIndex(m_aircraft->aircraftType->findText("Fixed Wing")); @@ -1118,6 +1106,7 @@ void ConfigAirframeWidget::setupAirframeUI(QString frameType) } m_aircraft->quadShape->setSceneRect(quad->boundingRect()); m_aircraft->quadShape->fitInView(quad, Qt::KeepAspectRatio); + setDirty(dirty); } /** @@ -1531,6 +1520,16 @@ bool ConfigAirframeWidget::setupFrameVtail() */ bool ConfigAirframeWidget::setupMixer(double mixerFactors[8][3]) { + qDebug()<<"Mixer factors"; + qDebug()< mmList; mmList << m_aircraft->multiMotor1 << m_aircraft->multiMotor2 << m_aircraft->multiMotor3 @@ -1548,11 +1547,15 @@ bool ConfigAirframeWidget::setupMixer(double mixerFactors[8][3]) double pFactor = (double)m_aircraft->mrPitchMixLevel->value()/100; double rFactor = (double)m_aircraft->mrRollMixLevel->value()/100; double yFactor = (double)m_aircraft->mrYawMixLevel->value()/100; + qDebug()<currentIndex()-1; - if (channel > -1) - setupQuadMotor(channel, mixerFactors[i][0]*pFactor, - rFactor*mixerFactors[i][1], yFactor*mixerFactors[i][2]); + if(mmList.at(i)->isEnabled()) + { + int channel = mmList.at(i)->currentIndex()-1; + if (channel > -1) + setupQuadMotor(channel, mixerFactors[i][0]*pFactor, + rFactor*mixerFactors[i][1], yFactor*mixerFactors[i][2]); + } } // obj->updated(); return true; @@ -1564,6 +1567,7 @@ bool ConfigAirframeWidget::setupMixer(double mixerFactors[8][3]) */ void ConfigAirframeWidget::setupQuadMotor(int channel, double pitch, double roll, double yaw) { + qDebug()<(getObjectManager()->getObject(QString("MixerSettings"))); Q_ASSERT(obj); UAVObjectField *field = obj->getField(mixerTypes.at(channel)); @@ -1575,10 +1579,13 @@ void ConfigAirframeWidget::setupQuadMotor(int channel, double pitch, double roll field->setValue(127, ti); ti = field->getElementNames().indexOf("Roll"); field->setValue(roll*127,ti); + qDebug()<<"Set roll="<getElementNames().indexOf("Pitch"); field->setValue(pitch*127,ti); + qDebug()<<"Set pitch="<getElementNames().indexOf("Yaw"); field->setValue(yaw*127,ti); + qDebug()<<"Set yaw="<customMixerTable); + addWidget(m_aircraft->customThrottle2Curve); + addWidget(m_aircraft->customThrottle1Curve); + addWidget(m_aircraft->multiThrottleCurve); + addWidget(m_aircraft->fixedWingThrottle); + addWidget(m_aircraft->fixedWingType); + addWidget(m_aircraft->feedForwardSlider); + addWidget(m_aircraft->accelTime); + addWidget(m_aircraft->decelTime); + addWidget(m_aircraft->maxAccelSlider); + addWidget(m_aircraft->multirotorFrameType); + addWidget(m_aircraft->multiMotor1); + addWidget(m_aircraft->multiMotor2); + addWidget(m_aircraft->multiMotor3); + addWidget(m_aircraft->multiMotor4); + addWidget(m_aircraft->multiMotor5); + addWidget(m_aircraft->multiMotor6); + addWidget(m_aircraft->multiMotor7); + addWidget(m_aircraft->multiMotor8); + addWidget(m_aircraft->triYawChannel); + addWidget(m_aircraft->aircraftType); + addWidget(m_aircraft->fwEngineChannel); + addWidget(m_aircraft->fwAileron1Channel); + addWidget(m_aircraft->fwAileron2Channel); + addWidget(m_aircraft->fwElevator1Channel); + addWidget(m_aircraft->fwElevator2Channel); + addWidget(m_aircraft->fwRudder1Channel); + addWidget(m_aircraft->fwRudder2Channel); + addWidget(m_aircraft->elevonSlider1); + addWidget(m_aircraft->elevonSlider2); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmType); + addWidget(m_aircraft->widget_3->m_ccpm->TabObject); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmTailChannel); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmEngineChannel); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmServoWChannel); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmServoXChannel); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmServoYChannel); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmSingleServo); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmServoZChannel); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmAngleW); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmAngleX); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmCorrectionAngle); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmAngleZ); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmAngleY); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmCollectivePassthrough); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmLinkRoll); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmLinkCyclic); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmRevoSlider); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmREVOspinBox); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmCollectiveSlider); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmCollectivespinBox); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmCollectiveScale); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmCollectiveScaleBox); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmCyclicScale); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmPitchScale); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmPitchScaleBox); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmRollScale); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmRollScaleBox); + addWidget(m_aircraft->widget_3->m_ccpm->SwashLvlPositionSlider); + addWidget(m_aircraft->widget_3->m_ccpm->SwashLvlPositionSpinBox); + addWidget(m_aircraft->widget_3->m_ccpm->CurveType); + addWidget(m_aircraft->widget_3->m_ccpm->NumCurvePoints); + addWidget(m_aircraft->widget_3->m_ccpm->CurveValue1); + addWidget(m_aircraft->widget_3->m_ccpm->CurveValue2); + addWidget(m_aircraft->widget_3->m_ccpm->CurveValue3); + addWidget(m_aircraft->widget_3->m_ccpm->CurveToGenerate); + addWidget(m_aircraft->widget_3->m_ccpm->CurveSettings); + addWidget(m_aircraft->widget_3->m_ccpm->ThrottleCurve); + addWidget(m_aircraft->widget_3->m_ccpm->PitchCurve); + addWidget(m_aircraft->widget_3->m_ccpm->ccpmAdvancedSettingsTable); +} + diff --git a/ground/openpilotgcs/src/plugins/config/configairframewidget.h b/ground/openpilotgcs/src/plugins/config/configairframewidget.h index 234a114c1..1383350ee 100644 --- a/ground/openpilotgcs/src/plugins/config/configairframewidget.h +++ b/ground/openpilotgcs/src/plugins/config/configairframewidget.h @@ -58,7 +58,7 @@ private: void updateCustomAirframeUI(); bool setupMixer(double mixerFactors[8][3]); void setupMotors(QList motorList); - + void addToDirtyMonitor(); void resetField(UAVObjectField * field); void resetMixer (MixerCurveWidget *mixer, int numElements, double maxvalue); void resetActuators(); diff --git a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp new file mode 100644 index 000000000..a1e6c1afb --- /dev/null +++ b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.cpp @@ -0,0 +1,257 @@ +/** + ****************************************************************************** + * + * @file configcamerastabilizationwidget.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup ConfigPlugin Config Plugin + * @{ + * @brief The Configuration Gadget used to update settings in the firmware + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#include "configcamerastabilizationwidget.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "camerastabsettings.h" +#include "hwsettings.h" +#include "mixersettings.h" +#include "actuatorcommand.h" + +ConfigCameraStabilizationWidget::ConfigCameraStabilizationWidget(QWidget *parent) : ConfigTaskWidget(parent) +{ + m_camerastabilization = new Ui_CameraStabilizationWidget(); + m_camerastabilization->setupUi(this); + + QComboBox * selectors[3] = { + m_camerastabilization->rollChannel, + m_camerastabilization->pitchChannel, + m_camerastabilization->yawChannel + }; + + for (int i = 0; i < 3; i++) { + selectors[i]->clear(); + selectors[i]->addItem("None"); + for (int j = 0; j < ActuatorCommand::CHANNEL_NUMELEM; j++) + selectors[i]->addItem(QString("Channel %1").arg(j+1)); + } + + connectUpdates(); + + // Connect buttons + connect(m_camerastabilization->camerastabilizationSaveRAM,SIGNAL(clicked()),this,SLOT(applySettings())); + connect(m_camerastabilization->camerastabilizationSaveSD,SIGNAL(clicked()),this,SLOT(saveSettings())); + connect(m_camerastabilization->camerastabilizationHelp, SIGNAL(clicked()), this, SLOT(openHelp())); +} + +ConfigCameraStabilizationWidget::~ConfigCameraStabilizationWidget() +{ + // Do nothing +} + +void ConfigCameraStabilizationWidget::connectUpdates() +{ + // Now connect the widget to the StabilizationSettings object + connect(MixerSettings::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(refreshValues())); + connect(CameraStabSettings::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(refreshValues())); + // TODO: This will need to support both CC and OP later + connect(HwSettings::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(refreshValues())); +} + +void ConfigCameraStabilizationWidget::disconnectUpdates() +{ + // Now connect the widget to the StabilizationSettings object + disconnect(MixerSettings::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(refreshValues())); + disconnect(CameraStabSettings::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(refreshValues())); + // TODO: This will need to support both CC and OP later + disconnect(HwSettings::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(refreshValues())); +} + +/** + * @brief Populate the gui settings into the appropriate + * UAV structures + */ +void ConfigCameraStabilizationWidget::applySettings() +{ + // Enable or disable the settings + HwSettings * hwSettings = HwSettings::GetInstance(getObjectManager()); + HwSettings::DataFields hwSettingsData = hwSettings->getData(); + hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_CAMERASTAB] = + m_camerastabilization->enableCameraStabilization->isChecked() ? + HwSettings::OPTIONALMODULES_ENABLED : + HwSettings::OPTIONALMODULES_DISABLED; + + // Update the mixer settings + MixerSettings * mixerSettings = MixerSettings::GetInstance(getObjectManager()); + MixerSettings::DataFields mixerSettingsData = mixerSettings->getData(); + const int NUM_MIXERS = 10; + + QComboBox * selectors[3] = { + m_camerastabilization->rollChannel, + m_camerastabilization->pitchChannel, + m_camerastabilization->yawChannel + }; + + // TODO: Need to reformat object so types are an + // array themselves. This gets really awkward + quint8 * mixerTypes[NUM_MIXERS] = { + &mixerSettingsData.Mixer1Type, + &mixerSettingsData.Mixer2Type, + &mixerSettingsData.Mixer3Type, + &mixerSettingsData.Mixer4Type, + &mixerSettingsData.Mixer5Type, + &mixerSettingsData.Mixer6Type, + &mixerSettingsData.Mixer7Type, + &mixerSettingsData.Mixer8Type, + &mixerSettingsData.Mixer9Type, + &mixerSettingsData.Mixer10Type, + }; + + m_camerastabilization->message->setText(""); + for (int i = 0; i < 3; i++) + { + // Channel 1 is second entry, so becomes zero + int mixerNum = selectors[i]->currentIndex() - 1; + + if ( mixerNum >= 0 && // Short circuit in case of none + *mixerTypes[mixerNum] != MixerSettings::MIXER1TYPE_DISABLED && + (*mixerTypes[mixerNum] != MixerSettings::MIXER1TYPE_CAMERAROLL + i) ) { + // If the mixer channel already to something that isn't what we are + // about to set it to reset to none + selectors[i]->setCurrentIndex(0); + m_camerastabilization->message->setText("One of the channels is already assigned, reverted to none"); + } else { + // Make sure no other channels have this output set + for (int j = 0; j < NUM_MIXERS; j++) + if (*mixerTypes[j] == (MixerSettings::MIXER1TYPE_CAMERAROLL + i)) + *mixerTypes[j] = MixerSettings::MIXER1TYPE_DISABLED; + + // If this channel is assigned to one of the outputs that is not disabled + // set it + if(mixerNum >= 0 && mixerNum < NUM_MIXERS) + *mixerTypes[mixerNum] = MixerSettings::MIXER1TYPE_CAMERAROLL + i; + } + } + + // Update the ranges + CameraStabSettings * cameraStab = CameraStabSettings::GetInstance(getObjectManager()); + CameraStabSettings::DataFields cameraStabData = cameraStab->getData(); + cameraStabData.OutputRange[CameraStabSettings::OUTPUTRANGE_ROLL] = m_camerastabilization->rollOutputRange->value(); + cameraStabData.OutputRange[CameraStabSettings::OUTPUTRANGE_PITCH] = m_camerastabilization->pitchOutputRange->value(); + cameraStabData.OutputRange[CameraStabSettings::OUTPUTRANGE_YAW] = m_camerastabilization->yawOutputRange->value(); + + // Because multiple objects are updated, and all of them trigger the callback + // they must be done together (if update one then load settings from second + // the first update would wipe the UI controls). However to be extra cautious + // I'm also disabling updates during the setting to the UAVObjects + disconnectUpdates(); + hwSettings->setData(hwSettingsData); + mixerSettings->setData(mixerSettingsData); + cameraStab->setData(cameraStabData); + connectUpdates(); +} + +/** + * Push settings into UAV objects then save them + */ +void ConfigCameraStabilizationWidget::saveSettings() +{ + applySettings(); + UAVObject * obj = HwSettings::GetInstance(getObjectManager()); + saveObjectToSD(obj); + obj = MixerSettings::GetInstance(getObjectManager()); + saveObjectToSD(obj); + obj = CameraStabSettings::GetInstance(getObjectManager()); + saveObjectToSD(obj); +} + +void ConfigCameraStabilizationWidget::refreshValues() +{ + HwSettings * hwSettings = HwSettings::GetInstance(getObjectManager()); + HwSettings::DataFields hwSettingsData = hwSettings->getData(); + m_camerastabilization->enableCameraStabilization->setChecked( + hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_CAMERASTAB] == + HwSettings::OPTIONALMODULES_ENABLED); + + CameraStabSettings * cameraStabSettings = CameraStabSettings::GetInstance(getObjectManager()); + CameraStabSettings::DataFields cameraStab = cameraStabSettings->getData(); + m_camerastabilization->rollOutputRange->setValue(cameraStab.OutputRange[CameraStabSettings::OUTPUTRANGE_ROLL]); + m_camerastabilization->pitchOutputRange->setValue(cameraStab.OutputRange[CameraStabSettings::OUTPUTRANGE_PITCH]); + m_camerastabilization->yawOutputRange->setValue(cameraStab.OutputRange[CameraStabSettings::OUTPUTRANGE_YAW]); + + MixerSettings * mixerSettings = MixerSettings::GetInstance(getObjectManager()); + MixerSettings::DataFields mixerSettingsData = mixerSettings->getData(); + const int NUM_MIXERS = 10; + QComboBox * selectors[3] = { + m_camerastabilization->rollChannel, + m_camerastabilization->pitchChannel, + m_camerastabilization->yawChannel + }; + + // TODO: Need to reformat object so types are an + // array themselves. This gets really awkward + quint8 * mixerTypes[NUM_MIXERS] = { + &mixerSettingsData.Mixer1Type, + &mixerSettingsData.Mixer2Type, + &mixerSettingsData.Mixer3Type, + &mixerSettingsData.Mixer4Type, + &mixerSettingsData.Mixer5Type, + &mixerSettingsData.Mixer6Type, + &mixerSettingsData.Mixer7Type, + &mixerSettingsData.Mixer8Type, + &mixerSettingsData.Mixer9Type, + &mixerSettingsData.Mixer10Type, + }; + + for (int i = 0; i < 3; i++) + { + // Default to none if not found. Then search for any mixer channels set to + // this + selectors[i]->setCurrentIndex(0); + for (int j = 0; j < NUM_MIXERS; j++) + if (*mixerTypes[j] == (MixerSettings::MIXER1TYPE_CAMERAROLL + i) && + selectors[i]->currentIndex() != (j + 1)) + selectors[i]->setCurrentIndex(j + 1); + } +} + +void ConfigCameraStabilizationWidget::openHelp() +{ + QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/Camera+Stabilization", QUrl::StrictMode) ); +} + +void ConfigCameraStabilizationWidget::enableControls(bool enable) +{ + m_camerastabilization->camerastabilizationSaveSD->setEnabled(enable); + m_camerastabilization->camerastabilizationSaveRAM->setEnabled(enable); +} + +/** + @} + @} + */ diff --git a/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h new file mode 100644 index 000000000..f5440e360 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/config/configcamerastabilizationwidget.h @@ -0,0 +1,68 @@ +/** + ****************************************************************************** + * + * @file configahrstwidget.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup ConfigPlugin Config Plugin + * @{ + * @brief Telemetry configuration panel + *****************************************************************************/ +/* + * 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 CONFIGCAMERASTABILIZATIONWIDGET_H +#define CONFIGCAMERASTABILIZATIONWIDGET_H + +#include "ui_camerastabilization.h" +#include "configtaskwidget.h" +#include "extensionsystem/pluginmanager.h" +#include "uavobjectmanager.h" +#include "uavobject.h" +#include +#include +#include +#include +#include +#include + +#include "camerastabsettings.h" + +class ConfigCameraStabilizationWidget: public ConfigTaskWidget +{ + Q_OBJECT + +public: + ConfigCameraStabilizationWidget(QWidget *parent = 0); + ~ConfigCameraStabilizationWidget(); + +private: + virtual void enableControls(bool enable); + + Ui_CameraStabilizationWidget *m_camerastabilization; + +private slots: + void openHelp(); + void applySettings(); + void saveSettings(); + void refreshValues(); + +protected: + void connectUpdates(); + void disconnectUpdates(); +}; + +#endif // ConfigCameraStabilization_H diff --git a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp index 51b63fadb..6ad28c666 100644 --- a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.cpp @@ -40,22 +40,19 @@ ConfigCCAttitudeWidget::ConfigCCAttitudeWidget(QWidget *parent) : { ui->setupUi(this); connect(ui->zeroBias,SIGNAL(clicked()),this,SLOT(startAccelCalibration())); - connect(ui->saveButton,SIGNAL(clicked()),this,SLOT(saveAttitudeSettings())); - connect(ui->applyButton,SIGNAL(clicked()),this,SLOT(applyAttitudeSettings())); - // Make it smart: - connect(parent, SIGNAL(autopilotConnected()),this, SLOT(onAutopilotConnect())); - connect(parent, SIGNAL(autopilotDisconnected()), this, SLOT(onAutopilotDisconnect())); - enableControls(true); - refreshValues(); // The 1st time this panel is instanciated, the autopilot is already connected. - UAVObject * settings = AttitudeSettings::GetInstance(getObjectManager()); - connect(settings,SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshValues())); + setupButtons(ui->applyButton,ui->saveButton); + addUAVObject("AttitudeSettings"); // Connect the help button connect(ui->ccAttitudeHelp, SIGNAL(clicked()), this, SLOT(openHelp())); + addUAVObjectToWidgetRelation("AttitudeSettings","ZeroDuringArming",ui->zeroGyroBiasOnArming); - + addUAVObjectToWidgetRelation("AttitudeSettings","BoardRotation",ui->rollBias,AttitudeSettings::BOARDROTATION_ROLL); + addUAVObjectToWidgetRelation("AttitudeSettings","BoardRotation",ui->pitchBias,AttitudeSettings::BOARDROTATION_PITCH); + addUAVObjectToWidgetRelation("AttitudeSettings","BoardRotation",ui->yawBias,AttitudeSettings::BOARDROTATION_YAW); + addWidget(ui->zeroBias); } ConfigCCAttitudeWidget::~ConfigCCAttitudeWidget() @@ -63,12 +60,6 @@ ConfigCCAttitudeWidget::~ConfigCCAttitudeWidget() delete ui; } -void ConfigCCAttitudeWidget::enableControls(bool enable) -{ - //ui->applyButton->setEnabled(enable); - ui->saveButton->setEnabled(enable); -} - void ConfigCCAttitudeWidget::attitudeRawUpdated(UAVObject * obj) { QMutexLocker locker(&startStop); @@ -107,7 +98,7 @@ void ConfigCCAttitudeWidget::attitudeRawUpdated(UAVObject * obj) { attitudeSettingsData.GyroBias[0] = -x_gyro_bias; attitudeSettingsData.GyroBias[1] = -y_gyro_bias; attitudeSettingsData.GyroBias[2] = -z_gyro_bias; - attitudeSettingsData.BiasCorrectGyro = initialBiasCorrected; + attitudeSettingsData.BiasCorrectGyro = AttitudeSettings::BIASCORRECTGYRO_TRUE; AttitudeSettings::GetInstance(getObjectManager())->setData(attitudeSettingsData); } else { @@ -130,26 +121,6 @@ void ConfigCCAttitudeWidget::timeout() { } -void ConfigCCAttitudeWidget::applyAttitudeSettings() { - AttitudeSettings::DataFields attitudeSettingsData = AttitudeSettings::GetInstance(getObjectManager())->getData(); - attitudeSettingsData.BoardRotation[AttitudeSettings::BOARDROTATION_ROLL] = ui->rollBias->value(); - attitudeSettingsData.BoardRotation[AttitudeSettings::BOARDROTATION_PITCH] = ui->pitchBias->value(); - attitudeSettingsData.BoardRotation[AttitudeSettings::BOARDROTATION_YAW] = ui->yawBias->value(); - attitudeSettingsData.ZeroDuringArming = ui->zeroGyroBiasOnArming->isChecked() ? AttitudeSettings::ZERODURINGARMING_TRUE : - AttitudeSettings::ZERODURINGARMING_FALSE; - AttitudeSettings::GetInstance(getObjectManager())->setData(attitudeSettingsData); -} - -void ConfigCCAttitudeWidget::refreshValues() { - AttitudeSettings::DataFields attitudeSettingsData = AttitudeSettings::GetInstance(getObjectManager())->getData(); - - ui->rollBias->setValue(attitudeSettingsData.BoardRotation[0]); - ui->pitchBias->setValue(attitudeSettingsData.BoardRotation[1]); - ui->yawBias->setValue(attitudeSettingsData.BoardRotation[2]); - ui->zeroGyroBiasOnArming->setChecked(attitudeSettingsData.ZeroDuringArming == AttitudeSettings::ZERODURINGARMING_TRUE); - -} - void ConfigCCAttitudeWidget::startAccelCalibration() { QMutexLocker locker(&startStop); @@ -163,7 +134,6 @@ void ConfigCCAttitudeWidget::startAccelCalibration() { // Disable gyro bias correction to see raw data AttitudeSettings::DataFields attitudeSettingsData = AttitudeSettings::GetInstance(getObjectManager())->getData(); - initialBiasCorrected = attitudeSettingsData.BiasCorrectGyro; attitudeSettingsData.BiasCorrectGyro = AttitudeSettings::BIASCORRECTGYRO_FALSE; AttitudeSettings::GetInstance(getObjectManager())->setData(attitudeSettingsData); @@ -184,16 +154,16 @@ void ConfigCCAttitudeWidget::startAccelCalibration() { } -void ConfigCCAttitudeWidget::saveAttitudeSettings() { - applyAttitudeSettings(); - - UAVDataObject * obj = dynamic_cast(getObjectManager()->getObject(QString("AttitudeSettings"))); - saveObjectToSD(obj); -} - void ConfigCCAttitudeWidget::openHelp() { QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/CopterControl+Attitude+Configuration", QUrl::StrictMode) ); } +void ConfigCCAttitudeWidget::enableControls(bool enable) +{ + if(ui->zeroBias) + ui->zeroBias->setEnabled(enable); + ConfigTaskWidget::enableControls(enable); + +} diff --git a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.h b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.h index 27176b22f..af107f670 100644 --- a/ground/openpilotgcs/src/plugins/config/configccattitudewidget.h +++ b/ground/openpilotgcs/src/plugins/config/configccattitudewidget.h @@ -50,9 +50,6 @@ private slots: void attitudeRawUpdated(UAVObject * obj); void timeout(); void startAccelCalibration(); - void saveAttitudeSettings(); - void applyAttitudeSettings(); - virtual void refreshValues(); void openHelp(); private: @@ -60,7 +57,6 @@ private: Ui_ccattitude *ui; QTimer timer; UAVObject::Metadata initialMdata; - quint8 initialBiasCorrected; int updates; @@ -69,6 +65,7 @@ private: static const int NUM_ACCEL_UPDATES = 60; static const float ACCEL_SCALE = 0.004f * 9.81f; +protected: virtual void enableControls(bool enable); }; diff --git a/ground/openpilotgcs/src/plugins/config/configccpmwidget.cpp b/ground/openpilotgcs/src/plugins/config/configccpmwidget.cpp index e53cbb70c..6d7a974c2 100644 --- a/ground/openpilotgcs/src/plugins/config/configccpmwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configccpmwidget.cpp @@ -39,6 +39,7 @@ #include "mixersettings.h" #include "systemsettings.h" +#include "actuatorcommand.h" #define Pi 3.14159265358979323846 @@ -70,8 +71,6 @@ ConfigccpmWidget::ConfigccpmWidget(QWidget *parent) : ConfigTaskWidget(parent) m_ccpm->SwashplateImage->setSceneRect(-50,-30,500,500); //m_ccpm->SwashplateImage->scale(.85,.85); - - QSvgRenderer *renderer = new QSvgRenderer(); renderer->load(QString(":/configgadget/images/ccpm_setup.svg")); @@ -132,78 +131,25 @@ ConfigccpmWidget::ConfigccpmWidget(QWidget *parent) : ConfigTaskWidget(parent) SwashLvlSpinBoxes[i] = new QSpinBox(m_ccpm->SwashLvlSwashplateImage); // use QGraphicsView m_ccpm->SwashLvlSwashplateImage->scene()->addWidget(SwashLvlSpinBoxes[i]); - //SwashLvlSpinBoxes[i]->move(i*50+50,20); - //SwashLvlSpinBoxes[i]->resize(40,20); - //SwashLvlSpinBoxes[i]->heightForWidth() - SwashLvlSpinBoxes[i]->setFixedSize(50,20); SwashLvlSpinBoxes[i]->setMaximum(10000); SwashLvlSpinBoxes[i]->setMinimum(0); SwashLvlSpinBoxes[i]->setValue(0); } - -/* - Servos[0] = new QGraphicsSvgItem(); - Servos[0]->setSharedRenderer(renderer); - Servos[0]->setElementId("ServoW"); - m_ccpm->SwashplateImage->scene()->addItem(Servos[0]); - - Servos[1] = new QGraphicsSvgItem(); - Servos[1]->setSharedRenderer(renderer); - Servos[1]->setElementId("ServoX"); - m_ccpm->SwashplateImage->scene()->addItem(Servos[1]); - - Servos[2] = new QGraphicsSvgItem(); - Servos[2]->setSharedRenderer(renderer); - Servos[2]->setElementId("ServoY"); - m_ccpm->SwashplateImage->scene()->addItem(Servos[2]); - - Servos[3] = new QGraphicsSvgItem(); - Servos[3]->setSharedRenderer(renderer); - Servos[3]->setElementId("ServoZ"); - m_ccpm->SwashplateImage->scene()->addItem(Servos[3]); - - - ServosText[0] = new QGraphicsTextItem(); - ServosText[0]->setDefaultTextColor(Qt::red); - ServosText[0]->setPlainText(QString("-")); - ServosText[0]->setFont(serifFont); - m_ccpm->SwashplateImage->scene()->addItem(ServosText[0]); - - ServosText[1] = new QGraphicsTextItem(); - ServosText[1]->setDefaultTextColor(Qt::red); - ServosText[1]->setPlainText(QString("-")); - ServosText[1]->setFont(serifFont); - m_ccpm->SwashplateImage->scene()->addItem(ServosText[1]); - - ServosText[2] = new QGraphicsTextItem(); - ServosText[2]->setDefaultTextColor(Qt::red); - ServosText[2]->setPlainText(QString("-")); - ServosText[2]->setFont(serifFont); - m_ccpm->SwashplateImage->scene()->addItem(ServosText[2]); - - ServosText[3] = new QGraphicsTextItem(); - ServosText[3]->setDefaultTextColor(Qt::red); - ServosText[3]->setPlainText(QString("-")); - ServosText[3]->setFont(serifFont); - m_ccpm->SwashplateImage->scene()->addItem(ServosText[3]); -*/ m_ccpm->PitchCurve->setMin(-1); resetMixer(m_ccpm->PitchCurve, 5); resetMixer(m_ccpm->ThrottleCurve, 5); - - - + MixerSettings * mixerSettings = MixerSettings::GetInstance(getObjectManager()); + Q_ASSERT(mixerSettings); + UAVObjectField * curve2source = mixerSettings->getField("Curve2Source"); + Q_ASSERT(curve2source); QStringList channels; - channels << "Channel1" << "Channel2" << - "Channel3" << "Channel4" << "Channel5" << "Channel6" << "Channel7" << "Channel8" ; - m_ccpm->ccpmCollectiveChannel->addItems(channels); - m_ccpm->ccpmCollectiveChannel->setCurrentIndex(8); - channels << "None" ; + channels << "Channel1" << "Channel2" << "Channel3" << "Channel4" << + "Channel5" << "Channel6" << "Channel7" << "Channel8" << "None"; m_ccpm->ccpmEngineChannel->addItems(channels); m_ccpm->ccpmEngineChannel->setCurrentIndex(8); m_ccpm->ccpmTailChannel->addItems(channels); @@ -218,17 +164,17 @@ ConfigccpmWidget::ConfigccpmWidget(QWidget *parent) : ConfigTaskWidget(parent) m_ccpm->ccpmServoZChannel->setCurrentIndex(8); QStringList Types; - Types << "CCPM 2 Servo 90º" << "CCPM 3 Servo 90º" << "CCPM 4 Servo 90º" << "CCPM 3 Servo 120º" << "CCPM 3 Servo 140º" << "FP 2 Servo 90º" << "Custom - User Angles" << "Custom - Advanced Settings" ; + Types << QString::fromUtf8("CCPM 2 Servo 90º") << QString::fromUtf8("CCPM 3 Servo 90º") << + QString::fromUtf8("CCPM 4 Servo 90º") << QString::fromUtf8("CCPM 3 Servo 120º") << + QString::fromUtf8("CCPM 3 Servo 140º") << QString::fromUtf8("FP 2 Servo 90º") << + QString::fromUtf8("Custom - User Angles") << QString::fromUtf8("Custom - Advanced Settings"); m_ccpm->ccpmType->addItems(Types); m_ccpm->ccpmType->setCurrentIndex(m_ccpm->ccpmType->count() - 1); requestccpmUpdate(); UpdateCurveSettings(); - //disable changing number of points in curves until UAVObjects have more than 5 m_ccpm->NumCurvePoints->setEnabled(0); - - UpdateType(); @@ -270,15 +216,12 @@ ConfigccpmWidget::ConfigccpmWidget(QWidget *parent) : ConfigTaskWidget(parent) connect(m_ccpm->SwashLvlCancelButton, SIGNAL(clicked()), this, SLOT(SwashLvlCancelButtonPressed())); connect(m_ccpm->SwashLvlFinishButton, SIGNAL(clicked()), this, SLOT(SwashLvlFinishButtonPressed())); - connect(m_ccpm->ccpmCollectivePassthrough, SIGNAL(clicked()), this, SLOT(SetUIComponentVisibilities())); connect(m_ccpm->ccpmLinkCyclic, SIGNAL(clicked()), this, SLOT(SetUIComponentVisibilities())); connect(m_ccpm->ccpmLinkRoll, SIGNAL(clicked()), this, SLOT(SetUIComponentVisibilities())); ccpmSwashplateRedraw(); - // connect(parent, SIGNAL(autopilotConnected()),this, SLOT(requestccpmUpdate())); - } ConfigccpmWidget::~ConfigccpmWidget() @@ -292,7 +235,7 @@ void ConfigccpmWidget::UpdateType() QString TypeText; double AdjustmentAngle=0; - UpdatCCPMOptionsFromUI(); + UpdateCCPMOptionsFromUI(); SetUIComponentVisibilities(); TypeInt = m_ccpm->ccpmType->count() - m_ccpm->ccpmType->currentIndex()-1; @@ -332,7 +275,7 @@ void ConfigccpmWidget::UpdateType() NumServosDefined=4; //set values for pre defined heli types - if (TypeText.compare(QString("CCPM 2 Servo 90º"), Qt::CaseInsensitive)==0) + if (TypeText.compare(QString::fromUtf8("CCPM 2 Servo 90º"), Qt::CaseInsensitive)==0) { m_ccpm->ccpmAngleW->setValue(AdjustmentAngle + 0); m_ccpm->ccpmAngleX->setValue(fmod(AdjustmentAngle + 90,360)); @@ -348,7 +291,7 @@ void ConfigccpmWidget::UpdateType() NumServosDefined=2; } - if (TypeText.compare(QString("CCPM 3 Servo 90º"), Qt::CaseInsensitive)==0) + if (TypeText.compare(QString::fromUtf8("CCPM 3 Servo 90º"), Qt::CaseInsensitive)==0) { m_ccpm->ccpmAngleW->setValue(AdjustmentAngle + 0); m_ccpm->ccpmAngleX->setValue(fmod(AdjustmentAngle + 90,360)); @@ -361,7 +304,7 @@ void ConfigccpmWidget::UpdateType() NumServosDefined=3; } - if (TypeText.compare(QString("CCPM 4 Servo 90º"), Qt::CaseInsensitive)==0) + if (TypeText.compare(QString::fromUtf8("CCPM 4 Servo 90º"), Qt::CaseInsensitive)==0) { m_ccpm->ccpmAngleW->setValue(AdjustmentAngle + 0); m_ccpm->ccpmAngleX->setValue(fmod(AdjustmentAngle + 90,360)); @@ -373,7 +316,7 @@ void ConfigccpmWidget::UpdateType() NumServosDefined=4; } - if (TypeText.compare(QString("CCPM 3 Servo 120º"), Qt::CaseInsensitive)==0) + if (TypeText.compare(QString::fromUtf8("CCPM 3 Servo 120º"), Qt::CaseInsensitive)==0) { m_ccpm->ccpmAngleW->setValue(AdjustmentAngle + 0); m_ccpm->ccpmAngleX->setValue(fmod(AdjustmentAngle + 120,360)); @@ -386,7 +329,7 @@ void ConfigccpmWidget::UpdateType() NumServosDefined=3; } - if (TypeText.compare(QString("CCPM 3 Servo 140º"), Qt::CaseInsensitive)==0) + if (TypeText.compare(QString::fromUtf8("CCPM 3 Servo 140º"), Qt::CaseInsensitive)==0) { m_ccpm->ccpmAngleW->setValue(AdjustmentAngle + 0); m_ccpm->ccpmAngleX->setValue(fmod(AdjustmentAngle + 140,360)); @@ -399,7 +342,7 @@ void ConfigccpmWidget::UpdateType() NumServosDefined=3; } - if (TypeText.compare(QString("FP 2 Servo 90º"), Qt::CaseInsensitive)==0) + if (TypeText.compare(QString::fromUtf8("FP 2 Servo 90º"), Qt::CaseInsensitive)==0) { m_ccpm->ccpmAngleW->setValue(AdjustmentAngle + 0); m_ccpm->ccpmAngleX->setValue(fmod(AdjustmentAngle + 90,360)); @@ -505,6 +448,9 @@ void ConfigccpmWidget::UpdateCurveWidgets() void ConfigccpmWidget::updatePitchCurveValue(QList curveValues0,double Value0) { + Q_UNUSED(curveValues0); + Q_UNUSED(Value0); + int NumCurvePoints,i; double CurrentValue; QList internalCurveValues; @@ -526,6 +472,9 @@ void ConfigccpmWidget::updatePitchCurveValue(QList curveValues0,double V void ConfigccpmWidget::updateThrottleCurveValue(QList curveValues0,double Value0) { + Q_UNUSED(curveValues0); + Q_UNUSED(Value0); + int NumCurvePoints,i; double CurrentValue; QList internalCurveValues; @@ -915,14 +864,10 @@ void ConfigccpmWidget::UpdateMixer() bool useCyclic; int i,j,ThisEnable[6]; float CollectiveConstant,PitchConstant,RollConstant,ThisAngle[6]; - //QTableWidgetItem *newItem;// = new QTableWidgetItem(); QString Channel; ccpmChannelCheck(); - //Type = m_ccpm->ccpmType->count() - m_ccpm->ccpmType->currentIndex()-1; - //CollectiveConstant=m_ccpm->ccpmCollectiveSlider->value()/100.0; - //CorrectionAngle=m_ccpm->ccpmCorrectionAngle->value(); - UpdatCCPMOptionsFromUI(); + UpdateCCPMOptionsFromUI(); useCCPM = !(GUIConfigData.heli.ccpmCollectivePassthroughState || !GUIConfigData.heli.ccpmLinkCyclicState); useCyclic = GUIConfigData.heli.ccpmLinkRollState; @@ -978,15 +923,6 @@ void ConfigccpmWidget::UpdateMixer() //go through the user data and update the mixer matrix for (i=0;i<6;i++) { - /* - data.Mixer0Type = 0;//Disabled,Motor,Servo - data.Mixer0Vector[0] = 0;//ThrottleCurve1 - data.Mixer0Vector[1] = 0;//ThrottleCurve2 - data.Mixer0Vector[2] = 0;//Roll - data.Mixer0Vector[3] = 0;//Pitch - data.Mixer0Vector[4] = 0;//Yaw - - */ if ((MixerChannelData[i]<8)&&((ThisEnable[i])||(i<2))) { m_ccpm->ccpmAdvancedSettingsTable->item(i,0)->setText(QString("%1").arg( MixerChannelData[i]+1 )); @@ -1055,7 +991,7 @@ void ConfigccpmWidget::UpdateMixer() } __attribute__((packed)) heliGUISettingsStruct; */ -void ConfigccpmWidget::UpdatCCPMOptionsFromUI() +void ConfigccpmWidget::UpdateCCPMOptionsFromUI() { bool useCCPM; bool useCyclic; @@ -1076,9 +1012,6 @@ void ConfigccpmWidget::UpdatCCPMOptionsFromUI() //correction angle GUIConfigData.heli.CorrectionAngle = m_ccpm->ccpmCorrectionAngle->value(); - //CollectiveChannel - GUIConfigData.heli.CollectiveChannel = m_ccpm->ccpmCollectiveChannel->currentIndex(); - //update sliders if (useCCPM) { @@ -1097,7 +1030,6 @@ void ConfigccpmWidget::UpdatCCPMOptionsFromUI() GUIConfigData.heli.SliderValue1 = m_ccpm->ccpmPitchScale->value(); } GUIConfigData.heli.SliderValue2 = m_ccpm->ccpmRollScale->value(); - //GUIConfigData.heli.RevoSlider = m_ccpm->ccpmREVOScale->value(); //servo assignments GUIConfigData.heli.ServoIndexW = m_ccpm->ccpmServoWChannel->currentIndex(); @@ -1106,7 +1038,7 @@ void ConfigccpmWidget::UpdatCCPMOptionsFromUI() GUIConfigData.heli.ServoIndexZ = m_ccpm->ccpmServoZChannel->currentIndex(); } -void ConfigccpmWidget::UpdatCCPMUIFromOptions() +void ConfigccpmWidget::UpdateCCPMUIFromOptions() { //swashplate config m_ccpm->ccpmType->setCurrentIndex(m_ccpm->ccpmType->count() - (GUIConfigData.heli.SwasplateType +1)); @@ -1119,10 +1051,7 @@ void ConfigccpmWidget::UpdatCCPMUIFromOptions() //correction angle m_ccpm->ccpmCorrectionAngle->setValue(GUIConfigData.heli.CorrectionAngle); - - //CollectiveChannel - m_ccpm->ccpmCollectiveChannel->setCurrentIndex(GUIConfigData.heli.CollectiveChannel); - + //update sliders m_ccpm->ccpmCollectiveScale->setValue(GUIConfigData.heli.SliderValue0); m_ccpm->ccpmCollectiveScaleBox->setValue(GUIConfigData.heli.SliderValue0); @@ -1134,7 +1063,6 @@ void ConfigccpmWidget::UpdatCCPMUIFromOptions() m_ccpm->ccpmRollScaleBox->setValue(GUIConfigData.heli.SliderValue2); m_ccpm->ccpmCollectiveSlider->setValue(GUIConfigData.heli.SliderValue0); m_ccpm->ccpmCollectivespinBox->setValue(GUIConfigData.heli.SliderValue0); - //m_ccpm->ccpmREVOScale->setValue(GUIConfigData.heli.RevoSlider); //servo assignments m_ccpm->ccpmServoWChannel->setCurrentIndex(GUIConfigData.heli.ServoIndexW); @@ -1147,16 +1075,13 @@ void ConfigccpmWidget::UpdatCCPMUIFromOptions() void ConfigccpmWidget::SetUIComponentVisibilities() { - UpdatCCPMOptionsFromUI(); + UpdateCCPMOptionsFromUI(); //set which sliders are user... m_ccpm->ccpmRevoMixingBox->setVisible(0); m_ccpm->ccpmPitchMixingBox->setVisible(!GUIConfigData.heli.ccpmCollectivePassthroughState && GUIConfigData.heli.ccpmLinkCyclicState); m_ccpm->ccpmCollectiveScalingBox->setVisible(GUIConfigData.heli.ccpmCollectivePassthroughState || !GUIConfigData.heli.ccpmLinkCyclicState); - m_ccpm->ccpmCollectiveChLabel->setVisible(GUIConfigData.heli.ccpmCollectivePassthroughState); - m_ccpm->ccpmCollectiveChannel->setVisible(GUIConfigData.heli.ccpmCollectivePassthroughState); - m_ccpm->ccpmLinkCyclic->setVisible(!GUIConfigData.heli.ccpmCollectivePassthroughState); m_ccpm->ccpmCyclicScalingBox->setVisible((GUIConfigData.heli.ccpmCollectivePassthroughState || !GUIConfigData.heli.ccpmLinkCyclicState) && GUIConfigData.heli.ccpmLinkRollState); @@ -1183,20 +1108,17 @@ void ConfigccpmWidget::requestccpmUpdate() #define MaxAngleError 2 int MixerDataFromHeli[8][5]; quint8 MixerOutputType[8]; - int EngineChannel,TailRotorChannel,ServoChannels[4],ServoAngles[4],SortAngles[4],CalcAngles[4],ServoCurve2[4]; + int EngineChannel,TailRotorChannel,ServoChannels[4],ServoAngles[4],SortAngles[4],ServoCurve2[4]; int NumServos=0; - double Collective=0.0; - double a1,a2; - int HeadRotation,temp; - int isCCPM=0; if (SwashLvlConfigurationInProgress)return; if (updatingToHardware)return; updatingFromHardware=TRUE; - int i,j; + unsigned int i,j; SystemSettings * systemSettings = SystemSettings::GetInstance(getObjectManager()); + Q_ASSERT(systemSettings); SystemSettings::DataFields systemSettingsData = systemSettings->getData(); Q_ASSERT(SystemSettings::GUICONFIGDATA_NUMELEM == @@ -1205,7 +1127,7 @@ void ConfigccpmWidget::requestccpmUpdate() for(i = 0; i < SystemSettings::GUICONFIGDATA_NUMELEM; i++) GUIConfigData.UAVObject[i]=systemSettingsData.GUIConfigData[i]; - UpdatCCPMUIFromOptions(); + UpdateCCPMUIFromOptions(); // Get existing mixer settings MixerSettings * mixerSettings = MixerSettings::GetInstance(getObjectManager()); @@ -1299,7 +1221,7 @@ void ConfigccpmWidget::requestccpmUpdate() } updatingFromHardware=FALSE; - UpdatCCPMUIFromOptions(); + UpdateCCPMUIFromOptions(); ccpmSwashplateUpdate(); } @@ -1310,116 +1232,83 @@ void ConfigccpmWidget::requestccpmUpdate() void ConfigccpmWidget::sendccpmUpdate() { int i,j; - UAVObjectField *field; - UAVDataObject* obj; if (SwashLvlConfigurationInProgress)return; updatingToHardware=TRUE; //ShowDisclaimer(1); + UpdateCCPMOptionsFromUI(); + + // Store the data required to reconstruct + SystemSettings * systemSettings = SystemSettings::GetInstance(getObjectManager()); + Q_ASSERT(systemSettings); + SystemSettings::DataFields systemSettingsData = systemSettings->getData(); + systemSettingsData.GUIConfigData[0] = GUIConfigData.UAVObject[0]; + systemSettingsData.GUIConfigData[1] = GUIConfigData.UAVObject[1]; + systemSettings->setData(systemSettingsData); + systemSettings->updated(); - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager *objManager = pm->getObject(); + MixerSettings * mixerSettings = MixerSettings::GetInstance(getObjectManager()); + Q_ASSERT(mixerSettings); + MixerSettings::DataFields mixerSettingsData = mixerSettings->getData(); - UpdatCCPMOptionsFromUI(); - obj = dynamic_cast(getObjectManager()->getObject(QString("SystemSettings"))); - field = obj->getField(QString("GUIConfigData")); - field->setValue(GUIConfigData.UAVObject[0],0); - field->setValue(GUIConfigData.UAVObject[1],1); - obj->updated(); - + UpdateMixer(); - - obj = dynamic_cast(objManager->getObject(QString("MixerSettings"))); - Q_ASSERT(obj); + // Set up some helper pointers + qint8 * mixers[8] = {mixerSettingsData.Mixer1Vector, + mixerSettingsData.Mixer2Vector, + mixerSettingsData.Mixer3Vector, + mixerSettingsData.Mixer4Vector, + mixerSettingsData.Mixer5Vector, + mixerSettingsData.Mixer6Vector, + mixerSettingsData.Mixer7Vector, + mixerSettingsData.Mixer8Vector + }; - UpdateMixer(); + quint8 * mixerTypes[8] = { + &mixerSettingsData.Mixer1Type, + &mixerSettingsData.Mixer2Type, + &mixerSettingsData.Mixer3Type, + &mixerSettingsData.Mixer4Type, + &mixerSettingsData.Mixer5Type, + &mixerSettingsData.Mixer6Type, + &mixerSettingsData.Mixer7Type, + &mixerSettingsData.Mixer8Type + }; - //clear the output types - for (i=0;i<8;i++) + //go through the user data and update the mixer matrix + for (i=0;i<6;i++) + { + if (MixerChannelData[i]<8) { - field = obj->getField( QString( "Mixer%1Type" ).arg( i+1 )); - //clear the mixer type - field->setValue("Disabled"); + //set the mixer type + *(mixerTypes[MixerChannelData[i]]) = i==0 ? + MixerSettings::MIXER1TYPE_MOTOR : + MixerSettings::MIXER1TYPE_SERVO; + + //config the vector + for (j=0;j<5;j++) + mixers[MixerChannelData[i]][j] = m_ccpm->ccpmAdvancedSettingsTable->item(i,j+1)->text().toInt(); } + } + //get the user data for the curve into the mixer settings + for (i=0;i<5;i++) + mixerSettingsData.ThrottleCurve1[i] = m_ccpm->CurveSettings->item(i, 0)->text().toDouble(); - //go through the user data and update the mixer matrix - for (i=0;i<6;i++) - { - /* - data.Mixer0Type = 0;//Disabled,Motor,Servo - data.Mixer0Vector[0] = 0;//ThrottleCurve1 - data.Mixer0Vector[1] = 0;//ThrottleCurve2 - data.Mixer0Vector[2] = 0;//Roll - data.Mixer0Vector[3] = 0;//Pitch - data.Mixer0Vector[4] = 0;//Yaw - - */ - if (MixerChannelData[i]<8) - { - //select the correct mixer for this config element - field = obj->getField(QString( "Mixer%1Type" ).arg( MixerChannelData[i]+1 )); - //set the mixer type - if (i==0) - { - field->setValue("Motor"); - } - else - { - field->setValue("Servo"); - } - - //select the correct mixer for this config element - field = obj->getField(QString( "Mixer%1Vector" ).arg( MixerChannelData[i]+1 )); - //config the vector - for (j=0;j<5;j++) - { - field->setValue(m_ccpm->ccpmAdvancedSettingsTable->item(i,j+1)->text().toInt(),j); - } - - } - - } - - - //get the user data for the curve into the mixer settings - field = obj->getField(QString("ThrottleCurve1")); - for (i=0;i<5;i++) - { - field->setValue(m_ccpm->CurveSettings->item(i, 0)->text().toDouble(),i); - } - field = obj->getField(QString("ThrottleCurve2")); - for (i=0;i<5;i++) - { - field->setValue(m_ccpm->CurveSettings->item(i, 1)->text().toDouble(),i); - } - - obj->updated(); - - field = obj->getField(QString("Curve2Source")); + for (i=0;i<5;i++) + mixerSettingsData.ThrottleCurve2[i] = m_ccpm->CurveSettings->item(i, 1)->text().toDouble(); //mapping of collective input to curve 2... //MixerSettings.Curve2Source = Throttle,Roll,Pitch,Yaw,Accessory0,Accessory1,Accessory2,Accessory3,Accessory4,Accessory5 //check if we are using throttle or directly from a channel... if (GUIConfigData.heli.ccpmCollectivePassthroughState) - {// input channel - field->setValue("Accessory0"); - obj->updated(); - - obj = dynamic_cast(objManager->getObject(QString("ManualControlSettings"))); - Q_ASSERT(obj); - field = obj->getField(QString("Accessory0")); - field->setValue(tr( "Channel%1" ).arg(GUIConfigData.heli.CollectiveChannel+1)); - - } + mixerSettingsData.Curve2Source = MixerSettings::CURVE2SOURCE_COLLECTIVE; else - {// throttle - - field->setValue("Throttle"); - } + mixerSettingsData.Curve2Source = MixerSettings::CURVE2SOURCE_THROTTLE; - obj->updated(); + mixerSettings->setData(mixerSettingsData); + mixerSettings->updated(); updatingToHardware=FALSE; } @@ -1820,7 +1709,6 @@ void ConfigccpmWidget::enableSwashplateLevellingControl(bool state) mdata.gcsTelemetryUpdateMode = UAVObject::UPDATEMODE_ONCHANGE; mdata.gcsTelemetryUpdatePeriod = 100; SwashLvlConfigurationInProgress=1; - connect(qApp, SIGNAL(focusChanged(QWidget*,QWidget*)),this, SLOT(FocusChanged(QWidget*,QWidget*))); m_ccpm->TabObject->setTabEnabled(0,0); m_ccpm->TabObject->setTabEnabled(2,0); m_ccpm->TabObject->setTabEnabled(3,0); @@ -1831,7 +1719,6 @@ void ConfigccpmWidget::enableSwashplateLevellingControl(bool state) mdata = SwashLvlaccInitialData; // Restore metadata SwashLvlConfigurationInProgress=0; - disconnect(qApp, SIGNAL(focusChanged(QWidget*,QWidget*)),this, SLOT(FocusChanged(QWidget*,QWidget*))); m_ccpm->TabObject->setTabEnabled(0,1); m_ccpm->TabObject->setTabEnabled(2,1); m_ccpm->TabObject->setTabEnabled(3,1); @@ -1857,41 +1744,24 @@ void ConfigccpmWidget::setSwashplateLevel(int percent) SwashLvlServoInterlock=1; - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("ActuatorCommand"))); - UAVObjectField * channel = obj->getField("Channel"); + ActuatorCommand * actuatorCommand = ActuatorCommand::GetInstance(getObjectManager()); + ActuatorCommand::DataFields actuatorCommandData = actuatorCommand->getData(); - - - if (level==0) - { - for (i=0;isetValue(newSwashLvlConfiguration.Neutral[i],newSwashLvlConfiguration.ServoChannels[i]); - SwashLvlSpinBoxes[i]->setValue(newSwashLvlConfiguration.Neutral[i]); - } - - } - else if (level>0) - { - for (i=0;i 0) value = (newSwashLvlConfiguration.Max[i] - newSwashLvlConfiguration.Neutral[i])*level + newSwashLvlConfiguration.Neutral[i]; - channel->setValue(value,newSwashLvlConfiguration.ServoChannels[i]); - SwashLvlSpinBoxes[i]->setValue(value); - } - - } - else if (level<0) - { - for (i=0;isetValue(value,newSwashLvlConfiguration.ServoChannels[i]); - SwashLvlSpinBoxes[i]->setValue(value); - } + actuatorCommandData.Channel[newSwashLvlConfiguration.ServoChannels[i]] = value; + SwashLvlSpinBoxes[i]->setValue(value); } - obj->updated(); + + actuatorCommand->setData(actuatorCommandData); + actuatorCommand->updated(); + SwashLvlServoInterlock=0; return; @@ -1900,76 +1770,41 @@ return; void ConfigccpmWidget::SwashLvlSpinBoxChanged(int value) { + Q_UNUSED(value); int i; if (SwashLvlServoInterlock==1)return; - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("ActuatorCommand"))); - UAVObjectField * channel = obj->getField("Channel"); - switch (SwashLvlState) - { - case 0: - break; - case 1: //Neutral levelling - for (i=0;igetData(); + + for (i = 0; i < CCPM_MAX_SWASH_SERVOS; i++) { + value = SwashLvlSpinBoxes[i]->value(); + + switch (SwashLvlState) { - newSwashLvlConfiguration.Neutral[i]=SwashLvlSpinBoxes[i]->value(); - channel->setValue(newSwashLvlConfiguration.Neutral[i],newSwashLvlConfiguration.ServoChannels[i]); + case 1: //Neutral levelling + newSwashLvlConfiguration.Neutral[i]=value; + break; + case 2: //Max levelling + newSwashLvlConfiguration.Max[i] = value; + break; + case 3: //Min levelling + newSwashLvlConfiguration.Min[i]= value; + break; + case 4: //levelling verification + break; + case 5: //levelling complete + break; + default: + break; } - obj->updated(); - break; - case 2: //Max levelling - for (i=0;ivalue(); - channel->setValue(newSwashLvlConfiguration.Max[i],newSwashLvlConfiguration.ServoChannels[i]); - } - obj->updated(); - break; - case 3: //Min levelling - for (i=0;ivalue(); - channel->setValue(newSwashLvlConfiguration.Min[i],newSwashLvlConfiguration.ServoChannels[i]); - } - obj->updated(); - break; - case 4: //levelling verification - break; - case 5: //levelling complete - break; - default: - break; + + actuatorCommandData.Channel[newSwashLvlConfiguration.ServoChannels[i]] = value; } + + + actuatorCommand->setData(actuatorCommandData); + actuatorCommand->updated(); + return; } - - -void ConfigccpmWidget::FocusChanged(QWidget *oldFocus, QWidget *newFocus) -{ - if (SwashLvlConfigurationInProgress!=1) return; - QMessageBox msgBox; - int ret; - msgBox.setText("

Warning!!!

"); - - if ((this->isAncestorOf(oldFocus))&&(!this->isAncestorOf(newFocus))) - { - msgBox.setInformativeText("You are in the middle of the levelling routine
Changing focus will cancel all levelling and return the OP hardware to the state it was in before levelling began.

Do you want to continue the levelling routine?"); - msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::No); - msgBox.setDefaultButton(QMessageBox::Yes); - msgBox.setIcon(QMessageBox::Information); - ret = msgBox.exec(); - - if (ret == QMessageBox::Yes) - { - - //m_ccpm->TabObject->setCurrentIndex(1); - //m_ccpm->SwashPlateLevel->setFocus(Qt::MouseFocusReason); - //m_ccpm->SwashLvlInstructionsBox->setFocus(Qt::MouseFocusReason); - oldFocus->setFocus(Qt::MouseFocusReason); - } - if (ret == QMessageBox::No) - { - SwashLvlCancelButtonPressed(); - } - } -} diff --git a/ground/openpilotgcs/src/plugins/config/configccpmwidget.h b/ground/openpilotgcs/src/plugins/config/configccpmwidget.h index d07da53c8..c6bc1b27b 100644 --- a/ground/openpilotgcs/src/plugins/config/configccpmwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configccpmwidget.h @@ -57,7 +57,6 @@ typedef struct { uint ccpmCollectivePassthroughState:1; uint ccpmLinkCyclicState:1; uint ccpmLinkRollState:1; - uint CollectiveChannel:3;//20bits uint SliderValue0:7; uint SliderValue1:7; uint SliderValue2:7;//41bits @@ -82,6 +81,8 @@ public: ConfigccpmWidget(QWidget *parent = 0); ~ConfigccpmWidget(); + friend class ConfigAirframeWidget; + private: Ui_ccpmWidget *m_ccpm; QGraphicsSvgItem *SwashplateImg; @@ -134,8 +135,8 @@ private: void SwashLvlCancelButtonPressed(); void SwashLvlFinishButtonPressed(); - void UpdatCCPMOptionsFromUI(); - void UpdatCCPMUIFromOptions(); + void UpdateCCPMOptionsFromUI(); + void UpdateCCPMUIFromOptions(); void SetUIComponentVisibilities(); void ccpmChannelCheck(); @@ -143,8 +144,6 @@ private: void enableSwashplateLevellingControl(bool state); void setSwashplateLevel(int percent); void SwashLvlSpinBoxChanged(int value); - void FocusChanged(QWidget *oldFocus, QWidget *newFocus); - virtual void refreshValues() {}; // Not used public slots: diff --git a/ground/openpilotgcs/src/plugins/config/configgadget.qrc b/ground/openpilotgcs/src/plugins/config/configgadget.qrc index 5f982053b..f24cb68b8 100644 --- a/ground/openpilotgcs/src/plugins/config/configgadget.qrc +++ b/ground/openpilotgcs/src/plugins/config/configgadget.qrc @@ -15,5 +15,7 @@ images/coptercontrol.svg images/hw_config.png images/gyroscope.png + images/TX.svg + images/camera.png diff --git a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp index 39acb5adf..d40db122f 100644 --- a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp @@ -33,6 +33,7 @@ #include "configinputwidget.h" #include "configoutputwidget.h" #include "configstabilizationwidget.h" +#include "configcamerastabilizationwidget.h" #include "config_pro_hw_widget.h" #include "config_cc_hw_widget.h" #include "defaultattitudewidget.h" @@ -81,6 +82,8 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent) qwd = new ConfigStabilizationWidget(this); ftw->insertTab(ConfigGadgetWidget::stabilization, qwd, QIcon(":/configgadget/images/gyroscope.png"), QString("Stabilization")); + qwd = new ConfigCameraStabilizationWidget(this); + ftw->insertTab(ConfigGadgetWidget::camerastabilization, qwd, QIcon(":/configgadget/images/camera.png"), QString("Camera Stab")); // qwd = new ConfigPipXtremeWidget(this); @@ -99,6 +102,8 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent) onAutopilotConnect(); help = 0; + connect(ftw,SIGNAL(currentAboutToShow(int,bool*)),this,SLOT(tabAboutToChange(int,bool*)));//,Qt::BlockingQueuedConnection); + } ConfigGadgetWidget::~ConfigGadgetWidget() @@ -115,11 +120,21 @@ void ConfigGadgetWidget::resizeEvent(QResizeEvent *event) } void ConfigGadgetWidget::onAutopilotDisconnect() { + ftw->setCurrentIndex(ConfigGadgetWidget::hardware); + ftw->removeTab(ConfigGadgetWidget::ins); + QWidget *qwd = new DefaultAttitudeWidget(this); + ftw->insertTab(ConfigGadgetWidget::ins, qwd, QIcon(":/configgadget/images/AHRS-v1.3.png"), QString("INS")); + ftw->removeTab(ConfigGadgetWidget::hardware); + qwd = new DefaultHwSettingsWidget(this); + ftw->insertTab(ConfigGadgetWidget::hardware, qwd, QIcon(":/configgadget/images/hw_config.png"), QString("HW Settings")); + ftw->setCurrentIndex(ConfigGadgetWidget::hardware); + emit autopilotDisconnected(); } void ConfigGadgetWidget::onAutopilotConnect() { + qDebug()<<"ConfigGadgetWidget onAutopilotConnect"; // First of all, check what Board type we are talking to, and // if necessary, remove/add tabs in the config gadget: ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); @@ -153,5 +168,24 @@ void ConfigGadgetWidget::onAutopilotConnect() { emit autopilotConnected(); } +void ConfigGadgetWidget::tabAboutToChange(int i,bool * proceed) +{ + Q_UNUSED(i); + *proceed=true; + ConfigTaskWidget * wid=qobject_cast(ftw->currentWidget()); + if(!wid) + return; + if(wid->isDirty()) + { + int ans=QMessageBox::warning(this,tr("Unsaved changes"),tr("The tab you are leaving has unsaved changes," + "if you proceed they will be lost." + "Do you still want to proceed?"),QMessageBox::Yes,QMessageBox::No); + if(ans==QMessageBox::No) + *proceed=false; + else + wid->setDirty(false); + } +} + diff --git a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.h b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.h index df2f553a3..633253507 100644 --- a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.h @@ -37,10 +37,10 @@ //#include #include #include "utils/pathutils.h" - +#include //#include "fancytabwidget.h" #include "utils/mytabbedstackwidget.h" - +#include "configtaskwidget.h" class ConfigGadgetWidget: public QWidget { @@ -50,11 +50,12 @@ class ConfigGadgetWidget: public QWidget public: ConfigGadgetWidget(QWidget *parent = 0); ~ConfigGadgetWidget(); - enum widgetTabs {hardware=0, aircraft, input, output, ins, stabilization}; + enum widgetTabs {hardware=0, aircraft, input, output, ins, stabilization, camerastabilization}; public slots: void onAutopilotConnect(); void onAutopilotDisconnect(); + void tabAboutToChange(int i,bool *); signals: void autopilotConnected(); diff --git a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp index 83e1a02ac..128f9885b 100644 --- a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp @@ -1,8 +1,8 @@ /** ****************************************************************************** * - * @file configservowidget.cpp - * @author E. Lafargue & The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @file configinputwidget.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup ConfigPlugin Config Plugin @@ -38,614 +38,233 @@ #include #include #include +#include +#include -#include "manualcontrolsettings.h" +#define ACCESS_MIN_MOVE -6 +#define ACCESS_MAX_MOVE 6 +#define STICK_MIN_MOVE -8 +#define STICK_MAX_MOVE 8 -ConfigInputWidget::ConfigInputWidget(QWidget *parent) : ConfigTaskWidget(parent) +ConfigInputWidget::ConfigInputWidget(QWidget *parent) : ConfigTaskWidget(parent),wizardStep(wizardNone),loop(NULL),skipflag(false),transmitterType(heli) { + manualCommandObj = ManualControlCommand::GetInstance(getObjectManager()); + manualSettingsObj = ManualControlSettings::GetInstance(getObjectManager()); + receiverActivityObj=ReceiverActivity::GetInstance(getObjectManager()); m_config = new Ui_InputWidget(); m_config->setupUi(this); - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager *objManager = pm->getObject(); + setupButtons(m_config->saveRCInputToRAM,m_config->saveRCInputToSD); - // First of all, put all the channel widgets into lists, so that we can - // manipulate those: - - - inMaxLabels << m_config->ch0Max - << m_config->ch1Max - << m_config->ch2Max - << m_config->ch3Max - << m_config->ch4Max - << m_config->ch5Max - << m_config->ch6Max - << m_config->ch7Max; - - inMinLabels << m_config->ch0Min - << m_config->ch1Min - << m_config->ch2Min - << m_config->ch3Min - << m_config->ch4Min - << m_config->ch5Min - << m_config->ch6Min - << m_config->ch7Min; - - inSliders << m_config->inSlider0 - << m_config->inSlider1 - << m_config->inSlider2 - << m_config->inSlider3 - << m_config->inSlider4 - << m_config->inSlider5 - << m_config->inSlider6 - << m_config->inSlider7; - - inRevCheckboxes << m_config->ch0Rev - << m_config->ch1Rev - << m_config->ch2Rev - << m_config->ch3Rev - << m_config->ch4Rev - << m_config->ch5Rev - << m_config->ch6Rev - << m_config->ch7Rev; - - inChannelAssign << m_config->ch0Assign - << m_config->ch1Assign - << m_config->ch2Assign - << m_config->ch3Assign - << m_config->ch4Assign - << m_config->ch5Assign - << m_config->ch6Assign - << m_config->ch7Assign; - - // Now connect the widget to the ManualControlCommand / Channel UAVObject - UAVDataObject* obj = dynamic_cast(objManager->getObject(QString("ManualControlCommand"))); - connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(updateChannels(UAVObject*))); - - // Register for ManualControlSettings changes: - obj = dynamic_cast(objManager->getObject(QString("ManualControlSettings"))); - connect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(refreshValues())); - - - // Get the receiver types supported by OpenPilot and fill the corresponding - // dropdown menu: - obj = dynamic_cast(objManager->getObject(QString("ManualControlSettings"))); - UAVObjectField * field; - // Fill in the dropdown menus for the channel RC Input assignement. - QStringList channelsList; - channelsList << "None"; - QList fieldList = obj->getFields(); - foreach (UAVObjectField* field, fieldList) { - if (field->getUnits().contains("channel")) { - channelsList.append(field->getName()); - } + unsigned int index=0; + foreach(QString name,manualSettingsObj->getFields().at(0)->getElementNames()) + { + Q_ASSERT(index < ManualControlSettings::CHANNELGROUPS_NUMELEM); + inputChannelForm * inp=new inputChannelForm(this,index==0); + m_config->channelSettings->layout()->addWidget(inp); + inp->ui->channelName->setText(name); + addUAVObjectToWidgetRelation("ManualControlSettings","ChannelGroups",inp->ui->channelGroup,index); + addUAVObjectToWidgetRelation("ManualControlSettings","ChannelNumber",inp->ui->channelNumber,index); + addUAVObjectToWidgetRelation("ManualControlSettings","ChannelMin",inp->ui->channelMin,index); + addUAVObjectToWidgetRelation("ManualControlSettings","ChannelNeutral",inp->ui->channelNeutral,index); + addUAVObjectToWidgetRelation("ManualControlSettings","ChannelMax",inp->ui->channelMax,index); + ++index; } - m_config->ch0Assign->addItems(channelsList); - m_config->ch1Assign->addItems(channelsList); - m_config->ch2Assign->addItems(channelsList); - m_config->ch3Assign->addItems(channelsList); - m_config->ch4Assign->addItems(channelsList); - m_config->ch5Assign->addItems(channelsList); - m_config->ch6Assign->addItems(channelsList); - m_config->ch7Assign->addItems(channelsList); + connect(m_config->configurationWizard,SIGNAL(clicked()),this,SLOT(goToWizard())); + connect(m_config->runCalibration,SIGNAL(toggled(bool)),this, SLOT(simpleCalibration(bool))); - // And the flight mode settings: - field = obj->getField(QString("FlightModePosition")); - m_config->fmsModePos1->addItems(field->getOptions()); - m_config->fmsModePos2->addItems(field->getOptions()); - m_config->fmsModePos3->addItems(field->getOptions()); - field = obj->getField(QString("Stabilization1Settings")); - channelsList.clear(); - channelsList.append(field->getOptions()); - m_config->fmsSsPos1Roll->addItems(channelsList); - m_config->fmsSsPos1Pitch->addItems(channelsList); - m_config->fmsSsPos1Yaw->addItems(channelsList); - m_config->fmsSsPos2Roll->addItems(channelsList); - m_config->fmsSsPos2Pitch->addItems(channelsList); - m_config->fmsSsPos2Yaw->addItems(channelsList); - m_config->fmsSsPos3Roll->addItems(channelsList); - m_config->fmsSsPos3Pitch->addItems(channelsList); - m_config->fmsSsPos3Yaw->addItems(channelsList); + connect(m_config->wzNext,SIGNAL(clicked()),this,SLOT(wzNext())); + connect(m_config->wzCancel,SIGNAL(clicked()),this,SLOT(wzCancel())); + connect(m_config->wzBack,SIGNAL(clicked()),this,SLOT(wzBack())); - // And the Armin configurations: - field = obj->getField(QString("Arming")); - m_config->armControl->clear(); - m_config->armControl->addItems(field->getOptions()); + m_config->stackedWidget->setCurrentIndex(0); + addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos1,0); + addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos2,1); + addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos3,2); + addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization1Settings",m_config->fmsSsPos1Roll,"Roll"); + addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization2Settings",m_config->fmsSsPos2Roll,"Roll"); + addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization3Settings",m_config->fmsSsPos3Roll,"Roll"); + addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization1Settings",m_config->fmsSsPos1Pitch,"Pitch"); + addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization2Settings",m_config->fmsSsPos2Pitch,"Pitch"); + addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization3Settings",m_config->fmsSsPos3Pitch,"Pitch"); + addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization1Settings",m_config->fmsSsPos1Yaw,"Yaw"); + addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization2Settings",m_config->fmsSsPos2Yaw,"Yaw"); + addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization3Settings",m_config->fmsSsPos3Yaw,"Yaw"); - connect(m_config->saveRCInputToSD, SIGNAL(clicked()), this, SLOT(saveRCInputObject())); - connect(m_config->saveRCInputToRAM, SIGNAL(clicked()), this, SLOT(sendRCInputUpdate())); - + addUAVObjectToWidgetRelation("ManualControlSettings","Arming",m_config->armControl); + addUAVObjectToWidgetRelation("ManualControlSettings","ArmedTimeout",m_config->armTimeout,0,1000); + connect( ManualControlCommand::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(moveFMSlider())); enableControls(false); - refreshValues(); - connect(parent, SIGNAL(autopilotConnected()),this, SLOT(onAutopilotConnect())); - connect(parent, SIGNAL(autopilotDisconnected()), this, SLOT(onAutopilotDisconnect())); - - connect(m_config->ch0Rev, SIGNAL(toggled(bool)), this, SLOT(reverseCheckboxClicked(bool))); - connect(m_config->ch1Rev, SIGNAL(toggled(bool)), this, SLOT(reverseCheckboxClicked(bool))); - connect(m_config->ch2Rev, SIGNAL(toggled(bool)), this, SLOT(reverseCheckboxClicked(bool))); - connect(m_config->ch3Rev, SIGNAL(toggled(bool)), this, SLOT(reverseCheckboxClicked(bool))); - connect(m_config->ch4Rev, SIGNAL(toggled(bool)), this, SLOT(reverseCheckboxClicked(bool))); - connect(m_config->ch5Rev, SIGNAL(toggled(bool)), this, SLOT(reverseCheckboxClicked(bool))); - connect(m_config->ch6Rev, SIGNAL(toggled(bool)), this, SLOT(reverseCheckboxClicked(bool))); - connect(m_config->ch7Rev, SIGNAL(toggled(bool)), this, SLOT(reverseCheckboxClicked(bool))); - connect(m_config->doRCInputCalibration,SIGNAL(stateChanged(int)),this,SLOT(updateTips(int))); - firstUpdate = true; + populateWidgets(); + refreshWidgetsValues(); // Connect the help button connect(m_config->inputHelp, SIGNAL(clicked()), this, SLOT(openHelp())); - updateTips(Qt::Unchecked); + m_config->graphicsView->setScene(new QGraphicsScene(this)); + m_config->graphicsView->setViewportUpdateMode(QGraphicsView::FullViewportUpdate); + m_renderer = new QSvgRenderer(); + QGraphicsScene *l_scene = m_config->graphicsView->scene(); + m_config->graphicsView->setBackgroundBrush(QBrush(Utils::StyleHelper::baseColor())); + if (QFile::exists(":/configgadget/images/TX.svg") && m_renderer->load(QString(":/configgadget/images/TX.svg")) && m_renderer->isValid()) + { + l_scene->clear(); // Deletes all items contained in the scene as well. + + m_txBackground = new QGraphicsSvgItem(); + // All other items will be clipped to the shape of the background + m_txBackground->setFlags(QGraphicsItem::ItemClipsChildrenToShape| + QGraphicsItem::ItemClipsToShape); + m_txBackground->setSharedRenderer(m_renderer); + m_txBackground->setElementId("background"); + l_scene->addItem(m_txBackground); + + m_txMainBody = new QGraphicsSvgItem(); + m_txMainBody->setParentItem(m_txBackground); + m_txMainBody->setSharedRenderer(m_renderer); + m_txMainBody->setElementId("body"); + l_scene->addItem(m_txMainBody); + + m_txLeftStick = new QGraphicsSvgItem(); + m_txLeftStick->setParentItem(m_txBackground); + m_txLeftStick->setSharedRenderer(m_renderer); + m_txLeftStick->setElementId("ljoy"); + + m_txRightStick = new QGraphicsSvgItem(); + m_txRightStick->setParentItem(m_txBackground); + m_txRightStick->setSharedRenderer(m_renderer); + m_txRightStick->setElementId("rjoy"); + + m_txAccess0 = new QGraphicsSvgItem(); + m_txAccess0->setParentItem(m_txBackground); + m_txAccess0->setSharedRenderer(m_renderer); + m_txAccess0->setElementId("access0"); + + m_txAccess1 = new QGraphicsSvgItem(); + m_txAccess1->setParentItem(m_txBackground); + m_txAccess1->setSharedRenderer(m_renderer); + m_txAccess1->setElementId("access1"); + + m_txAccess2 = new QGraphicsSvgItem(); + m_txAccess2->setParentItem(m_txBackground); + m_txAccess2->setSharedRenderer(m_renderer); + m_txAccess2->setElementId("access2"); + + m_txFlightMode = new QGraphicsSvgItem(); + m_txFlightMode->setParentItem(m_txBackground); + m_txFlightMode->setSharedRenderer(m_renderer); + m_txFlightMode->setElementId("flightModeCenter"); + m_txFlightMode->setZValue(-10); + + m_txArrows = new QGraphicsSvgItem(); + m_txArrows->setParentItem(m_txBackground); + m_txArrows->setSharedRenderer(m_renderer); + m_txArrows->setElementId("arrows"); + m_txArrows->setVisible(false); + + QRectF orig=m_renderer->boundsOnElement("ljoy"); + QMatrix Matrix = m_renderer->matrixForElement("ljoy"); + orig=Matrix.mapRect(orig); + m_txLeftStickOrig.translate(orig.x(),orig.y()); + m_txLeftStick->setTransform(m_txLeftStickOrig,false); + + orig=m_renderer->boundsOnElement("arrows"); + Matrix = m_renderer->matrixForElement("arrows"); + orig=Matrix.mapRect(orig); + m_txArrowsOrig.translate(orig.x(),orig.y()); + m_txArrows->setTransform(m_txArrowsOrig,false); + + orig=m_renderer->boundsOnElement("body"); + Matrix = m_renderer->matrixForElement("body"); + orig=Matrix.mapRect(orig); + m_txMainBodyOrig.translate(orig.x(),orig.y()); + m_txMainBody->setTransform(m_txMainBodyOrig,false); + + orig=m_renderer->boundsOnElement("flightModeCenter"); + Matrix = m_renderer->matrixForElement("flightModeCenter"); + orig=Matrix.mapRect(orig); + m_txFlightModeCOrig.translate(orig.x(),orig.y()); + m_txFlightMode->setTransform(m_txFlightModeCOrig,false); + + orig=m_renderer->boundsOnElement("flightModeLeft"); + Matrix = m_renderer->matrixForElement("flightModeLeft"); + orig=Matrix.mapRect(orig); + m_txFlightModeLOrig.translate(orig.x(),orig.y()); + orig=m_renderer->boundsOnElement("flightModeRight"); + Matrix = m_renderer->matrixForElement("flightModeRight"); + orig=Matrix.mapRect(orig); + m_txFlightModeROrig.translate(orig.x(),orig.y()); + + orig=m_renderer->boundsOnElement("rjoy"); + Matrix = m_renderer->matrixForElement("rjoy"); + orig=Matrix.mapRect(orig); + m_txRightStickOrig.translate(orig.x(),orig.y()); + m_txRightStick->setTransform(m_txRightStickOrig,false); + + orig=m_renderer->boundsOnElement("access0"); + Matrix = m_renderer->matrixForElement("access0"); + orig=Matrix.mapRect(orig); + m_txAccess0Orig.translate(orig.x(),orig.y()); + m_txAccess0->setTransform(m_txAccess0Orig,false); + + orig=m_renderer->boundsOnElement("access1"); + Matrix = m_renderer->matrixForElement("access1"); + orig=Matrix.mapRect(orig); + m_txAccess1Orig.translate(orig.x(),orig.y()); + m_txAccess1->setTransform(m_txAccess1Orig,false); + + orig=m_renderer->boundsOnElement("access2"); + Matrix = m_renderer->matrixForElement("access2"); + orig=Matrix.mapRect(orig); + m_txAccess2Orig.translate(orig.x(),orig.y()); + m_txAccess2->setTransform(m_txAccess2Orig,true); + } + m_config->graphicsView->fitInView(m_txMainBody, Qt::KeepAspectRatio ); + animate=new QTimer(this); + connect(animate,SIGNAL(timeout()),this,SLOT(moveTxControls())); + + heliChannelOrder << ManualControlSettings::CHANNELGROUPS_COLLECTIVE << + ManualControlSettings::CHANNELGROUPS_THROTTLE << + ManualControlSettings::CHANNELGROUPS_ROLL << + ManualControlSettings::CHANNELGROUPS_PITCH << + ManualControlSettings::CHANNELGROUPS_YAW << + ManualControlSettings::CHANNELGROUPS_FLIGHTMODE << + ManualControlSettings::CHANNELGROUPS_ACCESSORY0 << + ManualControlSettings::CHANNELGROUPS_ACCESSORY1 << + ManualControlSettings::CHANNELGROUPS_ACCESSORY2; + + acroChannelOrder << ManualControlSettings::CHANNELGROUPS_THROTTLE << + ManualControlSettings::CHANNELGROUPS_ROLL << + ManualControlSettings::CHANNELGROUPS_PITCH << + ManualControlSettings::CHANNELGROUPS_YAW << + ManualControlSettings::CHANNELGROUPS_FLIGHTMODE << + ManualControlSettings::CHANNELGROUPS_ACCESSORY0 << + ManualControlSettings::CHANNELGROUPS_ACCESSORY1 << + ManualControlSettings::CHANNELGROUPS_ACCESSORY2; +} +void ConfigInputWidget::resetTxControls() +{ + + m_txLeftStick->setTransform(m_txLeftStickOrig,false); + m_txRightStick->setTransform(m_txRightStickOrig,false); + m_txAccess0->setTransform(m_txAccess0Orig,false); + m_txAccess1->setTransform(m_txAccess1Orig,false); + m_txAccess2->setTransform(m_txAccess2Orig,false); + m_txFlightMode->setElementId("flightModeCenter"); + m_txFlightMode->setTransform(m_txFlightModeCOrig,false); + m_txArrows->setVisible(false); } ConfigInputWidget::~ConfigInputWidget() { - // Do nothing -} - -/** - Slot called whenever we revert a signal - */ -void ConfigInputWidget::reverseCheckboxClicked(bool state) -{ - QObject* obj = sender(); - int i = inRevCheckboxes.indexOf((QCheckBox*)obj); - - inSliders[i]->setInvertedAppearance(state); - int max = inMaxLabels[i]->text().toInt(); - int min = inMinLabels[i]->text().toInt(); - if ((state && (max>min)) || - (!state && (max < min))) { - inMaxLabels[i]->setText(QString::number(min)); - inMinLabels[i]->setText(QString::number(max)); - } -} - - -// ************************************ - -/* - Enable or disable some controls depending on whether we are connected - or not to the board. Actually, this i mostly useless IMHO, I don't - know who added this into the code (Ed's note) - */ -void ConfigInputWidget::enableControls(bool enable) -{ - //m_config->saveRCInputToRAM->setEnabled(enable); - m_config->saveRCInputToSD->setEnabled(enable); - m_config->doRCInputCalibration->setEnabled(enable); -} - - -/******************************** - * Input settings - *******************************/ - -/** - Request the current config from the board - */ -void ConfigInputWidget::refreshValues() -{ - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("ManualControlSettings"))); - Q_ASSERT(obj); - //obj->requestUpdate(); - UAVObjectField *field; - - // Now update all the slider values: - - UAVObjectField *field_max = obj->getField(QString("ChannelMax")); - UAVObjectField *field_min = obj->getField(QString("ChannelMin")); - UAVObjectField *field_neu = obj->getField(QString("ChannelNeutral")); - Q_ASSERT(field_max); - Q_ASSERT(field_min); - Q_ASSERT(field_neu); - for (int i = 0; i < 8; i++) { - QVariant max = field_max->getValue(i); - QVariant min = field_min->getValue(i); - QVariant neutral = field_neu->getValue(i); - inMaxLabels[i]->setText(max.toString()); - inMinLabels[i]->setText(min.toString()); - if (max.toInt()> min.toInt()) { - inRevCheckboxes[i]->setChecked(false); - inSliders[i]->setMaximum(max.toInt()); - inSliders[i]->setMinimum(min.toInt()); - } else { - inRevCheckboxes[i]->setChecked(true); - inSliders[i]->setMaximum(min.toInt()); - inSliders[i]->setMinimum(max.toInt()); - } - inSliders[i]->setValue(neutral.toInt()); - } - - // Update receiver type - field = obj->getField(QString("InputMode")); - m_config->receiverType->setText(field->getValue().toString()); - - // Reset all channel assignement dropdowns: - foreach (QComboBox *combo, inChannelAssign) { - combo->setCurrentIndex(0); - } - - // Update all channels assignements - QList fieldList = obj->getFields(); - foreach (UAVObjectField *field, fieldList) { - if (field->getUnits().contains("channel")) - assignChannel(obj, field->getName()); - } - - // Update all the flight mode settingsin the relevant tab - field = obj->getField(QString("FlightModePosition")); - m_config->fmsModePos1->setCurrentIndex((m_config->fmsModePos1->findText(field->getValue(0).toString()))); - m_config->fmsModePos2->setCurrentIndex((m_config->fmsModePos2->findText(field->getValue(1).toString()))); - m_config->fmsModePos3->setCurrentIndex((m_config->fmsModePos3->findText(field->getValue(2).toString()))); - - field = obj->getField(QString("Stabilization1Settings")); - m_config->fmsSsPos1Roll->setCurrentIndex(m_config->fmsSsPos1Roll->findText(field->getValue(field->getElementNames().indexOf("Roll")).toString())); - m_config->fmsSsPos1Pitch->setCurrentIndex(m_config->fmsSsPos1Pitch->findText(field->getValue(field->getElementNames().indexOf("Pitch")).toString())); - m_config->fmsSsPos1Yaw->setCurrentIndex(m_config->fmsSsPos1Yaw->findText(field->getValue(field->getElementNames().indexOf("Yaw")).toString())); - field = obj->getField(QString("Stabilization2Settings")); - m_config->fmsSsPos2Roll->setCurrentIndex(m_config->fmsSsPos2Roll->findText(field->getValue(field->getElementNames().indexOf("Roll")).toString())); - m_config->fmsSsPos2Pitch->setCurrentIndex(m_config->fmsSsPos2Pitch->findText(field->getValue(field->getElementNames().indexOf("Pitch")).toString())); - m_config->fmsSsPos2Yaw->setCurrentIndex(m_config->fmsSsPos2Yaw->findText(field->getValue(field->getElementNames().indexOf("Yaw")).toString())); - field = obj->getField(QString("Stabilization3Settings")); - m_config->fmsSsPos3Roll->setCurrentIndex(m_config->fmsSsPos3Roll->findText(field->getValue(field->getElementNames().indexOf("Roll")).toString())); - m_config->fmsSsPos3Pitch->setCurrentIndex(m_config->fmsSsPos3Pitch->findText(field->getValue(field->getElementNames().indexOf("Pitch")).toString())); - m_config->fmsSsPos3Yaw->setCurrentIndex(m_config->fmsSsPos3Yaw->findText(field->getValue(field->getElementNames().indexOf("Yaw")).toString())); - - // Load the arming settings - field = obj->getField(QString("Arming")); - m_config->armControl->setCurrentIndex(m_config->armControl->findText(field->getValue().toString())); - field = obj->getField(QString("ArmedTimeout")); - m_config->armTimeout->setValue(field->getValue().toInt()/1000); -} - - -/** - * Sends the config to the board, without saving to the SD card - */ -void ConfigInputWidget::sendRCInputUpdate() -{ - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager *objManager = pm->getObject(); - UAVDataObject* obj = dynamic_cast(objManager->getObject(QString("ManualControlSettings"))); - Q_ASSERT(obj); - // Now update all fields from the sliders: - QString fieldName = QString("ChannelMax"); - UAVObjectField * field = obj->getField(fieldName); - for (int i = 0; i < 8; i++) { - field->setValue(inMaxLabels[i]->text().toInt(), i); - } - - fieldName = QString("ChannelMin"); - field = obj->getField(fieldName); - for (int i = 0; i < 8; i++) { - field->setValue(inMinLabels[i]->text().toInt(), i); - } - - fieldName = QString("ChannelNeutral"); - field = obj->getField(fieldName); - for (int i = 0; i < 8; i++) - field->setValue(inSliders[i]->value(), i); - - // Set Roll/Pitch/Yaw/Etc assignement: - // Rule: if two channels have the same setting (which is wrong!) the higher channel - // will get the setting. - - // First, reset all channel assignements: - QList fieldList = obj->getFields(); - foreach (UAVObjectField* field, fieldList) { - if (field->getUnits().contains("channel")) { - field->setValue(field->getOptions().last()); - } - } - - // Then assign according to current GUI state: - if (m_config->ch0Assign->currentIndex() != 0) { - field = obj->getField(m_config->ch0Assign->currentText()); - field->setValue(field->getOptions().at(0)); // -> This way we don't depend on channel naming convention - } - if (m_config->ch1Assign->currentIndex() != 0) { - field = obj->getField(m_config->ch1Assign->currentText()); - field->setValue(field->getOptions().at(1)); - } - if (m_config->ch2Assign->currentIndex() != 0) { - field = obj->getField(m_config->ch2Assign->currentText()); - field->setValue(field->getOptions().at(2)); - } - if (m_config->ch3Assign->currentIndex() != 0) { - field = obj->getField(m_config->ch3Assign->currentText()); - field->setValue(field->getOptions().at(3)); - } - if (m_config->ch4Assign->currentIndex() != 0) { - field = obj->getField(m_config->ch4Assign->currentText()); - field->setValue(field->getOptions().at(4)); - } - if (m_config->ch5Assign->currentIndex() != 0) { - field = obj->getField(m_config->ch5Assign->currentText()); - field->setValue(field->getOptions().at(5)); - } - if (m_config->ch6Assign->currentIndex() != 0) { - field = obj->getField(m_config->ch6Assign->currentText()); - field->setValue(field->getOptions().at(6)); - } - if (m_config->ch7Assign->currentIndex() != 0) { - field = obj->getField(m_config->ch7Assign->currentText()); - field->setValue(field->getOptions().at(7)); - } - - // Send all the flight mode settings - field = obj->getField(QString("FlightModePosition")); - field->setValue(m_config->fmsModePos1->currentText(),0); - field->setValue(m_config->fmsModePos2->currentText(),1); - field->setValue(m_config->fmsModePos3->currentText(),2); - - field = obj->getField(QString("Stabilization1Settings")); - field->setValue(m_config->fmsSsPos1Roll->currentText(), field->getElementNames().indexOf("Roll")); - field->setValue(m_config->fmsSsPos1Pitch->currentText(), field->getElementNames().indexOf("Pitch")); - field->setValue(m_config->fmsSsPos1Yaw->currentText(), field->getElementNames().indexOf("Yaw")); - field = obj->getField(QString("Stabilization2Settings")); - field->setValue(m_config->fmsSsPos2Roll->currentText(), field->getElementNames().indexOf("Roll")); - field->setValue(m_config->fmsSsPos2Pitch->currentText(), field->getElementNames().indexOf("Pitch")); - field->setValue(m_config->fmsSsPos2Yaw->currentText(), field->getElementNames().indexOf("Yaw")); - field = obj->getField(QString("Stabilization3Settings")); - field->setValue(m_config->fmsSsPos3Roll->currentText(), field->getElementNames().indexOf("Roll")); - field->setValue(m_config->fmsSsPos3Pitch->currentText(), field->getElementNames().indexOf("Pitch")); - field->setValue(m_config->fmsSsPos3Yaw->currentText(), field->getElementNames().indexOf("Yaw")); - - // Save the arming settings - field = obj->getField(QString("Arming")); - field->setValue(m_config->armControl->currentText()); - field = obj->getField(QString("ArmedTimeout")); - field->setValue(m_config->armTimeout->value()*1000); - - // ... and send to the OP Board - obj->updated(); } -/** - Sends the config to the board and request saving into the SD card - */ -void ConfigInputWidget::saveRCInputObject() +void ConfigInputWidget::resizeEvent(QResizeEvent *event) { - // Send update so that the latest value is saved - sendRCInputUpdate(); - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("ManualControlSettings"))); - Q_ASSERT(obj); - saveObjectToSD(obj); -} - - -/** - * Set the dropdown option for a channel Input assignement - */ -void ConfigInputWidget::assignChannel(UAVDataObject *obj, QString str) -{ - UAVObjectField* field = obj->getField(str); - QStringList options = field->getOptions(); - switch (options.indexOf(field->getValue().toString())) { - case 0: - m_config->ch0Assign->setCurrentIndex(m_config->ch0Assign->findText(str)); - break; - case 1: - m_config->ch1Assign->setCurrentIndex(m_config->ch0Assign->findText(str)); - break; - case 2: - m_config->ch2Assign->setCurrentIndex(m_config->ch0Assign->findText(str)); - break; - case 3: - m_config->ch3Assign->setCurrentIndex(m_config->ch0Assign->findText(str)); - break; - case 4: - m_config->ch4Assign->setCurrentIndex(m_config->ch0Assign->findText(str)); - break; - case 5: - m_config->ch5Assign->setCurrentIndex(m_config->ch0Assign->findText(str)); - break; - case 6: - m_config->ch6Assign->setCurrentIndex(m_config->ch0Assign->findText(str)); - break; - case 7: - m_config->ch7Assign->setCurrentIndex(m_config->ch0Assign->findText(str)); - break; - } -} - -/** - * Updates the slider positions and min/max values - * - */ -void ConfigInputWidget::updateChannels(UAVObject* controlCommand) -{ - - QString fieldName = QString("Connected"); - UAVObjectField *field = controlCommand->getField(fieldName); - if (field->getValue().toBool()) - { - m_config->RCInputConnected->setText("RC Receiver connected"); - m_config->lblMissingInputs->setText(""); - } - else - { - m_config->RCInputConnected->setText("RC Receiver not connected or invalid input configuration (missing channels)"); - receiverHelp(); - } - if (m_config->doRCInputCalibration->isChecked()) { - if (firstUpdate) { - // Increase the data rate from the board so that the sliders - // move faster - UAVObject::Metadata mdata = controlCommand->getMetadata(); - mdata.flightTelemetryUpdateMode = UAVObject::UPDATEMODE_PERIODIC; - mccDataRate = mdata.flightTelemetryUpdatePeriod; - mdata.flightTelemetryUpdatePeriod = 150; - controlCommand->setMetadata(mdata); - - // Also protect the user by setting all values to zero - // and making the ActuatorCommand object readonly - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("ActuatorCommand"))); - mdata = obj->getMetadata(); - mdata.flightAccess = UAVObject::ACCESS_READONLY; - obj->setMetadata(mdata); - UAVObjectField *field = obj->getField("Channel"); - for (uint i=0; i< field->getNumElements(); i++) { - field->setValue(0,i); - } - obj->updated(); - - // OP-534: make sure the airframe can NEVER arm - obj = dynamic_cast(getObjectManager()->getObject(QString("ManualControlSettings"))); - field = obj->getField("Arming"); - field->setValue("Always Disarmed"); - obj->updated(); - - // Last, make sure the user won't apply/save during calibration - m_config->saveRCInputToRAM->setEnabled(false); - m_config->saveRCInputToSD->setEnabled(false); - - // Reset all slider values to zero - field = controlCommand->getField(QString("Channel")); - for (int i = 0; i < 8; i++) - updateChannelInSlider(inSliders[i], inMinLabels[i], inMaxLabels[i], field->getValue(i).toInt(),inRevCheckboxes[i]->isChecked()); - firstUpdate = false; - // Tell a few things to the user: - QMessageBox msgBox; - msgBox.setText(tr("Arming Settings are now set to Always Disarmed for your safety.")); - msgBox.setDetailedText(tr("You will have to reconfigure arming settings yourself afterwards.")); - msgBox.setStandardButtons(QMessageBox::Ok); - msgBox.setDefaultButton(QMessageBox::Ok); - msgBox.exec(); - - } - - field = controlCommand->getField(QString("Channel")); - for (int i = 0; i < 8; i++) - updateChannelInSlider(inSliders[i], inMinLabels[i], inMaxLabels[i], field->getValue(i).toInt(),inRevCheckboxes[i]->isChecked()); - } - else { - if (!firstUpdate) { - // Restore original data rate from the board: - UAVObject::Metadata mdata = controlCommand->getMetadata(); - mdata.flightTelemetryUpdateMode = UAVObject::UPDATEMODE_PERIODIC; - mdata.flightTelemetryUpdatePeriod = mccDataRate; - controlCommand->setMetadata(mdata); - - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("ActuatorCommand"))); - mdata = obj->getMetadata(); - mdata.flightAccess = UAVObject::ACCESS_READWRITE; - obj->setMetadata(mdata); - - // Set some slider values to better defaults - // Find some channels first - int throttleChannel = -1; - int fmChannel = -1; - for (int i=0; i < inChannelAssign.length(); i++) { - if (inChannelAssign.at(i)->currentText() == "Throttle") { - // TODO: this is very ugly, because this relies on the name of the - // channel input, everywhere else in the gadget we don't rely on the - // naming... - throttleChannel = i; - } - if (inChannelAssign.at(i)->currentText() == "FlightMode") { - // TODO: this is very ugly, because this relies on the name of the - // channel input, everywhere else in the gadget we don't rely on the - // naming... - fmChannel = i; - } - } - - // Throttle neutral defaults to 2% of range - if (throttleChannel > -1) { - inSliders.at(throttleChannel)->setValue( - inSliders.at(throttleChannel)->minimum() + - (inSliders.at(throttleChannel)->maximum()- - inSliders.at(throttleChannel)->minimum())*0.02); - } - - // Flight mode at 50% of range: - if (fmChannel > -1) { - inSliders.at(fmChannel)->setValue( - inSliders.at(fmChannel)->minimum()+ - (inSliders.at(fmChannel)->maximum()- - inSliders.at(fmChannel)->minimum())*0.5); - } - - m_config->saveRCInputToRAM->setEnabled(true); - m_config->saveRCInputToSD->setEnabled(true); - } - firstUpdate = true; - } - - //Update the Flight mode channel slider - ManualControlSettings * manualSettings = ManualControlSettings::GetInstance(getObjectManager()); - ManualControlSettings::DataFields manualSettingsData = manualSettings->getData(); - uint chIndex = manualSettingsData.FlightMode; - if (chIndex < manualSettings->FLIGHTMODE_NONE) { - float valueScaled; - - int chMin = manualSettingsData.ChannelMin[chIndex]; - int chMax = manualSettingsData.ChannelMax[chIndex]; - int chNeutral = manualSettingsData.ChannelNeutral[chIndex]; - - int value = controlCommand->getField("Channel")->getValue(chIndex).toInt(); - if ((chMax > chMin && value >= chNeutral) || (chMin > chMax && value <= chNeutral)) - { - if (chMax != chNeutral) - valueScaled = (float)(value - chNeutral) / (float)(chMax - chNeutral); - else - valueScaled = 0; - } - else - { - if (chMin != chNeutral) - valueScaled = (float)(value - chNeutral) / (float)(chNeutral - chMin); - else - valueScaled = 0; - } - - if(valueScaled < -(1.0 / 3.0)) - m_config->fmsSlider->setValue(-100); - else if (valueScaled > (1.0/3.0)) - m_config->fmsSlider->setValue(100); - else - m_config->fmsSlider->setValue(0); - - } -} - -void ConfigInputWidget::updateChannelInSlider(QSlider *slider, QLabel *min, QLabel *max, int value, bool reversed) -{ - if (!slider || !min || !max) - return; - - if (firstUpdate) { - // Reset all the min/max values of the progress bar since we are starting the calibration. - slider->setMaximum(value); - slider->setMinimum(value); - slider->setValue(value); - max->setText(QString::number(value)); - min->setText(QString::number(value)); - return; - } - - if (value > 0) { - // avoids glitches... - if (value > slider->maximum()) { - slider->setMaximum(value); - if (reversed) - min->setText(QString::number(value)); - else - max->setText(QString::number(value)); - } - if (value < slider->minimum()) { - slider->setMinimum(value); - if (reversed) - max->setText(QString::number(value)); - else - min->setText(QString::number(value)); - } - slider->setValue(value); - } + QWidget::resizeEvent(event); + m_config->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio ); } void ConfigInputWidget::openHelp() @@ -653,77 +272,945 @@ void ConfigInputWidget::openHelp() QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/Input+Configuration", QUrl::StrictMode) ); } -void ConfigInputWidget::receiverHelp() +void ConfigInputWidget::goToWizard() { - QString unassigned; - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager *objManager = pm->getObject(); - UAVDataObject* controlCommand = dynamic_cast(objManager->getObject(QString("ManualControlSettings"))); - - UAVObjectField *field; - - field= controlCommand->getField("Roll"); - if(field->getValue().toString()=="None") - unassigned.append("Roll"); - - field =controlCommand->getField("Pitch"); - if(field->getValue().toString()=="None") - { - if(unassigned.length()>0) - unassigned.append(", "); - unassigned.append("Pitch"); - } - - field =controlCommand->getField("Yaw"); - if(field->getValue().toString()=="None") - { - if(unassigned.length()>0) - unassigned.append(", "); - unassigned.append("Yaw"); - } - - field =controlCommand->getField("Throttle"); - if(field->getValue().toString()=="None") - { - if(unassigned.length()>0) - unassigned.append(", "); - unassigned.append("Throttle"); - } - - field =controlCommand->getField("FlightMode"); - if(field->getValue().toString()=="None") - { - if(unassigned.length()>0) - unassigned.append(", "); - unassigned.append("FlightMode"); - } - if(unassigned.length()>0) - m_config->lblMissingInputs->setText(QString("Channels left to assign: ")+unassigned); - else - m_config->lblMissingInputs->setText(""); + QMessageBox msgBox; + msgBox.setText(tr("Arming Settings are now set to Always Disarmed for your safety.")); + msgBox.setDetailedText(tr("You will have to reconfigure arming settings yourself afterwards.")); + msgBox.setStandardButtons(QMessageBox::Ok); + msgBox.setDefaultButton(QMessageBox::Ok); + msgBox.exec(); + wizardSetUpStep(wizardWelcome); + m_config->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio ); } -void ConfigInputWidget::updateTips(int value) + +void ConfigInputWidget::wzCancel() { - if(value==Qt::Checked) + dimOtherControls(false); + manualCommandObj->setMetadata(manualCommandObj->getDefaultMetadata()); + m_config->stackedWidget->setCurrentIndex(0); + + if(wizardStep != wizardNone) + wizardTearDownStep(wizardStep); + wizardStep=wizardNone; + m_config->stackedWidget->setCurrentIndex(0); + + // Load settings back from beginning of wizard + manualSettingsObj->setData(previousManualSettingsData); +} + +void ConfigInputWidget::wzNext() +{ + // In identify sticks mode the next button can indicate + // channel advance + if(wizardStep != wizardNone && + wizardStep != wizardIdentifySticks) + wizardTearDownStep(wizardStep); + + // State transitions for next button + switch(wizardStep) { + case wizardWelcome: + wizardSetUpStep(wizardChooseMode); + break; + case wizardChooseMode: + wizardSetUpStep(wizardChooseType); + break; + case wizardChooseType: + wizardSetUpStep(wizardIdentifySticks); + break; + case wizardIdentifySticks: + nextChannel(); + if(currentChannelNum==-1) { // Gone through all channels + wizardTearDownStep(wizardIdentifySticks); + wizardSetUpStep(wizardIdentifyCenter); + } + break; + case wizardIdentifyCenter: + wizardSetUpStep(wizardIdentifyLimits); + break; + case wizardIdentifyLimits: + wizardSetUpStep(wizardIdentifyInverted); + break; + case wizardIdentifyInverted: + wizardSetUpStep(wizardFinish); + break; + case wizardFinish: + wizardStep=wizardNone; + m_config->stackedWidget->setCurrentIndex(0); + break; + default: + Q_ASSERT(0); + } +} + +void ConfigInputWidget::wzBack() +{ + if(wizardStep != wizardNone && + wizardStep != wizardIdentifySticks) + wizardTearDownStep(wizardStep); + + // State transitions for next button + switch(wizardStep) { + case wizardChooseMode: + wizardSetUpStep(wizardWelcome); + break; + case wizardChooseType: + wizardSetUpStep(wizardChooseMode); + break; + case wizardIdentifySticks: + prevChannel(); + if(currentChannelNum == -1) { + wizardTearDownStep(wizardIdentifySticks); + wizardSetUpStep(wizardChooseType); + } + break; + case wizardIdentifyCenter: + wizardSetUpStep(wizardIdentifySticks); + break; + case wizardIdentifyLimits: + wizardSetUpStep(wizardIdentifyCenter); + break; + case wizardIdentifyInverted: + wizardSetUpStep(wizardIdentifyLimits); + break; + case wizardFinish: + wizardSetUpStep(wizardIdentifyInverted); + break; + default: + Q_ASSERT(0); + } +} + +void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step) +{ + switch(step) { + case wizardWelcome: + m_config->graphicsView->setVisible(false); + setTxMovement(nothing); + manualSettingsData=manualSettingsObj->getData(); + manualSettingsData.Arming=ManualControlSettings::ARMING_ALWAYSDISARMED; + previousManualSettingsData = manualSettingsData; + manualSettingsObj->setData(manualSettingsData); + m_config->wzText->setText(tr("Welcome to the inputs configuration wizard.\n" + "Please follow the instructions on the screen and only move your controls when asked to.\n" + "Make sure you already configured your hardware settings on the proper tab and restarted your board.\n" + "At any time you can press 'back' to return to the previous screeen or 'Cancel' to cancel the wizard.\n")); + m_config->stackedWidget->setCurrentIndex(1); + m_config->wzBack->setEnabled(false); + break; + case wizardChooseMode: { - m_config->ch0Cur->setToolTip("Current channel value"); - m_config->ch1Cur->setToolTip("Current channel value"); - m_config->ch2Cur->setToolTip("Current channel value"); - m_config->ch3Cur->setToolTip("Current channel value"); - m_config->ch4Cur->setToolTip("Current channel value"); - m_config->ch5Cur->setToolTip("Current channel value"); - m_config->ch6Cur->setToolTip("Current channel value"); - m_config->ch7Cur->setToolTip("Current channel value"); + m_config->graphicsView->setVisible(true); + setTxMovement(nothing); + m_config->wzText->setText(tr("Please choose your transmiter type.\n" + "Mode 1 means your throttle stick is on the right\n" + "Mode 2 means your throttle stick is on the left\n")); + m_config->wzBack->setEnabled(true); + QRadioButton * mode1=new QRadioButton(tr("Mode 1"),this); + QRadioButton * mode2=new QRadioButton(tr("Mode 2"),this); + mode2->setChecked(true); + extraWidgets.clear(); + extraWidgets.append(mode1); + extraWidgets.append(mode2); + m_config->checkBoxesLayout->layout()->addWidget(mode1); + m_config->checkBoxesLayout->layout()->addWidget(mode2); + } + break; + case wizardChooseType: + { + m_config->wzText->setText(tr("Please choose your transmiter mode.\n" + "Acro means normal transmitter\n" + "Heli means there is a collective pitch and throttle input\n" + "If you are using a heli transmitter please engage throttle hold now please.\n")); + m_config->wzBack->setEnabled(true); + QRadioButton * typeAcro=new QRadioButton(tr("Acro"),this); + QRadioButton * typeHeli=new QRadioButton(tr("Heli"),this); + typeAcro->setChecked(true); + typeHeli->setChecked(false); + extraWidgets.clear(); + extraWidgets.append(typeAcro); + extraWidgets.append(typeHeli); + m_config->checkBoxesLayout->layout()->addWidget(typeAcro); + m_config->checkBoxesLayout->layout()->addWidget(typeHeli); + wizardStep=wizardChooseType; + } + break; + case wizardIdentifySticks: + usedChannels.clear(); + currentChannelNum=-1; + nextChannel(); + manualSettingsData=manualSettingsObj->getData(); + connect(receiverActivityObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyControls())); + m_config->wzNext->setEnabled(false); + break; + case wizardIdentifyCenter: + setTxMovement(centerAll); + m_config->wzText->setText(QString(tr("Please center all control controls and press next when ready (if your FlightMode switch has only two positions, leave it on either position)"))); + break; + case wizardIdentifyLimits: + { + setTxMovement(nothing); + m_config->wzText->setText(QString(tr("Please move all controls to their maximum extents on both directions and press next when ready"))); + fastMdata(); + manualSettingsData=manualSettingsObj->getData(); + for(uint i=0;igetField("ChannelMax")->getElementNames().length(); index++) + { + QString name = manualSettingsObj->getField("ChannelMax")->getElementNames().at(index); + if(!name.contains("Access") && !name.contains("Flight")) + { + QCheckBox * cb=new QCheckBox(name,this); + // Make sure checked status matches current one + cb->setChecked(manualSettingsData.ChannelMax[index] < manualSettingsData.ChannelMin[index]); + + extraWidgets.append(cb); + m_config->checkBoxesLayout->layout()->addWidget(cb); + + connect(cb,SIGNAL(toggled(bool)),this,SLOT(invertControls())); + } + } + connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); + m_config->wzText->setText(QString(tr("Please check the picture below and check all the sticks which show an inverted movement and press next when ready"))); + fastMdata(); + break; + case wizardFinish: + dimOtherControls(true); + connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); + m_config->wzText->setText(QString(tr("You have completed this wizard, please check below if the picture below mimics your sticks movement.\n" + "This new settings aren't saved to the board yet, after pressing next you will go to the initial screen where you can do that."))); + fastMdata(); + + manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_THROTTLE]= + manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_THROTTLE]+ + ((manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_THROTTLE]- + manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_THROTTLE])*0.02); + if((abs(manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_FLIGHTMODE]-manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_FLIGHTMODE])<100) || + (abs(manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_FLIGHTMODE]-manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_FLIGHTMODE])<100)) + { + manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_FLIGHTMODE]=manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_FLIGHTMODE]+ + (manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_FLIGHTMODE]-manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_FLIGHTMODE])/2; + } + manualSettingsObj->setData(manualSettingsData); + break; + default: + Q_ASSERT(0); + } + wizardStep = step; +} + +void ConfigInputWidget::wizardTearDownStep(enum wizardSteps step) +{ + QRadioButton * mode, * type; + Q_ASSERT(step == wizardStep); + switch(step) { + case wizardWelcome: + break; + case wizardChooseMode: + mode=qobject_cast(extraWidgets.at(0)); + if(mode->isChecked()) + transmitterMode=mode1; + else + transmitterMode=mode2; + delete extraWidgets.at(0); + delete extraWidgets.at(1); + extraWidgets.clear(); + break; + case wizardChooseType: + type=qobject_cast(extraWidgets.at(0)); + if(type->isChecked()) + transmitterType=acro; + else + transmitterType=heli; + delete extraWidgets.at(0); + delete extraWidgets.at(1); + extraWidgets.clear(); + break; + case wizardIdentifySticks: + disconnect(receiverActivityObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyControls())); + m_config->wzNext->setEnabled(true); + setTxMovement(nothing); + break; + case wizardIdentifyCenter: + manualCommandData=manualCommandObj->getData(); + manualSettingsData=manualSettingsObj->getData(); + for(unsigned int i=0;isetData(manualSettingsData); + setTxMovement(nothing); + break; + case wizardIdentifyLimits: + disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyLimits())); + disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); + manualSettingsObj->setData(manualSettingsData); + restoreMdata(); + setTxMovement(nothing); + break; + case wizardIdentifyInverted: + dimOtherControls(false); + foreach(QWidget * wd,extraWidgets) + { + QCheckBox * cb=qobject_cast(wd); + if(cb) + { + disconnect(cb,SIGNAL(toggled(bool)),this,SLOT(invertControls())); + delete cb; + } + } + extraWidgets.clear(); + disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); + restoreMdata(); + break; + case wizardFinish: + dimOtherControls(false); + setTxMovement(nothing); + disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); + restoreMdata(); + break; + default: + Q_ASSERT(0); + } +} + +/** + * Set manual control command to fast updates + */ +void ConfigInputWidget::fastMdata() +{ + manualControlMdata = manualCommandObj->getMetadata(); + UAVObject::Metadata mdata = manualControlMdata; + mdata.flightTelemetryUpdateMode = UAVObject::UPDATEMODE_PERIODIC; + mdata.flightTelemetryUpdatePeriod = 150; + manualCommandObj->setMetadata(mdata); +} + +/** + * Restore previous update settings for manual control data + */ +void ConfigInputWidget::restoreMdata() +{ + manualCommandObj->setMetadata(manualControlMdata); +} + +/** + * Set the display to indicate which channel the person should move + */ +void ConfigInputWidget::setChannel(int newChan) +{ + if(newChan == ManualControlSettings::CHANNELGROUPS_COLLECTIVE) + m_config->wzText->setText(QString(tr("Please enable throttle hold mode and move the collective pitch stick"))); + else if (newChan == ManualControlSettings::CHANNELGROUPS_FLIGHTMODE) + m_config->wzText->setText(QString(tr("Please flick the flight mode switch. For switches you may have to repeat this rapidly."))); + else + m_config->wzText->setText(QString(tr("Please move each control once at a time according to the instructions and picture below.\n\n" + "Move the %1 stick")).arg(manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan))); + + if(manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan).contains("Accessory")) { + m_config->wzNext->setEnabled(true); + m_config->wzText->setText(m_config->wzText->text() + tr(" or click next to skip this channel.")); + } else + m_config->wzNext->setEnabled(false); + + setMoveFromCommand(newChan); + + currentChannelNum = newChan; + channelDetected = false; +} + +/** + * Unfortunately order of channel should be different in different conditions. Selects + * next channel based on heli or acro mode + */ +void ConfigInputWidget::nextChannel() +{ + QList order = (transmitterType == heli) ? heliChannelOrder : acroChannelOrder; + + if(currentChannelNum == -1) { + setChannel(order[0]); + return; + } + for (int i = 0; i < order.length() - 1; i++) { + if(order[i] == currentChannelNum) { + setChannel(order[i+1]); + return; + } + } + currentChannelNum = -1; // hit end of list +} + +/** + * Unfortunately order of channel should be different in different conditions. Selects + * previous channel based on heli or acro mode + */ +void ConfigInputWidget::prevChannel() +{ + QList order = transmitterType == heli ? heliChannelOrder : acroChannelOrder; + + // No previous from unset channel or next state + if(currentChannelNum == -1) + return; + + for (int i = 1; i < order.length(); i++) { + if(order[i] == currentChannelNum) { + setChannel(order[i-1]); + usedChannels.removeLast(); + return; + } + } + currentChannelNum = -1; // hit end of list +} + +void ConfigInputWidget::identifyControls() +{ + static int debounce=0; + + receiverActivityData=receiverActivityObj->getData(); + if(receiverActivityData.ActiveChannel==255) + return; + if(channelDetected) + return; + else + { + receiverActivityData=receiverActivityObj->getData(); + currentChannel.group=receiverActivityData.ActiveGroup; + currentChannel.number=receiverActivityData.ActiveChannel; + if(currentChannel==lastChannel) + ++debounce; + lastChannel.group= currentChannel.group; + lastChannel.number=currentChannel.number; + if(!usedChannels.contains(lastChannel) && debounce>1) + { + channelDetected = true; + debounce=0; + usedChannels.append(lastChannel); + manualSettingsData=manualSettingsObj->getData(); + manualSettingsData.ChannelGroups[currentChannelNum]=currentChannel.group; + manualSettingsData.ChannelNumber[currentChannelNum]=currentChannel.number; + manualSettingsObj->setData(manualSettingsData); + } + else + return; + } + + m_config->wzText->clear(); + setTxMovement(nothing); + + QTimer::singleShot(500, this, SLOT(wzNext())); +} + +void ConfigInputWidget::identifyLimits() +{ + manualCommandData=manualCommandObj->getData(); + for(uint i=0;imanualCommandData.Channel[i]) + manualSettingsData.ChannelMin[i]=manualCommandData.Channel[i]; + if(manualSettingsData.ChannelMax[i]manualCommandData.Channel[i]) + manualSettingsData.ChannelMax[i]=manualCommandData.Channel[i]; + if(manualSettingsData.ChannelMin[i]setData(manualSettingsData); +} +void ConfigInputWidget::setMoveFromCommand(int command) +{ + //CHANNELNUMBER_ROLL=0, CHANNELNUMBER_PITCH=1, CHANNELNUMBER_YAW=2, CHANNELNUMBER_THROTTLE=3, CHANNELNUMBER_FLIGHTMODE=4, CHANNELNUMBER_ACCESSORY0=5, CHANNELNUMBER_ACCESSORY1=6, CHANNELNUMBER_ACCESSORY2=7 } ChannelNumberElem; + if(command==ManualControlSettings::CHANNELNUMBER_ROLL) + { + setTxMovement(moveRightHorizontalStick); + } + else if(command==ManualControlSettings::CHANNELNUMBER_PITCH) + { + if(transmitterMode==mode2) + setTxMovement(moveRightVerticalStick); + else + setTxMovement(moveLeftVerticalStick); + } + else if(command==ManualControlSettings::CHANNELNUMBER_YAW) + { + setTxMovement(moveLeftHorizontalStick); + } + else if(command==ManualControlSettings::CHANNELNUMBER_THROTTLE) + { + if(transmitterMode==mode2) + setTxMovement(moveLeftVerticalStick); + else + setTxMovement(moveRightVerticalStick); + } + else if(command==ManualControlSettings::CHANNELNUMBER_COLLECTIVE) + { + if(transmitterMode==mode2) + setTxMovement(moveLeftVerticalStick); + else + setTxMovement(moveRightVerticalStick); + } + else if(command==ManualControlSettings::CHANNELNUMBER_FLIGHTMODE) + { + setTxMovement(moveFlightMode); + } + else if(command==ManualControlSettings::CHANNELNUMBER_ACCESSORY0) + { + setTxMovement(moveAccess0); + } + else if(command==ManualControlSettings::CHANNELNUMBER_ACCESSORY1) + { + setTxMovement(moveAccess1); + } + else if(command==ManualControlSettings::CHANNELNUMBER_ACCESSORY2) + { + setTxMovement(moveAccess2); + } + +} + +void ConfigInputWidget::setTxMovement(txMovements movement) +{ + resetTxControls(); + switch(movement) + { + case moveLeftVerticalStick: + movePos=0; + growing=true; + currentMovement=moveLeftVerticalStick; + animate->start(100); + break; + case moveRightVerticalStick: + movePos=0; + growing=true; + currentMovement=moveRightVerticalStick; + animate->start(100); + break; + case moveLeftHorizontalStick: + movePos=0; + growing=true; + currentMovement=moveLeftHorizontalStick; + animate->start(100); + break; + case moveRightHorizontalStick: + movePos=0; + growing=true; + currentMovement=moveRightHorizontalStick; + animate->start(100); + break; + case moveAccess0: + movePos=0; + growing=true; + currentMovement=moveAccess0; + animate->start(100); + break; + case moveAccess1: + movePos=0; + growing=true; + currentMovement=moveAccess1; + animate->start(100); + break; + case moveAccess2: + movePos=0; + growing=true; + currentMovement=moveAccess2; + animate->start(100); + break; + case moveFlightMode: + movePos=0; + growing=true; + currentMovement=moveFlightMode; + animate->start(1000); + break; + case centerAll: + movePos=0; + currentMovement=centerAll; + animate->start(1000); + break; + case moveAll: + movePos=0; + growing=true; + currentMovement=moveAll; + animate->start(50); + break; + case nothing: + movePos=0; + animate->stop(); + break; + default: + break; + } +} + +void ConfigInputWidget::moveTxControls() +{ + QTransform trans; + QGraphicsItem * item; + txMovementType move; + int limitMax; + int limitMin; + static bool auxFlag=false; + switch(currentMovement) + { + case moveLeftVerticalStick: + item=m_txLeftStick; + trans=m_txLeftStickOrig; + limitMax=STICK_MAX_MOVE; + limitMin=STICK_MIN_MOVE; + move=vertical; + break; + case moveRightVerticalStick: + item=m_txRightStick; + trans=m_txRightStickOrig; + limitMax=STICK_MAX_MOVE; + limitMin=STICK_MIN_MOVE; + move=vertical; + break; + case moveLeftHorizontalStick: + item=m_txLeftStick; + trans=m_txLeftStickOrig; + limitMax=STICK_MAX_MOVE; + limitMin=STICK_MIN_MOVE; + move=horizontal; + break; + case moveRightHorizontalStick: + item=m_txRightStick; + trans=m_txRightStickOrig; + limitMax=STICK_MAX_MOVE; + limitMin=STICK_MIN_MOVE; + move=horizontal; + break; + case moveAccess0: + item=m_txAccess0; + trans=m_txAccess0Orig; + limitMax=ACCESS_MAX_MOVE; + limitMin=ACCESS_MIN_MOVE; + move=horizontal; + break; + case moveAccess1: + item=m_txAccess1; + trans=m_txAccess1Orig; + limitMax=ACCESS_MAX_MOVE; + limitMin=ACCESS_MIN_MOVE; + move=horizontal; + break; + case moveAccess2: + item=m_txAccess2; + trans=m_txAccess2Orig; + limitMax=ACCESS_MAX_MOVE; + limitMin=ACCESS_MIN_MOVE; + move=horizontal; + break; + case moveFlightMode: + item=m_txFlightMode; + move=jump; + break; + case centerAll: + item=m_txArrows; + move=jump; + break; + case moveAll: + limitMax=STICK_MAX_MOVE; + limitMin=STICK_MIN_MOVE; + move=mix; + break; + default: + break; + } + if(move==vertical) + item->setTransform(trans.translate(0,movePos*10),false); + else if(move==horizontal) + item->setTransform(trans.translate(movePos*10,0),false); + else if(move==jump) + { + if(item==m_txArrows) + { + m_txArrows->setVisible(!m_txArrows->isVisible()); + } + else if(item==m_txFlightMode) + { + QGraphicsSvgItem * svg; + svg=(QGraphicsSvgItem *)item; + if (svg) + { + if(svg->elementId()=="flightModeCenter") + { + if(growing) + { + svg->setElementId("flightModeRight"); + m_txFlightMode->setTransform(m_txFlightModeROrig,false); + } + else + { + svg->setElementId("flightModeLeft"); + m_txFlightMode->setTransform(m_txFlightModeLOrig,false); + } + } + else if(svg->elementId()=="flightModeRight") + { + growing=false; + svg->setElementId("flightModeCenter"); + m_txFlightMode->setTransform(m_txFlightModeCOrig,false); + } + else if(svg->elementId()=="flightModeLeft") + { + growing=true; + svg->setElementId("flightModeCenter"); + m_txFlightMode->setTransform(m_txFlightModeCOrig,false); + } + } + } + } + else if(move==mix) + { + trans=m_txAccess0Orig; + m_txAccess0->setTransform(trans.translate(movePos*10*ACCESS_MAX_MOVE/STICK_MAX_MOVE,0),false); + trans=m_txAccess1Orig; + m_txAccess1->setTransform(trans.translate(movePos*10*ACCESS_MAX_MOVE/STICK_MAX_MOVE,0),false); + trans=m_txAccess2Orig; + m_txAccess2->setTransform(trans.translate(movePos*10*ACCESS_MAX_MOVE/STICK_MAX_MOVE,0),false); + + if(auxFlag) + { + trans=m_txLeftStickOrig; + m_txLeftStick->setTransform(trans.translate(0,movePos*10),false); + trans=m_txRightStickOrig; + m_txRightStick->setTransform(trans.translate(0,movePos*10),false); + } + else + { + trans=m_txLeftStickOrig; + m_txLeftStick->setTransform(trans.translate(movePos*10,0),false); + trans=m_txRightStickOrig; + m_txRightStick->setTransform(trans.translate(movePos*10,0),false); + } + + if(movePos==0) + { + m_txFlightMode->setElementId("flightModeCenter"); + m_txFlightMode->setTransform(m_txFlightModeCOrig,false); + } + else if(movePos==ACCESS_MAX_MOVE/2) + { + m_txFlightMode->setElementId("flightModeRight"); + m_txFlightMode->setTransform(m_txFlightModeROrig,false); + } + else if(movePos==ACCESS_MIN_MOVE/2) + { + m_txFlightMode->setElementId("flightModeLeft"); + m_txFlightMode->setTransform(m_txFlightModeLOrig,false); + } + } + if(move==horizontal || move==vertical ||move==mix) + { + if(movePos==0 && growing) + auxFlag=!auxFlag; + if(growing) + ++movePos; + else + --movePos; + if(movePos>limitMax) + { + movePos=movePos-2; + growing=false; + } + if(movePosgetData(); + if(transmitterMode==mode2) + { + trans=m_txLeftStickOrig; + m_txLeftStick->setTransform(trans.translate(manualCommandData.Yaw*STICK_MAX_MOVE*10,-manualCommandData.Throttle*STICK_MAX_MOVE*10),false); + trans=m_txRightStickOrig; + m_txRightStick->setTransform(trans.translate(manualCommandData.Roll*STICK_MAX_MOVE*10,manualCommandData.Pitch*STICK_MAX_MOVE*10),false); } else { - m_config->ch0Cur->setToolTip("Channel neutral point"); - m_config->ch1Cur->setToolTip("Channel neutral point"); - m_config->ch2Cur->setToolTip("Channel neutral point"); - m_config->ch3Cur->setToolTip("Channel neutral point"); - m_config->ch4Cur->setToolTip("Channel neutral point"); - m_config->ch5Cur->setToolTip("Channel neutral point"); - m_config->ch6Cur->setToolTip("Channel neutral point"); - m_config->ch7Cur->setToolTip("Channel neutral point"); + trans=m_txRightStickOrig; + m_txRightStick->setTransform(trans.translate(manualCommandData.Roll*STICK_MAX_MOVE*10,-manualCommandData.Throttle*STICK_MAX_MOVE*10),false); + trans=m_txLeftStickOrig; + m_txLeftStick->setTransform(trans.translate(manualCommandData.Yaw*STICK_MAX_MOVE*10,manualCommandData.Pitch*STICK_MAX_MOVE*10),false); + } +} + +void ConfigInputWidget::dimOtherControls(bool value) +{ + qreal opac; + if(value) + opac=0.1; + else + opac=1; + m_txAccess0->setOpacity(opac); + m_txAccess1->setOpacity(opac); + m_txAccess2->setOpacity(opac); + m_txFlightMode->setOpacity(opac); +} + +void ConfigInputWidget::enableControls(bool enable) +{ + m_config->configurationWizard->setEnabled(enable); + m_config->runCalibration->setEnabled(enable); + + ConfigTaskWidget::enableControls(enable); + +} + +void ConfigInputWidget::invertControls() +{ + manualSettingsData=manualSettingsObj->getData(); + foreach(QWidget * wd,extraWidgets) + { + QCheckBox * cb=qobject_cast(wd); + if(cb) + { + int index=manualSettingsObj->getFields().at(0)->getElementNames().indexOf(cb->text()); + if((cb->isChecked() && (manualSettingsData.ChannelMax[index]>manualSettingsData.ChannelMin[index])) || + (!cb->isChecked() && (manualSettingsData.ChannelMax[index]setData(manualSettingsData); +} +void ConfigInputWidget::moveFMSlider() +{ + ManualControlSettings::DataFields manualSettingsDataPriv = manualSettingsObj->getData(); + ManualControlCommand::DataFields manualCommandDataPriv=manualCommandObj->getData(); + + float valueScaled; + int chMin = manualSettingsDataPriv.ChannelMin[ManualControlSettings::CHANNELMIN_FLIGHTMODE]; + int chMax = manualSettingsDataPriv.ChannelMax[ManualControlSettings::CHANNELMAX_FLIGHTMODE]; + int chNeutral = manualSettingsDataPriv.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_FLIGHTMODE]; + + int value = manualCommandDataPriv.Channel[ManualControlSettings::CHANNELMIN_FLIGHTMODE]; + if ((chMax > chMin && value >= chNeutral) || (chMin > chMax && value <= chNeutral)) + { + if (chMax != chNeutral) + valueScaled = (float)(value - chNeutral) / (float)(chMax - chNeutral); + else + valueScaled = 0; + } + else + { + if (chMin != chNeutral) + valueScaled = (float)(value - chNeutral) / (float)(chNeutral - chMin); + else + valueScaled = 0; + } + + if(valueScaled < -(1.0 / 3.0)) + m_config->fmsSlider->setValue(-100); + else if (valueScaled > (1.0/3.0)) + m_config->fmsSlider->setValue(100); + else + m_config->fmsSlider->setValue(0); +} + +void ConfigInputWidget::updateCalibration() +{ + manualCommandData=manualCommandObj->getData(); + for(uint i=0;imanualCommandData.Channel[i]) || + (reverse[i] && manualSettingsData.ChannelMin[i]manualCommandData.Channel[i])) + manualSettingsData.ChannelMax[i]=manualCommandData.Channel[i]; + manualSettingsData.ChannelNeutral[i] = manualCommandData.Channel[i]; + } + + manualSettingsObj->setData(manualSettingsData); + manualSettingsObj->updated(); +} + +void ConfigInputWidget::simpleCalibration(bool enable) +{ + if (enable) { + m_config->configurationWizard->setEnabled(false); + + QMessageBox msgBox; + msgBox.setText(tr("Arming Settings are now set to Always Disarmed for your safety.")); + msgBox.setDetailedText(tr("You will have to reconfigure arming settings yourself afterwards.")); + msgBox.setStandardButtons(QMessageBox::Ok); + msgBox.setDefaultButton(QMessageBox::Ok); + msgBox.exec(); + + manualCommandData = manualCommandObj->getData(); + + manualSettingsData=manualSettingsObj->getData(); + manualSettingsData.Arming=ManualControlSettings::ARMING_ALWAYSDISARMED; + manualSettingsObj->setData(manualSettingsData); + + for (unsigned int i = 0; i < ManualControlCommand::CHANNEL_NUMELEM; i++) { + reverse[i] = manualSettingsData.ChannelMax[i] < manualSettingsData.ChannelMin[i]; + manualSettingsData.ChannelMin[i] = manualCommandData.Channel[i]; + manualSettingsData.ChannelNeutral[i] = manualCommandData.Channel[i]; + manualSettingsData.ChannelMax[i] = manualCommandData.Channel[i]; + } + + fastMdata(); + + connect(manualCommandObj, SIGNAL(objectUnpacked(UAVObject*)), this, SLOT(updateCalibration())); + } else { + m_config->configurationWizard->setEnabled(true); + + manualCommandData = manualCommandObj->getData(); + manualSettingsData = manualSettingsObj->getData(); + + restoreMdata(); + + for (int i = 0; i < ManualControlCommand::CHANNEL_NUMELEM; i++) + manualSettingsData.ChannelNeutral[i] = manualCommandData.Channel[i]; + + // Force flight mode neutral to middle + manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNUMBER_FLIGHTMODE] = + (manualSettingsData.ChannelMax[ManualControlSettings::CHANNELNUMBER_FLIGHTMODE] + + manualSettingsData.ChannelMin[ManualControlSettings::CHANNELNUMBER_FLIGHTMODE]) / 2; + + // Force throttle to be near min + manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_THROTTLE]= + manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_THROTTLE]+ + ((manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_THROTTLE]- + manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_THROTTLE])*0.02); + + manualSettingsObj->setData(manualSettingsData); + + disconnect(manualCommandObj, SIGNAL(objectUnpacked(UAVObject*)), this, SLOT(updateCalibration())); } } diff --git a/ground/openpilotgcs/src/plugins/config/configinputwidget.h b/ground/openpilotgcs/src/plugins/config/configinputwidget.h index 75f47cc8d..0110bccb0 100644 --- a/ground/openpilotgcs/src/plugins/config/configinputwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configinputwidget.h @@ -34,52 +34,126 @@ #include "uavobject.h" #include #include +#include "inputchannelform.h" +#include "ui_inputchannelform.h" +#include +#include "manualcontrolcommand.h" +#include "manualcontrolsettings.h" +#include "receiveractivity.h" +#include +#include +#include class Ui_InputWidget; class ConfigInputWidget: public ConfigTaskWidget { Q_OBJECT - public: ConfigInputWidget(QWidget *parent = 0); ~ConfigInputWidget(); - + enum wizardSteps{wizardWelcome,wizardChooseMode,wizardChooseType,wizardIdentifySticks,wizardIdentifyCenter,wizardIdentifyLimits,wizardIdentifyInverted,wizardFinish,wizardNone}; + enum txMode{mode1,mode2}; + enum txMovements{moveLeftVerticalStick,moveRightVerticalStick,moveLeftHorizontalStick,moveRightHorizontalStick,moveAccess0,moveAccess1,moveAccess2,moveFlightMode,centerAll,moveAll,nothing}; + enum txMovementType{vertical,horizontal,jump,mix}; + enum txType {acro, heli}; public slots: private: + bool growing; + bool reverse[ManualControlSettings::CHANNELNEUTRAL_NUMELEM]; + txMovements currentMovement; + int movePos; + void setTxMovement(txMovements movement); Ui_InputWidget *m_config; + wizardSteps wizardStep; + QList extraWidgets; + txMode transmitterMode; + txType transmitterType; + struct channelsStruct + { + bool operator ==(const channelsStruct& rhs) const + { + return((group==rhs.group) &&(number==rhs.number)); + } + int group; + int number; + }lastChannel; + channelsStruct currentChannel; + QList usedChannels; + bool channelDetected; + QEventLoop * loop; + bool skipflag; - QList sliders; + int currentChannelNum; + QList heliChannelOrder; + QList acroChannelOrder; - void updateChannelInSlider(QSlider *slider, QLabel *min, QLabel *max, int value, bool reversed); + ManualControlCommand * manualCommandObj; + ManualControlCommand::DataFields manualCommandData; + UAVObject::Metadata manualControlMdata; + ManualControlSettings * manualSettingsObj; + ManualControlSettings::DataFields manualSettingsData; + ManualControlSettings::DataFields previousManualSettingsData; + ReceiverActivity * receiverActivityObj; + ReceiverActivity::DataFields receiverActivityData; - void assignChannel(UAVDataObject *obj, QString str); - void assignOutputChannel(UAVDataObject *obj, QString str); + QSvgRenderer *m_renderer; - int mccDataRate; + // Background: background + QGraphicsSvgItem *m_txMainBody; + QGraphicsSvgItem *m_txLeftStick; + QGraphicsSvgItem *m_txRightStick; + QGraphicsSvgItem *m_txAccess0; + QGraphicsSvgItem *m_txAccess1; + QGraphicsSvgItem *m_txAccess2; + QGraphicsSvgItem *m_txFlightMode; + QGraphicsSvgItem *m_txBackground; + QGraphicsSvgItem *m_txArrows; + QTransform m_txLeftStickOrig; + QTransform m_txRightStickOrig; + QTransform m_txAccess0Orig; + QTransform m_txAccess1Orig; + QTransform m_txAccess2Orig; + QTransform m_txFlightModeCOrig; + QTransform m_txFlightModeLOrig; + QTransform m_txFlightModeROrig; + QTransform m_txMainBodyOrig; + QTransform m_txArrowsOrig; + QTimer * animate; + void resetTxControls(); + void setMoveFromCommand(int command); - UAVObject::Metadata accInitialData; + void fastMdata(); + void restoreMdata(); - QList inSliders; - QList inMaxLabels; - QList inMinLabels; - QList inNeuLabels; - QList inRevCheckboxes; - QList inChannelAssign; + void setChannel(int); + void nextChannel(); + void prevChannel(); - bool firstUpdate; - - virtual void enableControls(bool enable); - void receiverHelp(); + void wizardSetUpStep(enum wizardSteps); + void wizardTearDownStep(enum wizardSteps); private slots: - void updateChannels(UAVObject* obj); - virtual void refreshValues(); - void sendRCInputUpdate(); - void saveRCInputObject(); - void reverseCheckboxClicked(bool state); + void wzNext(); + void wzBack(); + void wzCancel(); + void goToWizard(); + void openHelp(); - void updateTips(int); + void identifyControls(); + void identifyLimits(); + void moveTxControls(); + void moveSticks(); + void dimOtherControls(bool value); + void moveFMSlider(); + void invertControls(); + void simpleCalibration(bool state); + void updateCalibration(); +protected: + void resizeEvent(QResizeEvent *event); + virtual void enableControls(bool enable); + + }; #endif diff --git a/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp b/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp index 1a961805b..0aa4ee809 100644 --- a/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp @@ -1,13 +1,13 @@ /** ****************************************************************************** * - * @file configservowidget.cpp + * @file configoutputwidget.cpp * @author E. Lafargue & The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup ConfigPlugin Config Plugin * @{ - * @brief Servo input/output configuration panel for the config gadget + * @brief Servo output configuration panel for the config gadget *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify @@ -26,6 +26,7 @@ */ #include "configoutputwidget.h" +#include "outputchannelform.h" #include "uavtalk/telemetrymanager.h" @@ -38,99 +39,41 @@ #include #include #include +#include "actuatorcommand.h" +#include "actuatorsettings.h" +#include "systemalarms.h" +#include "uavsettingsimportexport/uavsettingsimportexportfactory.h" -ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(parent) +ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(parent),wasItMe(false) { m_config = new Ui_OutputWidget(); m_config->setupUi(this); - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager *objManager = pm->getObject(); + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + setupButtons(m_config->saveRCOutputToRAM,m_config->saveRCOutputToSD); + addUAVObject("ActuatorSettings"); - // First of all, put all the channel widgets into lists, so that we can - // manipulate those: + UAVSettingsImportExportFactory * importexportplugin = pm->getObject(); + connect(importexportplugin,SIGNAL(importAboutToBegin()),this,SLOT(stopTests())); - // NOTE: for historical reasons, we have objects below called ch0 to ch7, but the convention for OP is Channel 1 to Channel 8. - outLabels << m_config->ch0OutValue - << m_config->ch1OutValue - << m_config->ch2OutValue - << m_config->ch3OutValue - << m_config->ch4OutValue - << m_config->ch5OutValue - << m_config->ch6OutValue - << m_config->ch7OutValue; - - outSliders << m_config->ch0OutSlider - << m_config->ch1OutSlider - << m_config->ch2OutSlider - << m_config->ch3OutSlider - << m_config->ch4OutSlider - << m_config->ch5OutSlider - << m_config->ch6OutSlider - << m_config->ch7OutSlider; - - outMin << m_config->ch0OutMin - << m_config->ch1OutMin - << m_config->ch2OutMin - << m_config->ch3OutMin - << m_config->ch4OutMin - << m_config->ch5OutMin - << m_config->ch6OutMin - << m_config->ch7OutMin; - - outMax << m_config->ch0OutMax - << m_config->ch1OutMax - << m_config->ch2OutMax - << m_config->ch3OutMax - << m_config->ch4OutMax - << m_config->ch5OutMax - << m_config->ch6OutMax - << m_config->ch7OutMax; - - reversals << m_config->ch0Rev - << m_config->ch1Rev - << m_config->ch2Rev - << m_config->ch3Rev - << m_config->ch4Rev - << m_config->ch5Rev - << m_config->ch6Rev - << m_config->ch7Rev; - - links << m_config->ch0Link - << m_config->ch1Link - << m_config->ch2Link - << m_config->ch3Link - << m_config->ch4Link - << m_config->ch5Link - << m_config->ch6Link - << m_config->ch7Link; + setupButtons(m_config->saveRCOutputToRAM,m_config->saveRCOutputToSD); + addUAVObject("ActuatorSettings"); + // NOTE: we have channel indices from 0 to 9, but the convention for OP is Channel 1 to Channel 10. // Register for ActuatorSettings changes: - UAVDataObject * obj = dynamic_cast(objManager->getObject(QString("ActuatorSettings"))); - connect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(refreshValues())); - - for (int i = 0; i < 8; i++) { - connect(outMin[i], SIGNAL(editingFinished()), this, SLOT(setChOutRange())); - connect(outMax[i], SIGNAL(editingFinished()), this, SLOT(setChOutRange())); - connect(reversals[i], SIGNAL(toggled(bool)), this, SLOT(reverseChannel(bool))); - // Now connect the channel out sliders to our signal to send updates in test mode - connect(outSliders[i], SIGNAL(valueChanged(int)), this, SLOT(sendChannelTest(int))); + for (unsigned int i = 0; i < ActuatorCommand::CHANNEL_NUMELEM; i++) + { + OutputChannelForm *form = new OutputChannelForm(i, this, i==0); + connect(m_config->channelOutTest, SIGNAL(toggled(bool)), + form, SLOT(enableChannelTest(bool))); + connect(form, SIGNAL(channelChanged(int,int)), + this, SLOT(sendChannelTest(int,int))); + m_config->channelLayout->addWidget(form); } connect(m_config->channelOutTest, SIGNAL(toggled(bool)), this, SLOT(runChannelTests(bool))); - for (int i = 0; i < links.count(); i++) - links[i]->setChecked(false); - for (int i = 0; i < links.count(); i++) - connect(links[i], SIGNAL(toggled(bool)), this, SLOT(linkToggled(bool))); - - connect(m_config->saveRCOutputToSD, SIGNAL(clicked()), this, SLOT(saveRCOutputObject())); - connect(m_config->saveRCOutputToRAM, SIGNAL(clicked()), this, SLOT(sendRCOutputUpdate())); - - enableControls(false); - refreshValues(); - connect(parent, SIGNAL(autopilotConnected()),this, SLOT(onAutopilotConnect())); - connect(parent, SIGNAL(autopilotDisconnected()), this, SLOT(onAutopilotDisconnect())); + refreshWidgetsValues(); firstUpdate = true; @@ -138,6 +81,24 @@ ConfigOutputWidget::ConfigOutputWidget(QWidget *parent) : ConfigTaskWidget(paren // Connect the help button connect(m_config->outputHelp, SIGNAL(clicked()), this, SLOT(openHelp())); + addWidget(m_config->cb_outputRate4); + addWidget(m_config->cb_outputRate3); + addWidget(m_config->cb_outputRate2); + addWidget(m_config->cb_outputRate1); + addWidget(m_config->spinningArmed); + + UAVObjectManager *objManager = pm->getObject(); + UAVObject* obj = objManager->getObject(QString("ActuatorCommand")); + if(obj->getMetadata().gcsTelemetryUpdateMode == UAVObject::UPDATEMODE_ONCHANGE) + this->setEnabled(false); + connect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(disableIfNotMe(UAVObject*))); +} +void ConfigOutputWidget::enableControls(bool enable) +{ + ConfigTaskWidget::enableControls(enable); + if(!enable) + m_config->channelOutTest->setChecked(false); + m_config->channelOutTest->setEnabled(enable); } ConfigOutputWidget::~ConfigOutputWidget() @@ -148,51 +109,29 @@ ConfigOutputWidget::~ConfigOutputWidget() // ************************************ -void ConfigOutputWidget::enableControls(bool enable) -{ - m_config->saveRCOutputToSD->setEnabled(enable); - //m_config->saveRCOutputToRAM->setEnabled(enable); -} - -// ************************************ - -/** - Toggles the channel linked state for use in testing mode - */ -void ConfigOutputWidget::linkToggled(bool state) -{ - Q_UNUSED(state) - // find the minimum slider value for the linked ones - int min = 10000; - int linked_count = 0; - for (int i = 0; i < outSliders.count(); i++) - { - if (!links[i]->checkState()) continue; - int value = outSliders[i]->value(); - if (min > value) min = value; - linked_count++; - } - - if (linked_count <= 0) - return; // no linked channels - - if (!m_config->channelOutTest->checkState()) - return; // we are not in Test Output mode - - // set the linked channels to the same value - for (int i = 0; i < outSliders.count(); i++) - { - if (!links[i]->checkState()) continue; - outSliders[i]->setValue(min); - } -} - /** Toggles the channel testing mode by making the GCS take over the ActuatorCommand objects */ void ConfigOutputWidget::runChannelTests(bool state) { + qDebug()<<"configoutputwidget runChannelTests"<getData(); + + if(state && systemAlarms.Alarm[SystemAlarms::ALARM_ACTUATOR] != SystemAlarms::ALARM_OK) { + QMessageBox mbox; + mbox.setText(QString(tr("The actuator module is in an error state. This can also occur because there are no inputs. Please fix these before testing outputs."))); + mbox.setStandardButtons(QMessageBox::Ok); + mbox.exec(); + + // Unfortunately must cache this since callback will reoccur + accInitialData = ActuatorCommand::GetInstance(getObjectManager())->getMetadata(); + + m_config->channelOutTest->setChecked(false); + return; + } + // Confirm this is definitely what they want if(state) { QMessageBox mbox; @@ -207,79 +146,54 @@ void ConfigOutputWidget::runChannelTests(bool state) } } - qDebug() << "Running with state " << state; - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager *objManager = pm->getObject(); - - UAVDataObject* obj = dynamic_cast(objManager->getObject(QString("ActuatorCommand"))); + ActuatorCommand * obj = ActuatorCommand::GetInstance(getObjectManager()); UAVObject::Metadata mdata = obj->getMetadata(); if (state) { + wasItMe=true; accInitialData = mdata; mdata.flightAccess = UAVObject::ACCESS_READONLY; mdata.flightTelemetryUpdateMode = UAVObject::UPDATEMODE_ONCHANGE; mdata.gcsTelemetryAcked = false; mdata.gcsTelemetryUpdateMode = UAVObject::UPDATEMODE_ONCHANGE; mdata.gcsTelemetryUpdatePeriod = 100; - - // Prevent stupid users from touching the minimum & maximum ranges while - // moving the sliders. Thanks Ivan for the tip :) - foreach (QSpinBox* box, outMin) { - box->setEnabled(false); - } - foreach (QSpinBox* box, outMax) { - box->setEnabled(false); - } - } else { + wasItMe=false; mdata = accInitialData; // Restore metadata - foreach (QSpinBox* box, outMin) { - box->setEnabled(true); - } - foreach (QSpinBox* box, outMax) { - box->setEnabled(true); - } - } obj->setMetadata(mdata); + obj->updated(); } +OutputChannelForm* ConfigOutputWidget::getOutputChannelForm(const int index) const +{ + QList outputChannelForms = findChildren(); + foreach(OutputChannelForm *outputChannelForm, outputChannelForms) + { + if( outputChannelForm->index() == index) + return outputChannelForm; + } + + // no OutputChannelForm found with given index + return NULL; +} + /** * Set the label for a channel output assignement */ void ConfigOutputWidget::assignOutputChannel(UAVDataObject *obj, QString str) { + //FIXME: use signal/ slot approach UAVObjectField* field = obj->getField(str); QStringList options = field->getOptions(); - switch (options.indexOf(field->getValue().toString())) { - case 0: - m_config->ch0Output->setText(str); - break; - case 1: - m_config->ch1Output->setText(str); - break; - case 2: - m_config->ch2Output->setText(str); - break; - case 3: - m_config->ch3Output->setText(str); - break; - case 4: - m_config->ch4Output->setText(str); - break; - case 5: - m_config->ch5Output->setText(str); - break; - case 6: - m_config->ch6Output->setText(str); - break; - case 7: - m_config->ch7Output->setText(str); - break; - } + int index = options.indexOf(field->getValue().toString()); + + OutputChannelForm *outputChannelForm = getOutputChannelForm(index); + if(outputChannelForm) + outputChannelForm->setAssignment(str); } /** @@ -287,63 +201,36 @@ void ConfigOutputWidget::assignOutputChannel(UAVDataObject *obj, QString str) */ void ConfigOutputWidget::setSpinningArmed(bool val) { - UAVDataObject *obj = dynamic_cast(getObjectManager()->getObject(QString("ActuatorSettings"))); - if (!obj) return; - UAVObjectField *field = obj->getField("MotorsSpinWhileArmed"); - if (!field) return; + ActuatorSettings *actuatorSettings = ActuatorSettings::GetInstance(getObjectManager()); + Q_ASSERT(actuatorSettings); + ActuatorSettings::DataFields actuatorSettingsData = actuatorSettings->getData(); + if(val) - field->setValue("TRUE"); + actuatorSettingsData.MotorsSpinWhileArmed = ActuatorSettings::MOTORSSPINWHILEARMED_TRUE; else - field->setValue("FALSE"); + actuatorSettingsData.MotorsSpinWhileArmed = ActuatorSettings::MOTORSSPINWHILEARMED_FALSE; + + // Apply settings + actuatorSettings->setData(actuatorSettingsData); } /** Sends the channel value to the UAV to move the servo. Returns immediately if we are not in testing mode */ -void ConfigOutputWidget::sendChannelTest(int value) +void ConfigOutputWidget::sendChannelTest(int index, int value) { - int in_value = value; + if (!m_config->channelOutTest->isChecked()) + return; - QSlider *ob = (QSlider *)QObject::sender(); - if (!ob) return; - int index = outSliders.indexOf(ob); - if (index < 0) return; + if(index < 0 || (unsigned)index >= ActuatorCommand::CHANNEL_NUMELEM) + return; - if (reversals[index]->isChecked()) - value = outMin[index]->value() - value + outMax[index]->value(); // the chsnnel is reversed - - // update the label - outLabels[index]->setText(QString::number(value)); - - if (links[index]->checkState()) - { // the channel is linked to other channels - // set the linked channels to the same value - for (int i = 0; i < outSliders.count(); i++) - { - if (i == index) continue; - if (!links[i]->checkState()) continue; - - int val = in_value; - if (val < outSliders[i]->minimum()) val = outSliders[i]->minimum(); - if (val > outSliders[i]->maximum()) val = outSliders[i]->maximum(); - - if (outSliders[i]->value() == val) continue; - - outSliders[i]->setValue(val); - outLabels[i]->setText(QString::number(val)); - } - } - - if (!m_config->channelOutTest->isChecked()) - return; - - UAVDataObject *obj = dynamic_cast(getObjectManager()->getObject(QString("ActuatorCommand"))); - if (!obj) return; - UAVObjectField *channel = obj->getField("Channel"); - if (!channel) return; - channel->setValue(value, index); - obj->updated(); + ActuatorCommand *actuatorCommand = ActuatorCommand::GetInstance(getObjectManager()); + Q_ASSERT(actuatorCommand); + ActuatorCommand::DataFields actuatorCommandFields = actuatorCommand->getData(); + actuatorCommandFields.Channel[index] = value; + actuatorCommand->setData(actuatorCommandFields); } @@ -355,22 +242,24 @@ void ConfigOutputWidget::sendChannelTest(int value) /** Request the current config from the board (RC Output) */ -void ConfigOutputWidget::refreshValues() +void ConfigOutputWidget::refreshWidgetsValues() { - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager *objManager = pm->getObject(); + bool dirty=isDirty(); // Reset all channel assignements: - m_config->ch0Output->setText("-"); - m_config->ch1Output->setText("-"); - m_config->ch2Output->setText("-"); - m_config->ch3Output->setText("-"); - m_config->ch4Output->setText("-"); - m_config->ch5Output->setText("-"); - m_config->ch6Output->setText("-"); - m_config->ch7Output->setText("-"); + QList outputChannelForms = findChildren(); + foreach(OutputChannelForm *outputChannelForm, outputChannelForms) + { + outputChannelForm->setAssignment("-"); + } - // Get the channel assignements: + // FIXME: Use static accessor method for retrieving channel assignments + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + Q_ASSERT(pm); + UAVObjectManager *objManager = pm->getObject(); + Q_ASSERT(objManager); + + // Get the channel assignements: UAVDataObject * obj = dynamic_cast(objManager->getObject(QString("ActuatorSettings"))); Q_ASSERT(obj); QList fieldList = obj->getFields(); @@ -380,197 +269,104 @@ void ConfigOutputWidget::refreshValues() } } + ActuatorSettings *actuatorSettings = ActuatorSettings::GetInstance(getObjectManager()); + Q_ASSERT(actuatorSettings); + ActuatorSettings::DataFields actuatorSettingsData = actuatorSettings->getData(); + // Get the SpinWhileArmed setting - UAVObjectField *field = obj->getField(QString("MotorsSpinWhileArmed")); - m_config->spinningArmed->setChecked(field->getValue().toString().contains("TRUE")); + m_config->spinningArmed->setChecked(actuatorSettingsData.MotorsSpinWhileArmed == ActuatorSettings::MOTORSSPINWHILEARMED_TRUE); // Get Output rates for both banks - field = obj->getField(QString("ChannelUpdateFreq")); + if(m_config->cb_outputRate1->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[0]))==-1) + { + m_config->cb_outputRate1->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[0])); + } + if(m_config->cb_outputRate2->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[1]))==-1) + { + m_config->cb_outputRate2->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[1])); + } + m_config->cb_outputRate1->setCurrentIndex(m_config->cb_outputRate1->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[0]))); + m_config->cb_outputRate2->setCurrentIndex(m_config->cb_outputRate2->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[1]))); + UAVObjectUtilManager* utilMngr = pm->getObject(); - m_config->outputRate1->setValue(field->getValue(0).toInt()); - m_config->outputRate2->setValue(field->getValue(1).toInt()); if (utilMngr) { int board = utilMngr->getBoardModel(); if ((board & 0xff00) == 1024) { // CopterControl family m_config->chBank1->setText("1-3"); m_config->chBank2->setText("4"); - m_config->chBank3->setText("5"); - m_config->chBank4->setText("6"); - m_config->outputRate1->setEnabled(true); - m_config->outputRate2->setEnabled(true); - m_config->outputRate3->setEnabled(true); - m_config->outputRate4->setEnabled(true); - m_config->outputRate3->setValue(field->getValue(2).toInt()); - m_config->outputRate4->setValue(field->getValue(3).toInt()); + m_config->chBank3->setText("5,7-8"); + m_config->chBank4->setText("6,9-10"); + m_config->cb_outputRate1->setEnabled(true); + m_config->cb_outputRate2->setEnabled(true); + m_config->cb_outputRate3->setEnabled(true); + m_config->cb_outputRate4->setEnabled(true); + if(m_config->cb_outputRate3->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[2]))==-1) + { + m_config->cb_outputRate3->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[2])); + } + if(m_config->cb_outputRate4->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[3]))==-1) + { + m_config->cb_outputRate4->addItem(QString::number(actuatorSettingsData.ChannelUpdateFreq[3])); + } + m_config->cb_outputRate3->setCurrentIndex(m_config->cb_outputRate3->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[2]))); + m_config->cb_outputRate4->setCurrentIndex(m_config->cb_outputRate4->findText(QString::number(actuatorSettingsData.ChannelUpdateFreq[3]))); } else if ((board & 0xff00) == 256 ) { // Mainboard family - m_config->outputRate1->setEnabled(true); - m_config->outputRate2->setEnabled(true); - m_config->outputRate3->setEnabled(false); - m_config->outputRate4->setEnabled(false); + m_config->cb_outputRate1->setEnabled(true); + m_config->cb_outputRate2->setEnabled(true); + m_config->cb_outputRate3->setEnabled(false); + m_config->cb_outputRate4->setEnabled(false); m_config->chBank1->setText("1-4"); m_config->chBank2->setText("5-8"); m_config->chBank3->setText("-"); m_config->chBank4->setText("-"); - m_config->outputRate3->setValue(0); - m_config->outputRate4->setValue(0); + m_config->cb_outputRate3->addItem("0"); + m_config->cb_outputRate3->setCurrentIndex(m_config->cb_outputRate3->findText("0")); + m_config->cb_outputRate4->addItem("0"); + m_config->cb_outputRate4->setCurrentIndex(m_config->cb_outputRate4->findText("0")); } } - // Get Channel ranges: - for (int i=0;i<8;i++) { - field = obj->getField(QString("ChannelMin")); - int minValue = field->getValue(i).toInt(); - outMin[i]->setValue(minValue); - field = obj->getField(QString("ChannelMax")); - int maxValue = field->getValue(i).toInt(); - outMax[i]->setValue(maxValue); - if (maxValue>minValue) { - outSliders[i]->setMinimum(minValue); - outSliders[i]->setMaximum(maxValue); - reversals[i]->setChecked(false); - } else { - outSliders[i]->setMinimum(maxValue); - outSliders[i]->setMaximum(minValue); - reversals[i]->setChecked(true); - } + foreach(OutputChannelForm *outputChannelForm, outputChannelForms) + { + int minValue = actuatorSettingsData.ChannelMin[outputChannelForm->index()]; + int maxValue = actuatorSettingsData.ChannelMax[outputChannelForm->index()]; + outputChannelForm->minmax(minValue, maxValue); + + int neutral = actuatorSettingsData.ChannelNeutral[outputChannelForm->index()]; + outputChannelForm->neutral(neutral); } - field = obj->getField(QString("ChannelNeutral")); - for (int i=0; i<8; i++) { - int value = field->getValue(i).toInt(); - outSliders[i]->setValue(value); - outLabels[i]->setText(QString::number(value)); - } - - + setDirty(dirty); } /** * Sends the config to the board, without saving to the SD card (RC Output) */ -void ConfigOutputWidget::sendRCOutputUpdate() +void ConfigOutputWidget::updateObjectsFromWidgets() { - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager *objManager = pm->getObject(); - UAVDataObject* obj = dynamic_cast(objManager->getObject(QString("ActuatorSettings"))); - Q_ASSERT(obj); + ActuatorSettings *actuatorSettings = ActuatorSettings::GetInstance(getObjectManager()); + Q_ASSERT(actuatorSettings); + ActuatorSettings::DataFields actuatorSettingsData = actuatorSettings->getData(); - // Now send channel ranges: - UAVObjectField * field = obj->getField(QString("ChannelMax")); - for (int i = 0; i < 8; i++) { - field->setValue(outMax[i]->value(),i); - } - - field = obj->getField(QString("ChannelMin")); - for (int i = 0; i < 8; i++) { - field->setValue(outMin[i]->value(),i); - } - - field = obj->getField(QString("ChannelNeutral")); - for (int i = 0; i < 8; i++) { - field->setValue(outSliders[i]->value(),i); - } - - field = obj->getField(QString("ChannelUpdateFreq")); - field->setValue(m_config->outputRate1->value(),0); - field->setValue(m_config->outputRate2->value(),1); - field->setValue(m_config->outputRate3->value(),2); - field->setValue(m_config->outputRate4->value(),3); - - // ... and send to the OP Board - obj->updated(); - -} - - -/** - Sends the config to the board and request saving into the SD card (RC Output) - */ -void ConfigOutputWidget::saveRCOutputObject() -{ - // Send update so that the latest value is saved - sendRCOutputUpdate(); - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("ActuatorSettings"))); - Q_ASSERT(obj); - saveObjectToSD(obj); - -} - - -/** - Sets the minimum/maximum value of the channel 0 to seven output sliders. - Have to do it here because setMinimum is not a slot. - - One added trick: if the slider is at its min when the value - is changed, then keep it on the min. - */ -void ConfigOutputWidget::setChOutRange() -{ - QSpinBox *spinbox = (QSpinBox*)QObject::sender(); - - int index = outMin.indexOf(spinbox); // This is the channel number - if (index < 0) - index = outMax.indexOf(spinbox); // We can't know if the signal came from min or max - - QSlider *slider = outSliders[index]; - - int oldMini = slider->minimum(); -// int oldMaxi = slider->maximum(); - - if (outMin[index]->value()value()) + // Set channel ranges + QList outputChannelForms = findChildren(); + foreach(OutputChannelForm *outputChannelForm, outputChannelForms) { - slider->setRange(outMin[index]->value(), outMax[index]->value()); - reversals[index]->setChecked(false); - } - else - { - slider->setRange(outMax[index]->value(), outMin[index]->value()); - reversals[index]->setChecked(true); - } - - if (slider->value() == oldMini) - slider->setValue(slider->minimum()); - -// if (slider->value() == oldMaxi) -// slider->setValue(slider->maximum()); // this can be dangerous if it happens to be controlling a motor at the time! -} - -/** - Reverses the channel when the checkbox is clicked - */ -void ConfigOutputWidget::reverseChannel(bool state) -{ - QCheckBox *checkbox = (QCheckBox*)QObject::sender(); - int index = reversals.indexOf(checkbox); // This is the channel number - - // Sanity check: if state became true, make sure the Maxvalue was higher than Minvalue - // the situations below can happen! - if (state && (outMax[index]->value()value())) - return; - if (!state && (outMax[index]->value()>outMin[index]->value())) - return; - - // Now, swap the min & max values (only on the spinboxes, the slider - // does not change! - int temp = outMax[index]->value(); - outMax[index]->setValue(outMin[index]->value()); - outMin[index]->setValue(temp); - - // Also update the channel value - // This is a trick to force the slider to update its value and - // emit the right signal itself, because our sendChannelTest(int) method - // relies on the object sender's identity. - if (outSliders[index]->value()maximum()) { - outSliders[index]->setValue(outSliders[index]->value()+1); - outSliders[index]->setValue(outSliders[index]->value()-1); - } else { - outSliders[index]->setValue(outSliders[index]->value()-1); - outSliders[index]->setValue(outSliders[index]->value()+1); + actuatorSettingsData.ChannelMax[outputChannelForm->index()] = outputChannelForm->max(); + actuatorSettingsData.ChannelMin[outputChannelForm->index()] = outputChannelForm->min(); + actuatorSettingsData.ChannelNeutral[outputChannelForm->index()] = outputChannelForm->neutral(); } + // Set update rates + actuatorSettingsData.ChannelUpdateFreq[0] = m_config->cb_outputRate1->currentText().toUInt(); + actuatorSettingsData.ChannelUpdateFreq[1] = m_config->cb_outputRate2->currentText().toUInt(); + actuatorSettingsData.ChannelUpdateFreq[2] = m_config->cb_outputRate3->currentText().toUInt(); + actuatorSettingsData.ChannelUpdateFreq[3] = m_config->cb_outputRate4->currentText().toUInt(); + // Apply settings + actuatorSettings->setData(actuatorSettingsData); } void ConfigOutputWidget::openHelp() @@ -579,4 +375,18 @@ void ConfigOutputWidget::openHelp() QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/display/Doc/Output+Configuration", QUrl::StrictMode) ); } +void ConfigOutputWidget::stopTests() +{ + m_config->channelOutTest->setChecked(false); +} +void ConfigOutputWidget::disableIfNotMe(UAVObject* obj) +{ + if(obj->getMetadata().gcsTelemetryUpdateMode == UAVObject::UPDATEMODE_ONCHANGE) + { + if(!wasItMe) + this->setEnabled(false); + } + else + this->setEnabled(true); +} diff --git a/ground/openpilotgcs/src/plugins/config/configoutputwidget.h b/ground/openpilotgcs/src/plugins/config/configoutputwidget.h index 2a197e3ac..76dc51658 100644 --- a/ground/openpilotgcs/src/plugins/config/configoutputwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configoutputwidget.h @@ -1,13 +1,13 @@ /** ****************************************************************************** * - * @file configservowidget.h + * @file configoutputwidget.h * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup ConfigPlugin Config Plugin * @{ - * @brief Servo input/output configuration panel for the config gadget + * @brief Servo output configuration panel for the config gadget *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify @@ -37,6 +37,7 @@ #include class Ui_OutputWidget; +class OutputChannelForm; class ConfigOutputWidget: public ConfigTaskWidget { @@ -46,6 +47,7 @@ public: ConfigOutputWidget(QWidget *parent = 0); ~ConfigOutputWidget(); + private: Ui_OutputWidget *m_config; @@ -55,33 +57,26 @@ private: void assignChannel(UAVDataObject *obj, QString str); void assignOutputChannel(UAVDataObject *obj, QString str); + OutputChannelForm* getOutputChannelForm(const int index) const; int mccDataRate; UAVObject::Metadata accInitialData; - QList outSliders; - QList outMin; - QList outMax; - QList reversals; - QList links; - QList outLabels; - bool firstUpdate; - virtual void enableControls(bool enable); - + bool wasItMe; private slots: - virtual void refreshValues(); - void sendRCOutputUpdate(); - void saveRCOutputObject(); + void stopTests(); + void disableIfNotMe(UAVObject *obj); + virtual void refreshWidgetsValues(); + void updateObjectsFromWidgets(); void runChannelTests(bool state); - void sendChannelTest(int value); - void setChOutRange(); - void reverseChannel(bool state); - void linkToggled(bool state); + void sendChannelTest(int index, int value); void setSpinningArmed(bool val); void openHelp(); +protected: + void enableControls(bool enable); }; #endif diff --git a/ground/openpilotgcs/src/plugins/config/configplugin.cpp b/ground/openpilotgcs/src/plugins/config/configplugin.cpp index dced1c231..622b3db9b 100644 --- a/ground/openpilotgcs/src/plugins/config/configplugin.cpp +++ b/ground/openpilotgcs/src/plugins/config/configplugin.cpp @@ -30,7 +30,7 @@ #include #include #include - +#include "objectpersistence.h" ConfigPlugin::ConfigPlugin() { @@ -58,7 +58,7 @@ bool ConfigPlugin::initialize(const QStringList& args, QString *errMsg) "ConfigPlugin.EraseAll", QList() << Core::Constants::C_GLOBAL_ID); - cmd->action()->setText("Erase all settings from board..."); + cmd->action()->setText(tr("Erase all settings from board...")); ac->menu()->addSeparator(); ac->appendGroup("Utilities"); @@ -80,6 +80,17 @@ bool ConfigPlugin::initialize(const QStringList& args, QString *errMsg) return true; } +/** + * @brief Return handle to object manager + */ +UAVObjectManager * ConfigPlugin::getObjectManager() +{ + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + UAVObjectManager * objMngr = pm->getObject(); + Q_ASSERT(objMngr); + return objMngr; +} + void ConfigPlugin::extensionsInitialized() { cmd->action()->setEnabled(false); @@ -122,18 +133,19 @@ void ConfigPlugin::eraseAllSettings() return; settingsErased = false; - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager * objMngr = pm->getObject(); - Q_ASSERT(objMngr); - ObjectPersistence* objper = dynamic_cast( objMngr->getObject(ObjectPersistence::NAME) ); + ObjectPersistence* objper = ObjectPersistence::GetInstance(getObjectManager()); Q_ASSERT(objper); + connect(objper, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(eraseDone(UAVObject *))); - ObjectPersistence::DataFields data; - data.Operation = ObjectPersistence::OPERATION_DELETE; - data.Selection = ObjectPersistence::SELECTION_ALLSETTINGS; + + ObjectPersistence::DataFields data = objper->getData(); + data.Operation = ObjectPersistence::OPERATION_FULLERASE; + + // No need for manual updated event, this is triggered by setData + // based on UAVO meta data objper->setData(data); objper->updated(); - QTimer::singleShot(1500,this,SLOT(eraseFailed())); + QTimer::singleShot(6000,this,SLOT(eraseFailed())); } @@ -141,37 +153,47 @@ void ConfigPlugin::eraseFailed() { if (settingsErased) return; - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager * objMngr = pm->getObject(); - Q_ASSERT(objMngr); - ObjectPersistence* objper = dynamic_cast( objMngr->getObject(ObjectPersistence::NAME)); - disconnect(objper, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(eraseDone(UAVObject *))); - QMessageBox msgBox; - msgBox.setText(tr("Error trying to erase settings.")); - msgBox.setInformativeText(tr("Power-cycle your board. Settings might be inconsistent.")); - msgBox.setStandardButtons(QMessageBox::Ok); - msgBox.setDefaultButton(QMessageBox::Ok); - msgBox.exec(); + + ObjectPersistence* objper = ObjectPersistence::GetInstance(getObjectManager()); + + ObjectPersistence::DataFields data = objper->getData(); + if(data.Operation == ObjectPersistence::OPERATION_FULLERASE) { + // First attempt via flash erase failed. Fall back on erase all settings + data.Operation = ObjectPersistence::OPERATION_DELETE; + data.Selection = ObjectPersistence::SELECTION_ALLSETTINGS; + objper->setData(data); + objper->updated(); + QTimer::singleShot(1500,this,SLOT(eraseFailed())); + } else { + disconnect(objper, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(eraseDone(UAVObject *))); + QMessageBox msgBox; + msgBox.setText(tr("Error trying to erase settings.")); + msgBox.setInformativeText(tr("Power-cycle your board after removing all blades. Settings might be inconsistent.")); + msgBox.setStandardButtons(QMessageBox::Ok); + msgBox.setDefaultButton(QMessageBox::Ok); + msgBox.exec(); + } } void ConfigPlugin::eraseDone(UAVObject * obj) { QMessageBox msgBox; - ObjectPersistence* objper = dynamic_cast(sender()); - Q_ASSERT(obj->getName().compare("ObjectPersistence") == 0); - QString tmp = obj->getField("Operation")->getValue().toString(); - if (obj->getField("Operation")->getValue().toString().compare(QString("Delete")) == 0 ) { + ObjectPersistence* objper = ObjectPersistence::GetInstance(getObjectManager()); + ObjectPersistence::DataFields data = objper->getData(); + Q_ASSERT(obj->getInstID() == objper->getInstID()); + + if(data.Operation != ObjectPersistence::OPERATION_COMPLETED) { return; } disconnect(objper, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(eraseDone(UAVObject *))); - if (obj->getField("Operation")->getValue().toString().compare(QString("Completed")) == 0) { + if (data.Operation == ObjectPersistence::OPERATION_COMPLETED) { settingsErased = true; msgBox.setText(tr("Settings are now erased.")); msgBox.setInformativeText(tr("Please now power-cycle your board to complete reset.")); } else { msgBox.setText(tr("Error trying to erase settings.")); - msgBox.setInformativeText(tr("Power-cycle your board. Settings might be inconsistent.")); + msgBox.setInformativeText(tr("Power-cycle your board after removing all blades. Settings might be inconsistent.")); } msgBox.setStandardButtons(QMessageBox::Ok); msgBox.setDefaultButton(QMessageBox::Ok); diff --git a/ground/openpilotgcs/src/plugins/config/configplugin.h b/ground/openpilotgcs/src/plugins/config/configplugin.h index f4fa677de..7091ad460 100644 --- a/ground/openpilotgcs/src/plugins/config/configplugin.h +++ b/ground/openpilotgcs/src/plugins/config/configplugin.h @@ -48,6 +48,7 @@ public: ConfigPlugin(); ~ConfigPlugin(); + UAVObjectManager * getObjectManager(); void extensionsInitialized(); bool initialize(const QStringList & arguments, QString * errorString); void shutdown(); diff --git a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp index 5cd0cfa04..cbe554f4e 100644 --- a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp @@ -43,21 +43,15 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa m_stabilization->setupUi(this); - connect(m_stabilization->saveStabilizationToSD, SIGNAL(clicked()), this, SLOT(saveStabilizationUpdate())); - connect(m_stabilization->saveStabilizationToRAM, SIGNAL(clicked()), this, SLOT(sendStabilizationUpdate())); + setupButtons(m_stabilization->saveStabilizationToRAM,m_stabilization->saveStabilizationToSD); - enableControls(false); - refreshValues(); - connect(parent, SIGNAL(autopilotConnected()),this, SLOT(onAutopilotConnect())); - connect(parent, SIGNAL(autopilotDisconnected()),this, SLOT(onAutopilotDisconnect())); + addUAVObject("StabilizationSettings"); - // Now connect the widget to the StabilizationSettings object - UAVObject *obj = getObjectManager()->getObject(QString("StabilizationSettings")); - connect(obj,SIGNAL(objectUpdated(UAVObject*)),this,SLOT(refreshValues())); + refreshWidgetsValues(); // Create a timer to regularly send the object update in case // we want realtime updates. - connect(&updateTimer, SIGNAL(timeout()), this, SLOT(sendStabilizationUpdate())); + connect(&updateTimer, SIGNAL(timeout()), this, SLOT(updateObjectsFromWidgets())); connect(m_stabilization->realTimeUpdates, SIGNAL(toggled(bool)), this, SLOT(realtimeUpdateToggle(bool))); // Connect the updates of the stab values @@ -79,6 +73,35 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa // Connect the help button connect(m_stabilization->stabilizationHelp, SIGNAL(clicked()), this, SLOT(openHelp())); + addWidget(m_stabilization->rateRollKp); + addWidget(m_stabilization->rateRollKi); + addWidget(m_stabilization->rateRollILimit); + addWidget(m_stabilization->ratePitchKp); + addWidget(m_stabilization->ratePitchKi); + addWidget(m_stabilization->ratePitchILimit); + addWidget(m_stabilization->rateYawKp); + addWidget(m_stabilization->rateYawKi); + addWidget(m_stabilization->rateYawILimit); + addWidget(m_stabilization->rollKp); + addWidget(m_stabilization->rollKi); + addWidget(m_stabilization->rollILimit); + addWidget(m_stabilization->yawILimit); + addWidget(m_stabilization->yawKi); + addWidget(m_stabilization->yawKp); + addWidget(m_stabilization->pitchKp); + addWidget(m_stabilization->pitchKi); + addWidget(m_stabilization->pitchILimit); + addWidget(m_stabilization->rollMax); + addWidget(m_stabilization->pitchMax); + addWidget(m_stabilization->yawMax); + addWidget(m_stabilization->manualRoll); + addWidget(m_stabilization->manualPitch); + addWidget(m_stabilization->manualYaw); + addWidget(m_stabilization->maximumRoll); + addWidget(m_stabilization->maximumPitch); + addWidget(m_stabilization->maximumYaw); + addWidget(m_stabilization->lowThrottleZeroIntegral); + } ConfigStabilizationWidget::~ConfigStabilizationWidget() @@ -86,13 +109,6 @@ ConfigStabilizationWidget::~ConfigStabilizationWidget() // Do nothing } - -void ConfigStabilizationWidget::enableControls(bool enable) -{ - //m_stabilization->saveStabilizationToRAM->setEnabled(enable); - m_stabilization->saveStabilizationToSD->setEnabled(enable); -} - void ConfigStabilizationWidget::updateRateRollKP(double val) { if (m_stabilization->linkRateRP->isChecked()) { @@ -187,8 +203,9 @@ void ConfigStabilizationWidget::updatePitchILimit(double val) /** Request stabilization settings from the board */ -void ConfigStabilizationWidget::refreshValues() +void ConfigStabilizationWidget::refreshWidgetsValues() { + bool dirty=isDirty(); // Not needed anymore as this slot is only called whenever we get // a signal that the object was just updated // stabSettings->requestUpdate(); @@ -229,9 +246,9 @@ void ConfigStabilizationWidget::refreshValues() m_stabilization->maximumRoll->setValue(stabData.MaximumRate[StabilizationSettings::MAXIMUMRATE_ROLL]); m_stabilization->maximumPitch->setValue(stabData.MaximumRate[StabilizationSettings::MAXIMUMRATE_PITCH]); m_stabilization->maximumYaw->setValue(stabData.MaximumRate[StabilizationSettings::MAXIMUMRATE_YAW]); + m_stabilization->lowThrottleZeroIntegral->setChecked(stabData.LowThrottleZeroIntegral==StabilizationSettings::LOWTHROTTLEZEROINTEGRAL_TRUE ? true : false); - m_stabilization->lowThrottleZeroIntegral->setChecked( - stabData.LowThrottleZeroIntegral == StabilizationSettings::LOWTHROTTLEZEROINTEGRAL_TRUE); + setDirty(dirty); } @@ -239,7 +256,7 @@ void ConfigStabilizationWidget::refreshValues() Send telemetry settings to the board */ -void ConfigStabilizationWidget::sendStabilizationUpdate() +void ConfigStabilizationWidget::updateObjectsFromWidgets() { StabilizationSettings::DataFields stabData = stabSettings->getData(); @@ -279,28 +296,12 @@ void ConfigStabilizationWidget::sendStabilizationUpdate() stabData.MaximumRate[StabilizationSettings::MAXIMUMRATE_PITCH] = m_stabilization->maximumPitch->value(); stabData.MaximumRate[StabilizationSettings::MAXIMUMRATE_YAW] = m_stabilization->maximumYaw->value(); - stabData.LowThrottleZeroIntegral = m_stabilization->lowThrottleZeroIntegral->isChecked() ? - StabilizationSettings::LOWTHROTTLEZEROINTEGRAL_TRUE : - StabilizationSettings::LOWTHROTTLEZEROINTEGRAL_FALSE; + stabData.LowThrottleZeroIntegral = (m_stabilization->lowThrottleZeroIntegral->isChecked() ? StabilizationSettings::LOWTHROTTLEZEROINTEGRAL_TRUE :StabilizationSettings::LOWTHROTTLEZEROINTEGRAL_FALSE); + stabSettings->setData(stabData); // this is atomic } - -/** - Send telemetry settings to the board and request saving to SD card - */ - -void ConfigStabilizationWidget::saveStabilizationUpdate() -{ - // Send update so that the latest value is saved - sendStabilizationUpdate(); - UAVDataObject* obj = dynamic_cast(getObjectManager()->getObject(QString("StabilizationSettings"))); - Q_ASSERT(obj); - saveObjectToSD(obj); -} - - void ConfigStabilizationWidget::realtimeUpdateToggle(bool state) { if (state) { diff --git a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h index 98db5530f..e512c5097 100644 --- a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h @@ -49,12 +49,10 @@ private: Ui_StabilizationWidget *m_stabilization; StabilizationSettings* stabSettings; QTimer updateTimer; - virtual void enableControls(bool enable); private slots: - virtual void refreshValues(); - void sendStabilizationUpdate(); - void saveStabilizationUpdate(); + virtual void refreshWidgetsValues(); + void updateObjectsFromWidgets(); void realtimeUpdateToggle(bool); void openHelp(); diff --git a/ground/openpilotgcs/src/plugins/config/configtaskwidget.cpp b/ground/openpilotgcs/src/plugins/config/configtaskwidget.cpp index 8fd35c596..c7a082507 100644 --- a/ground/openpilotgcs/src/plugins/config/configtaskwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configtaskwidget.cpp @@ -26,14 +26,17 @@ */ #include "configtaskwidget.h" #include +#include "uavsettingsimportexport/uavsettingsimportexportfactory.h" +#include "configgadgetwidget.h" - -ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent),smartsave(NULL),dirty(false) +ConfigTaskWidget::ConfigTaskWidget(QWidget *parent) : QWidget(parent),isConnected(false),smartsave(NULL),dirty(false) { pm = ExtensionSystem::PluginManager::instance(); objManager = pm->getObject(); - connect(parent, SIGNAL(autopilotConnected()),this, SLOT(onAutopilotConnect())); - connect(parent, SIGNAL(autopilotDisconnected()),this, SLOT(onAutopilotDisconnect())); + connect((ConfigGadgetWidget*)parent, SIGNAL(autopilotConnected()),this, SLOT(onAutopilotConnect())); + connect((ConfigGadgetWidget*)parent, SIGNAL(autopilotDisconnected()),this, SLOT(onAutopilotDisconnect())); + UAVSettingsImportExportFactory * importexportplugin = pm->getObject(); + connect(importexportplugin,SIGNAL(importAboutToBegin()),this,SLOT(invalidateObjects())); } void ConfigTaskWidget::addWidget(QWidget * widget) { @@ -43,13 +46,29 @@ void ConfigTaskWidget::addUAVObject(QString objectName) { addUAVObjectToWidgetRelation(objectName,"",NULL); } -void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget * widget) +void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget * widget, QString index) +{ + UAVObject *obj=NULL; + UAVObjectField *_field=NULL; + obj = objManager->getObject(QString(object)); + Q_ASSERT(obj); + _field = obj->getField(QString(field)); + Q_ASSERT(_field); + addUAVObjectToWidgetRelation(object,field,widget,_field->getElementNames().indexOf(index)); +} + +void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString field, QWidget * widget, int index,int scale) { UAVObject *obj=NULL; UAVObjectField *_field=NULL; if(!object.isEmpty()) + { obj = objManager->getObject(QString(object)); - connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues())); + Q_ASSERT(obj); + objectUpdates.insert(obj,true); + connect(obj, SIGNAL(objectUpdated(UAVObject*)),this, SLOT(objectUpdated(UAVObject*))); + connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(refreshWidgetsValues())); + } //smartsave->addObject(obj); if(!field.isEmpty() && obj) _field = obj->getField(QString(field)); @@ -57,9 +76,11 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString fiel ow->field=_field; ow->object=obj; ow->widget=widget; + ow->index=index; + ow->scale=scale; objOfInterest.append(ow); if(obj) - smartsave->addObject(obj); + smartsave->addObject((UAVDataObject*)obj); if(widget==NULL) { // do nothing @@ -88,6 +109,15 @@ void ConfigTaskWidget::addUAVObjectToWidgetRelation(QString object, QString fiel { connect(cb,SIGNAL(valueChanged(double)),this,SLOT(widgetsContentsChanged())); } + else if(QCheckBox * cb=qobject_cast(widget)) + { + connect(cb,SIGNAL(clicked()),this,SLOT(widgetsContentsChanged())); + } + else if(QPushButton * cb=qobject_cast(widget)) + { + connect(cb,SIGNAL(clicked()),this,SLOT(widgetsContentsChanged())); + } + } @@ -98,6 +128,7 @@ ConfigTaskWidget::~ConfigTaskWidget() void ConfigTaskWidget::saveObjectToSD(UAVObject *obj) { + qDebug()<<"ConfigTaskWidget::saveObjectToSD"; // saveObjectToSD is now handled by the UAVUtils plugin in one // central place (and one central queue) ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); @@ -126,17 +157,23 @@ double ConfigTaskWidget::listMean(QList list) void ConfigTaskWidget::onAutopilotDisconnect() { - enableControls(false); + isConnected=false; + enableControls(false); + invalidateObjects(); } void ConfigTaskWidget::onAutopilotConnect() { - enableControls(true); - refreshWidgetsValues(); + invalidateObjects(); + dirty=false; + isConnected=true; + enableControls(true); + refreshWidgetsValues(); } void ConfigTaskWidget::populateWidgets() { + bool dirtyBack=dirty; foreach(objectToWidget * ow,objOfInterest) { if(ow->object==NULL || ow->field==NULL) @@ -146,18 +183,31 @@ void ConfigTaskWidget::populateWidgets() else if(QComboBox * cb=qobject_cast(ow->widget)) { cb->addItems(ow->field->getOptions()); - cb->setCurrentIndex(cb->findText(ow->field->getValue().toString())); + cb->setCurrentIndex(cb->findText(ow->field->getValue(ow->index).toString())); } else if(QLabel * cb=qobject_cast(ow->widget)) { - cb->setText(ow->field->getValue().toString()); + cb->setText(ow->field->getValue(ow->index).toString()); + } + else if(QSpinBox * cb=qobject_cast(ow->widget)) + { + cb->setValue(ow->field->getValue(ow->index).toInt()/ow->scale); + } + else if(QSlider * cb=qobject_cast(ow->widget)) + { + cb->setValue(ow->field->getValue(ow->index).toInt()/ow->scale); + } + else if(QCheckBox * cb=qobject_cast(ow->widget)) + { + cb->setChecked(ow->field->getValue(ow->index).toBool()); } } - dirty=false; + setDirty(dirtyBack); } void ConfigTaskWidget::refreshWidgetsValues() { + bool dirtyBack=dirty; foreach(objectToWidget * ow,objOfInterest) { if(ow->object==NULL || ow->field==NULL) @@ -166,13 +216,26 @@ void ConfigTaskWidget::refreshWidgetsValues() } else if(QComboBox * cb=qobject_cast(ow->widget)) { - cb->setCurrentIndex(cb->findText(ow->field->getValue().toString())); + cb->setCurrentIndex(cb->findText(ow->field->getValue(ow->index).toString())); } else if(QLabel * cb=qobject_cast(ow->widget)) { - cb->setText(ow->field->getValue().toString()); + cb->setText(ow->field->getValue(ow->index).toString()); + } + else if(QSpinBox * cb=qobject_cast(ow->widget)) + { + cb->setValue(ow->field->getValue(ow->index).toInt()/ow->scale); + } + else if(QSlider * cb=qobject_cast(ow->widget)) + { + cb->setValue(ow->field->getValue(ow->index).toInt()/ow->scale); + } + else if(QCheckBox * cb=qobject_cast(ow->widget)) + { + cb->setChecked(ow->field->getValue(ow->index).toBool()); } } + setDirty(dirtyBack); } void ConfigTaskWidget::updateObjectsFromWidgets() @@ -185,11 +248,23 @@ void ConfigTaskWidget::updateObjectsFromWidgets() } else if(QComboBox * cb=qobject_cast(ow->widget)) { - ow->field->setValue(cb->currentText()); + ow->field->setValue(cb->currentText(),ow->index); } else if(QLabel * cb=qobject_cast(ow->widget)) { - ow->field->setValue(cb->text()); + ow->field->setValue(cb->text(),ow->index); + } + else if(QSpinBox * cb=qobject_cast(ow->widget)) + { + ow->field->setValue(cb->value()* ow->scale,ow->index); + } + else if(QSlider * cb=qobject_cast(ow->widget)) + { + ow->field->setValue(cb->value()* ow->scale,ow->index); + } + else if(QCheckBox * cb=qobject_cast(ow->widget)) + { + ow->field->setValue((cb->isChecked()?"TRUE":"FALSE"),ow->index); } } } @@ -197,10 +272,11 @@ void ConfigTaskWidget::updateObjectsFromWidgets() void ConfigTaskWidget::setupButtons(QPushButton *update, QPushButton *save) { smartsave=new smartSaveButton(update,save); - connect(smartsave, SIGNAL(preProcessOperations()), this, SLOT(updateObjectsFromWidgets())); + connect(smartsave,SIGNAL(preProcessOperations()), this, SLOT(updateObjectsFromWidgets())); connect(smartsave,SIGNAL(saveSuccessfull()),this,SLOT(clearDirty())); connect(smartsave,SIGNAL(beginOp()),this,SLOT(disableObjUpdates())); connect(smartsave,SIGNAL(endOp()),this,SLOT(enableObjUpdates())); + enableControls(false); } void ConfigTaskWidget::enableControls(bool enable) @@ -211,17 +287,23 @@ void ConfigTaskWidget::enableControls(bool enable) void ConfigTaskWidget::widgetsContentsChanged() { - dirty=true; + setDirty(true); } void ConfigTaskWidget::clearDirty() { - dirty=false; + setDirty(false); +} +void ConfigTaskWidget::setDirty(bool value) +{ + dirty=value; } - bool ConfigTaskWidget::isDirty() { - return dirty; + if(isConnected) + return dirty; + else + return false; } void ConfigTaskWidget::refreshValues() @@ -246,6 +328,30 @@ void ConfigTaskWidget::enableObjUpdates() } } +void ConfigTaskWidget::objectUpdated(UAVObject *obj) +{ + objectUpdates[obj]=true; +} + +bool ConfigTaskWidget::allObjectsUpdated() +{ + bool ret=true; + foreach(UAVObject *obj, objectUpdates.keys()) + { + ret=ret & objectUpdates[obj]; + } + qDebug()<<"ALL OBJECTS UPDATE:"< #include #include +#include +#include + class ConfigTaskWidget: public QWidget { Q_OBJECT @@ -51,6 +54,8 @@ public: UAVObject * object; UAVObjectField * field; QWidget * widget; + int index; + int scale; }; ConfigTaskWidget(QWidget *parent = 0); @@ -60,21 +65,30 @@ public: static double listMean(QList list); void addUAVObject(QString objectName); void addWidget(QWidget * widget); - void addUAVObjectToWidgetRelation(QString object,QString field,QWidget * widget); + void addUAVObjectToWidgetRelation(QString object,QString field,QWidget * widget,int index=0,int scale=1); + void setupButtons(QPushButton * update,QPushButton * save); bool isDirty(); + void setDirty(bool value); + void addUAVObjectToWidgetRelation(QString object, QString field, QWidget *widget, QString index); + bool allObjectsUpdated(); public slots: void onAutopilotDisconnect(); void onAutopilotConnect(); + void invalidateObjects(); private slots: virtual void refreshValues(); virtual void updateObjectsFromWidgets(); + void objectUpdated(UAVObject*); private: + bool isConnected; + QStringList objectsList; QList objOfInterest; ExtensionSystem::PluginManager *pm; UAVObjectManager *objManager; smartSaveButton *smartsave; + QMap objectUpdates; bool dirty; protected slots: virtual void disableObjUpdates(); diff --git a/ground/openpilotgcs/src/plugins/config/fancytabwidget.cpp b/ground/openpilotgcs/src/plugins/config/fancytabwidget.cpp index 97ae45303..bb0b65b09 100644 --- a/ground/openpilotgcs/src/plugins/config/fancytabwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/fancytabwidget.cpp @@ -284,6 +284,10 @@ void FancyTabBar::paintTab(QPainter *painter, int tabIndex) const } void FancyTabBar::setCurrentIndex(int index) { + bool proceed=true; + emit aboutToChange(&proceed); + if(!proceed) + return; m_currentIndex = index; update(); emit currentChanged(index); @@ -319,7 +323,6 @@ FancyTabWidget::FancyTabWidget(QWidget *parent, bool isVertical) : QWidget(parent) { m_tabBar = new FancyTabBar(this, isVertical); - m_selectionWidget = new QWidget(this); QBoxLayout *selectionLayout; if (isVertical) { @@ -477,3 +480,7 @@ void FancyTabWidget::setTabToolTip(int index, const QString &toolTip) { m_tabBar->setTabToolTip(index, toolTip); } +QWidget * FancyTabWidget::currentWidget() +{ + return m_modesStack->currentWidget(); +} diff --git a/ground/openpilotgcs/src/plugins/config/fancytabwidget.h b/ground/openpilotgcs/src/plugins/config/fancytabwidget.h index 47c7ddeb5..73da2aae8 100644 --- a/ground/openpilotgcs/src/plugins/config/fancytabwidget.h +++ b/ground/openpilotgcs/src/plugins/config/fancytabwidget.h @@ -91,6 +91,7 @@ public: signals: void currentChanged(int); + void aboutToChange(bool *); public slots: void updateHover(); @@ -116,7 +117,7 @@ class FancyTabWidget : public QWidget public: FancyTabWidget(QWidget *parent = 0, bool isVertical = false); - + FancyTabBar *m_tabBar; void insertTab(int index, QWidget *tab, const QIcon &icon, const QString &label); void removeTab(int index); void setBackgroundBrush(const QBrush &brush); @@ -132,6 +133,7 @@ public: int currentIndex() const; QStatusBar *statusBar() const; + QWidget * currentWidget(); signals: void currentAboutToShow(int index); void currentChanged(int index); @@ -143,7 +145,6 @@ private slots: void showWidget(int index); private: - FancyTabBar *m_tabBar; QWidget *m_cornerWidgetContainer; QStackedLayout *m_modesStack; QWidget *m_selectionWidget; diff --git a/ground/openpilotgcs/src/plugins/config/images/TX.svg b/ground/openpilotgcs/src/plugins/config/images/TX.svg new file mode 100644 index 000000000..ebfee4463 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/config/images/TX.svg @@ -0,0 +1,571 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + image/svg+xml + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Flight Mode + + Accessory2 + + + + Accessory1 + + + Accessory0 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/config/images/camera.png b/ground/openpilotgcs/src/plugins/config/images/camera.png new file mode 100644 index 000000000..b412c28d6 Binary files /dev/null and b/ground/openpilotgcs/src/plugins/config/images/camera.png differ diff --git a/ground/openpilotgcs/src/plugins/config/input.ui b/ground/openpilotgcs/src/plugins/config/input.ui index e1eb0b435..2fac45ec9 100644 --- a/ground/openpilotgcs/src/plugins/config/input.ui +++ b/ground/openpilotgcs/src/plugins/config/input.ui @@ -25,770 +25,105 @@ - - - - 75 - true - - - - Receiver Type: - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - - - 234 - 54 - - - - - 75 - true - - - - Indicates whether OpenPilot is getting a signal from the RC receiver. - - - RC Receiver not connected or invalid input configuration (missing channels) - - - true - - - - - - - - - Rev. - - - Qt::AlignBottom|Qt::AlignLeading|Qt::AlignLeft - - - - - - - - 16 - 16 - - - - true - - - - - - - true - - - 1000 - - - 2000 - - - 1500 - - - Qt::Horizontal - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Maximum channel pulse width</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html> - - - 2000 - - - - - - - Check this to reverse the channel. -(Useful for transmitters without channel -reversal capabilities). - - - - - - - - - - - - - true - - - 1000 - - - 2000 - - - 1500 - - - Qt::Horizontal - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Maximum channel pulse width</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html> - - - 2000 - - - - - - - Check this to reverse the channel. -(Useful for transmitters without channel -reversal capabilities). - - - - - - - - - - - - - true - - - 1000 - - - 2000 - - - 1500 - - - Qt::Horizontal - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Maximum channel pulse width</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html> - - - 2000 - - - - - - - Check this to reverse the channel. -(Useful for transmitters without channel -reversal capabilities). - - - - - - - - - - - - - true - - - 1000 - - - 2000 - - - 1500 - - - Qt::Horizontal - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Maximum channel pulse width</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html> - - - 2000 - - - - - - - Check this to reverse the channel. -(Useful for transmitters without channel -reversal capabilities). - - - - - - - - - - - - - true - - - 1000 - - - 2000 - - - 1500 - - - Qt::Horizontal - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Maximum channel pulse width</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html> - - - 2000 - - - - - - - Check this to reverse the channel. -(Useful for transmitters without channel -reversal capabilities). - - - - - - - - - - - - - true - - - 1000 - - - 2000 - - - 1500 - - - Qt::Horizontal - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Maximum channel pulse width</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html> - - - 2000 - - - - - - - Check this to reverse the channel. -(Useful for transmitters without channel -reversal capabilities). - - - - - - - - - - - - - true - - - 1000 - - - 2000 - - - 1500 - - - Qt::Horizontal - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Maximum channel pulse width</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html> - - - 2000 - - - - - - - Check this to reverse the channel. -(Useful for transmitters without channel -reversal capabilities). - - - - - - - - - - - - - true - - - 1000 - - - 2000 - - - 1500 - - - Qt::Horizontal - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Maximum channel pulse width</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html> - - - 2000 - - - - - - - Check this to reverse the channel. -(Useful for transmitters without channel -reversal capabilities). - - - - - - - - - - - 75 - true - - - - BEWARE: make sure your engines are not connected when running calibration! - - - - - - - - - 75 - true - - - - - - - - - - - - 50 - false - - - - Start calibrating the RC Inputs. -Uncheck/Check to restart calibration. -During calibration: move your RC controls over their whole range, -then leave them on Neutral, uncheck calibration and save. -Neutral should be put at the bottom of the slider for the throttle. - - - Run Calibration - - - - - - - - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Minimum channel pulse width</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html> - - - 1000 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Minimum channel pulse width</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html> - - - 1000 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Minimum channel pulse width</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html> - - - 1000 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Minimum channel pulse width</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html> - - - 1000 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Minimum channel pulse width</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html> - - - 1000 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Minimum channel pulse width</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html> - - - 1000 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Minimum channel pulse width</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html> - - - 1000 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Minimum channel pulse width</p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">(microseconds)</p></body></html> - - - 1000 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:10pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:9pt;">Current channel value.</span></p></body></html> - - - 1500 - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:10pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:9pt;">Current channel value.</span></p></body></html> - - - 1500 - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:10pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:9pt;">Current channel value.</span></p></body></html> - - - 1500 - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:10pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:9pt;">Current channel value.</span></p></body></html> - - - 1500 - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:10pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:9pt;">Current channel value.</span></p></body></html> - - - 1500 - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:10pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:9pt;">Current channel value.</span></p></body></html> - - - 1500 - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:10pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:9pt;">Current channel value.</span></p></body></html> - - - 1500 - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:10pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:9pt;">Current channel value.</span></p></body></html> - - - 1500 - + + + 1 + + + + + + + + + + Start Configuration Wizard + + + + + + + Run Calibration + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + + + + 0 + 0 + + + + + 0 + 70 + + + + TextLabel + + + true + + + + + + + + + + + + + + + + + + + Back + + + + + + + Next + + + + + + + Cancel + + + + + + + @@ -1243,14 +578,6 @@ Applies and Saves all settings to SD - ch0Assign - ch1Assign - ch2Assign - ch3Assign - ch4Assign - ch5Assign - ch6Assign - ch7Assign fmsSlider fmsModePos3 fmsSsPos3Roll @@ -1268,134 +595,5 @@ Applies and Saves all settings to SD - - - inSlider0 - valueChanged(int) - ch0Cur - setNum(int) - - - 291 - 93 - - - 150 - 104 - - - - - inSlider1 - valueChanged(int) - ch1Cur - setNum(int) - - - 283 - 137 - - - 160 - 138 - - - - - inSlider2 - valueChanged(int) - ch2Cur - setNum(int) - - - 341 - 163 - - - 156 - 167 - - - - - inSlider3 - valueChanged(int) - ch3Cur - setNum(int) - - - 283 - 211 - - - 159 - 210 - - - - - inSlider4 - valueChanged(int) - ch4Cur - setNum(int) - - - 287 - 239 - - - 156 - 242 - - - - - inSlider5 - valueChanged(int) - ch5Cur - setNum(int) - - - 309 - 272 - - - 164 - 276 - - - - - inSlider6 - valueChanged(int) - ch6Cur - setNum(int) - - - 282 - 300 - - - 144 - 311 - - - - - inSlider7 - valueChanged(int) - ch7Cur - setNum(int) - - - 278 - 339 - - - 168 - 340 - - - - + diff --git a/ground/openpilotgcs/src/plugins/config/inputchannelform.cpp b/ground/openpilotgcs/src/plugins/config/inputchannelform.cpp new file mode 100644 index 000000000..98f71ea31 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/config/inputchannelform.cpp @@ -0,0 +1,126 @@ +#include "inputchannelform.h" +#include "ui_inputchannelform.h" + +#include "manualcontrolsettings.h" + +inputChannelForm::inputChannelForm(QWidget *parent,bool showlegend) : + QWidget(parent), + ui(new Ui::inputChannelForm) +{ + ui->setupUi(this); + if(!showlegend) + { + layout()->removeWidget(ui->legend0); + layout()->removeWidget(ui->legend1); + layout()->removeWidget(ui->legend2); + layout()->removeWidget(ui->legend3); + layout()->removeWidget(ui->legend4); + layout()->removeWidget(ui->legend5); + delete ui->legend0; + delete ui->legend1; + delete ui->legend2; + delete ui->legend3; + delete ui->legend4; + delete ui->legend5; + } + + connect(ui->channelMin,SIGNAL(valueChanged(int)),this,SLOT(minMaxUpdated())); + connect(ui->channelMax,SIGNAL(valueChanged(int)),this,SLOT(minMaxUpdated())); + connect(ui->channelGroup,SIGNAL(currentIndexChanged(int)),this,SLOT(groupUpdated())); + connect(ui->channelNeutral,SIGNAL(valueChanged(int)), this, SLOT(neutralUpdated(int))); + + // This is awkward but since we want the UI to be a dropdown but the field is not an enum + // it breaks the UAUVObject widget relation of the task gadget. Running the data through + // a spin box fixes this + connect(ui->channelNumberDropdown,SIGNAL(currentIndexChanged(int)),this,SLOT(channelDropdownUpdated(int))); + connect(ui->channelNumber,SIGNAL(valueChanged(int)),this,SLOT(channelNumberUpdated(int))); +} + +inputChannelForm::~inputChannelForm() +{ + delete ui; +} + +/** + * Update the direction of the slider and boundaries + */ +void inputChannelForm::minMaxUpdated() +{ + bool reverse = ui->channelMin->value() > ui->channelMax->value(); + if(reverse) { + ui->channelNeutral->setMinimum(ui->channelMax->value()); + ui->channelNeutral->setMaximum(ui->channelMin->value()); + } else { + ui->channelNeutral->setMinimum(ui->channelMin->value()); + ui->channelNeutral->setMaximum(ui->channelMax->value()); + } + ui->channelRev->setChecked(reverse); + ui->channelNeutral->setInvertedAppearance(reverse); + ui->channelNeutral->setInvertedControls(reverse); +} + +void inputChannelForm::neutralUpdated(int newval) +{ + ui->neutral->setText(QString::number(newval)); +} + +/** + * Update the channel options based on the selected receiver type + * + * I fully admit this is terrible practice to embed data within UI + * like this. Open to suggestions. JC 2011-09-07 + */ +void inputChannelForm::groupUpdated() +{ + ui->channelNumberDropdown->clear(); + ui->channelNumberDropdown->addItem("Disabled"); + + quint8 count = 0; + + switch(ui->channelGroup->currentIndex()) { + case -1: // Nothing selected + count = 0; + break; + case ManualControlSettings::CHANNELGROUPS_PWM: + count = 8; // Need to make this 6 for CC + break; + case ManualControlSettings::CHANNELGROUPS_PPM: + case ManualControlSettings::CHANNELGROUPS_DSMMAINPORT: + case ManualControlSettings::CHANNELGROUPS_DSMFLEXIPORT: + count = 12; + break; + case ManualControlSettings::CHANNELGROUPS_SBUS: + count = 18; + break; + case ManualControlSettings::CHANNELGROUPS_GCS: + count = 5; + break; + case ManualControlSettings::CHANNELGROUPS_NONE: + count = 0; + break; + default: + Q_ASSERT(0); + } + + for (int i = 0; i < count; i++) + ui->channelNumberDropdown->addItem(QString(tr("Chan %1").arg(i+1))); + + ui->channelNumber->setMaximum(count); + ui->channelNumber->setMinimum(0); +} + +/** + * Update the dropdown from the hidden control + */ +void inputChannelForm::channelDropdownUpdated(int newval) +{ + ui->channelNumber->setValue(newval); +} + +/** + * Update the hidden control from the dropdown + */ +void inputChannelForm::channelNumberUpdated(int newval) +{ + ui->channelNumberDropdown->setCurrentIndex(newval); +} diff --git a/ground/openpilotgcs/src/plugins/config/inputchannelform.h b/ground/openpilotgcs/src/plugins/config/inputchannelform.h new file mode 100644 index 000000000..eb8ad7d18 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/config/inputchannelform.h @@ -0,0 +1,30 @@ +#ifndef INPUTCHANNELFORM_H +#define INPUTCHANNELFORM_H + +#include +#include "configinputwidget.h" +namespace Ui { + class inputChannelForm; +} + +class inputChannelForm : public QWidget +{ + Q_OBJECT + +public: + explicit inputChannelForm(QWidget *parent = 0,bool showlegend=false); + ~inputChannelForm(); + friend class ConfigInputWidget; + +private slots: + void minMaxUpdated(); + void neutralUpdated(int); + void groupUpdated(); + void channelDropdownUpdated(int); + void channelNumberUpdated(int); + +private: + Ui::inputChannelForm *ui; +}; + +#endif // INPUTCHANNELFORM_H diff --git a/ground/openpilotgcs/src/plugins/config/inputchannelform.ui b/ground/openpilotgcs/src/plugins/config/inputchannelform.ui new file mode 100644 index 000000000..044e2437f --- /dev/null +++ b/ground/openpilotgcs/src/plugins/config/inputchannelform.ui @@ -0,0 +1,272 @@ + + + inputChannelForm + + + + 0 + 0 + 543 + 49 + + + + Form + + + + 1 + + + 1 + + + 2 + + + 0 + + + + + + 0 + 0 + + + + + 70 + 0 + + + + TextLabel + + + + + + + + 6 + 0 + + + + + 100 + 16777215 + + + + + + + + QAbstractSpinBox::NoButtons + + + 9999 + + + 1000 + + + + + + + QAbstractSpinBox::NoButtons + + + 9999 + + + 1000 + + + + + + + true + + + Function + + + + + + + true + + + Number + + + + + + + true + + + Type + + + + + + + true + + + Max + + + + + + + true + + + Min + + + + + + + true + + + + 0 + 0 + + + + Neutral + + + + + + + + 0 + 0 + + + + Qt::Horizontal + + + + + + + + 4 + 0 + + + + + 80 + 16777215 + + + + 7 + + + + + + + true + + + + 0 + 0 + + + + + + + + false + + + Rev + + + + + + + + 0 + 0 + + + + + 30 + 0 + + + + + 30 + 16777215 + + + + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 20 + + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/config/output.ui b/ground/openpilotgcs/src/plugins/config/output.ui index 9c1fdacca..de87ef7eb 100644 --- a/ground/openpilotgcs/src/plugins/config/output.ui +++ b/ground/openpilotgcs/src/plugins/config/output.ui @@ -38,102 +38,6 @@ 2 - - - - false - - - Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes. -Leave at 50Hz for fixed wing. - - - 400 - - - - - - - - - - - Qt::AlignCenter - - - - - - - - - - - Qt::AlignCenter - - - - - - - - - - - Qt::AlignCenter - - - - - - - false - - - Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes. -Leave at 50Hz for fixed wing. - - - 400 - - - - - - - false - - - Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes. -Leave at 50Hz for fixed wing. - - - 400 - - - - - - - false - - - Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes. -Leave at 50Hz for fixed wing. - - - 400 - - - - - - - - - - - Qt::AlignCenter - - - @@ -206,750 +110,235 @@ Leave at 50Hz for fixed wing. + + + + false + + + Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes. +Leave at 50Hz for fixed wing. + + + + 50 + + + + + 60 + + + + + 125 + + + + + 165 + + + + + 270 + + + + + 330 + + + + + 400 + + + + + + + + false + + + Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes. +Leave at 50Hz for fixed wing. + + + + 50 + + + + + 60 + + + + + 125 + + + + + 165 + + + + + 270 + + + + + 330 + + + + + 400 + + + + + + + + false + + + Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes. +Leave at 50Hz for fixed wing. + + + + 50 + + + + + 60 + + + + + 125 + + + + + 165 + + + + + 270 + + + + + 330 + + + + + 400 + + + + + + + + false + + + Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes. +Leave at 50Hz for fixed wing. + + + + 50 + + + + + 60 + + + + + 125 + + + + + 165 + + + + + 270 + + + + + 330 + + + + + 400 + + + + + + + + - + + + Qt::AlignCenter + + + + + + + - + + + Qt::AlignCenter + + + + + + + - + + + Qt::AlignCenter + + + + + + + - + + + Qt::AlignCenter + + + - - - - - Channel 1: - - - - - - - true - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'Sans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Minimum PWM value, beware of not overdriving your servo.</p></body></html> - - - 9999 - - - - - - - true - - - 9999 - - - Qt::Horizontal - - - - - - - true - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'Sans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Maximum PWM value, beware of not overdriving your servo.</p></body></html> - - - 9999 - - - - - - - Current value of slider. - - - 0000 - - - - - - - - FreeSans - 8 - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html> - - - - - - - - - - Only used with Test Output mode - - - - - - - - - - Link - - - - - - - Rev. - - - - - - - Channel 2: - - - - - - - true - - - 9999 - - - - - - - true - - - 9999 - - - Qt::Horizontal - - - - - - - true - - - 9999 - - - - - - - 0000 - - - - - - - - FreeSans - 8 - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html> - - - - - - - - - - Only used with Test Output mode - - - - - - - - - - Channel 3: - - - - - - - true - - - 9999 - - - - - - - true - - - 9999 - - - Qt::Horizontal - - - - - - - true - - - 9999 - - - - - - - 0000 - - - - - - - - FreeSans - 8 - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html> - - - - - - - - - - Only used with Test Output mode - - - - - - - - - - Channel 4: - - - - - - - true - - - 9999 - - - - - - - true - - - 9999 - - - Qt::Horizontal - - - - - - - true - - - 9999 - - - - - - - 0000 - - - - - - - - FreeSans - 8 - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html> - - - - - - - - - - Only used with Test Output mode - - - - - - - - - - Channel 5: - - - - - - - 9999 - - - - - - - 9999 - - - Qt::Horizontal - - - - - - - 9999 - - - - - - - 0000 - - - - - - - - FreeSans - 8 - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html> - - - - - - - - - - Only used with Test Output mode - - - - - - - - - - Channel 6: - - - - - - - 9999 - - - - - - - 9999 - - - Qt::Horizontal - - - - - - - 9999 - - - - - - - 0000 - - - - - - - - FreeSans - 8 - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html> - - - - - - - - - - Only used with Test Output mode - - - - - - - - - - Channel 7: - - - - - - - Channel 8: - - - - - - - 9999 - - - - - - - 9999 - - - Qt::Horizontal - - - - - - - 9999 - - - - - - - 0000 - - - - - - - - FreeSans - 8 - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html> - - - - - - - - - - Only used with Test Output mode - - - - - - - - - - 9999 - - - - - - - 9999 - - - Qt::Horizontal - - - - - - - 9999 - - - - - - - 0000 - - - - - - - - FreeSans - 8 - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> -<html><head><meta name="qrichtext" content="1" /><style type="text/css"> -p, li { white-space: pre-wrap; } -</style></head><body style=" font-family:'FreeSans'; font-size:8pt; font-weight:400; font-style:normal;"> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Check to invert the channel.</p></body></html> - - - - - - - - - - Only used with Test Output mode - - - - - - - - - - - 9 - - - - - - - - Qt::AlignCenter - - - - - - - - 9 - - - - - - - - Qt::AlignCenter - - - - - - - - 9 - - - - - - - - Qt::AlignCenter - - - - - - - - 9 - - - - - - - - Qt::AlignCenter - - - - - - - - 9 - - - - - - - - Qt::AlignCenter - - - - - - - - 9 - - - - - - - - Qt::AlignCenter - - - - - - - - 9 - - - - - - - - Qt::AlignCenter - - - - - - - - 9 - - - - - - - - Qt::AlignCenter - - - - - - - Assignment - - - - + @@ -1090,50 +479,6 @@ Applies and Saves all settings to SD - outputRate1 - outputRate2 - outputRate3 - outputRate4 - ch0OutMin - ch0OutMax - ch1OutMin - ch1OutMax - ch2OutMin - ch2OutMax - ch3OutMin - ch3OutMax - ch4OutMin - ch4OutMax - ch5OutMin - ch5OutMax - ch6OutMin - ch6OutMax - ch7OutMin - ch7OutMax - ch0OutSlider - ch0Rev - ch0Link - ch1OutSlider - ch1Rev - ch1Link - ch2OutSlider - ch2Rev - ch2Link - ch3OutSlider - ch3Rev - ch3Link - ch4OutSlider - ch4Rev - ch4Link - ch5OutSlider - ch5Rev - ch5Link - ch6OutSlider - ch6Rev - ch6Link - ch7OutSlider - ch7Rev - ch7Link channelOutTest saveRCOutputToRAM saveRCOutputToSD diff --git a/ground/openpilotgcs/src/plugins/config/outputchannelform.cpp b/ground/openpilotgcs/src/plugins/config/outputchannelform.cpp new file mode 100644 index 000000000..131af2623 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/config/outputchannelform.cpp @@ -0,0 +1,297 @@ +/** + ****************************************************************************** + * + * @file outputchannelform.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup ConfigPlugin Config Plugin + * @{ + * @brief Servo output configuration form for the config output gadget + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "outputchannelform.h" +#include "configoutputwidget.h" + +OutputChannelForm::OutputChannelForm(const int index, QWidget *parent, const bool showLegend) : + QWidget(parent), + ui(), + m_index(index), + m_inChannelTest(false) +{ + ui.setupUi(this); + if(!showLegend) + { + // Remove legend + QGridLayout *grid_layout = dynamic_cast(layout()); + Q_ASSERT(grid_layout); + for (int col = 0; col < grid_layout->columnCount(); col++) + { // remove every item in first row + QLayoutItem *item = grid_layout->itemAtPosition(0, col); + if (!item) continue; + // get widget from layout item + QWidget *legend_widget = item->widget(); + if (!legend_widget) continue; + // delete widget + grid_layout->removeWidget(legend_widget); + delete legend_widget; + } + } + + // The convention for OP is Channel 1 to Channel 10. + ui.actuatorNumber->setText(QString("%1:").arg(m_index+1)); + + // Register for ActuatorSettings changes: + connect(ui.actuatorMin, SIGNAL(editingFinished()), + this, SLOT(setChannelRange())); + connect(ui.actuatorMax, SIGNAL(editingFinished()), + this, SLOT(setChannelRange())); + connect(ui.actuatorRev, SIGNAL(toggled(bool)), + this, SLOT(reverseChannel(bool))); + // Now connect the channel out sliders to our signal to send updates in test mode + connect(ui.actuatorNeutral, SIGNAL(valueChanged(int)), + this, SLOT(sendChannelTest(int))); + + ui.actuatorLink->setChecked(false); + connect(ui.actuatorLink, SIGNAL(toggled(bool)), + this, SLOT(linkToggled(bool))); +} + +OutputChannelForm::~OutputChannelForm() +{ + // Do nothing +} + +/** + * Restrict UI to protect users from accidental misuse. + */ +void OutputChannelForm::enableChannelTest(bool state) +{ + if (m_inChannelTest == state) return; + m_inChannelTest = state; + + if(m_inChannelTest) + { + // Prevent stupid users from touching the minimum & maximum ranges while + // moving the sliders. Thanks Ivan for the tip :) + ui.actuatorMin->setEnabled(false); + ui.actuatorMax->setEnabled(false); + ui.actuatorRev->setEnabled(false); + } + else + { + ui.actuatorMin->setEnabled(true); + ui.actuatorMax->setEnabled(true); + ui.actuatorRev->setEnabled(true); + } +} + + +/** + * Toggles the channel linked state for use in testing mode + */ +void OutputChannelForm::linkToggled(bool state) +{ + Q_UNUSED(state) + + if (!m_inChannelTest) + return; // we are not in Test Output mode + + // find the minimum slider value for the linked ones + if (!parent()) return; + int min = 10000; + int linked_count = 0; + QList outputChannelForms = parent()->findChildren(); + // set the linked channels of the parent widget to the same value + foreach(OutputChannelForm *outputChannelForm, outputChannelForms) + { + if (!outputChannelForm->ui.actuatorLink->checkState()) + continue; + if (this == outputChannelForm) + continue; + int value = outputChannelForm->ui.actuatorNeutral->value(); + if(min > value) min = value; + linked_count++; + } + + if (linked_count <= 0) + return; // no linked channels + + // set the linked channels to the same value + foreach(OutputChannelForm *outputChannelForm, outputChannelForms) + { + if (!outputChannelForm->ui.actuatorLink->checkState()) + continue; + outputChannelForm->ui.actuatorNeutral->setValue(min); + } +} + +/** + * Set maximal channel value. + */ +void OutputChannelForm::max(int maximum) +{ + minmax(ui.actuatorMin->value(), maximum); +} + +/** + * Set minimal channel value. + */ +void OutputChannelForm::min(int minimum) +{ + minmax(minimum, ui.actuatorMax->value()); +} + +/** + * Set minimal and maximal channel value. + */ +void OutputChannelForm::minmax(int minimum, int maximum) +{ + ui.actuatorMin->setValue(minimum); + ui.actuatorMax->setValue(maximum); + setChannelRange(); + if(ui.actuatorMin->value() > ui.actuatorMax->value()) + ui.actuatorRev->setChecked(true); + else + ui.actuatorRev->setChecked(false); +} + +/** + * Set neutral of channel. + */ +void OutputChannelForm::neutral(int value) +{ + ui.actuatorNeutral->setValue(value); +} + +/** + * Set the channel assignment label. + */ +void OutputChannelForm::setAssignment(const QString &assignment) +{ + ui.actuatorName->setText(assignment); +} + +/** + * Sets the minimum/maximum value of the channel output sliders. + * Have to do it here because setMinimum is not a slot. + * + * One added trick: if the slider is at its min when the value + * is changed, then keep it on the min. + */ +void OutputChannelForm::setChannelRange() +{ + int oldMini = ui.actuatorNeutral->minimum(); +// int oldMaxi = ui.actuatorNeutral->maximum(); + + if (ui.actuatorMin->value() < ui.actuatorMax->value()) + { + ui.actuatorNeutral->setRange(ui.actuatorMin->value(), ui.actuatorMax->value()); + ui.actuatorRev->setChecked(false); + } + else + { + ui.actuatorNeutral->setRange(ui.actuatorMax->value(), ui.actuatorMin->value()); + ui.actuatorRev->setChecked(true); + } + + if (ui.actuatorNeutral->value() == oldMini) + ui.actuatorNeutral->setValue(ui.actuatorNeutral->minimum()); + +// if (ui.actuatorNeutral->value() == oldMaxi) +// ui.actuatorNeutral->setValue(ui.actuatorNeutral->maximum()); // this can be dangerous if it happens to be controlling a motor at the time! +} + +/** + * Reverses the channel when the checkbox is clicked + */ +void OutputChannelForm::reverseChannel(bool state) +{ + // Sanity check: if state became true, make sure the Maxvalue was higher than Minvalue + // the situations below can happen! + if (state && (ui.actuatorMax->value() < ui.actuatorMin->value())) + return; + if (!state && (ui.actuatorMax->value() > ui.actuatorMin->value())) + return; + + // Now, swap the min & max values (only on the spinboxes, the slider + // does not change! + int temp = ui.actuatorMax->value(); + ui.actuatorMax->setValue(ui.actuatorMin->value()); + ui.actuatorMin->setValue(temp); + + // Also update the channel value + // This is a trick to force the slider to update its value and + // emit the right signal itself, because our sendChannelTest(int) method + // relies on the object sender's identity. + if (ui.actuatorNeutral->value() < ui.actuatorNeutral->maximum()) + { + ui.actuatorNeutral->setValue(ui.actuatorNeutral->value()+1); + ui.actuatorNeutral->setValue(ui.actuatorNeutral->value()-1); + } + else + { + ui.actuatorNeutral->setValue(ui.actuatorNeutral->value()-1); + ui.actuatorNeutral->setValue(ui.actuatorNeutral->value()+1); + } +} + +/** + * Emits the channel value which will be send to the UAV to move the servo. + * Returns immediately if we are not in testing mode. + */ +void OutputChannelForm::sendChannelTest(int value) +{ + int in_value = value; + + QSlider *ob = (QSlider *)QObject::sender(); + if (!ob) return; + + if (ui.actuatorRev->isChecked()) + value = ui.actuatorMin->value() - value + ui.actuatorMax->value(); // the channel is reversed + + // update the label + ui.actuatorValue->setText(QString::number(value)); + + if (ui.actuatorLink->checkState() && parent()) + { // the channel is linked to other channels + QList outputChannelForms = parent()->findChildren(); + // set the linked channels of the parent widget to the same value + foreach(OutputChannelForm *outputChannelForm, outputChannelForms) + { + if (this == outputChannelForm) continue; + if (!outputChannelForm->ui.actuatorLink->checkState()) continue; + + int val = in_value; + if (val < outputChannelForm->ui.actuatorNeutral->minimum()) + val = outputChannelForm->ui.actuatorNeutral->minimum(); + if (val > outputChannelForm->ui.actuatorNeutral->maximum()) + val = outputChannelForm->ui.actuatorNeutral->maximum(); + + if (outputChannelForm->ui.actuatorNeutral->value() == val) continue; + + outputChannelForm->ui.actuatorNeutral->setValue(val); + outputChannelForm->ui.actuatorValue->setText(QString::number(val)); + } + } + + if (!m_inChannelTest) + return; // we are not in Test Output mode + + emit channelChanged(index(), value); +} diff --git a/ground/openpilotgcs/src/plugins/config/outputchannelform.h b/ground/openpilotgcs/src/plugins/config/outputchannelform.h new file mode 100644 index 000000000..7d492dc1a --- /dev/null +++ b/ground/openpilotgcs/src/plugins/config/outputchannelform.h @@ -0,0 +1,92 @@ +/** + ****************************************************************************** + * + * @file outputchannelform.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup ConfigPlugin Config Plugin + * @{ + * @brief Servo output configuration form for the config output gadget + *****************************************************************************/ +/* + * 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 OUTPUTCHANNELFORM_H +#define OUTPUTCHANNELFORM_H + +#include +#include "ui_outputchannelform.h" + +class ConfigOnputWidget; + +class OutputChannelForm : public QWidget +{ + Q_OBJECT + +public: + explicit OutputChannelForm(const int index, QWidget *parent = NULL, const bool showLegend = false); + ~OutputChannelForm(); + friend class ConfigOnputWidget; + + void setAssignment(const QString &assignment); + int index() const; + +public slots: + void max(int maximum); + int max() const; + void min(int minimum); + int min() const; + void minmax(int minimum, int maximum); + void neutral(int value); + int neutral() const; + void enableChannelTest(bool state); + +signals: + void channelChanged(int index, int value); + +private: + Ui::outputChannelForm ui; + /// Channel index + int m_index; + bool m_inChannelTest; + +private slots: + void linkToggled(bool state); + void reverseChannel(bool state); + void sendChannelTest(int value); + void setChannelRange(); +}; + +inline int OutputChannelForm::index() const +{ + return m_index; +} + +inline int OutputChannelForm::max() const +{ + return ui.actuatorMax->value(); +} + +inline int OutputChannelForm::min() const +{ + return ui.actuatorMin->value(); +} + +inline int OutputChannelForm::neutral() const +{ + return ui.actuatorNeutral->value(); +} +#endif // OUTPUTCHANNELFORM_H diff --git a/ground/openpilotgcs/src/plugins/config/outputchannelform.ui b/ground/openpilotgcs/src/plugins/config/outputchannelform.ui new file mode 100644 index 000000000..cb1fd73f2 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/config/outputchannelform.ui @@ -0,0 +1,323 @@ + + + outputChannelForm + + + + 0 + 0 + 605 + 56 + + + + Form + + + + 1 + + + 1 + + + + + + 0 + 0 + + + + + 20 + 0 + + + + Channel Number + + + Qt::LeftToRight + + + TextLabel + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 90 + 0 + + + + TextLabel + + + Qt::AlignCenter + + + + + + + Minimum PWM value, beware of not overdriving your servo. + + + 9999 + + + + + + + Qt::Horizontal + + + QSizePolicy::Minimum + + + + 0 + 20 + + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + 9999 + + + Qt::Horizontal + + + + + + + Qt::Horizontal + + + QSizePolicy::Minimum + + + + 5 + 20 + + + + + + + + + 0 + 0 + + + + + 40 + 0 + + + + Check to invert the channel. + + + + + + + + 0 + 0 + + + + + 40 + 0 + + + + Output mode + + + + + + + Maximum PWM value, beware of not overdriving your servo. + + + 9999 + + + + + + + + 0 + 0 + + + + Assignment + + + + + + + + 0 + 0 + + + + Min + + + + + + + + 0 + 0 + + + + Neutral (slowest for motor) + + + + + + + + 0 + 0 + + + + Max + + + + + + + + 0 + 0 + + + + + 25 + 0 + + + + Rev. + + + + + + + + 0 + 0 + + + + + 25 + 0 + + + + Link + + + + + + + + 0 + 0 + + + + Current value of slider. + + + 0000 + + + + + + + + 0 + 0 + + + + + 20 + 0 + + + + Qt::LeftToRight + + + # + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/config/smartsavebutton.cpp b/ground/openpilotgcs/src/plugins/config/smartsavebutton.cpp index ed5abf2c7..69ddb9cb2 100644 --- a/ground/openpilotgcs/src/plugins/config/smartsavebutton.cpp +++ b/ground/openpilotgcs/src/plugins/config/smartsavebutton.cpp @@ -24,8 +24,11 @@ void smartSaveButton::processClick() bool error=false; ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); UAVObjectUtilManager* utilMngr = pm->getObject(); - foreach(UAVObject * obj,objects) + foreach(UAVDataObject * obj,objects) { + UAVObject::Metadata mdata= obj->getMetadata(); + if(mdata.gcsAccess==UAVObject::ACCESS_READONLY) + continue; up_result=false; current_object=obj; for(int i=0;i<3;++i) @@ -35,7 +38,9 @@ void smartSaveButton::processClick() connect(&timer,SIGNAL(timeout()),&loop,SLOT(quit())); obj->updated(); timer.start(1000); + //qDebug()<<"begin loop"; loop.exec(); + //qDebug()<<"end loop"; timer.stop(); disconnect(obj,SIGNAL(transactionCompleted(UAVObject*,bool)),this,SLOT(transaction_finished(UAVObject*, bool))); disconnect(&timer,SIGNAL(timeout()),&loop,SLOT(quit())); @@ -44,30 +49,33 @@ void smartSaveButton::processClick() } if(up_result==false) { + qDebug()<<"Object upload error:"<getName(); error=true; continue; } sv_result=false; current_objectID=obj->getObjID(); - if(save) + if(save && (obj->isSettings())) { - for(int i=0;i<3;++i) - { - connect(utilMngr,SIGNAL(saveCompleted(int,bool)),this,SLOT(saving_finished(int,bool))); - connect(&timer,SIGNAL(timeout()),&loop,SLOT(quit())); - utilMngr->saveObjectToSD(obj); - timer.start(1000); - loop.exec(); - timer.stop(); - disconnect(utilMngr,SIGNAL(saveCompleted(int,bool)),this,SLOT(saving_finished(int,bool))); - disconnect(&timer,SIGNAL(timeout()),&loop,SLOT(quit())); - if(sv_result) - break; - } - if(sv_result==false) - { - error=true; - } + for(int i=0;i<3;++i) + { + qDebug()<<"try to save:"<getName(); + connect(utilMngr,SIGNAL(saveCompleted(int,bool)),this,SLOT(saving_finished(int,bool))); + connect(&timer,SIGNAL(timeout()),&loop,SLOT(quit())); + utilMngr->saveObjectToSD(obj); + timer.start(1000); + loop.exec(); + timer.stop(); + disconnect(utilMngr,SIGNAL(saveCompleted(int,bool)),this,SLOT(saving_finished(int,bool))); + disconnect(&timer,SIGNAL(timeout()),&loop,SLOT(quit())); + if(sv_result) + break; + } + if(sv_result==false) + { + qDebug()<<"failed to save:"<getName(); + error=true; + } } } button->setEnabled(true); @@ -83,14 +91,15 @@ void smartSaveButton::processClick() emit endOp(); } -void smartSaveButton::setObjects(QList list) +void smartSaveButton::setObjects(QList list) { objects=list; } -void smartSaveButton::addObject(UAVObject * obj) +void smartSaveButton::addObject(UAVDataObject * obj) { - objects.append(obj); + if(!objects.contains(obj)) + objects.append(obj); } void smartSaveButton::clearObjects() @@ -111,6 +120,7 @@ void smartSaveButton::saving_finished(int id, bool result) if(id==current_objectID) { sv_result=result; + //qDebug()<<"saving_finished result="<); - void addObject(UAVObject *); + void setObjects(QList); + void addObject(UAVDataObject *); void clearObjects(); signals: void preProcessOperations(); @@ -34,11 +34,11 @@ private: QPushButton *bupdate; QPushButton *bsave; quint32 current_objectID; - UAVObject * current_object; + UAVDataObject * current_object; bool up_result; bool sv_result; QEventLoop loop; - QList objects; + QList objects; protected: public slots: void enableControls(bool value); diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index 96c414055..5c2de727e 100644 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -6,649 +6,689 @@ 0 0 - 639 - 611 + 683 + 685 Form - + - + - + 0 - 0 + 1 - - - 0 - 150 - + + QFrame::NoFrame - - Rate Stabilization Coefficients (Inner Loop) + + true - - - - - Kp - - - Qt::AlignCenter - - - - - - - Ki - - - Qt::AlignCenter - - - - - - - ILimit - - - Qt::AlignCenter - - - - - - - Roll - - - - - - - Slowly raise Kp until you start seeing clear oscillations when you fly. + + + + 0 + 0 + 665 + 627 + + + + + 0 + 0 + + + + + 0 + + + 0 + + + + + + 0 + 0 + + + + + 0 + 150 + + + + Rate Stabilization Coefficients (Inner Loop) + + + + + + Kp + + + Qt::AlignCenter + + + + + + + Ki + + + Qt::AlignCenter + + + + + + + ILimit + + + Qt::AlignCenter + + + + + + + Roll + + + + + + + Slowly raise Kp until you start seeing clear oscillations when you fly. Then lower the value by 20% or so. - - - 6 - - - 0.000100000000000 - - - - - - - I factor for rate stabilization is usually very low or even zero. - - - 6 - - - 0.000100000000000 - - - - - - - 6 - - - 0.000100000000000 - - - - - - - If checked, the Roll and Pitch factors will be identical. + + + 6 + + + 0.000100000000000 + + + + + + + I factor for rate stabilization is usually very low or even zero. + + + 6 + + + 0.000100000000000 + + + + + + + 6 + + + 0.000100000000000 + + + + + + + If checked, the Roll and Pitch factors will be identical. When you change one, the other is updated. - - - Link - - - - - - - Pitch - - - - - - - Slowly raise Kp until you start seeing clear oscillations when you fly. + + + Link + + + + + + + Pitch + + + + + + + Slowly raise Kp until you start seeing clear oscillations when you fly. Then lower the value by 20% or so. - - - 6 - - - 0.000100000000000 - - - - - - - I factor for rate stabilization is usually very low or even zero. - - - 6 - - - 0.000100000000000 - - - - - - - 6 - - - 0.000100000000000 - - - - - - - Yaw - - - - - - - Slowly raise Kp until you start seeing clear oscillations when you fly. + + + 6 + + + 0.000100000000000 + + + + + + + I factor for rate stabilization is usually very low or even zero. + + + 6 + + + 0.000100000000000 + + + + + + + 6 + + + 0.000100000000000 + + + + + + + Yaw + + + + + + + Slowly raise Kp until you start seeing clear oscillations when you fly. Then lower the value by 20% or so. You can usually go for higher values for Yaw factors. - - - 6 - - - 0.000100000000000 - - - - - - - As a rule of thumb, you can set YawRate Ki at roughly the same + + + 6 + + + 0.000100000000000 + + + + + + + As a rule of thumb, you can set YawRate Ki at roughly the same value as YawRate Kp. - - - 6 - - - 0.000100000000000 - - - - - - - 6 - - - 0.000100000000000 - - - - - - - - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 20 - 5 - - - - - - - - - 0 - 0 - - - - - 0 - 150 - - - - Attitude Stabization Coefficients (Outer Loop) - - - - - - Once Rate stabilization is done, you should increase the Kp factor until the airframe oscillates again, and go back down 20% or so. + + + 6 + + + 0.000100000000000 + + + + + + + 6 + + + 0.000100000000000 + + + + + + + + + + Qt::Vertical + + + QSizePolicy::Fixed + + + + 20 + 13 + + + + + + + + + 0 + 0 + + + + + 0 + 150 + + + + Attitude Stabization Coefficients (Outer Loop) + + + + + + Once Rate stabilization is done, you should increase the Kp factor until the airframe oscillates again, and go back down 20% or so. - - - 6 - - - 0.100000000000000 - - - - - - - Ki can usually be almost identical to Kp. - - - 6 - - - 0.100000000000000 - - - - - - - ILimit can be equal to three to four times Ki, but you can adjust + + + 6 + + + 0.100000000000000 + + + + + + + Ki can usually be almost identical to Kp. + + + 6 + + + 0.100000000000000 + + + + + + + ILimit can be equal to three to four times Ki, but you can adjust depending on whether your airframe is well balanced, and your flying style. - - - 6 - - - 0.100000000000000 - - - - - - - Kp - - - Qt::AlignCenter - - - - - - - Ki - - - Qt::AlignCenter - - - - - - - ILimit - - - Qt::AlignCenter - - - - - - - ILimit can be equal to three to four times Ki, but you can adjust + + + 6 + + + 0.100000000000000 + + + + + + + Kp + + + Qt::AlignCenter + + + + + + + Ki + + + Qt::AlignCenter + + + + + + + ILimit + + + Qt::AlignCenter + + + + + + + ILimit can be equal to three to four times Ki, but you can adjust depending on whether your airframe is well balanced, and your flying style. - - - 6 - - - 0.100000000000000 - - - - - - - Ki can usually be almost identical to Kp. - - - 6 - - - 0.100000000000000 - - - - - - - Once Rate stabilization is done, you should increase the Kp factor until the airframe oscillates again, and go back down 20% or so. + + + 6 + + + 0.100000000000000 + + + + + + + Ki can usually be almost identical to Kp. + + + 6 + + + 0.100000000000000 + + + + + + + Once Rate stabilization is done, you should increase the Kp factor until the airframe oscillates again, and go back down 20% or so. - - - 6 - - - 0.100000000000000 - - - - - - - Once Rate stabilization is done, you should increase the Kp factor until the airframe oscillates again, and go back down 20% or so. + + + 6 + + + 0.100000000000000 + + + + + + + Once Rate stabilization is done, you should increase the Kp factor until the airframe oscillates again, and go back down 20% or so. - - - 6 - - - 0.100000000000000 - - - - - - - Yaw - - - - - - - Pitch - - - - - - - Roll - - - - - - - Ki can usually be almost identical to Kp. - - - 6 - - - 0.100000000000000 - - - - - - - ILimit can be equal to three to four times Ki, but you can adjust + + + 6 + + + 0.100000000000000 + + + + + + + Yaw + + + + + + + Pitch + + + + + + + Roll + + + + + + + Ki can usually be almost identical to Kp. + + + 6 + + + 0.100000000000000 + + + + + + + ILimit can be equal to three to four times Ki, but you can adjust depending on whether your airframe is well balanced, and your flying style. - - - 6 - - - 0.100000000000000 - - - - - - - If checked, the Roll and Pitch factors will be identical. + + + 6 + + + 0.100000000000000 + + + + + + + If checked, the Roll and Pitch factors will be identical. When you change one, the other is updated. - - - Link - - - - + + + Link + + + + + + + + + + Qt::Vertical + + + QSizePolicy::Fixed + + + + 20 + 13 + + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + Stick range and limits + + + + QLayout::SetMinAndMaxSize + + + + + Roll + + + Qt::AlignCenter + + + + + + + Pitch + + + Qt::AlignCenter + + + + + + + Yaw + + + Qt::AlignCenter + + + + + + + 180 + + + + + + + 180 + + + + + + + 180 + + + + + + + + 150 + 0 + + + + + 50 + false + + + + Full stick angle (deg) + + + + + + + + 150 + 0 + + + + + 50 + false + + + + Full stick rate (deg/s) + + + + + + + 500 + + + + + + + 500 + + + + + + + 500 + + + + + + + + 150 + 0 + + + + + 50 + false + + + + + + + Maximum rate in attitude mode (deg/s) + + + + + + + 500 + + + + + + + 500 + + + + + + + 500 + + + + + + + + + + Zero the integral when throttle is low + + + + + + + Qt::Vertical + + + + 20 + 0 + + + + + + - - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 20 - 5 - - - - - - - - - 0 - 0 - - - - - 0 - 0 - - - - Stick range and limits - - - - QLayout::SetMinAndMaxSize - - - - - Roll - - - Qt::AlignCenter - - - - - - - Pitch - - - Qt::AlignCenter - - - - - - - Yaw - - - Qt::AlignCenter - - - - - - - 180 - - - - - - - 180 - - - - - - - 180 - - - - - - - - 150 - 0 - - - - - 50 - false - - - - Full stick angle (deg) - - - - - - - - 150 - 0 - - - - - 50 - false - - - - Full stick rate (deg/s) - - - - - - - 300 - - - - - - - 300 - - - - - - - 300 - - - - - - - - 150 - 0 - - - - - 50 - false - - - - - - - Maximum rate in attitude mode (deg/s) - - - - - - - 300 - - - - - - - 300 - - - - - - - 300 - - - - - - - - - - Zero the integral when throttle is low - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - diff --git a/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml b/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml index 9847730e8..fb6187949 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml +++ b/ground/openpilotgcs/src/plugins/coreplugin/OpenPilotGCS.xml @@ -995,7 +995,7 @@ 0.0.0 - %%DATAPATH%%dials/default/lineardial-vertical.svg + %%DATAPATH%%dials/deluxe/lineardial-vertical.svg 0 1 Andale Mono,12,-1,5,75,0,0,0,0,0 @@ -1018,7 +1018,7 @@ 0.0.0 - %%DATAPATH%%dials/default/lineardial-horizontal.svg + %%DATAPATH%%dials/deluxe/lineardial-horizontal.svg 2 1 Andale Mono,8,-1,5,50,0,0,0,0,0 @@ -1041,7 +1041,7 @@ 0.0.0 - %%DATAPATH%%dials/default/lineardial-horizontal.svg + %%DATAPATH%%dials/deluxe/lineardial-horizontal.svg 2 1 Andale Mono,6,-1,5,50,0,0,0,0,0 @@ -1064,7 +1064,7 @@ 0.0.0 - %%DATAPATH%%dials/default/lineardial-horizontal.svg + %%DATAPATH%%dials/deluxe/lineardial-horizontal.svg 2 1 Andale Mono,8,-1,5,50,0,0,0,0,0 @@ -1202,7 +1202,7 @@ 0.0.0 - %%DATAPATH%%dials/default/lineardial-vertical.svg + %%DATAPATH%%dials/deluxe/lineardial-vertical.svg 0 1 Andale Mono,12,-1,5,75,0,0,0,0,0 @@ -1225,7 +1225,7 @@ 0.0.0 - %%DATAPATH%%dials/default/lineardial-vertical.svg + %%DATAPATH%%dials/deluxe/lineardial-vertical.svg 2 1 Andale Mono,12,-1,5,75,0,0,0,0,0 @@ -1248,7 +1248,7 @@ 0.0.0 - %%DATAPATH%%dials/default/lineardial-vertical.svg + %%DATAPATH%%dials/deluxe/lineardial-vertical.svg 2 1 Andale Mono,12,-1,5,75,0,0,0,0,0 @@ -1271,7 +1271,7 @@ 0.0.0 - %%DATAPATH%%dials/default/lineardial-vertical.svg + %%DATAPATH%%dials/deluxe/lineardial-vertical.svg 2 1 Andale Mono,12,-1,5,75,0,0,0,0,0 @@ -1294,7 +1294,7 @@ 0.0.0 - %%DATAPATH%%dials/default/lineardial-vertical.svg + %%DATAPATH%%dials/deluxe/lineardial-vertical.svg 2 1 Andale Mono,12,-1,5,75,0,0,0,0,0 @@ -1317,7 +1317,7 @@ 0.0.0 - %%DATAPATH%%dials/default/lineardial-vertical.svg + %%DATAPATH%%dials/deluxe/lineardial-vertical.svg 2 1 Andale Mono,12,-1,5,75,0,0,0,0,0 @@ -1340,7 +1340,7 @@ 0.0.0 - %%DATAPATH%%dials/default/lineardial-horizontal.svg + %%DATAPATH%%dials/deluxe/lineardial-horizontal.svg 0 1 Andale Mono,12,-1,5,75,0,0,0,0,0 @@ -1363,7 +1363,7 @@ 0.0.0 - %%DATAPATH%%dials/default/lineardial-horizontal.svg + %%DATAPATH%%dials/deluxe/lineardial-horizontal.svg 0 1 Andale Mono,12,-1,5,75,0,0,0,0,0 @@ -1386,7 +1386,7 @@ 0.0.0 - %%DATAPATH%%dials/default/lineardial-vertical.svg + %%DATAPATH%%dials/deluxe/lineardial-vertical.svg 2 1 Andale Mono,12,-1,5,75,0,0,0,0,0 @@ -1409,7 +1409,7 @@ 0.0.0 - %%DATAPATH%%dials/default/lineardial-vertical.svg + %%DATAPATH%%dials/deluxe/lineardial-vertical.svg 2 1 Andale Mono,12,-1,5,75,0,0,0,0,0 @@ -1432,7 +1432,7 @@ 0.0.0 - %%DATAPATH%%dials/default/lineardial-vertical.svg + %%DATAPATH%%dials/deluxe/lineardial-vertical.svg 2 1 Andale Mono,12,-1,5,75,0,0,0,0,0 @@ -1627,6 +1627,17 @@ false + + + false + 0.0.0 + + + %%DATAPATH%%models/multi/ricoo/ricoo.3DS + %%DATAPATH%%models/backgrounds/default_background.png + false + + false diff --git a/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.cpp b/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.cpp index f63c6e7da..9dfa46518 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.cpp +++ b/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.cpp @@ -358,7 +358,10 @@ void ConnectionManager::devChanged(IConnection *connection) if(m_mainWindow->generalSettings()->autoConnect() || m_mainWindow->generalSettings()->autoSelect()) m_availableDevList->setCurrentIndex(m_availableDevList->count()-1); if(m_mainWindow->generalSettings()->autoConnect()) + { connectDevice(); + qDebug()<<"ConnectionManager::devChanged autoconnected USB device"; + } } } if(m_ioDev)//if a device is connected make it the one selected on the dropbox diff --git a/ground/openpilotgcs/src/plugins/coreplugin/mainwindow.cpp b/ground/openpilotgcs/src/plugins/coreplugin/mainwindow.cpp index a2b8137f4..1849b4e8b 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/mainwindow.cpp +++ b/ground/openpilotgcs/src/plugins/coreplugin/mainwindow.cpp @@ -179,6 +179,8 @@ MainWindow::MainWindow() : m_modeStack->setIconSize(QSize(24,24)); m_modeStack->setTabPosition(QTabWidget::South); m_modeStack->setMovable(false); + m_modeStack->setMinimumWidth(512); + m_modeStack->setElideMode(Qt::ElideRight); #ifndef Q_WS_MAC m_modeStack->setDocumentMode(true); #endif diff --git a/ground/openpilotgcs/src/plugins/coreplugin/manhattanstyle.cpp b/ground/openpilotgcs/src/plugins/coreplugin/manhattanstyle.cpp index 4b00525c4..cec350d99 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/manhattanstyle.cpp +++ b/ground/openpilotgcs/src/plugins/coreplugin/manhattanstyle.cpp @@ -55,6 +55,7 @@ #include #include #include +#include // We define a currently unused state for indicating animations #define State_Animating 0x00000040 @@ -217,7 +218,35 @@ QRect ManhattanStyle::subControlRect(ComplexControl control, const QStyleOptionC SubControl subControl, const QWidget *widget) const { QRect rect; +#ifndef Q_WS_MACX + // Not using OSX, size combo dropdown to fit contents + if(control == CC_ComboBox && subControl == SC_ComboBoxListBoxPopup) + { + const QStyleOptionComboBox *cb = qstyleoption_cast(option); + const QComboBox* combo = qobject_cast(widget); + QRect comboRect = cb->rect; + int newWidth = combo->view()->sizeHintForColumn(0); + if(newWidth > comboRect.width()) + { + // Set new rectangle, only width matters, list height is set by + // combination of number of combo box items and setMaxVisibleItems + rect.setRect(comboRect.x(), comboRect.y(), newWidth, comboRect.height()); + rect = visualRect(cb->direction, cb->rect, rect); + } + else + { + rect = d->style->subControlRect(control, option, subControl, widget); + } + } + else + { + rect = d->style->subControlRect(control, option, subControl, widget); + } +#else + // Using OSX, use default style behaviour as this already sizes the + // combo dropdown to fit rect = d->style->subControlRect(control, option, subControl, widget); +#endif return rect; } diff --git a/ground/openpilotgcs/src/plugins/debuggadget/DebugGadget.pluginspec b/ground/openpilotgcs/src/plugins/debuggadget/DebugGadget.pluginspec new file mode 100644 index 000000000..05cea6931 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/debuggadget/DebugGadget.pluginspec @@ -0,0 +1,10 @@ + + The OpenPilot Project + (C) 2010 OpenPilot Project + The GNU Public License (GPL) Version 3 + An debug gadget + http://www.openpilot.org + + + + diff --git a/ground/openpilotgcs/src/plugins/debuggadget/debug.ui b/ground/openpilotgcs/src/plugins/debuggadget/debug.ui new file mode 100644 index 000000000..72adcb7ee --- /dev/null +++ b/ground/openpilotgcs/src/plugins/debuggadget/debug.ui @@ -0,0 +1,31 @@ + + + Form + + + + 0 + 0 + 400 + 300 + + + + Form + + + + + + Save to file + + + + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/debuggadget/debugengine.cpp b/ground/openpilotgcs/src/plugins/debuggadget/debugengine.cpp new file mode 100644 index 000000000..48ec18525 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/debuggadget/debugengine.cpp @@ -0,0 +1,13 @@ +#include "debugengine.h" +debugengine::debugengine() +{ +} + +void debugengine::writeToStdErr(const QString &level, const QList &msgs) +{ + emit dbgMsgError(level,msgs); +} +void debugengine::writeToStdOut(const QString &level, const QList &msgs) +{ + emit dbgMsg(level,msgs); +} diff --git a/ground/openpilotgcs/src/plugins/debuggadget/debugengine.h b/ground/openpilotgcs/src/plugins/debuggadget/debugengine.h new file mode 100644 index 000000000..5452f7590 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/debuggadget/debugengine.h @@ -0,0 +1,18 @@ +#ifndef DEBUGENGINE_H +#define DEBUGENGINE_H +#include "qxtbasicstdloggerengine.h" +#include +class debugengine:public QObject,public QxtBasicSTDLoggerEngine +{ + Q_OBJECT +public: + debugengine(); +protected: + void writeToStdErr ( const QString & level, const QList & msgs ); + void writeToStdOut ( const QString & level, const QList & msgs ); +signals: + void dbgMsgError( const QString & level, const QList & msgs ); + void dbgMsg( const QString & level, const QList & msgs ); +}; + +#endif // DEBUGENGINE_H diff --git a/ground/openpilotgcs/src/plugins/debuggadget/debuggadget.cpp b/ground/openpilotgcs/src/plugins/debuggadget/debuggadget.cpp new file mode 100644 index 000000000..05c147c03 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/debuggadget/debuggadget.cpp @@ -0,0 +1,39 @@ +/** + ****************************************************************************** + * + * @file debuggadget.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup DebugGadgetPlugin Debug Gadget Plugin + * @{ + * @brief A place holder gadget plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#include "debuggadget.h" +#include "debuggadgetwidget.h" + +DebugGadget::DebugGadget(QString classId, DebugGadgetWidget *widget, QWidget *parent) : + IUAVGadget(classId, parent), + m_widget(widget) +{ +} + +DebugGadget::~DebugGadget() +{ + delete m_widget; +} diff --git a/ground/openpilotgcs/src/plugins/debuggadget/debuggadget.h b/ground/openpilotgcs/src/plugins/debuggadget/debuggadget.h new file mode 100644 index 000000000..b39f8b5b5 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/debuggadget/debuggadget.h @@ -0,0 +1,59 @@ +/** + ****************************************************************************** + * + * @file debuggadget.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup DebugGadgetPlugin Debug Gadget Plugin + * @{ + * @brief A place holder gadget plugin + *****************************************************************************/ +/* + * 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 DEBUGGADGET_H_ +#define DEBUGGADGET_H_ + +#include + +namespace Core { +class IUAVGadget; +} +//class QWidget; +//class QString; +class DebugGadgetWidget; + +using namespace Core; + +class DebugGadget : public Core::IUAVGadget +{ + Q_OBJECT +public: + DebugGadget(QString classId, DebugGadgetWidget *widget, QWidget *parent = 0); + ~DebugGadget(); + + QList context() const { return m_context; } + QWidget *widget() { return m_widget; } + QString contextHelpId() const { return QString(); } + +private: + QWidget *m_widget; + QList m_context; +}; + + +#endif // DEBUGGADGET_H_ diff --git a/ground/openpilotgcs/src/plugins/debuggadget/debuggadget.pro b/ground/openpilotgcs/src/plugins/debuggadget/debuggadget.pro new file mode 100644 index 000000000..a45db6697 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/debuggadget/debuggadget.pro @@ -0,0 +1,21 @@ +TEMPLATE = lib +TARGET = DebugGadget + +include(../../openpilotgcsplugin.pri) +include(../../plugins/coreplugin/coreplugin.pri) +include(../../libs/libqxt/core/logengines.pri) +HEADERS += debugplugin.h \ + debugengine.h +HEADERS += debuggadget.h +HEADERS += debuggadgetwidget.h +HEADERS += debuggadgetfactory.h +SOURCES += debugplugin.cpp \ + debugengine.cpp +SOURCES += debuggadget.cpp +SOURCES += debuggadgetfactory.cpp +SOURCES += debuggadgetwidget.cpp + +OTHER_FILES += DebugGadget.pluginspec + +FORMS += \ + debug.ui diff --git a/ground/openpilotgcs/src/plugins/debuggadget/debuggadgetfactory.cpp b/ground/openpilotgcs/src/plugins/debuggadget/debuggadgetfactory.cpp new file mode 100644 index 000000000..f7d925b39 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/debuggadget/debuggadgetfactory.cpp @@ -0,0 +1,47 @@ +/** + ****************************************************************************** + * + * @file debuggadgetfactory.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup DebugGadgetPlugin Debug Gadget Plugin + * @{ + * @brief A place holder gadget plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#include "debuggadgetfactory.h" +#include "debuggadgetwidget.h" +#include "debuggadget.h" +#include + +DebugGadgetFactory::DebugGadgetFactory(QObject *parent) : + IUAVGadgetFactory(QString("DebugGadget"), + tr("DebugGadget"), + parent) +{ +} + +DebugGadgetFactory::~DebugGadgetFactory() +{ + +} + +IUAVGadget* DebugGadgetFactory::createGadget(QWidget *parent) { + DebugGadgetWidget* gadgetWidget = new DebugGadgetWidget(parent); + return new DebugGadget(QString("DebugGadget"), gadgetWidget, parent); +} diff --git a/ground/openpilotgcs/src/plugins/debuggadget/debuggadgetfactory.h b/ground/openpilotgcs/src/plugins/debuggadget/debuggadgetfactory.h new file mode 100644 index 000000000..186fca5f6 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/debuggadget/debuggadgetfactory.h @@ -0,0 +1,50 @@ +/** + ****************************************************************************** + * + * @file debuggadgetfactory.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup DebugGadgetPlugin Debug Gadget Plugin + * @{ + * @brief A place holder gadget plugin + *****************************************************************************/ +/* + * 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 DEBUGGADGETFACTORY_H_ +#define DEBUGGADGETFACTORY_H_ + +#include + +namespace Core { +class IUAVGadget; +class IUAVGadgetFactory; +} + +using namespace Core; + +class DebugGadgetFactory : public IUAVGadgetFactory +{ + Q_OBJECT +public: + DebugGadgetFactory(QObject *parent = 0); + ~DebugGadgetFactory(); + + IUAVGadget *createGadget(QWidget *parent); +}; + +#endif // DEBUGGADGETFACTORY_H_ diff --git a/ground/openpilotgcs/src/plugins/debuggadget/debuggadgetwidget.cpp b/ground/openpilotgcs/src/plugins/debuggadget/debuggadgetwidget.cpp new file mode 100644 index 000000000..34043c806 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/debuggadget/debuggadgetwidget.cpp @@ -0,0 +1,96 @@ +/** + ****************************************************************************** + * + * @file debuggadgetwidget.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup DebugGadgetPlugin Debug Gadget Plugin + * @{ + * @brief A place holder gadget plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#include "debuggadgetwidget.h" + +#include +#include +#include +#include +#include +#include +#include "qxtlogger.h" +#include "debugengine.h" +#include +#include +#include +#include +#include +DebugGadgetWidget::DebugGadgetWidget(QWidget *parent) : QLabel(parent) +{ + m_config = new Ui_Form(); + m_config->setupUi(this); + debugengine * de=new debugengine(); + QxtLogger::getInstance()->addLoggerEngine("debugplugin", de); + connect(de,SIGNAL(dbgMsg(QString,QList)),this,SLOT(dbgMsg(QString,QList))); + connect(de,SIGNAL(dbgMsgError(QString,QList)),this,SLOT(dbgMsgError(QString,QList))); + connect(m_config->pushButton,SIGNAL(clicked()),this,SLOT(saveLog())); +} + +DebugGadgetWidget::~DebugGadgetWidget() +{ + // Do nothing +} + +void DebugGadgetWidget::dbgMsg(const QString &level, const QList &msgs) +{ + m_config->plainTextEdit->setTextColor(Qt::red); + + m_config->plainTextEdit->append(QString("%2[%0]%1").arg(level).arg(msgs[0].toString()).arg(QTime::currentTime().toString())); + + QScrollBar *sb = m_config->plainTextEdit->verticalScrollBar(); + sb->setValue(sb->maximum()); +} + +void DebugGadgetWidget::dbgMsgError(const QString &level, const QList &msgs) +{ + m_config->plainTextEdit->setTextColor(Qt::black); + + + m_config->plainTextEdit->append(QString("%2[%0]%1").arg(level).arg(msgs[0].toString()).arg(QTime::currentTime().toString())); + + QScrollBar *sb = m_config->plainTextEdit->verticalScrollBar(); + sb->setValue(sb->maximum()); +} +void DebugGadgetWidget::saveLog() +{ + QString fileName = QFileDialog::getSaveFileName(0, tr("Save log File As"), ""); + if (fileName.isEmpty()) { + return; + } + + QFile file(fileName); + if (file.open(QIODevice::WriteOnly) && + (file.write(m_config->plainTextEdit->toHtml().toAscii()) != -1)) { + file.close(); + } else { + QMessageBox::critical(0, + tr("Log Save"), + tr("Unable to save log: ") + fileName, + QMessageBox::Ok); + return; + } +} diff --git a/ground/openpilotgcs/src/plugins/debuggadget/debuggadgetwidget.h b/ground/openpilotgcs/src/plugins/debuggadget/debuggadgetwidget.h new file mode 100644 index 000000000..ed71f73c2 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/debuggadget/debuggadgetwidget.h @@ -0,0 +1,49 @@ +/** + ****************************************************************************** + * + * @file debuggadgetwidget.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup DebugGadgetPlugin Debug Gadget Plugin + * @{ + * @brief A place holder gadget plugin + *****************************************************************************/ +/* + * 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 DEBUGGADGETWIDGET_H_ +#define DEBUGGADGETWIDGET_H_ + +#include +#include "ui_debug.h" +class DebugGadgetWidget : public QLabel +{ + Q_OBJECT + +public: + DebugGadgetWidget(QWidget *parent = 0); + ~DebugGadgetWidget(); + +private: + Ui_Form *m_config; +private slots: + void saveLog(); + void dbgMsgError( const QString & level, const QList & msgs ); + void dbgMsg( const QString & level, const QList & msgs ); +}; + +#endif /* DEBUGGADGETWIDGET_H_ */ diff --git a/ground/openpilotgcs/src/plugins/debuggadget/debugplugin.cpp b/ground/openpilotgcs/src/plugins/debuggadget/debugplugin.cpp new file mode 100644 index 000000000..f83395ef7 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/debuggadget/debugplugin.cpp @@ -0,0 +1,65 @@ +/** + ****************************************************************************** + * + * @file debugplugin.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup DebugGadgetPlugin Debug Gadget Plugin + * @{ + * @brief A place holder gadget plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#include "debugplugin.h" +#include "debuggadgetfactory.h" +#include +#include +#include +#include + + +DebugPlugin::DebugPlugin() +{ + // Do nothing +} + +DebugPlugin::~DebugPlugin() +{ + // Do nothing +} + +bool DebugPlugin::initialize(const QStringList& args, QString *errMsg) +{ + Q_UNUSED(args); + Q_UNUSED(errMsg); + mf = new DebugGadgetFactory(this); + addAutoReleasedObject(mf); + + return true; +} + +void DebugPlugin::extensionsInitialized() +{ + // Do nothing +} + +void DebugPlugin::shutdown() +{ + // Do nothing +} +Q_EXPORT_PLUGIN(DebugPlugin) + diff --git a/ground/openpilotgcs/src/plugins/debuggadget/debugplugin.h b/ground/openpilotgcs/src/plugins/debuggadget/debugplugin.h new file mode 100644 index 000000000..9cdbefd02 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/debuggadget/debugplugin.h @@ -0,0 +1,47 @@ +/** + ****************************************************************************** + * + * @file debugplugin.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup DebugGadgetPlugin Debug Gadget Plugin + * @{ + * @brief A place holder gadget plugin + *****************************************************************************/ +/* + * 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 DEBUGPLUGIN_H_ +#define DEBUGPLUGIN_H_ + +#include + +class DebugGadgetFactory; + +class DebugPlugin : public ExtensionSystem::IPlugin +{ +public: + DebugPlugin(); + ~DebugPlugin(); + + void extensionsInitialized(); + bool initialize(const QStringList & arguments, QString * errorString); + void shutdown(); +private: + DebugGadgetFactory *mf; +}; +#endif /* DEBUGPLUGIN_H_ */ diff --git a/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrol.ui b/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrol.ui index fdcac0346..024db71bb 100644 --- a/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrol.ui +++ b/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrol.ui @@ -1,134 +1,142 @@ - - - GCSControl - - - - 0 - 0 - 653 - 295 - - - - - 0 - 0 - - - - Form - - - - 2 - - - 5 - - - - - - - - - GCS Control - - - - - - - Armed - - - - - - - Flight Mode: - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - - - - - - - 10 - - - 0 - - - - - - 0 - 0 - - - - - 100 - 100 - - - - false - - - - - - - - 0 - 0 - - - - - 100 - 100 - - - - - - - - Qt::Vertical - - - - 2 - 40 - - - - - - - - - - - JoystickControl - QWidget -

joystickcontrol.h
- 1 - - - - - + + + GCSControl + + + + 0 + 0 + 653 + 295 + + + + + 0 + 0 + + + + Form + + + + + + + 2 + + + 5 + + + + + + + + + + GCS Control + + + + + + + Armed + + + + + + + Flight Mode: + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + + + + + 10 + + + 0 + + + + + + 0 + 0 + + + + + 100 + 100 + + + + false + + + background:transparent + + + + + + + Qt::Vertical + + + + 2 + 40 + + + + + + + + + 0 + 0 + + + + + 100 + 100 + + + + background:transparent + + + + + + + + + + JoystickControl + QWidget +
joystickcontrol.h
+ 1 +
+
+ + +
diff --git a/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrolgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrolgadgetwidget.cpp index d266ec18b..68f0162f5 100644 --- a/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrolgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrolgadgetwidget.cpp @@ -67,7 +67,6 @@ GCSControlGadgetWidget::GCSControlGadgetWidget(QWidget *parent) : QLabel(parent) // Connect object updated event from UAVObject to also update check boxes and dropdown connect(obj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(mccChanged(UAVObject*))); - leftX = 0; leftY = 0; rightX = 0; diff --git a/ground/openpilotgcs/src/plugins/gcscontrol/images/joystick.svg b/ground/openpilotgcs/src/plugins/gcscontrol/images/joystick.svg index 729a48476..386881587 100644 --- a/ground/openpilotgcs/src/plugins/gcscontrol/images/joystick.svg +++ b/ground/openpilotgcs/src/plugins/gcscontrol/images/joystick.svg @@ -1,5 +1,5 @@ - + image/svg+xml + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - image/svg+xml - - - - - - - - - - - - - - - - - - - - - - - - - - - - + xlink:href="data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAEAAAABACAYAAACqaXHeAAAACXBIWXMAAAsSAAALEgHS3X78AAAA BGdBTUEAAK/INwWK6QAAABl0RVh0U29mdHdhcmUAQWRvYmUgSW1hZ2VSZWFkeXHJZTwAAAYeSURB VHja7FuLjts2ECQlSn4k6f9/Z5OzrSdbA2KxmMwuSdlO7poTQEhnnyzPcHa5D9q5z+PPPvw7fl78 PxDwzM+PH4UAX/l3Cdj4KjL8i4Cza7+DgEgAx2cS4V8E3Bdc470ILMJ1KSm/lACvAC8ZGgGxcjxE gn/SrONoyLkxiGDAV3Fe4bV07RR1FB/hSbOOQHG0QEIDBEgAKxkLeY2Zga8lIjwAHmdcgtVGel+S 4BTwS2Z4UAYSEZ9NAAPPgAcyWnFGNSABEuSsjEb8zwr3+xoSwoPgE5gErtuuOzIkIegTIhCQgE7K SO/77f/ddm8DJDxFARZ4OeMJaK8MSYRUgRMA5MzfgY5iDNu53d5jK8oiSHAlRNQoQAOfgB02oPfz cTvLIUlohS/wYP8I/g78tt1/2545iO+SjhnMoMgfhMrljoHvBcg78NM2juKMJEhf4Ij8pw1kAn+/ 9wo+BRWEx1pCQtjp9BB8AnoW4yTOR0FAL0CgAhYx+4mA6zZ6YUKNEsPIOMKXBEmhUPoNgA9C9kcB 9gsMSUZSAfqBdCyCgGmb+ZsgD++zgqgoVBAtfxAqIj0pf5z9O8ivYnwDEk4GEGco4E7AJTP7LHiS KjCDo1Dh+BqwfTn7XwTwv7bzV0FCIqAHAjQTkApg4PEeFj02xP5/UkGoiPOZ4zsK6SMBiYQzIaA1 CJg3BRwM6UcSMc4QRK3EH1SZgDfk34H8JQGoAukDegiGPIkD0ipwAIcpzQXjBRYtrmJJ3LUKOMMB ogLOYP/fhB84g/13xJFFADbB/6GvmJVgadxeCyQocswMQoX8W2X5OwEJuBIw+28UBSQVhAx4XCrT YObiLWcYdjpADH7OyjgR+SMwzAVWkjBp4G8iUOqVUNtbdY+wYwkMIqBJBBwh+juJ17Uv55UgZiEz huBv5PPxGUwFcc8yyBSAKjiQHACToM5IhZ2xdiezOMDqcDDA52b/PzJyJuAKkqAevkivpMAtOFRX kLRIAjojw+zgOa1RglN9gC8MhVkK3GW+EJbIWHU4fTHp9Fql0NIVgm9ydc9QEANoRZCWVHoCKYE1 hkfOZZ5amS0o5TZGcLUTtFTAzIFdNwZ4TXExU2ZnBdbcs7JV72ZHm6u29u8ywGsLsCW9huJyf+P+ 8CNHQDQKDnu7NqU1+z2dIkee/XBRNCpdGZl14bWWn+eaF9HoC5Y2TLRJKFaAxfBKQM+ZlLT0i0UD MOsVLAXPyioiKF6Yzf6aqduPSu0+rRArEB+VslYOOHs2koK9xGoTYAyyuv0ENfsRiOiM2N8rLfGV gJ6M1JeRoKmuKheIpPLCgA9Qwj5Caop5f0vWfGZmk6gOjaRPMADxk6KCaDn3oLzpM7MykpT0uoG/ FhQwG6UgEmHmB/KMq/j7ZpDAVFBtApoCRvhyF6WGh1mdVRBhdcFBAL8IAi5AxLBDBZSAaMwKI+AK LbFcyXs2/MIK5a4RwL+JcRFDI+BhH8Bq7jOZnYvS82PgWVHUE/nLwkcC/+Pf8X07/9hekyYxgjNc lVUglpqA5gMm0aAMRr8OKzlaXdARApJNJ4BvG/jvgoQ3QYJmArHWBHJmMBu7QFjTAk2mN1pj2BgZ gICkgL+FCqQvGAQB66NOEFWwiv57AsXS0FwN71BIAJrYRYBORLyBD0jEWQ4w1qwC2lLYiA0KjVHD QyAH0huwOkOD4gRR/tIJSvuPe02AqUDuuJiVHDwaBFwr2uPSB9yECq6wAjAHyHICt7c5ioVKaQqz siFBA3Eg5XFW91+M2v9VCYRGJRQuyghLFIDyzoXNKGNri0yj9AYx2pThL4bBJdHfbhNg8lkNAhZC gLZJqjVaY1rfbxQOz4r8Vle4e7S0IOINEnIhs7VNrlEIWJy9TU4Cn2vtfq8CNBKi0a+fXH6jpM98 BhsS+LKnElRLgEWClThpW2VZc0RKd1EKIlrZDTdPF9cea/cKs5XBKxnk4so3S7PaIwO6OH33+K6t 8+95u7y2VX7NVIR3A3mEiN/1gwn3CPhnEKB1fV7xkxlnzPZv+8lMjghNJTVNEefe+Y+mSvqJtc/8 kD+be/Xnf5gfTj7redF9Hp/Hy49/BBgApEegBA3kNcsAAAAASUVORK5CYII=" + transform="translate(1,1)" + id="image41" + style="opacity:0.75"> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 50 % + + 75 % + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 75 % + + 50 % + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/ground/openpilotgcs/src/plugins/logging/logfile.cpp b/ground/openpilotgcs/src/plugins/logging/logfile.cpp index f02bce22a..7a74d6367 100644 --- a/ground/openpilotgcs/src/plugins/logging/logfile.cpp +++ b/ground/openpilotgcs/src/plugins/logging/logfile.cpp @@ -88,9 +88,12 @@ void LogFile::timerFired() if(file.bytesAvailable() > 4) { - // TODO: going back in time will be a problem - while ((myTime.elapsed() - timeOffset) * playbackSpeed > lastTimeStamp) { + int time; + time = myTime.elapsed(); + // TODO: going back in time will be a problem + while ((lastPlayed + ((time - timeOffset)* playbackSpeed) > lastTimeStamp)) { + lastPlayed += ((time - timeOffset)* playbackSpeed); if(file.bytesAvailable() < 4) { stopReplay(); return; @@ -98,6 +101,11 @@ void LogFile::timerFired() file.read((char *) &dataSize, sizeof(dataSize)); + if (dataSize<1 || dataSize>(1024*1024)) { + qDebug() << "Error: Logfile corrupted! Unlikely packet size: " << dataSize << "\n"; + stopReplay(); + return; + } if(file.bytesAvailable() < dataSize) { stopReplay(); return; @@ -113,7 +121,19 @@ void LogFile::timerFired() return; } + int save=lastTimeStamp; file.read((char *) &lastTimeStamp,sizeof(lastTimeStamp)); + // some validity checks + if (lastTimeStamp (60*60*1000)) { // gap of more than 60 minutes) + qDebug() << "Error: Logfile corrupted! Unlikely timestamp " << lastTimeStamp << " after "<< save << "\n"; + stopReplay(); + return; + } + + timeOffset = time; + time = myTime.elapsed(); + } } else { stopReplay(); @@ -125,6 +145,7 @@ bool LogFile::startReplay() { dataBuffer.clear(); myTime.restart(); timeOffset = 0; + lastPlayed = 0; playbackSpeed = 1; file.read((char *) &lastTimeStamp,sizeof(lastTimeStamp)); timer.setInterval(10); @@ -142,12 +163,11 @@ bool LogFile::stopReplay() { void LogFile::pauseReplay() { timer.stop(); - pausedTime = myTime.elapsed(); } void LogFile::resumeReplay() { - timeOffset += myTime.elapsed() - pausedTime; + timeOffset = myTime.elapsed(); timer.start(); } diff --git a/ground/openpilotgcs/src/plugins/logging/logfile.h b/ground/openpilotgcs/src/plugins/logging/logfile.h index 861249e4a..a07e1832a 100644 --- a/ground/openpilotgcs/src/plugins/logging/logfile.h +++ b/ground/openpilotgcs/src/plugins/logging/logfile.h @@ -27,7 +27,7 @@ public: bool stopReplay(); public slots: - void setReplaySpeed(double val) { playbackSpeed = pow(10,(val)/100); qDebug() << playbackSpeed; }; + void setReplaySpeed(double val) { playbackSpeed = val; qDebug() << playbackSpeed; }; void pauseReplay(); void resumeReplay(); @@ -45,11 +45,11 @@ protected: QTime myTime; QFile file; qint32 lastTimeStamp; + qint32 lastPlayed; QMutex mutex; int timeOffset; - int pausedTime; double playbackSpeed; }; diff --git a/ground/openpilotgcs/src/plugins/pfd/pfdgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/pfd/pfdgadgetwidget.cpp index 079a206b5..072c54be3 100644 --- a/ground/openpilotgcs/src/plugins/pfd/pfdgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/pfd/pfdgadgetwidget.cpp @@ -27,6 +27,7 @@ #include "pfdgadgetwidget.h" #include +#include #include #include #include @@ -73,6 +74,7 @@ PFDGadgetWidget::PFDGadgetWidget(QWidget *parent) : QGraphicsView(parent) connect(&skyDialTimer, SIGNAL(timeout()), this, SLOT(moveSky())); skyDialTimer.start(30); + } PFDGadgetWidget::~PFDGadgetWidget() @@ -81,6 +83,14 @@ PFDGadgetWidget::~PFDGadgetWidget() dialTimer.stop(); } +void PFDGadgetWidget::setToolTipPrivate() +{ + static qint32 updateRate=0; + UAVObject::Metadata mdata=attitudeObj->getMetadata(); + if(mdata.flightTelemetryUpdatePeriod!=updateRate) + this->setToolTip("Current refresh rate:"+QString::number(mdata.flightTelemetryUpdatePeriod)+" miliseconds"+"\nIf you want to change it please edit the AttitudeActual metadata on the object browser."); +} + /*! \brief Enables/Disables OpenGL */ @@ -173,7 +183,6 @@ void PFDGadgetWidget::connectNeedles() { qDebug() << "Error: Object is unknown (FlightBatteryState)."; } } - } @@ -228,6 +237,7 @@ void PFDGadgetWidget::updateLinkStatus(UAVObject *object1) { Resolution is 1 degree roll & 1/7.5 degree pitch. */ void PFDGadgetWidget::updateAttitude(UAVObject *object1) { + setToolTipPrivate(); UAVObjectField * rollField = object1->getField(QString("Roll")); UAVObjectField * yawField = object1->getField(QString("Yaw")); UAVObjectField * pitchField = object1->getField(QString("Pitch")); @@ -383,7 +393,7 @@ void PFDGadgetWidget::setDialFile(QString dfn) - Battery stats: battery-txt */ l_scene->clear(); // Deletes all items contained in the scene as well. - m_background = new QGraphicsSvgItem(); + m_background = new CachedSvgItem(); // All other items will be clipped to the shape of the background m_background->setFlags(QGraphicsItem::ItemClipsChildrenToShape| QGraphicsItem::ItemClipsToShape); @@ -391,28 +401,28 @@ void PFDGadgetWidget::setDialFile(QString dfn) m_background->setElementId("background"); l_scene->addItem(m_background); - m_world = new QGraphicsSvgItem(); + m_world = new CachedSvgItem(); m_world->setParentItem(m_background); m_world->setSharedRenderer(m_renderer); m_world->setElementId("world"); l_scene->addItem(m_world); // red Roll scale: rollscale - m_rollscale = new QGraphicsSvgItem(); + m_rollscale = new CachedSvgItem(); m_rollscale->setSharedRenderer(m_renderer); m_rollscale->setElementId("rollscale"); l_scene->addItem(m_rollscale); // Home point: - m_homewaypoint = new QGraphicsSvgItem(); + m_homewaypoint = new CachedSvgItem(); // Next point: - m_nextwaypoint = new QGraphicsSvgItem(); + m_nextwaypoint = new CachedSvgItem(); // Home point bearing: - m_homepointbearing = new QGraphicsSvgItem(); + m_homepointbearing = new CachedSvgItem(); // Next point bearing: - m_nextpointbearing = new QGraphicsSvgItem(); + m_nextpointbearing = new CachedSvgItem(); - QGraphicsSvgItem *m_foreground = new QGraphicsSvgItem(); + QGraphicsSvgItem *m_foreground = new CachedSvgItem(); m_foreground->setParentItem(m_background); m_foreground->setSharedRenderer(m_renderer); m_foreground->setElementId("foreground"); @@ -429,7 +439,7 @@ void PFDGadgetWidget::setDialFile(QString dfn) // into a QGraphicsSvgItem which we will display at the same // place: we do this so that the heading scale can be clipped to // the compass dial region. - m_compass = new QGraphicsSvgItem(); + m_compass = new CachedSvgItem(); m_compass->setSharedRenderer(m_renderer); m_compass->setElementId("compass"); m_compass->setFlags(QGraphicsItem::ItemClipsChildrenToShape| @@ -440,7 +450,7 @@ void PFDGadgetWidget::setDialFile(QString dfn) m_compass->setTransform(matrix,false); // Now place the compass scale inside: - m_compassband = new QGraphicsSvgItem(); + m_compassband = new CachedSvgItem(); m_compassband->setSharedRenderer(m_renderer); m_compassband->setElementId("compass-band"); m_compassband->setParentItem(m_compass); @@ -462,7 +472,7 @@ void PFDGadgetWidget::setDialFile(QString dfn) compassMatrix = m_renderer->matrixForElement("speed-bg"); startX = compassMatrix.mapRect(m_renderer->boundsOnElement("speed-bg")).x(); startY = compassMatrix.mapRect(m_renderer->boundsOnElement("speed-bg")).y(); - QGraphicsSvgItem *verticalbg = new QGraphicsSvgItem(); + QGraphicsSvgItem *verticalbg = new CachedSvgItem(); verticalbg->setSharedRenderer(m_renderer); verticalbg->setElementId("speed-bg"); verticalbg->setFlags(QGraphicsItem::ItemClipsChildrenToShape| @@ -477,7 +487,7 @@ void PFDGadgetWidget::setDialFile(QString dfn) m_speedscale = new QGraphicsItemGroup(); m_speedscale->setParentItem(verticalbg); - QGraphicsSvgItem *speedscalelines = new QGraphicsSvgItem(); + QGraphicsSvgItem *speedscalelines = new CachedSvgItem(); speedscalelines->setSharedRenderer(m_renderer); speedscalelines->setElementId("speed-scale"); speedScaleHeight = m_renderer->matrixForElement("speed-scale").mapRect( @@ -523,7 +533,7 @@ void PFDGadgetWidget::setDialFile(QString dfn) startX = compassMatrix.mapRect(m_renderer->boundsOnElement("speed-window")).x(); startY = compassMatrix.mapRect(m_renderer->boundsOnElement("speed-window")).y(); qreal speedWindowHeight = compassMatrix.mapRect(m_renderer->boundsOnElement("speed-window")).height(); - QGraphicsSvgItem *speedwindow = new QGraphicsSvgItem(); + QGraphicsSvgItem *speedwindow = new CachedSvgItem(); speedwindow->setSharedRenderer(m_renderer); speedwindow->setElementId("speed-window"); speedwindow->setFlags(QGraphicsItem::ItemClipsChildrenToShape| @@ -548,7 +558,7 @@ void PFDGadgetWidget::setDialFile(QString dfn) compassMatrix = m_renderer->matrixForElement("altitude-bg"); startX = compassMatrix.mapRect(m_renderer->boundsOnElement("altitude-bg")).x(); startY = compassMatrix.mapRect(m_renderer->boundsOnElement("altitude-bg")).y(); - verticalbg = new QGraphicsSvgItem(); + verticalbg = new CachedSvgItem(); verticalbg->setSharedRenderer(m_renderer); verticalbg->setElementId("altitude-bg"); verticalbg->setFlags(QGraphicsItem::ItemClipsChildrenToShape| @@ -563,7 +573,7 @@ void PFDGadgetWidget::setDialFile(QString dfn) m_altitudescale = new QGraphicsItemGroup(); m_altitudescale->setParentItem(verticalbg); - QGraphicsSvgItem *altitudescalelines = new QGraphicsSvgItem(); + QGraphicsSvgItem *altitudescalelines = new CachedSvgItem(); altitudescalelines->setSharedRenderer(m_renderer); altitudescalelines->setElementId("altitude-scale"); altitudeScaleHeight = m_renderer->matrixForElement("altitude-scale").mapRect( @@ -604,7 +614,7 @@ void PFDGadgetWidget::setDialFile(QString dfn) startX = compassMatrix.mapRect(m_renderer->boundsOnElement("altitude-window")).x(); startY = compassMatrix.mapRect(m_renderer->boundsOnElement("altitude-window")).y(); qreal altitudeWindowHeight = compassMatrix.mapRect(m_renderer->boundsOnElement("altitude-window")).height(); - QGraphicsSvgItem *altitudewindow = new QGraphicsSvgItem(); + QGraphicsSvgItem *altitudewindow = new CachedSvgItem(); altitudewindow->setSharedRenderer(m_renderer); altitudewindow->setElementId("altitude-window"); altitudewindow->setFlags(QGraphicsItem::ItemClipsChildrenToShape| @@ -633,7 +643,7 @@ void PFDGadgetWidget::setDialFile(QString dfn) compassMatrix = m_renderer->matrixForElement("gcstelemetry-Disconnected"); startX = compassMatrix.mapRect(m_renderer->boundsOnElement("gcstelemetry-Disconnected")).x(); startY = compassMatrix.mapRect(m_renderer->boundsOnElement("gcstelemetry-Disconnected")).y(); - gcsTelemetryArrow = new QGraphicsSvgItem(); + gcsTelemetryArrow = new CachedSvgItem(); gcsTelemetryArrow->setSharedRenderer(m_renderer); gcsTelemetryArrow->setElementId("gcstelemetry-Disconnected"); l_scene->addItem(gcsTelemetryArrow); @@ -669,7 +679,7 @@ void PFDGadgetWidget::setDialFile(QString dfn) compassMatrix = m_renderer->matrixForElement("gcstelemetry-Disconnected"); startX = compassMatrix.mapRect(m_renderer->boundsOnElement("gcstelemetry-Disconnected")).x(); startY = compassMatrix.mapRect(m_renderer->boundsOnElement("gcstelemetry-Disconnected")).y(); - gcsTelemetryArrow = new QGraphicsSvgItem(); + gcsTelemetryArrow = new CachedSvgItem(); gcsTelemetryArrow->setSharedRenderer(m_renderer); gcsTelemetryArrow->setElementId("gcstelemetry-Disconnected"); l_scene->addItem(gcsTelemetryArrow); @@ -702,7 +712,7 @@ void PFDGadgetWidget::setDialFile(QString dfn) compassMatrix = m_renderer->matrixForElement("gcstelemetry-Disconnected"); startX = compassMatrix.mapRect(m_renderer->boundsOnElement("gcstelemetry-Disconnected")).x(); startY = compassMatrix.mapRect(m_renderer->boundsOnElement("gcstelemetry-Disconnected")).y(); - gcsTelemetryArrow = new QGraphicsSvgItem(); + gcsTelemetryArrow = new CachedSvgItem(); gcsTelemetryArrow->setSharedRenderer(m_renderer); gcsTelemetryArrow->setElementId("gcstelemetry-Disconnected"); l_scene->addItem(gcsTelemetryArrow); @@ -771,7 +781,7 @@ void PFDGadgetWidget::setDialFile(QString dfn) { qDebug()<<"Error on PFD artwork file."; m_renderer->load(QString(":/pfd/images/pfd-default.svg")); l_scene->clear(); // This also deletes all items contained in the scene. - m_background = new QGraphicsSvgItem(); + m_background = new CachedSvgItem(); m_background->setSharedRenderer(m_renderer); l_scene->addItem(m_background); pfdError = true; diff --git a/ground/openpilotgcs/src/plugins/pfd/pfdgadgetwidget.h b/ground/openpilotgcs/src/plugins/pfd/pfdgadgetwidget.h index b7aff7d25..553a07ef9 100644 --- a/ground/openpilotgcs/src/plugins/pfd/pfdgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/pfd/pfdgadgetwidget.h @@ -54,6 +54,7 @@ public: void setHqFonts(bool flag) { hqFonts = flag; } void enableSmoothUpdates(bool flag) { beSmooth = flag; } + public slots: void updateAttitude(UAVObject *object1); void updateHeading(UAVObject *object1); @@ -72,7 +73,7 @@ private slots: void moveNeedles(); void moveVerticalScales(); void moveSky(); - + void setToolTipPrivate(); private: QSvgRenderer *m_renderer; diff --git a/ground/openpilotgcs/src/plugins/plugins.pro b/ground/openpilotgcs/src/plugins/plugins.pro index 7a86f53be..9012582e6 100644 --- a/ground/openpilotgcs/src/plugins/plugins.pro +++ b/ground/openpilotgcs/src/plugins/plugins.pro @@ -19,6 +19,11 @@ plugin_emptygadget.subdir = emptygadget plugin_emptygadget.depends = plugin_coreplugin SUBDIRS += plugin_emptygadget +# Debug Gadget plugin +plugin_debuggadget.subdir = debuggadget +plugin_debuggadget.depends = plugin_coreplugin +SUBDIRS += plugin_debuggadget + # Welcome plugin plugin_welcome.subdir = welcome plugin_welcome.depends = plugin_coreplugin @@ -107,6 +112,7 @@ SUBDIRS += plugin_systemhealth plugin_config.subdir = config plugin_config.depends = plugin_coreplugin plugin_config.depends += plugin_uavobjects +plugin_config.depends += plugin_uavsettingsimportexport SUBDIRS += plugin_config #GPS Display gadget diff --git a/ground/openpilotgcs/src/plugins/rawhid/pjrc_rawhid.h b/ground/openpilotgcs/src/plugins/rawhid/pjrc_rawhid.h index b8e2459a2..3ff096db5 100644 --- a/ground/openpilotgcs/src/plugins/rawhid/pjrc_rawhid.h +++ b/ground/openpilotgcs/src/plugins/rawhid/pjrc_rawhid.h @@ -37,7 +37,6 @@ #if defined( Q_OS_MAC) -// todo: #elif defined(Q_OS_UNIX) //#elif defined(Q_OS_LINUX) @@ -104,10 +103,12 @@ public: void mytest(int num); signals: void deviceUnplugged(int);//just to make pips changes compile -private: #if defined( Q_OS_MAC) - // todo: +#endif + +private: +#if defined( Q_OS_MAC) #elif defined(Q_OS_UNIX) //#elif defined(Q_OS_LINUX) diff --git a/ground/openpilotgcs/src/plugins/rawhid/pjrc_rawhid_mac.cpp b/ground/openpilotgcs/src/plugins/rawhid/pjrc_rawhid_mac.cpp index 34c78fa8f..382c43829 100644 --- a/ground/openpilotgcs/src/plugins/rawhid/pjrc_rawhid_mac.cpp +++ b/ground/openpilotgcs/src/plugins/rawhid/pjrc_rawhid_mac.cpp @@ -44,6 +44,18 @@ #include #include #include +#include +#include +#include + +class delay : public QThread +{ +public: + static void msleep(unsigned long msecs) + { + QThread::msleep(msecs); + } +}; #define BUFFER_SIZE 64 @@ -54,6 +66,8 @@ typedef struct hid_struct hid_t; typedef struct buffer_struct buffer_t; static hid_t *first_hid = NULL; static hid_t *last_hid = NULL; +// Make sure we use the correct runloop +CFRunLoopRef the_correct_runloop = NULL; struct hid_struct { IOHIDDeviceRef ref; int open; @@ -75,9 +89,10 @@ static void free_all_hid(void); static void hid_close(hid_t *); static void attach_callback(void *, IOReturn, void *, IOHIDDeviceRef); static void detach_callback(void *, IOReturn, void *hid_mgr, IOHIDDeviceRef dev); -static void timeout_callback(CFRunLoopTimerRef, void *); static void input_callback(void *, IOReturn, void *, IOHIDReportType, uint32_t, uint8_t *, CFIndex); static void output_callback(hid_t *context, IOReturn ret, void *sender, IOHIDReportType type, uint32_t id, uint8_t *data, CFIndex len); +static void timeout_callback(CFRunLoopTimerRef, void *); + pjrc_rawhid::pjrc_rawhid() { @@ -164,6 +179,8 @@ int pjrc_rawhid::open(int max, int vid, int pid, int usage_page, int usage) CFRelease(hid_manager); return 0; } + // Set the run loop reference: + the_correct_runloop = CFRunLoopGetCurrent(); printf("run loop\n"); // let it do the callback for all devices while (CFRunLoopRunInMode(kCFRunLoopDefaultMode, 0, true) == kCFRunLoopRunHandledSource) ; @@ -183,47 +200,56 @@ int pjrc_rawhid::open(int max, int vid, int pid, int usage_page, int usage) // int pjrc_rawhid::receive(int num, void *buf, int len, int timeout) { - hid_t *hid; - buffer_t *b; - CFRunLoopTimerRef timer=NULL; - CFRunLoopTimerContext context; - int ret=0, timeout_occurred=0; + hid_t *hid; + buffer_t *b; + CFRunLoopTimerRef timer=NULL; + CFRunLoopTimerContext context; + int ret=0, timeout_occurred=0; - if (len < 1) return 0; - hid = get_hid(num); - if (!hid || !hid->open) return -1; - if ((b = hid->first_buffer) != NULL) { - if (len > b->len) len = b->len; - memcpy(buf, b->buf, len); - hid->first_buffer = b->next; - free(b); - return len; - } - memset(&context, 0, sizeof(context)); - context.info = &timeout_occurred; - timer = CFRunLoopTimerCreate(NULL, CFAbsoluteTimeGetCurrent() + - (double)timeout / 1000.0, 0, 0, 0, timeout_callback, &context); - CFRunLoopAddTimer(CFRunLoopGetCurrent(), timer, kCFRunLoopDefaultMode); - while (1) { - CFRunLoopRun(); - if ((b = hid->first_buffer) != NULL) { - if (len > b->len) len = b->len; - memcpy(buf, b->buf, len); - hid->first_buffer = b->next; - free(b); - ret = len; + if (len < 1) return 0; + hid = get_hid(num); + if (!hid || !hid->open) return -1; + if ((b = hid->first_buffer) != NULL) { + if (len > b->len) len = b->len; + memcpy(buf, b->buf, len); + hid->first_buffer = b->next; + free(b); + return len; + } + memset(&context, 0, sizeof(context)); + context.info = &timeout_occurred; + timer = CFRunLoopTimerCreate(NULL, CFAbsoluteTimeGetCurrent() + + (double)timeout / 1000.0, 0, 0, 0, timeout_callback, &context); + CFRunLoopAddTimer(CFRunLoopGetCurrent(), timer, kCFRunLoopDefaultMode); + the_correct_runloop = CFRunLoopGetCurrent(); + //qDebug("--"); + while (1) { + //qDebug("."); + CFRunLoopRun(); // Found the problem: somehow the input_callback does not + // stop this CFRunLoopRun because it is hooked to a different run loop !!! + // Hence the use of the "correct_runloop" variable above. + //qDebug(" .."); + + if ((b = hid->first_buffer) != NULL) { + if (len > b->len) len = b->len; + memcpy(buf, b->buf, len); + hid->first_buffer = b->next; + free(b); + ret = len; + //qDebug("*************"); + break; + } + if (!hid->open) { + printf("pjrc_rawhid_recv, device not open\n"); + ret = -1; + break; + } + if (timeout_occurred) break; - } - if (!hid->open) { - printf("pjrc_rawhid_recv, device not open\n"); - ret = -1; - break; - } - if (timeout_occurred) break; - } - CFRunLoopTimerInvalidate(timer); - CFRelease(timer); - return ret; + } + CFRunLoopTimerInvalidate(timer); + CFRelease(timer); + return ret; } // send - send a packet @@ -335,10 +361,11 @@ static void input_callback(void *context, IOReturn ret, void *sender, IOHIDRepor buffer_t *n; hid_t *hid; - printf("input_callback, report id: %i buf: %x %x, len: %d\n", id, data[0], data[1], len); + //qDebug("input_callback, ret: %i - report id: %i buf: %x %x, len: %d\n", ret, id, data[0], data[1], len); if (ret != kIOReturnSuccess || len < 1) return; hid = (hid_t*)context; if (!hid || hid->ref != sender) return; + printf("Processing packet"); n = (buffer_t *)malloc(sizeof(buffer_t)); if (!n) return; if (len > BUFFER_SIZE) len = BUFFER_SIZE; @@ -352,14 +379,16 @@ static void input_callback(void *context, IOReturn ret, void *sender, IOHIDRepor hid->last_buffer->next = n; hid->last_buffer = n; } - CFRunLoopStop(CFRunLoopGetCurrent()); + //qDebug() << "Stop CFRunLoop from input_callback" << CFRunLoopGetCurrent(); + CFRunLoopStop(the_correct_runloop); } static void timeout_callback(CFRunLoopTimerRef timer, void *info) { - printf("timeout_callback\n"); - *(int *)info = 1; - CFRunLoopStop(CFRunLoopGetCurrent()); + //qDebug("timeout_callback\n"); + *(int *)info = 1; + //qDebug() << "Stop CFRunLoop from timeout_callback" << CFRunLoopGetCurrent(); + CFRunLoopStop(CFRunLoopGetCurrent()); } static void add_hid(hid_t *h) diff --git a/ground/openpilotgcs/src/plugins/rawhid/rawhid.pro b/ground/openpilotgcs/src/plugins/rawhid/rawhid.pro index 4a3557982..f857ef72a 100644 --- a/ground/openpilotgcs/src/plugins/rawhid/rawhid.pro +++ b/ground/openpilotgcs/src/plugins/rawhid/rawhid.pro @@ -7,9 +7,11 @@ HEADERS += rawhid_global.h \ rawhid.h \ pjrc_rawhid.h \ rawhid_const.h \ - usbmonitor.h + usbmonitor.h \ + usbsignalfilter.h SOURCES += rawhidplugin.cpp \ - rawhid.cpp + rawhid.cpp \ + usbsignalfilter.cpp FORMS += RESOURCES += DEFINES += RAWHID_LIBRARY diff --git a/ground/openpilotgcs/src/plugins/rawhid/rawhidplugin.h b/ground/openpilotgcs/src/plugins/rawhid/rawhidplugin.h index 0bbeac524..ee9aa49aa 100644 --- a/ground/openpilotgcs/src/plugins/rawhid/rawhidplugin.h +++ b/ground/openpilotgcs/src/plugins/rawhid/rawhidplugin.h @@ -31,7 +31,7 @@ #include "rawhid_global.h" #include "rawhid.h" #include "usbmonitor.h" - +#include "usbsignalfilter.h" #include "coreplugin/iconnection.h" #include diff --git a/ground/openpilotgcs/src/plugins/rawhid/usbmonitor.h b/ground/openpilotgcs/src/plugins/rawhid/usbmonitor.h index 1d8eea087..fd114042f 100644 --- a/ground/openpilotgcs/src/plugins/rawhid/usbmonitor.h +++ b/ground/openpilotgcs/src/plugins/rawhid/usbmonitor.h @@ -202,5 +202,4 @@ private: #endif }; - #endif // USBMONITOR_H diff --git a/ground/openpilotgcs/src/plugins/rawhid/usbmonitor_mac.cpp b/ground/openpilotgcs/src/plugins/rawhid/usbmonitor_mac.cpp index e094a9a68..51fd6cce7 100644 --- a/ground/openpilotgcs/src/plugins/rawhid/usbmonitor_mac.cpp +++ b/ground/openpilotgcs/src/plugins/rawhid/usbmonitor_mac.cpp @@ -117,7 +117,7 @@ void USBMonitor::removeDevice(IOHIDDeviceRef dev) { */ void USBMonitor::detach_callback(void *context, IOReturn r, void *hid_mgr, IOHIDDeviceRef dev) { - + qDebug() << "USBMonitor: Device detached event"; instance()->removeDevice(dev); } @@ -136,6 +136,8 @@ void USBMonitor::attach_callback(void *context, IOReturn r, void *hid_mgr, IOHID deviceInfo.dev_handle = dev; + qDebug() << "USBMonitor: Device attached event"; + // Populate the device info structure got_properties &= HID_GetIntProperty(dev, CFSTR( kIOHIDVendorIDKey ), &deviceInfo.vendorID); got_properties &= HID_GetIntProperty(dev, CFSTR( kIOHIDProductIDKey ), &deviceInfo.productID); @@ -149,6 +151,7 @@ void USBMonitor::attach_callback(void *context, IOReturn r, void *hid_mgr, IOHID // Currently only enumerating objects that have the complete list of properties if(got_properties) { + qDebug() << "USBMonitor: Adding device"; instance()->addDevice(deviceInfo); } } diff --git a/ground/openpilotgcs/src/plugins/rawhid/usbmonitor_win.cpp b/ground/openpilotgcs/src/plugins/rawhid/usbmonitor_win.cpp index 4eded8e7c..aa653179a 100644 --- a/ground/openpilotgcs/src/plugins/rawhid/usbmonitor_win.cpp +++ b/ground/openpilotgcs/src/plugins/rawhid/usbmonitor_win.cpp @@ -28,7 +28,8 @@ #include #include #include - +#include +#include #include "usbmonitor.h" #include #define printf qDebug @@ -77,14 +78,32 @@ USBMonitor::~USBMonitor() QList USBMonitor::availableDevices(int vid, int pid, int bcdDeviceMSB, int bcdDeviceLSB) { QList allPorts = availableDevices(); + qDebug()<<"USBMonitor::availableDevices list off all ports:"; + qDebug()<<"USBMonitor::availableDevices total ports:"< thePortsWeWant; - + qDebug()<<"USBMonitor::availableDevices bcdLSB="< +void USBSignalFilter::m_deviceDiscovered(USBPortInfo port) +{ + if((port.vendorID==m_vid || m_vid==-1) && (port.productID==m_pid || m_pid==-1) && ((port.bcdDevice>>8)==m_boardModel || m_boardModel==-1) && + ( (port.bcdDevice&0x00ff) ==m_runState || m_runState==-1)) + { + qDebug()<<"USBSignalFilter emit device discovered"; + emit deviceDiscovered(); + } +} + +USBSignalFilter::USBSignalFilter(int vid, int pid, int boardModel, int runState): + m_vid(vid), + m_pid(pid), + m_boardModel(boardModel), + m_runState(runState) +{ + connect(USBMonitor::instance(),SIGNAL(deviceDiscovered(USBPortInfo)),this,SLOT(m_deviceDiscovered(USBPortInfo))); +} + + diff --git a/ground/openpilotgcs/src/plugins/rawhid/usbsignalfilter.h b/ground/openpilotgcs/src/plugins/rawhid/usbsignalfilter.h new file mode 100644 index 000000000..6a9310d46 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/rawhid/usbsignalfilter.h @@ -0,0 +1,21 @@ +#ifndef USBSIGNALFILTER_H +#define USBSIGNALFILTER_H +#include +#include "usbmonitor.h" + +class RAWHID_EXPORT USBSignalFilter : public QObject +{ + Q_OBJECT +private: + int m_vid; + int m_pid; + int m_boardModel; + int m_runState; +signals: + void deviceDiscovered(); +private slots: + void m_deviceDiscovered(USBPortInfo port); +public: + USBSignalFilter(int vid, int pid, int boardModel, int runState); +}; +#endif // USBSIGNALFILTER_H diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.cpp b/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.cpp index fb2bbf796..395765a9e 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.cpp @@ -385,8 +385,15 @@ void ScopeGadgetWidget::addCurvePlot(QString uavObject, QString uavFieldSubField ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); UAVObjectManager *objManager = pm->getObject(); UAVDataObject* obj = dynamic_cast(objManager->getObject((plotData->uavObject))); - + if(!obj) { + qDebug() << "Object " << plotData->uavObject << " is missing"; + return; + } UAVObjectField* field = obj->getField(plotData->uavField); + if(!field) { + qDebug() << "Field " << plotData->uavField << " of object " << plotData->uavObject << " is missing"; + return; + } QString units = field->getUnits(); if(units == 0) @@ -702,7 +709,7 @@ int ScopeGadgetWidget::csvLoggingInsertData() } else { - ss << QString().sprintf("%3.6g",plotData2->yData->last()/pow(10,plotData2->scalePower)); + ss << QString().sprintf("%3.6g",plotData2->yData->last()); m_csvLoggingDataValid=1; } } diff --git a/ground/openpilotgcs/src/plugins/serialconnection/serialconnection.pro b/ground/openpilotgcs/src/plugins/serialconnection/serialconnection.pro index 057c1f249..1c2f0fcf8 100644 --- a/ground/openpilotgcs/src/plugins/serialconnection/serialconnection.pro +++ b/ground/openpilotgcs/src/plugins/serialconnection/serialconnection.pro @@ -3,11 +3,13 @@ TARGET = Serial include(../../openpilotgcsplugin.pri) include(serial_dependencies.pri) INCLUDEPATH += ../../libs/qextserialport/src -HEADERS += serialplugin.h -#HEADERS += serialplugin.h \ -# serial_global.h -SOURCES += serialplugin.cpp -FORMS += +HEADERS += serialplugin.h \ + serialpluginconfiguration.h \ + serialpluginoptionspage.h +SOURCES += serialplugin.cpp \ + serialpluginconfiguration.cpp \ + serialpluginoptionspage.cpp +FORMS += \ + serialpluginoptions.ui RESOURCES += -#DEFINES += SERIAL_LIBRARY OTHER_FILES += Serial.pluginspec diff --git a/ground/openpilotgcs/src/plugins/serialconnection/serialplugin.cpp b/ground/openpilotgcs/src/plugins/serialconnection/serialplugin.cpp index e62afb44a..23bb8f9f9 100644 --- a/ground/openpilotgcs/src/plugins/serialconnection/serialplugin.cpp +++ b/ground/openpilotgcs/src/plugins/serialconnection/serialplugin.cpp @@ -76,6 +76,11 @@ SerialConnection::SerialConnection() : enablePolling(true), m_enumerateThread(this) { serialHandle = NULL; + m_config = new SerialPluginConfiguration("Serial Telemetry", NULL, this); + m_config->restoresettings(); + + m_optionspage = new SerialPluginOptionsPage(m_config,this); + // Experimental: enable polling on all OS'es since there // were reports that autodetect does not work on XP amongst @@ -142,7 +147,8 @@ QIODevice *SerialConnection::openDevice(const QString &deviceName) { //we need to handle port settings here... PortSettings set; - set.BaudRate = BAUD57600; + set.BaudRate = stringToBaud(m_config->speed()); + qDebug()<<"Serial telemetry running at "<speed(); set.DataBits = DATA_8; set.Parity = PAR_NONE; set.StopBits = STOP_1; @@ -198,6 +204,33 @@ void SerialConnection::resumePolling() enablePolling = true; } +BaudRateType SerialConnection::stringToBaud(QString str) +{ + if(str=="1200") + return BAUD1200; + else if(str=="2400") + return BAUD1200; + else if(str== "4800") + return BAUD2400; + else if(str== "9600") + return BAUD9600; + else if(str== "19200") + return BAUD19200; + else if(str== "38400") + return BAUD38400; + else if(str== "57600") + return BAUD56000; + else if(str== "115200") + return BAUD115200; + else if(str== "230400") + return BAUD230400; + else if(str== "460800") + return BAUD460800; + else if(str== "921600") + return BAUD921600; + else + return BAUD56000; +} SerialPlugin::SerialPlugin() { @@ -205,19 +238,23 @@ SerialPlugin::SerialPlugin() SerialPlugin::~SerialPlugin() { - + removeObject(m_connection->Optionspage()); } void SerialPlugin::extensionsInitialized() { - addAutoReleasedObject(new SerialConnection); + addAutoReleasedObject(m_connection); } bool SerialPlugin::initialize(const QStringList &arguments, QString *errorString) { Q_UNUSED(arguments); Q_UNUSED(errorString); - + m_connection = new SerialConnection(); + //must manage this registration of child object ourselves + //if we use an autorelease here it causes the GCS to crash + //as it is deleting objects as the app closes... + addObject(m_connection->Optionspage()); return true; } diff --git a/ground/openpilotgcs/src/plugins/serialconnection/serialplugin.h b/ground/openpilotgcs/src/plugins/serialconnection/serialplugin.h index 829ee6512..388117ead 100644 --- a/ground/openpilotgcs/src/plugins/serialconnection/serialplugin.h +++ b/ground/openpilotgcs/src/plugins/serialconnection/serialplugin.h @@ -33,6 +33,8 @@ #include #include "coreplugin/iconnection.h" #include +#include "serialpluginconfiguration.h" +#include "serialpluginoptionspage.h" #include class IConnection; @@ -87,12 +89,16 @@ public: virtual void resumePolling(); bool deviceOpened() {return m_deviceOpened;} + SerialPluginConfiguration * Config() const { return m_config; } + SerialPluginOptionsPage * Optionspage() const { return m_optionspage; } private: QextSerialPort* serialHandle; bool enablePolling; - + SerialPluginConfiguration *m_config; + SerialPluginOptionsPage *m_optionspage; + BaudRateType stringToBaud(QString str); protected slots: void onEnumerationChanged(); @@ -116,6 +122,8 @@ public: virtual bool initialize(const QStringList &arguments, QString *error_message); virtual void extensionsInitialized(); +private: + SerialConnection *m_connection; }; diff --git a/ground/openpilotgcs/src/plugins/serialconnection/serialpluginconfiguration.cpp b/ground/openpilotgcs/src/plugins/serialconnection/serialpluginconfiguration.cpp new file mode 100644 index 000000000..789085596 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/serialconnection/serialpluginconfiguration.cpp @@ -0,0 +1,81 @@ +/** + ****************************************************************************** + * + * @file serialpluginconfiguration.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @see The GNU Public License (GPL) Version 3 + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup SerialPlugin Serial Connection Plugin + * @{ + * @brief Impliments serial connection to the flight hardware for Telemetry + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "serialpluginconfiguration.h" +#include "utils/pathutils.h" +#include + +/** + * Loads a saved configuration or defaults if non exist. + * + */ +SerialPluginConfiguration::SerialPluginConfiguration(QString classId, QSettings* qSettings, QObject *parent) : + IUAVGadgetConfiguration(classId, parent), + m_speed("57600") +{ + settings = Core::ICore::instance()->settings(); +} + +/** + * Clones a configuration. + * + */ +IUAVGadgetConfiguration *SerialPluginConfiguration::clone() +{ + SerialPluginConfiguration *m = new SerialPluginConfiguration(this->classId()); + m->m_speed=m_speed; + return m; +} + +/** + * Saves a configuration. + * + */ +void SerialPluginConfiguration::saveConfig(QSettings* settings) const { + settings->setValue("speed", m_speed); +} +void SerialPluginConfiguration::restoresettings() +{ + settings->beginGroup(QLatin1String("SerialConnection")); + QString str=(settings->value(QLatin1String("speed"), tr("")).toString()); + if(str.isEmpty()) + m_speed="57600"; + else + m_speed=str; + settings->endGroup(); + +} +void SerialPluginConfiguration::savesettings() const +{ + settings->beginGroup(QLatin1String("SerialConnection")); + settings->setValue(QLatin1String("speed"), m_speed); + settings->endGroup(); +} +SerialPluginConfiguration::~SerialPluginConfiguration() +{ +} diff --git a/ground/openpilotgcs/src/plugins/serialconnection/serialpluginconfiguration.h b/ground/openpilotgcs/src/plugins/serialconnection/serialpluginconfiguration.h new file mode 100644 index 000000000..793ad102b --- /dev/null +++ b/ground/openpilotgcs/src/plugins/serialconnection/serialpluginconfiguration.h @@ -0,0 +1,58 @@ +/** + ****************************************************************************** + * + * @file serialpluginconfiguration.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @see The GNU Public License (GPL) Version 3 + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup SerialPlugin Serial Connection Plugin + * @{ + * @brief Impliments serial connection to the flight hardware for Telemetry + *****************************************************************************/ +/* + * 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 SERIALPLUGINCONFIGURATION_H +#define SERIALPLUGINCONFIGURATION_H + +#include + +using namespace Core; + +/* Despite its name, this is actually a generic analog Serial + supporting up to two rotating "needle" indicators. + */ +class SerialPluginConfiguration : public IUAVGadgetConfiguration +{ +Q_OBJECT +public: + explicit SerialPluginConfiguration(QString classId, QSettings* qSettings = 0, QObject *parent = 0); + QString speed() {return m_speed;} + void saveConfig(QSettings* settings) const; + IUAVGadgetConfiguration *clone(); + void savesettings() const; + void restoresettings(); + virtual ~SerialPluginConfiguration(); +private: + QString m_speed; + QSettings* settings; +public slots: + void setSpeed(QString speed) { m_speed = speed; } + +}; + +#endif // SERIALPLUGINCONFIGURATION_H diff --git a/ground/openpilotgcs/src/plugins/serialconnection/serialpluginoptions.ui b/ground/openpilotgcs/src/plugins/serialconnection/serialpluginoptions.ui new file mode 100644 index 000000000..04f9faf06 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/serialconnection/serialpluginoptions.ui @@ -0,0 +1,100 @@ + + + SerialPluginOptionsPage + + + + 0 + 0 + 400 + 300 + + + + Form + + + + + + Serial telemetry speed: + + + + + + + + 1200 + + + + + 2400 + + + + + 4800 + + + + + 9600 + + + + + 19200 + + + + + 38400 + + + + + 57600 + + + + + 115200 + + + + + 230400 + + + + + 460800 + + + + + 921600 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/serialconnection/serialpluginoptionspage.cpp b/ground/openpilotgcs/src/plugins/serialconnection/serialpluginoptionspage.cpp new file mode 100644 index 000000000..29d8b3784 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/serialconnection/serialpluginoptionspage.cpp @@ -0,0 +1,71 @@ +/** + ****************************************************************************** + * + * @file serialpluginoptionspage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @see The GNU Public License (GPL) Version 3 + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup SerialPlugin Serial Connection Plugin + * @{ + * @brief Impliments serial connection to the flight hardware for Telemetry + *****************************************************************************/ + /* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "serialpluginoptionspage.h" +#include "serialpluginconfiguration.h" +#include "ui_serialpluginoptions.h" +#include "extensionsystem/pluginmanager.h" + +SerialPluginOptionsPage::SerialPluginOptionsPage(SerialPluginConfiguration *config, QObject *parent) : + IOptionsPage(parent), + m_config(config) +{ +} + +//creates options page widget (uses the UI file) +QWidget *SerialPluginOptionsPage::createPage(QWidget *parent) +{ + + Q_UNUSED(parent); + options_page = new Ui::SerialPluginOptionsPage(); + //main widget + QWidget *optionsPageWidget = new QWidget; + //main layout + options_page->setupUi(optionsPageWidget); + options_page->cb_speed->setCurrentIndex(options_page->cb_speed->findText(m_config->speed())); + return optionsPageWidget; +} + +/** + * Called when the user presses apply or OK. + * + * Saves the current values + * + */ +void SerialPluginOptionsPage::apply() +{ + m_config->setSpeed(options_page->cb_speed->currentText()); + m_config->savesettings(); +} + + + +void SerialPluginOptionsPage::finish() +{ + delete options_page; +} diff --git a/ground/openpilotgcs/src/plugins/serialconnection/serialpluginoptionspage.h b/ground/openpilotgcs/src/plugins/serialconnection/serialpluginoptionspage.h new file mode 100644 index 000000000..6ce23b743 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/serialconnection/serialpluginoptionspage.h @@ -0,0 +1,71 @@ +/** + ****************************************************************************** + * + * @file serialpluginoptionspage.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @see The GNU Public License (GPL) Version 3 + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup SerialPlugin Serial Connection Plugin + * @{ + * @brief Impliments serial connection to the flight hardware for Telemetry + *****************************************************************************/ + /* + * 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 SERIALpluginOPTIONSPAGE_H +#define SERIALpluginOPTIONSPAGE_H + +#include "coreplugin/dialogs/ioptionspage.h" +#include "QString" +#include +#include +#include + +namespace Core { +class IUAVpluginConfiguration; +} + +class SerialPluginConfiguration; + +namespace Ui { + class SerialPluginOptionsPage; +} + +using namespace Core; + +class SerialPluginOptionsPage : public IOptionsPage +{ +Q_OBJECT +public: + explicit SerialPluginOptionsPage(SerialPluginConfiguration *config, QObject *parent = 0); + + QString id() const { return QLatin1String("settings"); } + QString trName() const { return tr("settings"); } + QString category() const { return "Serial Telemetry"; } + QString trCategory() const { return "Serial Telemetry"; } + QWidget *createPage(QWidget *parent); + void apply(); + void finish(); + +private: + Ui::SerialPluginOptionsPage *options_page; + SerialPluginConfiguration *m_config; + + +}; + +#endif // SERIALpluginOPTIONSPAGE_H diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp index 8841429fa..da71fd943 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp @@ -492,6 +492,45 @@ QVariant UAVObjectField::getValue(quint32 index) return QVariant(); } +bool UAVObjectField::checkValue(const QVariant& value, quint32 index) +{ + QMutexLocker locker(obj->getMutex()); + // Check that index is not out of bounds + if ( index >= numElements ) + { + return false; + } + // Get metadata + UAVObject::Metadata mdata = obj->getMetadata(); + // Update value if the access mode permits + if ( mdata.gcsAccess == UAVObject::ACCESS_READWRITE ) + { + switch (type) + { + case INT8: + case INT16: + case INT32: + case UINT8: + case UINT16: + case UINT32: + case FLOAT32: + case STRING: + return true; + break; + case ENUM: + { + qint8 tmpenum = options.indexOf( value.toString() ); + return ((tmpenum < 0) ? false : true); + break; + } + default: + qDebug() << "checkValue: other types" << type; + Q_ASSERT(0); // To catch any programming errors where we tried to test invalid values + break; + } + } +} + void UAVObjectField::setValue(const QVariant& value, quint32 index) { QMutexLocker locker(obj->getMutex()); diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.h b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.h index 9ae9d0d72..3cefc25e6 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.h +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.h @@ -56,6 +56,7 @@ public: qint32 pack(quint8* dataOut); qint32 unpack(const quint8* dataIn); QVariant getValue(quint32 index = 0); + bool checkValue(const QVariant& data, quint32 index = 0); void setValue(const QVariant& data, quint32 index = 0); double getDouble(quint32 index = 0); void setDouble(double value, quint32 index = 0); diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro index 9c6188fad..511253626 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro @@ -31,11 +31,11 @@ HEADERS += $$UAVOBJECT_SYNTHETICS/accessorydesired.h \ $$UAVOBJECT_SYNTHETICS/ahrssettings.h \ $$UAVOBJECT_SYNTHETICS/gcstelemetrystats.h \ $$UAVOBJECT_SYNTHETICS/attituderaw.h \ + $$UAVOBJECT_SYNTHETICS/camerastabsettings.h \ $$UAVOBJECT_SYNTHETICS/flighttelemetrystats.h \ $$UAVOBJECT_SYNTHETICS/systemstats.h \ $$UAVOBJECT_SYNTHETICS/systemalarms.h \ $$UAVOBJECT_SYNTHETICS/objectpersistence.h \ - $$UAVOBJECT_SYNTHETICS/telemetrysettings.h \ $$UAVOBJECT_SYNTHETICS/systemsettings.h \ $$UAVOBJECT_SYNTHETICS/stabilizationsettings.h \ $$UAVOBJECT_SYNTHETICS/manualcontrolsettings.h \ @@ -69,7 +69,10 @@ HEADERS += $$UAVOBJECT_SYNTHETICS/accessorydesired.h \ $$UAVOBJECT_SYNTHETICS/sonaraltitude.h \ $$UAVOBJECT_SYNTHETICS/flightstatus.h \ $$UAVOBJECT_SYNTHETICS/hwsettings.h \ - $$UAVOBJECT_SYNTHETICS/attitudesettings.h + $$UAVOBJECT_SYNTHETICS/gcsreceiver.h \ + $$UAVOBJECT_SYNTHETICS/receiveractivity.h \ + $$UAVOBJECT_SYNTHETICS/attitudesettings.h \ + $$UAVOBJECT_SYNTHETICS/cameradesired.h SOURCES += $$UAVOBJECT_SYNTHETICS/accessorydesired.cpp \ $$UAVOBJECT_SYNTHETICS/ahrsstatus.cpp \ @@ -79,11 +82,11 @@ SOURCES += $$UAVOBJECT_SYNTHETICS/accessorydesired.cpp \ $$UAVOBJECT_SYNTHETICS/ahrssettings.cpp \ $$UAVOBJECT_SYNTHETICS/gcstelemetrystats.cpp \ $$UAVOBJECT_SYNTHETICS/attituderaw.cpp \ + $$UAVOBJECT_SYNTHETICS/camerastabsettings.cpp \ $$UAVOBJECT_SYNTHETICS/flighttelemetrystats.cpp \ $$UAVOBJECT_SYNTHETICS/systemstats.cpp \ $$UAVOBJECT_SYNTHETICS/systemalarms.cpp \ $$UAVOBJECT_SYNTHETICS/objectpersistence.cpp \ - $$UAVOBJECT_SYNTHETICS/telemetrysettings.cpp \ $$UAVOBJECT_SYNTHETICS/systemsettings.cpp \ $$UAVOBJECT_SYNTHETICS/stabilizationsettings.cpp \ $$UAVOBJECT_SYNTHETICS/manualcontrolsettings.cpp \ @@ -118,4 +121,7 @@ SOURCES += $$UAVOBJECT_SYNTHETICS/accessorydesired.cpp \ $$UAVOBJECT_SYNTHETICS/uavobjectsinit.cpp \ $$UAVOBJECT_SYNTHETICS/flightstatus.cpp \ $$UAVOBJECT_SYNTHETICS/hwsettings.cpp \ - $$UAVOBJECT_SYNTHETICS/attitudesettings.cpp + $$UAVOBJECT_SYNTHETICS/gcsreceiver.cpp \ + $$UAVOBJECT_SYNTHETICS/receiveractivity.cpp \ + $$UAVOBJECT_SYNTHETICS/attitudesettings.cpp \ + $$UAVOBJECT_SYNTHETICS/cameradesired.cpp diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjecttemplate.m b/ground/openpilotgcs/src/plugins/uavobjects/uavobjecttemplate.m index b6259b0a1..96d727dff 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjecttemplate.m +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjecttemplate.m @@ -1,60 +1,129 @@ -function [] = OPLogConvert() - %% Define indices and arrays of structures to hold data -$(ALLOCATIONCODE) - - %% Open file - %fid = fopen('log.opl'); - [FileName,PathName,FilterIndex] = uigetfile('*.opl'); - logfile = strcat(PathName,FileName); - fid = fopen(logfile); - - while (1) - %% Read logging header - timestamp = fread(fid, 1, 'uint32'); - if (feof(fid)); break; end - datasize = fread(fid, 1, 'int64'); - - - %% Read message header - % get sync field (0x3C, 1 byte) - sync = fread(fid, 1, 'uint8'); - if sync ~= hex2dec('3C') - disp ('Wrong sync byte'); - return - end - % get msg type (quint8 1 byte ) should be 0x20, ignore the rest? - msgType = fread(fid, 1, 'uint8'); - if msgType ~= hex2dec('20') - disp ('Wrong msgType'); - return - end - % get msg size (quint16 2 bytes) excludes crc, include msg header and data payload - msgSize = fread(fid, 1, 'uint16'); - % get obj id (quint32 4 bytes) - objID = fread(fid, 1, 'uint32'); - - - %% Read object - switch objID -$(SWITCHCODE) - otherwise - disp('Unknown object ID'); - msgBytesLeft = datasize - 1 - 1 - 2 - 4; - fread(fid, msgBytesLeft, 'uint8'); - end - - end - - %% Clean Up and Save mat file - fclose(fid); - - matfile = strrep(logfile,'opl','mat'); - save(matfile $(SAVEOBJECTSCODE)); - +function [] = OPLogConvert(varargin) +%% Define indices and arrays of structures to hold data +% THIS FILE IS AUTOMATICALLY GENERATED. + +outputType='mat'; %Default output is a .mat file + +if nargin==0 + %% + if (exist('uigetfile')) + [FileName, PathName]=uigetfile('*.opl'); + logfile=fullfile(PathName, FileName); + + else + error('Your technical computing program does not support file choosers. Please input the file name in the argument. ') + end +elseif nargin>0 + logfile=varargin{1}; + if nargin>1 + outputType=varargin{2}; + end end +if ~strcmpi(outputType,'mat') && ~strcmpi(outputType,'csv') + error('Incorrect file format specified. Second argument must be ''mat'' or ''csv''.'); +end + +$(ALLOCATIONCODE) + + +fid = fopen(logfile); +correctMsgByte=hex2dec('20'); +correctSyncByte=hex2dec('3C'); + +% Parse log file, entry by entry +while (1) + %% Read logging header + timestamp = fread(fid, 1, '*uint32'); + if (feof(fid)); break; end + datasize = fread(fid, 1, '*int64'); + + + %% Read message header + % get sync field (0x3C, 1 byte) + sync = fread(fid, 1, 'uint8'); + if sync ~= correctSyncByte + disp ('Wrong sync byte'); + return + end + % get msg type (quint8 1 byte ) should be 0x20, ignore the rest? + msgType = fread(fid, 1, 'uint8'); + if msgType ~= correctMsgByte + disp ('Wrong msgType'); + return + end + % get msg size (quint16 2 bytes) excludes crc, include msg header and data payload + msgSize = fread(fid, 1, 'uint16'); + % get obj id (quint32 4 bytes) + objID = fread(fid, 1, 'uint32'); + + if (isempty(objID)) %End of file + break; + end + + %% Read object + switch objID +$(SWITCHCODE) + otherwise + disp(['Unknown object ID: 0x' dec2hex(objID)]); + msgBytesLeft = datasize - 1 - 1 - 2 - 4; + fread(fid, msgBytesLeft, 'uint8'); + end + +end + +%% Clean Up and Save mat file +fclose(fid); + +% Trim output structs +$(CLEANUPCODE) + +if strcmpi(outputType,'mat') + matfile = strrep(logfile,'opl','mat'); + save(matfile $(SAVEOBJECTSCODE)); +else +$(EXPORTCSVCODE); +end + + %% Object reading functions $(FUNCTIONSCODE) +% This function prunes the excess pre-allocated space +function [structOut]=PruneStructOfArrays(structIn, lastIndex) + + fieldNames = fieldnames(structIn); + for i=1:length(fieldNames) + structOut.(fieldNames{i})=structIn.(fieldNames{i})(1:lastIndex); + end + + +function OPLog2csv(structIn, structName, logfile) + %Get each field name from the structure + fieldNames = fieldnames(structIn); + + %Create a text string with the field names + headerOut=sprintf('%s,',fieldNames{:}); + headerOut=headerOut(1:end-1); %Trim off last `,` and `\t` + + %Assign the structure arrays to a matrix. + matOut=zeros(max(size(structIn.(fieldNames{1}))), length(fieldNames)); + + if isempty(structIn.(fieldNames{1})); + matOut=[]; + else + for i=1:length(fieldNames) + matOut(:,i)=structIn.(fieldNames{i}); + end + end + % Create filename by replacing opl by csv + [path, name] = fileparts(logfile); + csvDirName=[name '_csv']; + [dummyA, dummyB]=mkdir(fullfile(path, csvDirName)); %Dummy outputs so the program doens't throw warnings about "Directory already exists" + csvfile=fullfile(path, csvDirName , [name '.csv']); + + %Write to csv. + dlmwrite(csvfile, headerOut, ''); + dlmwrite(csvfile, matOut, '-append'); diff --git a/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp b/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp index b5070c269..0fc0e5fd9 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp @@ -34,6 +34,7 @@ #include #include #include +#include // ****************************** // constructor/destructor @@ -168,18 +169,25 @@ void UAVObjectUtilManager::objectPersistenceTransactionCompleted(UAVObject* obj, */ void UAVObjectUtilManager::objectPersistenceOperationFailed() { - qDebug() << "objectPersistenceOperationFailed"; if(saveState == AWAITING_COMPLETED) { //TODO: some warning that this operation failed somehow // We have to disconnect the object persistence 'updated' signal // and ask to save the next object: - UAVObject *obj = getObjectManager()->getObject(ObjectPersistence::NAME); - obj->disconnect(this); - queue.dequeue(); // We can now remove the object, it failed anyway. + + ObjectPersistence * objectPersistence = ObjectPersistence::GetInstance(getObjectManager()); + Q_ASSERT(objectPersistence); + + UAVObject* obj = queue.dequeue(); // We can now remove the object, it failed anyway. + Q_ASSERT(obj); + + objectPersistence->disconnect(this); + saveState = IDLE; - emit saveCompleted(obj->getField("ObjectID")->getValue().toInt(), false); + emit saveCompleted(obj->getObjID(), false); + saveNextObject(); } + } diff --git a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.cpp b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.cpp index 342b845e9..5418b455c 100644 --- a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.cpp +++ b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.cpp @@ -31,7 +31,7 @@ #include #include #include - +#include "importsummary.h" // for menu item #include #include @@ -62,321 +62,20 @@ UAVSettingsImportExportPlugin::~UAVSettingsImportExportPlugin() bool UAVSettingsImportExportPlugin::initialize(const QStringList& args, QString *errMsg) { - Q_UNUSED(args); - Q_UNUSED(errMsg); - - // Add Menu entry - Core::ActionManager* am = Core::ICore::instance()->actionManager(); - Core::ActionContainer* ac = am->actionContainer(Core::Constants::M_FILE); - Core::Command* cmd = am->registerAction(new QAction(this), - "UAVSettingsImportExportPlugin.UAVSettingsExport", - QList() << - Core::Constants::C_GLOBAL_ID); - cmd->setDefaultKeySequence(QKeySequence("Ctrl+E")); - cmd->action()->setText(tr("Export UAV Settings...")); - ac->addAction(cmd, Core::Constants::G_FILE_SAVE); - connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(exportUAVSettings())); - - cmd = am->registerAction(new QAction(this), - "UAVSettingsImportExportPlugin.UAVSettingsImport", - QList() << - Core::Constants::C_GLOBAL_ID); - cmd->setDefaultKeySequence(QKeySequence("Ctrl+I")); - cmd->action()->setText(tr("Import UAV Settings...")); - ac->addAction(cmd, Core::Constants::G_FILE_SAVE); - connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(importUAVSettings())); - - cmd = am->registerAction(new QAction(this), - "UAVSettingsImportExportPlugin.UAVDataExport", - QList() << - Core::Constants::C_GLOBAL_ID); - cmd->action()->setText(tr("Export UAV Data...")); - ac->addAction(cmd, Core::Constants::G_FILE_SAVE); - connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(exportUAVData())); - + Q_UNUSED(args); + Q_UNUSED(errMsg); + mf = new UAVSettingsImportExportFactory(this); + addAutoReleasedObject(mf); return true; -} - -void UAVSettingsImportExportPlugin::extensionsInitialized() -{ - // Do nothing -} - - -// Slot called by the menu manager on user action -void UAVSettingsImportExportPlugin::importUAVSettings() -{ - // ask for file name - QString fileName; - QString filters = tr("UAVSettings XML files (*.uav);; XML files (*.xml)"); - fileName = QFileDialog::getOpenFileName(0, tr("Import UAV Settings"), "", filters); - if (fileName.isEmpty()) { - return; - } - - // Now open the file - QFile file(fileName); - QDomDocument doc("UAVSettings"); - file.open(QFile::ReadOnly|QFile::Text); - if (!doc.setContent(file.readAll())) { - QMessageBox msgBox; - msgBox.setText(tr("File Parsing Failed.")); - msgBox.setInformativeText(tr("This file is not a correct XML file")); - msgBox.setStandardButtons(QMessageBox::Ok); - msgBox.exec(); - return; - } - file.close(); - - QDomElement root = doc.documentElement(); - if (root.tagName() != "settings") { - QMessageBox msgBox; - msgBox.setText(tr("Wrong file contents.")); - msgBox.setInformativeText(tr("This file is not a correct UAVSettings file")); - msgBox.setStandardButtons(QMessageBox::Ok); - msgBox.exec(); - return; - } - - // We are now ok: setup the import summary dialog & update it as we - // go along. - ImportSummaryDialog swui; - - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager *objManager = pm->getObject(); - swui.show(); - - QDomNode node = root.firstChild(); - while (!node.isNull()) { - QDomElement e = node.toElement(); - if (e.tagName() == "object") { - // - Read each object - QString uavObjectName = e.attribute("name"); - uint uavObjectID = e.attribute("id").toUInt(NULL,16); - - // Sanity Check: - UAVObject* obj = objManager->getObject(uavObjectName); - if (obj == NULL) { - // This object is unknown! - qDebug() << "Object unknown:" << uavObjectName << uavObjectID; - swui.addLine(uavObjectName, "Error (Object unknown)", false); - - } else { - // - Update each field - // - Issue and "updated" command - bool error=false; - QDomNode field = node.firstChild(); - while(!field.isNull()) { - QDomElement f = field.toElement(); - if (f.tagName() == "field") { - UAVObjectField *uavfield = obj->getField(f.attribute("name")); - if (uavfield) { - QStringList list = f.attribute("values").split(","); - if (list.length() == 1) { - uavfield->setValue(f.attribute("values")); - } else { - // This is an enum: - int i=0; - QStringList list = f.attribute("values").split(","); - foreach (QString element, list) { - uavfield->setValue(element,i++); - } - } - error = false; - } else { - error = true; - } - } - field = field.nextSibling(); - } - obj->updated(); - if (error) { - swui.addLine(uavObjectName, "Warning (Object field unknown)", true); - } else if (uavObjectID != obj->getObjID()) { - qDebug() << "Mismatch for Object " << uavObjectName << uavObjectID << " - " << obj->getObjID(); - swui.addLine(uavObjectName, "Warning (ObjectID mismatch)", true); - } else - swui.addLine(uavObjectName, "OK", true); - } - } - node = node.nextSibling(); - } - swui.exec(); - - - -} - -// Create an XML document from UAVObject database -QString UAVSettingsImportExportPlugin::createXMLDocument( - const QString docName, const bool isSettings, const bool fullExport) -{ - // generate an XML first (used for all export formats as a formatted data source) - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager *objManager = pm->getObject(); - - QDomDocument doc(docName); - QDomElement root = doc.createElement(isSettings ? "settings" : "data"); - doc.appendChild(root); - QDomElement versionInfo =doc.createElement("versionInfo"); - root.appendChild(versionInfo); - QDomElement fw=doc.createElement("Embedded"); - UAVObjectUtilManager* utilMngr = pm->getObject(); - - fw.setAttribute("gitcommittag",utilMngr->getBoardDescriptionStruct().gitTag); - fw.setAttribute("fwtag",utilMngr->getBoardDescriptionStruct().description); - fw.setAttribute("cpuSerial",QString(utilMngr->getBoardCPUSerial().toHex())); - - versionInfo.appendChild(fw); - QDomElement gcs=doc.createElement("GCS"); - gcs.setAttribute("revision",QString::fromLatin1(Core::Constants::GCS_REVISION_STR)); - versionInfo.appendChild(gcs); - // iterate over settings objects - QList< QList > objList = objManager->getDataObjects(); - foreach (QList list, objList) { - foreach (UAVDataObject* obj, list) { - if (obj->isSettings() == isSettings) { - - // add each object to the XML - QDomElement o = doc.createElement("object"); - o.setAttribute("name", obj->getName()); - o.setAttribute("id", QString("0x")+ QString().setNum(obj->getObjID(),16).toUpper()); - if (fullExport) { - QDomElement d = doc.createElement("description"); - QDomText t = doc.createTextNode(obj->getDescription().remove("@Ref ", Qt::CaseInsensitive)); - d.appendChild(t); - o.appendChild(d); - } - - // iterate over fields - QList fieldList = obj->getFields(); - - foreach (UAVObjectField* field, fieldList) { - QDomElement f = doc.createElement("field"); - - // iterate over values - QString vals; - quint32 nelem = field->getNumElements(); - for (unsigned int n = 0; n < nelem; ++n) { - vals.append(QString("%1,").arg(field->getValue(n).toString())); - } - vals.chop(1); - - f.setAttribute("name", field->getName()); - f.setAttribute("values", vals); - if (fullExport) { - f.setAttribute("type", field->getTypeAsString()); - f.setAttribute("units", field->getUnits()); - f.setAttribute("elements", nelem); - if (field->getType() == UAVObjectField::ENUM) { - f.setAttribute("options", field->getOptions().join(",")); - } - } - o.appendChild(f); - } - root.appendChild(o); - } - } - } - - return doc.toString(4); -} - -// Slot called by the menu manager on user action -void UAVSettingsImportExportPlugin::exportUAVSettings() -{ - // ask for file name - QString fileName; - QString filters = tr("UAVSettings XML files (*.uav)"); - - fileName = QFileDialog::getSaveFileName(0, tr("Save UAV Settings File As"), "", filters); - if (fileName.isEmpty()) { - return; - } - - bool fullExport = false; - // If the filename ends with .xml, we will do a full export, otherwise, a simple export - if (fileName.endsWith(".xml")) { - fullExport = true; - } else if (!fileName.endsWith(".uav")) { - fileName.append(".uav"); - } - - // generate an XML first (used for all export formats as a formatted data source) - QString xml = createXMLDocument("UAVSettings", true, fullExport); - - // save file - QFile file(fileName); - if (file.open(QIODevice::WriteOnly) && - (file.write(xml.toAscii()) != -1)) { - file.close(); - } else { - QMessageBox::critical(0, - tr("UAV Settings Export"), - tr("Unable to save settings: ") + fileName, - QMessageBox::Ok); - return; - } - - QMessageBox msgBox; - msgBox.setText(tr("Settings saved.")); - msgBox.setStandardButtons(QMessageBox::Ok); - msgBox.exec(); -} - -// Slot called by the menu manager on user action -void UAVSettingsImportExportPlugin::exportUAVData() -{ - if (QMessageBox::question(0, tr("Are you sure?"), - tr("This option is only useful for passing your current " - "system data to the technical support staff. " - "Do you really want to export?"), - QMessageBox::Ok | QMessageBox::Cancel, - QMessageBox::Ok) != QMessageBox::Ok) { - return; - } - - // ask for file name - QString fileName; - QString filters = tr("UAVData XML files (*.uav)"); - - fileName = QFileDialog::getSaveFileName(0, tr("Save UAV Data File As"), "", filters); - if (fileName.isEmpty()) { - return; - } - - bool fullExport = false; - // If the filename ends with .xml, we will do a full export, otherwise, a simple export - if (fileName.endsWith(".xml")) { - fullExport = true; - } else if (!fileName.endsWith(".uav")) { - fileName.append(".uav"); - } - - // generate an XML first (used for all export formats as a formatted data source) - QString xml = createXMLDocument("UAVData", false, fullExport); - - // save file - QFile file(fileName); - if (file.open(QIODevice::WriteOnly) && - (file.write(xml.toAscii()) != -1)) { - file.close(); - } else { - QMessageBox::critical(0, - tr("UAV Data Export"), - tr("Unable to save data: ") + fileName, - QMessageBox::Ok); - return; - } - - QMessageBox msgBox; - msgBox.setText(tr("Data saved.")); - msgBox.setStandardButtons(QMessageBox::Ok); - msgBox.exec(); } void UAVSettingsImportExportPlugin::shutdown() { // Do nothing } +void UAVSettingsImportExportPlugin::extensionsInitialized() +{ +} Q_EXPORT_PLUGIN(UAVSettingsImportExportPlugin) + + diff --git a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.h b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.h index ff8972227..a63454153 100644 --- a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.h +++ b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.h @@ -29,9 +29,10 @@ #include #include "uavobjectutil/uavobjectutilmanager.h" -#include "importsummary.h" +#include "uavsettingsimportexport_global.h" #include "../../../../../build/ground/openpilotgcs/gcsversioninfo.h" -class UAVSettingsImportExportPlugin : public ExtensionSystem::IPlugin +#include "uavsettingsimportexportfactory.h" +class UAVSETTINGSIMPORTEXPORT_EXPORT UAVSettingsImportExportPlugin : public ExtensionSystem::IPlugin { Q_OBJECT @@ -42,16 +43,10 @@ public: void extensionsInitialized(); bool initialize(const QStringList & arguments, QString * errorString); void shutdown(); - private: - QString createXMLDocument(const QString docName, - const bool isSettings, - const bool fullExport); + UAVSettingsImportExportFactory *mf; + -private slots: - void importUAVSettings(); - void exportUAVSettings(); - void exportUAVData(); }; diff --git a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.pri b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.pri new file mode 100644 index 000000000..bddd38181 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.pri @@ -0,0 +1,2 @@ +include(uavsettingsimportexport_dependencies.pri) +LIBS *= -l$$qtLibraryName(UAVSettingsImportExport) diff --git a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.pro b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.pro index fcdc11ae6..aa8abccf1 100644 --- a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.pro +++ b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.pro @@ -3,14 +3,16 @@ TEMPLATE = lib QT += xml TARGET = UAVSettingsImportExport - +DEFINES += UAVSETTINGSIMPORTEXPORT_LIBRARY include(../../openpilotgcsplugin.pri) include(uavsettingsimportexport_dependencies.pri) HEADERS += uavsettingsimportexport.h \ - importsummary.h + importsummary.h \ + uavsettingsimportexportfactory.h SOURCES += uavsettingsimportexport.cpp \ - importsummary.cpp + importsummary.cpp \ + uavsettingsimportexportfactory.cpp OTHER_FILES += uavsettingsimportexport.pluginspec diff --git a/flight/UAVObjects/uavobjectsinit_linker.c b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport_global.h similarity index 60% rename from flight/UAVObjects/uavobjectsinit_linker.c rename to ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport_global.h index 3d4abd7eb..703771b4f 100644 --- a/flight/UAVObjects/uavobjectsinit_linker.c +++ b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport_global.h @@ -1,45 +1,40 @@ -/** - ****************************************************************************** - * - * @file uavobjectsinit.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Initialize all objects. - * Automatically generated by the UAVObjectGenerator. - * - * @note This is an automatically generated file. - * DO NOT modify manually. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "openpilot.h" - -/** - * Function used to initialize the first instance of each object. - * This file is automatically updated by the UAVObjectGenerator. - */ -extern initcall_t __uavobj_initcall_start[], __uavobj_initcall_end[]; - -void UAVObjectsInitializeAll() -{ - initcall_t *fn; - int32_t ret; - - for (fn = __uavobj_initcall_start; fn < __uavobj_initcall_end; fn++) - ret = (*fn)(); -} +/** + ****************************************************************************** + * + * @file uavsettingsimportexport_global.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @see The GNU Public License (GPL) Version 3 + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup + * @{ + * @brief + *****************************************************************************/ +/* + * 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 UAVSETTINGSIMPORTEXPORT_GLOBAL_H +#define UAVSETTINGSIMPORTEXPORT_GLOBAL_H + +#include + +#if defined(UAVSETTINGSIMPORTEXPORT_LIBRARY) +# define UAVSETTINGSIMPORTEXPORT_EXPORT Q_DECL_EXPORT +#else +# define UAVSETTINGSIMPORTEXPORT_EXPORT Q_DECL_IMPORT +#endif + +#endif // UAVSETTINGSIMPORTEXPORT_GLOBAL_H diff --git a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp new file mode 100644 index 000000000..b082e1eb5 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp @@ -0,0 +1,377 @@ +/** + ****************************************************************************** + * + * @file uavsettingsimportexportfactory.cpp + * @author (C) 2011 The OpenPilot Team, http://www.openpilot.org + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup UAVSettingsImportExport UAVSettings Import/Export Plugin + * @{ + * @brief UAVSettings Import/Export Plugin + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "uavsettingsimportexportfactory.h" +#include +#include +#include +#include +#include "importsummary.h" +// for menu item +#include +#include +#include +#include + +// for UAVObjects +#include "uavdataobject.h" +#include "uavobjectmanager.h" +#include "extensionsystem/pluginmanager.h" + +// for XML object +#include + +// for file dialog and error messages +#include +#include + + + +UAVSettingsImportExportFactory::~UAVSettingsImportExportFactory() +{ + // Do nothing +} + +UAVSettingsImportExportFactory::UAVSettingsImportExportFactory(QObject * parent):QObject(parent) +{ + + // Add Menu entry + Core::ActionManager* am = Core::ICore::instance()->actionManager(); + Core::ActionContainer* ac = am->actionContainer(Core::Constants::M_FILE); + Core::Command* cmd = am->registerAction(new QAction(this), + "UAVSettingsImportExportPlugin.UAVSettingsExport", + QList() << + Core::Constants::C_GLOBAL_ID); + cmd->setDefaultKeySequence(QKeySequence("Ctrl+E")); + cmd->action()->setText(tr("Export UAV Settings...")); + ac->addAction(cmd, Core::Constants::G_FILE_SAVE); + connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(exportUAVSettings())); + + cmd = am->registerAction(new QAction(this), + "UAVSettingsImportExportPlugin.UAVSettingsImport", + QList() << + Core::Constants::C_GLOBAL_ID); + cmd->setDefaultKeySequence(QKeySequence("Ctrl+I")); + cmd->action()->setText(tr("Import UAV Settings...")); + ac->addAction(cmd, Core::Constants::G_FILE_SAVE); + connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(importUAVSettings())); + + cmd = am->registerAction(new QAction(this), + "UAVSettingsImportExportPlugin.UAVDataExport", + QList() << + Core::Constants::C_GLOBAL_ID); + cmd->action()->setText(tr("Export UAV Data...")); + ac->addAction(cmd, Core::Constants::G_FILE_SAVE); + connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(exportUAVData())); + +} + +// Slot called by the menu manager on user action +void UAVSettingsImportExportFactory::importUAVSettings() +{ + // ask for file name + QString fileName; + QString filters = tr("UAVSettings XML files (*.uav);; XML files (*.xml)"); + fileName = QFileDialog::getOpenFileName(0, tr("Import UAV Settings"), "", filters); + if (fileName.isEmpty()) { + return; + } + + // Now open the file + QFile file(fileName); + QDomDocument doc("UAVSettings"); + file.open(QFile::ReadOnly|QFile::Text); + if (!doc.setContent(file.readAll())) { + QMessageBox msgBox; + msgBox.setText(tr("File Parsing Failed.")); + msgBox.setInformativeText(tr("This file is not a correct XML file")); + msgBox.setStandardButtons(QMessageBox::Ok); + msgBox.exec(); + return; + } + file.close(); + emit importAboutToBegin(); + qDebug()<<"Import about to begin"; + QDomElement root = doc.documentElement(); + if (root.tagName() != "settings") { + QMessageBox msgBox; + msgBox.setText(tr("Wrong file contents.")); + msgBox.setInformativeText(tr("This file is not a correct UAVSettings file")); + msgBox.setStandardButtons(QMessageBox::Ok); + msgBox.exec(); + return; + } + + // We are now ok: setup the import summary dialog & update it as we + // go along. + ImportSummaryDialog swui; + + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + UAVObjectManager *objManager = pm->getObject(); + swui.show(); + + QDomNode node = root.firstChild(); + while (!node.isNull()) { + QDomElement e = node.toElement(); + if (e.tagName() == "object") { + // - Read each object + QString uavObjectName = e.attribute("name"); + uint uavObjectID = e.attribute("id").toUInt(NULL,16); + + // Sanity Check: + UAVObject* obj = objManager->getObject(uavObjectName); + if (obj == NULL) { + // This object is unknown! + qDebug() << "Object unknown:" << uavObjectName << uavObjectID; + swui.addLine(uavObjectName, "Error (Object unknown)", false); + + } else { + // - Update each field + // - Issue and "updated" command + bool error=false; + bool setError=false; + QDomNode field = node.firstChild(); + while(!field.isNull()) { + QDomElement f = field.toElement(); + if (f.tagName() == "field") { + UAVObjectField *uavfield = obj->getField(f.attribute("name")); + if (uavfield) { + QStringList list = f.attribute("values").split(","); + if (list.length() == 1) { + if (false == uavfield->checkValue(f.attribute("values"))) { + qDebug() << "checkValue returned false on: " << uavObjectName << f.attribute("values"); + setError = true; + } else + uavfield->setValue(f.attribute("values")); + } else { + // This is an enum: + int i=0; + QStringList list = f.attribute("values").split(","); + foreach (QString element, list) { + if (false == uavfield->checkValue(element,i)) { + qDebug() << "checkValue(list) returned false on: " << uavObjectName << list; + setError = true; + } else + uavfield->setValue(element,i); + i++; + } + } + } else { + error = true; + } + } + field = field.nextSibling(); + } + obj->updated(); + if (error) { + swui.addLine(uavObjectName, "Warning (Object field unknown)", true); + } else if (uavObjectID != obj->getObjID()) { + qDebug() << "Mismatch for Object " << uavObjectName << uavObjectID << " - " << obj->getObjID(); + swui.addLine(uavObjectName, "Warning (ObjectID mismatch)", true); + } else if (setError) { + swui.addLine(uavObjectName, "Warning (Objects field value(s) invalid)", false); + } else + swui.addLine(uavObjectName, "OK", true); + } + } + node = node.nextSibling(); + } + qDebug()<<"End import"; + swui.exec(); + + + +} + +// Create an XML document from UAVObject database +QString UAVSettingsImportExportFactory::createXMLDocument( + const QString docName, const bool isSettings, const bool fullExport) +{ + // generate an XML first (used for all export formats as a formatted data source) + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + UAVObjectManager *objManager = pm->getObject(); + + QDomDocument doc(docName); + QDomElement root = doc.createElement(isSettings ? "settings" : "data"); + doc.appendChild(root); + QDomElement versionInfo =doc.createElement("versionInfo"); + root.appendChild(versionInfo); + QDomElement fw=doc.createElement("Embedded"); + UAVObjectUtilManager* utilMngr = pm->getObject(); + + deviceDescriptorStruct struc=utilMngr->getBoardDescriptionStruct(); + fw.setAttribute("gitcommittag",struc.gitTag); + fw.setAttribute("fwtag",struc.description); + fw.setAttribute("cpuSerial",QString(utilMngr->getBoardCPUSerial().toHex())); + + versionInfo.appendChild(fw); + QDomElement gcs=doc.createElement("GCS"); + gcs.setAttribute("revision",QString::fromLatin1(Core::Constants::GCS_REVISION_STR)); + versionInfo.appendChild(gcs); + // iterate over settings objects + QList< QList > objList = objManager->getDataObjects(); + foreach (QList list, objList) { + foreach (UAVDataObject* obj, list) { + if (obj->isSettings() == isSettings) { + + // add each object to the XML + QDomElement o = doc.createElement("object"); + o.setAttribute("name", obj->getName()); + o.setAttribute("id", QString("0x")+ QString().setNum(obj->getObjID(),16).toUpper()); + if (fullExport) { + QDomElement d = doc.createElement("description"); + QDomText t = doc.createTextNode(obj->getDescription().remove("@Ref ", Qt::CaseInsensitive)); + d.appendChild(t); + o.appendChild(d); + } + + // iterate over fields + QList fieldList = obj->getFields(); + + foreach (UAVObjectField* field, fieldList) { + QDomElement f = doc.createElement("field"); + + // iterate over values + QString vals; + quint32 nelem = field->getNumElements(); + for (unsigned int n = 0; n < nelem; ++n) { + vals.append(QString("%1,").arg(field->getValue(n).toString())); + } + vals.chop(1); + + f.setAttribute("name", field->getName()); + f.setAttribute("values", vals); + if (fullExport) { + f.setAttribute("type", field->getTypeAsString()); + f.setAttribute("units", field->getUnits()); + f.setAttribute("elements", nelem); + if (field->getType() == UAVObjectField::ENUM) { + f.setAttribute("options", field->getOptions().join(",")); + } + } + o.appendChild(f); + } + root.appendChild(o); + } + } + } + + return doc.toString(4); +} + +// Slot called by the menu manager on user action +void UAVSettingsImportExportFactory::exportUAVSettings() +{ + // ask for file name + QString fileName; + QString filters = tr("UAVSettings XML files (*.uav)"); + + fileName = QFileDialog::getSaveFileName(0, tr("Save UAV Settings File As"), "", filters); + if (fileName.isEmpty()) { + return; + } + + bool fullExport = false; + // If the filename ends with .xml, we will do a full export, otherwise, a simple export + if (fileName.endsWith(".xml")) { + fullExport = true; + } else if (!fileName.endsWith(".uav")) { + fileName.append(".uav"); + } + + // generate an XML first (used for all export formats as a formatted data source) + QString xml = createXMLDocument("UAVSettings", true, fullExport); + + // save file + QFile file(fileName); + if (file.open(QIODevice::WriteOnly) && + (file.write(xml.toAscii()) != -1)) { + file.close(); + } else { + QMessageBox::critical(0, + tr("UAV Settings Export"), + tr("Unable to save settings: ") + fileName, + QMessageBox::Ok); + return; + } + + QMessageBox msgBox; + msgBox.setText(tr("Settings saved.")); + msgBox.setStandardButtons(QMessageBox::Ok); + msgBox.exec(); +} + +// Slot called by the menu manager on user action +void UAVSettingsImportExportFactory::exportUAVData() +{ + if (QMessageBox::question(0, tr("Are you sure?"), + tr("This option is only useful for passing your current " + "system data to the technical support staff. " + "Do you really want to export?"), + QMessageBox::Ok | QMessageBox::Cancel, + QMessageBox::Ok) != QMessageBox::Ok) { + return; + } + + // ask for file name + QString fileName; + QString filters = tr("UAVData XML files (*.uav)"); + + fileName = QFileDialog::getSaveFileName(0, tr("Save UAV Data File As"), "", filters); + if (fileName.isEmpty()) { + return; + } + + bool fullExport = false; + // If the filename ends with .xml, we will do a full export, otherwise, a simple export + if (fileName.endsWith(".xml")) { + fullExport = true; + } else if (!fileName.endsWith(".uav")) { + fileName.append(".uav"); + } + + // generate an XML first (used for all export formats as a formatted data source) + QString xml = createXMLDocument("UAVData", false, fullExport); + + // save file + QFile file(fileName); + if (file.open(QIODevice::WriteOnly) && + (file.write(xml.toAscii()) != -1)) { + file.close(); + } else { + QMessageBox::critical(0, + tr("UAV Data Export"), + tr("Unable to save data: ") + fileName, + QMessageBox::Ok); + return; + } + + QMessageBox msgBox; + msgBox.setText(tr("Data saved.")); + msgBox.setStandardButtons(QMessageBox::Ok); + msgBox.exec(); +} diff --git a/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.h b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.h new file mode 100644 index 000000000..a130d5c4a --- /dev/null +++ b/ground/openpilotgcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.h @@ -0,0 +1,55 @@ +/** + ****************************************************************************** + * + * @file uavsettingsimportexportfactory.h + * @author (C) 2011 The OpenPilot Team, http://www.openpilot.org + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup UAVSettingsImportExport UAVSettings Import/Export Plugin + * @{ + * @brief UAVSettings Import/Export Plugin + *****************************************************************************/ +/* + * 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 UAVSETTINGSIMPORTEXPORTFACTORY_H +#define UAVSETTINGSIMPORTEXPORTFACTORY_H +#include "uavsettingsimportexport_global.h" +#include "uavobjectutil/uavobjectutilmanager.h" +#include "../../../../../build/ground/openpilotgcs/gcsversioninfo.h" +class UAVSETTINGSIMPORTEXPORT_EXPORT UAVSettingsImportExportFactory : public QObject +{ + Q_OBJECT + +public: + UAVSettingsImportExportFactory(QObject *parent = 0); + ~UAVSettingsImportExportFactory(); + +private: + QString createXMLDocument(const QString docName, + const bool isSettings, + const bool fullExport); + +private slots: + void importUAVSettings(); + void exportUAVSettings(); + void exportUAVData(); +signals: + void importAboutToBegin(); + void importEnded(); + +}; + +#endif // UAVSETTINGSIMPORTEXPORTFACTORY_H diff --git a/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.cpp b/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.cpp index 6a9d22d5f..7295f79c3 100644 --- a/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.cpp +++ b/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.cpp @@ -282,9 +282,15 @@ bool UAVTalk::processInputByte(quint8 rxbyte) // Determine data length if (rxType == TYPE_OBJ_REQ || rxType == TYPE_ACK || rxType == TYPE_NACK) + { rxLength = 0; + rxInstanceLength = 0; + } else + { rxLength = rxObj->getNumBytes(); + rxInstanceLength = (rxObj->isSingleInstance() ? 0 : 2); + } // Check length and determine next state if (rxLength >= MAX_PAYLOAD_LENGTH) @@ -295,7 +301,7 @@ bool UAVTalk::processInputByte(quint8 rxbyte) } // Check the lengths match - if ((rxPacketLength + rxLength + (rxObj->isSingleInstance() ? 0 : 2)) != packetSize) + if ((rxPacketLength + rxInstanceLength + rxLength) != packetSize) { // packet error - mismatched packet size stats.rxErrors++; rxState = STATE_SYNC; diff --git a/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.h b/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.h index 99549f691..163fb9fa3 100644 --- a/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.h +++ b/ground/openpilotgcs/src/plugins/uavtalk/uavtalk.h @@ -107,6 +107,7 @@ private: quint16 rxInstId; quint16 rxLength; quint16 rxPacketLength; + quint8 rxInstanceLength; quint8 rxCSPacket, rxCS; qint32 rxCount; diff --git a/ground/openpilotgcs/src/plugins/uploader/devicewidget.cpp b/ground/openpilotgcs/src/plugins/uploader/devicewidget.cpp index e2300bdcd..9e57a4225 100644 --- a/ground/openpilotgcs/src/plugins/uploader/devicewidget.cpp +++ b/ground/openpilotgcs/src/plugins/uploader/devicewidget.cpp @@ -183,7 +183,7 @@ bool deviceWidget::populateBoardStructuredDescription(QByteArray desc) if(UAVObjectUtilManager::descriptionToStructure(desc,&onBoardDescrition)) { myDevice->lblGitTag->setText(onBoardDescrition.gitTag); - myDevice->lblBuildDate->setText(onBoardDescrition.buildDate); + myDevice->lblBuildDate->setText(onBoardDescrition.buildDate.insert(4,"-").insert(7,"-")); if(onBoardDescrition.description.startsWith("release",Qt::CaseInsensitive)) { myDevice->lblDescription->setText(QString("Firmware tag: ")+onBoardDescrition.description); @@ -213,7 +213,7 @@ bool deviceWidget::populateLoadedStructuredDescription(QByteArray desc) if(UAVObjectUtilManager::descriptionToStructure(desc,&LoadedDescrition)) { myDevice->lblGitTagL->setText(LoadedDescrition.gitTag); - myDevice->lblBuildDateL->setText( LoadedDescrition.buildDate); + myDevice->lblBuildDateL->setText( LoadedDescrition.buildDate.insert(4,"-").insert(7,"-")); if(LoadedDescrition.description.startsWith("release",Qt::CaseInsensitive)) { myDevice->lblDescritpionL->setText(LoadedDescrition.description); @@ -303,7 +303,10 @@ void deviceWidget::loadFirmware() myDevice->youdont->setChecked(false); QByteArray desc = loadedFW.right(100); QPixmap px; - myDevice->lblCRCL->setText( QString::number(DFUObject::CRCFromQBArray(loadedFW,m_dfu->devices[deviceID].SizeOfCode))); + if(loadedFW.length()>m_dfu->devices[deviceID].SizeOfCode) + myDevice->lblCRCL->setText(tr("Can't calculate, file too big for device")); + else + myDevice->lblCRCL->setText( QString::number(DFUObject::CRCFromQBArray(loadedFW,m_dfu->devices[deviceID].SizeOfCode))); //myDevice->lblFirmwareSizeL->setText(QString("Firmware size: ")+QVariant(loadedFW.length()).toString()+ QString(" bytes")); if (populateLoadedStructuredDescription(desc)) { diff --git a/ground/openpilotgcs/src/plugins/uploader/op_dfu.cpp b/ground/openpilotgcs/src/plugins/uploader/op_dfu.cpp index 8a9045233..961103d22 100644 --- a/ground/openpilotgcs/src/plugins/uploader/op_dfu.cpp +++ b/ground/openpilotgcs/src/plugins/uploader/op_dfu.cpp @@ -80,29 +80,43 @@ DFUObject::DFUObject(bool _debug,bool _use_serial,QString portname): } else { - send_delay=10; - use_delay=true; -// int numDevices=0; + mready = false; + QEventLoop m_eventloop; + QTimer::singleShot(200,&m_eventloop, SLOT(quit())); + m_eventloop.exec(); QList devices; - int count=0; - while((devices.length()==0) && count < 10) - { - if (debug) - qDebug() << "."; - delay::msleep(500); - // processEvents enables XP to process the system - // plug/unplug events, otherwise it will not process - // those events before the end of the call! - QApplication::processEvents(); - devices = USBMonitor::instance()->availableDevices(0x20a0,-1,-1,USBMonitor::Bootloader); - count++; - } - if (devices.length()==1) { - hidHandle.open(1,devices.first().vendorID,devices.first().productID,0,0); + devices = USBMonitor::instance()->availableDevices(0x20a0,-1,-1,USBMonitor::Bootloader); + if (devices.length()==1 && hidHandle.open(1,devices.first().vendorID,devices.first().productID,0,0)==1) { + qDebug()<<"OP_DFU detected first time"; + mready=true; } else { - qDebug() << devices.length() << " device(s) detected, don't know what to do!"; - mready = false; - } + // Wait for the board to appear on the USB bus: + USBSignalFilter filter(0x20a0,-1,-1,USBMonitor::Bootloader); + connect(&filter, SIGNAL(deviceDiscovered()),&m_eventloop, SLOT(quit())); + for(int x=0;x<4;++x) + { + qDebug()<<"OP_DFU trying to detect bootloader:"<availableDevices(0x20a0,-1,-1,USBMonitor::Bootloader); + if (devices.length()==1) { + if(hidHandle.open(1,devices.first().vendorID,devices.first().productID,0,0)==1) + { + qDebug()<<"OP_DFU detected after delay"; + mready=true; + break; + } + } + else { + qDebug() << devices.length() << " device(s) detected, don't know what to do!"; + mready = false; + } + } + } } } @@ -956,7 +970,7 @@ quint32 DFUObject::CRC32WideFast(quint32 Crc, quint32 Size, quint32 *Buffer) */ quint32 DFUObject::CRCFromQBArray(QByteArray array, quint32 Size) { - int pad=Size-array.length(); + quint32 pad=Size-array.length(); array.append(QByteArray(pad,255)); quint32 t[Size/4]; for(int x=0;x> 8) { + case BOARD_ID_MB: // Mainboard family + brdType = eBoardMainbrd; + break; + case BOARD_ID_INS: // Inertial Nav + brdType = eBoardINS; + break; + case BOARD_ID_PIP: // PIP RF Modem + brdType = eBoardPip; + break; + case BOARD_ID_CC: // CopterControl family + brdType = eBoardCC; + break; +#if 0 // Someday ;-) + case BOARD_ID_PRO: // Pro board + brdType = eBoardPro; + break; +#endif + } + return brdType; +} + + diff --git a/ground/openpilotgcs/src/plugins/uploader/op_dfu.h b/ground/openpilotgcs/src/plugins/uploader/op_dfu.h index 420e0a3ea..79624b546 100644 --- a/ground/openpilotgcs/src/plugins/uploader/op_dfu.h +++ b/ground/openpilotgcs/src/plugins/uploader/op_dfu.h @@ -4,6 +4,7 @@ #include #include #include +#include #include #include #include @@ -17,6 +18,7 @@ #include "delay.h" #include #include +#include #include "SSP/qssp.h" #include "SSP/port.h" #include "SSP/qsspt.h" @@ -91,6 +93,16 @@ namespace OP_DFU { }; + enum eBoardType + { + eBoardUnkwn = 0, + eBoardMainbrd = 1, + eBoardINS, + eBoardPip, + eBoardCC, + eBoardPro, + }; + struct device { int ID; @@ -153,6 +165,7 @@ namespace OP_DFU { // Helper functions: QString StatusToString(OP_DFU::Status const & status); static quint32 CRC32WideFast(quint32 Crc, quint32 Size, quint32 *Buffer); + OP_DFU::eBoardType GetBoardType(int boardNum); diff --git a/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.cpp b/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.cpp index 2cb513344..fcde00125 100644 --- a/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.cpp +++ b/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.cpp @@ -128,7 +128,7 @@ void runningDeviceWidget::populate() myDevice->lblCertified->setToolTip(tr("Untagged or custom firmware build")); } myDevice->lblGitCommitTag->setText("Git commit tag: "+devDesc.gitTag); - myDevice->lblFWDate->setText(QString("Firmware date: ") + devDesc.buildDate); + myDevice->lblFWDate->setText(QString("Firmware date: ") + devDesc.buildDate.insert(4,"-").insert(7,"-")); } else { diff --git a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp index 397533c2b..c0a1aea90 100755 --- a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp @@ -25,6 +25,9 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ #include "uploadergadgetwidget.h" +#include "../../../../../build/ground/openpilotgcs/gcsversioninfo.h" +#include +#include #define DFU_DEBUG true @@ -37,18 +40,21 @@ UploaderGadgetWidget::UploaderGadgetWidget(QWidget *parent) : QWidget(parent) dfu = NULL; m_timer = 0; m_progress = 0; - + msg=new QErrorMessage(this); // Listen to autopilot connection events ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); TelemetryManager* telMngr = pm->getObject(); connect(telMngr, SIGNAL(connected()), this, SLOT(onAutopilotConnect())); + connect(telMngr, SIGNAL(connected()), this, SLOT(versionMatchCheck())); + connect(telMngr, SIGNAL(disconnected()), this, SLOT(onAutopilotDisconnect())); connect(m_config->haltButton, SIGNAL(clicked()), this, SLOT(goToBootloader())); connect(m_config->resetButton, SIGNAL(clicked()), this, SLOT(systemReset())); connect(m_config->bootButton, SIGNAL(clicked()), this, SLOT(systemBoot())); connect(m_config->rescueButton, SIGNAL(clicked()), this, SLOT(systemRescue())); - + Core::ConnectionManager *cm = Core::ICore::instance()->connectionManager(); + connect(cm,SIGNAL(deviceConnected(QIODevice*)),this,SLOT(onPhisicalHWConnect())); getSerialPorts(); QIcon rbi; @@ -59,7 +65,10 @@ UploaderGadgetWidget::UploaderGadgetWidget(QWidget *parent) : QWidget(parent) // And check whether by any chance we are not already connected if (telMngr->isConnected()) + { onAutopilotConnect(); + versionMatchCheck(); + } } @@ -105,12 +114,22 @@ QString UploaderGadgetWidget::getPortDevice(const QString &friendName) } return ""; } - +void UploaderGadgetWidget::onPhisicalHWConnect() +{ + m_config->bootButton->setEnabled(false); + m_config->rescueButton->setEnabled(false); + m_config->telemetryLink->setEnabled(false); +} /** Enables widget buttons if autopilot connected */ void UploaderGadgetWidget::onAutopilotConnect(){ + QTimer::singleShot(1000,this,SLOT(populate())); +} + +void UploaderGadgetWidget::populate() +{ m_config->haltButton->setEnabled(true); m_config->resetButton->setEnabled(true); m_config->bootButton->setEnabled(false); @@ -127,7 +146,6 @@ void UploaderGadgetWidget::onAutopilotConnect(){ runningDeviceWidget* dw = new runningDeviceWidget(this); dw->populate(); m_config->systemElements->addTab(dw, QString("Connected Device")); - } /** @@ -235,9 +253,7 @@ void UploaderGadgetWidget::goToBootloader(UAVObject* callerObj, bool success) currentStep = IAP_STATE_BOOTLOADER; // Tell the mainboard to get into bootloader state: - log("Detecting devices, please wait 5 seconds..."); - this->repaint(); - delay::msleep(5100); // Required to let the board(s) settle + log("Detecting devices, please wait a few seconds..."); if (!dfu) { if (dlj.startsWith("USB")) dfu = new DFUObject(DFU_DEBUG, false, QString()); @@ -476,7 +492,7 @@ void UploaderGadgetWidget::systemRescue() m_config->rescueButton->setEnabled(true); return; } - if(QMessageBox::question(this,tr("OpenPilot Uploader"),tr("If you want to search for other boards connect power now and press Yes"),QMessageBox::Yes,QMessageBox::No)==QMessageBox::Yes) + if ((eBoardCC != dfu->GetBoardType(0)) && (QMessageBox::question(this,tr("OpenPilot Uploader"),tr("If you want to search for other boards connect power now and press Yes"),QMessageBox::Yes,QMessageBox::No)==QMessageBox::Yes)) { log("\nWaiting..."); QTimer::singleShot(3000, &m_eventloop, SLOT(quit())); @@ -599,3 +615,22 @@ void UploaderGadgetWidget::info(QString infoString, int infoNumber) Q_UNUSED(infoNumber); m_config->boardStatus->setText(infoString); } + +void UploaderGadgetWidget::versionMatchCheck() +{ + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + UAVObjectUtilManager* utilMngr = pm->getObject(); + deviceDescriptorStruct boardDescription=utilMngr->getBoardDescriptionStruct(); + QString gcsDescription=QString::fromLatin1(Core::Constants::GCS_REVISION_STR); + if(boardDescription.gitTag!=gcsDescription.mid(gcsDescription.indexOf(":")+1,8)) + { + qDebug()<0) + msg->showMessage(QString("Incompatible GCS and FW detected, you should upgrade your board's Firmware to %1 version.").arg(gcsDescription)); + else + msg->showMessage(QString("Incompatible GCS and FW detected, you should upgrade your GCS to %1 version.").arg(boardDescription.gitTag+":"+boardDescription.buildDate)); + + } + } diff --git a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.h b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.h index 075dc18a0..9b1fa1433 100755 --- a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.h @@ -54,6 +54,7 @@ #include #include "devicedescriptorstruct.h" #include +#include using namespace OP_DFU; @@ -72,7 +73,7 @@ public: public slots: void onAutopilotConnect(); void onAutopilotDisconnect(); - + void populate(); private: Ui_UploaderWidget *m_config; DFUObject *dfu; @@ -84,7 +85,10 @@ private: QTimer* m_timer; QLineEdit* openFileNameLE; QEventLoop m_eventloop; + QErrorMessage * msg; private slots: + void onPhisicalHWConnect(); + void versionMatchCheck(); void error(QString errorString,int errorNumber); void info(QString infoString,int infoNumber); void goToBootloader(UAVObject* = NULL, bool = false); diff --git a/ground/uavobjgenerator/generators/flight/uavobjectgeneratorflight.cpp b/ground/uavobjgenerator/generators/flight/uavobjectgeneratorflight.cpp index 8d3a30b30..3d9fd12b6 100644 --- a/ground/uavobjgenerator/generators/flight/uavobjectgeneratorflight.cpp +++ b/ground/uavobjgenerator/generators/flight/uavobjectgeneratorflight.cpp @@ -34,6 +34,7 @@ bool UAVObjectGeneratorFlight::generate(UAVObjectParser* parser,QString template <<"uint16_t" << "uint32_t" << "float" << "uint8_t"; QString flightObjInit,objInc,objFileNames,objNames; + qint32 sizeCalc; flightCodePath = QDir( templatepath + QString("flight/UAVObjects")); flightOutputPath = QDir( outputpath + QString("flight") ); flightOutputPath.mkpath(flightOutputPath.absolutePath()); @@ -41,6 +42,7 @@ bool UAVObjectGeneratorFlight::generate(UAVObjectParser* parser,QString template flightCodeTemplate = readFile( flightCodePath.absoluteFilePath("uavobjecttemplate.c") ); flightIncludeTemplate = readFile( flightCodePath.absoluteFilePath("inc/uavobjecttemplate.h") ); flightInitTemplate = readFile( flightCodePath.absoluteFilePath("uavobjectsinittemplate.c") ); + flightInitIncludeTemplate = readFile( flightCodePath.absoluteFilePath("inc/uavobjectsinittemplate.h") ); flightMakeTemplate = readFile( flightCodePath.absoluteFilePath("Makefiletemplate.inc") ); if ( flightCodeTemplate.isNull() || flightIncludeTemplate.isNull() || flightInitTemplate.isNull()) { @@ -48,6 +50,7 @@ bool UAVObjectGeneratorFlight::generate(UAVObjectParser* parser,QString template return false; } + sizeCalc = 0; for (int objidx = 0; objidx < parser->getNumObjects(); ++objidx) { ObjectInfo* info=parser->getObjectByIndex(objidx); process_object(info); @@ -57,6 +60,9 @@ bool UAVObjectGeneratorFlight::generate(UAVObjectParser* parser,QString template objInc.append("#include \"" + info->namelc + ".h\"\r\n"); objFileNames.append(" " + info->namelc); objNames.append(" " + info->name); + if (parser->getNumBytes(objidx)>sizeCalc) { + sizeCalc = parser->getNumBytes(objidx); + } } // Write the flight object inialization files @@ -65,7 +71,16 @@ bool UAVObjectGeneratorFlight::generate(UAVObjectParser* parser,QString template bool res = writeFileIfDiffrent( flightOutputPath.absolutePath() + "/uavobjectsinit.c", flightInitTemplate ); if (!res) { - cout << "Error: Could not write flight object init files" << endl; + cout << "Error: Could not write flight object init file" << endl; + return false; + } + + // Write the flight object initialization header + flightInitIncludeTemplate.replace( QString("$(SIZECALCULATION)"), QString().setNum(sizeCalc)); + res = writeFileIfDiffrent( flightOutputPath.absolutePath() + "/uavobjectsinit.h", + flightInitIncludeTemplate ); + if (!res) { + cout << "Error: Could not write flight object init header file" << endl; return false; } diff --git a/ground/uavobjgenerator/generators/flight/uavobjectgeneratorflight.h b/ground/uavobjgenerator/generators/flight/uavobjectgeneratorflight.h index 1050b2943..db728374b 100644 --- a/ground/uavobjgenerator/generators/flight/uavobjectgeneratorflight.h +++ b/ground/uavobjgenerator/generators/flight/uavobjectgeneratorflight.h @@ -34,7 +34,7 @@ class UAVObjectGeneratorFlight public: bool generate(UAVObjectParser* gen,QString templatepath,QString outputpath); QStringList fieldTypeStrC; - QString flightCodeTemplate, flightIncludeTemplate, flightInitTemplate, flightMakeTemplate; + QString flightCodeTemplate, flightIncludeTemplate, flightInitTemplate, flightInitIncludeTemplate, flightMakeTemplate; QDir flightCodePath; QDir flightOutputPath; diff --git a/ground/uavobjgenerator/generators/generator_common.h b/ground/uavobjgenerator/generators/generator_common.h index 0ae6f470e..95dab21e5 100644 --- a/ground/uavobjgenerator/generators/generator_common.h +++ b/ground/uavobjgenerator/generators/generator_common.h @@ -31,7 +31,7 @@ #include "generator_io.h" // These special chars (regexp) will be removed from C/java identifiers -#define ENUM_SPECIAL_CHARS "[\\.\\-\\s/]" +#define ENUM_SPECIAL_CHARS "[\\.\\-\\s\\+/\\(\\)]" void replaceCommonTags(QString& out, ObjectInfo* info); void replaceCommonTags(QString& out); diff --git a/ground/uavobjgenerator/generators/matlab/uavobjectgeneratormatlab.cpp b/ground/uavobjgenerator/generators/matlab/uavobjectgeneratormatlab.cpp index 61882e6b9..9f160ad52 100644 --- a/ground/uavobjgenerator/generators/matlab/uavobjectgeneratormatlab.cpp +++ b/ground/uavobjgenerator/generators/matlab/uavobjectgeneratormatlab.cpp @@ -50,9 +50,11 @@ bool UAVObjectGeneratorMatlab::generate(UAVObjectParser* parser,QString template } matlabCodeTemplate.replace( QString("$(ALLOCATIONCODE)"), matlabAllocationCode); - matlabCodeTemplate.replace( QString("$(SWITCHCODE)"), matlabSwithCode); + matlabCodeTemplate.replace( QString("$(SWITCHCODE)"), matlabSwitchCode); + matlabCodeTemplate.replace( QString("$(CLEANUPCODE)"), matlabCleanupCode); matlabCodeTemplate.replace( QString("$(SAVEOBJECTSCODE)"), matlabSaveObjectsCode); matlabCodeTemplate.replace( QString("$(FUNCTIONSCODE)"), matlabFunctionsCode); + matlabCodeTemplate.replace( QString("$(EXPORTCSVCODE)"), matlabExportCsvCode); bool res = writeFile( matlabOutputPath.absolutePath() + "/OPLogConvert.m", matlabCodeTemplate ); if (!res) { @@ -71,48 +73,106 @@ bool UAVObjectGeneratorMatlab::process_object(ObjectInfo* info) if (info == NULL) return false; + //Declare variables QString objectName(info->name); // QString objectTableName(objectName + "Objects"); QString objectTableName(objectName); QString tableIdxName(objectName.toLower() + "Idx"); QString functionName("Read" + info->name + "Object"); - QString functionCall(functionName + "(fid, timestamp)"); + QString functionCall(functionName + "(fid, timestamp, "); QString objectID(QString().setNum(info->id)); QString isSingleInst = boolTo01String( info->isSingleInst ); - // Generate allocation code (will replace the $(ALLOCATIONCODE) tag) - matlabAllocationCode.append("\n " + tableIdxName + " = 1;\n"); - matlabAllocationCode.append(" " + objectTableName + ".timestamp = 0;\n"); - QString type; - QString allocfields; - for (int n = 0; n < info->fields.length(); ++n) { - // Determine type - type = fieldTypeStrMatlab[info->fields[n]->type]; - // Append field - if ( info->fields[n]->numElements > 1 ) - allocfields.append(" " + objectTableName + "(1)." + info->fields[n]->name + " = zeros(1," + QString::number(info->fields[n]->numElements, 10) + ");\n"); - else - allocfields.append(" " + objectTableName + "(1)." + info->fields[n]->name + " = 0;\n"); + + //===================================================================// + // Generate allocation code (will replace the $(ALLOCATIONCODE) tag) // + //===================================================================// + // matlabSwitchCode.append("\t\tcase " + objectID + "\n"); + matlabAllocationCode.append("\n\t" + tableIdxName + " = 0;\n"); + QString type; + QString allocfields; + if (0){ + matlabAllocationCode.append("\t" + objectTableName + ".timestamp = 0;\n"); + for (int n = 0; n < info->fields.length(); ++n) { + // Determine type + type = fieldTypeStrMatlab[info->fields[n]->type]; + // Append field + if ( info->fields[n]->numElements > 1 ) + allocfields.append("\t" + objectTableName + "(1)." + info->fields[n]->name + " = zeros(" + QString::number(info->fields[n]->numElements, 10) + ",1);\n"); + else + allocfields.append("\t" + objectTableName + "(1)." + info->fields[n]->name + " = 0;\n"); + } + } + else{ + matlabAllocationCode.append("\t" + objectTableName + "=struct('timestamp', 0"); + if (!info->isSingleInst) { + allocfields.append(",...\n\t\t 'instanceID', 0"); + } + for (int n = 0; n < info->fields.length(); ++n) { + // Determine type + type = fieldTypeStrMatlab[info->fields[n]->type]; + // Append field + if ( info->fields[n]->numElements > 1 ) + allocfields.append(",...\n\t\t '" + info->fields[n]->name + "', zeros(" + QString::number(info->fields[n]->numElements, 10) + ",1)"); + else + allocfields.append(",...\n\t\t '" + info->fields[n]->name + "', 0"); + } + allocfields.append(");\n"); } matlabAllocationCode.append(allocfields); + matlabAllocationCode.append("\t" + objectTableName.toUpper() + "_OBJID=" + objectID + ";\n"); - // Generate 'swith:' code (will replace the $(SWITCHCODE) tag) - matlabSwithCode.append(" case " + objectID + "\n"); - matlabSwithCode.append(" " + objectTableName + "(" + tableIdxName +") = " + functionCall + ";\n"); - matlabSwithCode.append(" " + tableIdxName + " = " + tableIdxName +" + 1;\n"); - // Generate objects saving code code (will replace the $(SAVEOBJECTSCODE) tag) + //==============================================================// + // Generate 'Switch:' code (will replace the $(SWITCHCODE) tag) // + //==============================================================// + + + + matlabSwitchCode.append("\t\tcase " + objectTableName.toUpper() + "_OBJID\n"); +// matlabSwitchCode.append("\t\t\t" + objectTableName + "(" + tableIdxName +") = " + functionCall + ";\n"); + matlabSwitchCode.append("\t\t\t" + tableIdxName + " = " + tableIdxName +" + 1;\n"); + matlabSwitchCode.append("\t\t\t" + objectTableName + "= " + functionCall + objectTableName + ", " + tableIdxName + ");\n"); + matlabSwitchCode.append("\t\t\tif " + tableIdxName + " >= length(" + objectTableName +") %Check to see if pre-allocated memory is exhausted\n"); + matlabSwitchCode.append("\t\t\t\tFieldNames= fieldnames(" + objectTableName +");\n"); + matlabSwitchCode.append("\t\t\t\tfor i=1:length(FieldNames) %Grow structure\n"); + matlabSwitchCode.append("\t\t\t\t\t" + objectTableName + ".(FieldNames{i})(:," + tableIdxName + "*2+1) = 0;\n"); + matlabSwitchCode.append("\t\t\t\tend;\n"); + matlabSwitchCode.append("\t\t\tend\n"); + + + //============================================================// + // Generate 'Cleanup:' code (will replace the $(CLEANUP) tag) // + //============================================================// + matlabCleanupCode.append(objectTableName + "=PruneStructOfArrays(" + objectTableName + "," + tableIdxName +"); %#ok\n" ); + + + //========================================================================// + // Generate objects saving code (will replace the $(SAVEOBJECTSCODE) tag) // + //========================================================================// matlabSaveObjectsCode.append(",'"+objectTableName+"'"); - // Generate functions code (will replace the $(FUNCTIONSCODE) tag) - matlabFunctionsCode.append("function [" + objectName + "] = " + functionCall + "\n"); - matlabFunctionsCode.append(" if " + isSingleInst + "\n"); - matlabFunctionsCode.append(" headerSize = 8;\n"); - matlabFunctionsCode.append(" else\n"); - matlabFunctionsCode.append(" " + objectName + ".instanceID = fread(fid, 1, 'uint16');\n"); - matlabFunctionsCode.append(" headerSize = 10;\n"); - matlabFunctionsCode.append(" end\n\n"); - matlabFunctionsCode.append(" " + objectName + ".timestamp = timestamp;\n"); + + //==========================================================================// + // Generate objects csv export code (will replace the $(EXPORTCSVCODE) tag) // + //==========================================================================// + matlabExportCsvCode.append("\tOPLog2csv(" + objectTableName + ", '"+objectTableName+"', logfile);\n"); +// OPLog2csv(ActuatorCommand, 'ActuatorCommand', logfile) + + //=================================================================// + // Generate functions code (will replace the $(FUNCTIONSCODE) tag) // + //=================================================================// + //Generate function description comment + matlabFunctionsCode.append("%%\n% " + objectName + " read function\n"); + + matlabFunctionsCode.append("function [" + objectName + "] = " + functionCall + objectTableName + ", " + tableIdxName + ")" + "\n"); + matlabFunctionsCode.append("\t" + objectName + ".timestamp(" + tableIdxName + ")= timestamp;\n"); + matlabFunctionsCode.append("\tif " + isSingleInst + "\n"); + matlabFunctionsCode.append("\t\theaderSize = 8;\n"); + matlabFunctionsCode.append("\telse\n"); + matlabFunctionsCode.append("\t\t" + objectName + ".instanceID(" + tableIdxName + ") = (fread(fid, 1, 'uint16'));\n"); + matlabFunctionsCode.append("\t\theaderSize = 10;\n"); + matlabFunctionsCode.append("\tend\n\n"); // Generate functions code, actual fields of the object QString funcfields; @@ -122,16 +182,16 @@ bool UAVObjectGeneratorMatlab::process_object(ObjectInfo* info) type = fieldTypeStrMatlab[info->fields[n]->type]; // Append field if ( info->fields[n]->numElements > 1 ) - funcfields.append(" " + objectName + "." + info->fields[n]->name + " = double(fread(fid, " + QString::number(info->fields[n]->numElements, 10) + ", '" + type + "'));\n"); + funcfields.append("\t" + objectName + "." + info->fields[n]->name + "(:," + tableIdxName + ") = double(fread(fid, " + QString::number(info->fields[n]->numElements, 10) + ", '" + type + "'));\n"); else - funcfields.append(" " + objectName + "." + info->fields[n]->name + " = double(fread(fid, 1, '" + type + "'));\n"); + funcfields.append("\t" + objectName + "." + info->fields[n]->name + "(" + tableIdxName + ") = double(fread(fid, 1, '" + type + "'));\n"); } matlabFunctionsCode.append(funcfields); - matlabFunctionsCode.append(" % read CRC\n"); - matlabFunctionsCode.append(" fread(fid, 1, 'uint8');\n"); + matlabFunctionsCode.append("\t% read CRC\n"); + matlabFunctionsCode.append("\tfread(fid, 1, '*uint8');\n"); - matlabFunctionsCode.append("end\n\n"); + matlabFunctionsCode.append("\n\n"); return true; } diff --git a/ground/uavobjgenerator/generators/matlab/uavobjectgeneratormatlab.h b/ground/uavobjgenerator/generators/matlab/uavobjectgeneratormatlab.h index a5652b9e5..c4025a4f4 100644 --- a/ground/uavobjgenerator/generators/matlab/uavobjectgeneratormatlab.h +++ b/ground/uavobjgenerator/generators/matlab/uavobjectgeneratormatlab.h @@ -37,8 +37,10 @@ public: private: bool process_object(ObjectInfo* info); QString matlabAllocationCode; - QString matlabSwithCode; + QString matlabSwitchCode; + QString matlabCleanupCode; QString matlabSaveObjectsCode; + QString matlabExportCsvCode; QString matlabFunctionsCode; QStringList fieldTypeStrMatlab; diff --git a/ground/uavobjgenerator/uavobjectparser.cpp b/ground/uavobjgenerator/uavobjectparser.cpp index cba02f8ee..414712658 100644 --- a/ground/uavobjgenerator/uavobjectparser.cpp +++ b/ground/uavobjgenerator/uavobjectparser.cpp @@ -111,6 +111,11 @@ int UAVObjectParser::getNumBytes(int objIndex) } } +bool fieldTypeLessThan(const FieldInfo* f1, const FieldInfo* f2) +{ + return f1->numBytes > f2->numBytes; +} + /** * Parse supplied XML file * @param xml The xml text @@ -200,6 +205,9 @@ QString UAVObjectParser::parseXML(QString& xml, QString& filename) // Get next element childNode = childNode.nextSibling(); } + + // Sort all fields according to size + qStableSort(info->fields.begin(), info->fields.end(), fieldTypeLessThan); // Make sure that required elements were found if ( !accessFound ) diff --git a/make/boards/ahrs/board-info.mk b/make/boards/ahrs/board-info.mk index 2103357ba..85135ea25 100644 --- a/make/boards/ahrs/board-info.mk +++ b/make/boards/ahrs/board-info.mk @@ -9,6 +9,8 @@ BOARD := STM32103CB_AHRS MODEL := MD MODEL_SUFFIX := +OPENOCD_CONFIG := stm32f1x.cfg + # Note: These must match the values in link_$(BOARD)_memory.ld BL_BANK_BASE := 0x08000000 # Start of bootloader flash BL_BANK_SIZE := 0x00002000 # Should include BD_INFO region diff --git a/make/boards/coptercontrol/board-info.mk b/make/boards/coptercontrol/board-info.mk index 012c6ef16..547692212 100644 --- a/make/boards/coptercontrol/board-info.mk +++ b/make/boards/coptercontrol/board-info.mk @@ -9,6 +9,8 @@ BOARD := STM32103CB_CC_Rev1 MODEL := MD MODEL_SUFFIX := _CC +OPENOCD_CONFIG := stm32f1x.cfg + # Note: These must match the values in link_$(BOARD)_memory.ld BL_BANK_BASE := 0x08000000 # Start of bootloader flash BL_BANK_SIZE := 0x00003000 # Should include BD_INFO region diff --git a/make/boards/ins/board-info.mk b/make/boards/ins/board-info.mk index 8a57661bf..a20bd606c 100644 --- a/make/boards/ins/board-info.mk +++ b/make/boards/ins/board-info.mk @@ -9,6 +9,8 @@ BOARD := STM3210E_INS MODEL := HD MODEL_SUFFIX := _OP +OPENOCD_CONFIG := stm32f1x.cfg + # Note: These must match the values in link_$(BOARD)_memory.ld BL_BANK_BASE := 0x08000000 # Start of bootloader flash BL_BANK_SIZE := 0x00002000 # Should include BD_INFO region diff --git a/make/boards/openpilot/board-info.mk b/make/boards/openpilot/board-info.mk index f1e35505c..d9cff166d 100644 --- a/make/boards/openpilot/board-info.mk +++ b/make/boards/openpilot/board-info.mk @@ -9,6 +9,8 @@ BOARD := STM3210E_OP MODEL := HD MODEL_SUFFIX := _OP +OPENOCD_CONFIG := stm32f1x.cfg + # Note: These must match the values in link_$(BOARD)_memory.ld BL_BANK_BASE := 0x08000000 # Start of bootloader flash BL_BANK_SIZE := 0x00005000 # Should include BD_INFO region diff --git a/make/firmware-defs.mk b/make/firmware-defs.mk index 901a6c454..b22a66639 100644 --- a/make/firmware-defs.mk +++ b/make/firmware-defs.mk @@ -201,6 +201,7 @@ endef # $(1) = Name of binary image to write # $(2) = Base of flash region to write/wipe # $(3) = Size of flash region to write/wipe +# $(4) = OpenOCD configuration file to use define JTAG_TEMPLATE # --------------------------------------------------------------------------- # Options for OpenOCD flash-programming @@ -213,7 +214,7 @@ OOCD_EXE ?= openocd OOCD_JTAG_SETUP = -d0 # interface and board/target settings (using the OOCD target-library here) OOCD_JTAG_SETUP += -s $(TOP)/flight/Project/OpenOCD -OOCD_JTAG_SETUP += -f foss-jtag.revb.cfg -f stm32.cfg +OOCD_JTAG_SETUP += -f foss-jtag.revb.cfg -f $(4) # initialize OOCD_BOARD_RESET = -c init @@ -242,4 +243,5 @@ wipe: -c "flash erase_address pad $(2) $(3)" \ -c "reset run" \ -c "shutdown" -endef \ No newline at end of file +endef + diff --git a/package/Makefile b/package/Makefile index 0a197844a..5598be8c3 100644 --- a/package/Makefile +++ b/package/Makefile @@ -29,11 +29,11 @@ CLEAN_GROUND := YES CLEAN_FLIGHT := YES endif -# Set up targets (PPM target seems to be broken at the moment) -FW_TARGETS := $(addprefix fw_, ahrs pipxtreme coptercontrol openpilot) +# Set up targets +FW_TARGETS := $(addprefix fw_, coptercontrol) FW_TARGETS_TOOLS := $(addprefix fw_, coptercontrol) -BL_TARGETS := $(addprefix bl_, coptercontrol openpilot ahrs pipxtreme) -BU_TARGETS := $(addprefix bu_, coptercontrol openpilot ahrs pipxtreme) +BL_TARGETS := $(addprefix bl_, coptercontrol) +BU_TARGETS := $(addprefix bu_, coptercontrol) help: @echo diff --git a/package/Makefile.linux b/package/Makefile.linux index c966ff6f2..fba2ef3ff 100644 --- a/package/Makefile.linux +++ b/package/Makefile.linux @@ -2,9 +2,75 @@ # Linux-specific packaging # +define CP_DEB_FILES_TEMPLATE +.PHONY: $(2)/$(1) +$(2)/$(1): $(3)/$(1) + $(V1)cp -a $$< $$@ +endef + +# Update this number for every formal release. The Deb packaging system relies on this to know to update a +# package or not. Otherwise, the user has to uninstall first. +VERNUM := 0.1.0 +VERSION_FULL := $(VERNUM)-$(PACKAGE_LBL) + +FLIGHT_FW := coptercontrol revolution + +DEB_BUILD_DIR := $(ROOT_DIR)/debian + +SED_DATE_STRG = $(shell date -R) +SED_SCRIPT = s//$(VERSION_FULL)/;s//$(SED_DATE_STRG)/ + +DEB_CFG_CMN := $(ROOT_DIR)/package/linux/deb_common +DEB_CFG_CMN_FILES := $(shell ls $(DEB_CFG_CMN)) +DEB_CFG_I386_DIR := $(ROOT_DIR)/package/linux/deb_i386 +DEB_CFG_I386_FILES := $(shell ls $(DEB_CFG_I386_DIR)) +DEB_CFG_AMD64_DIR := $(ROOT_DIR)/package/linux/deb_amd64 +DEB_CFG_AMD64_FILES := $(shell ls $(DEB_CFG_AMD64_DIR)) +DEB_PLATFORM := amd64 +DEB_MACHINE_DIR := $(DEB_CFG_AMD64_DIR) +DEB_MACHINE_FILES := $(DEB_CFG_AMD64_FILES) +MACHINE_TYPE := $(shell uname -m) +ifneq ($(MACHINE_TYPE), x86_64) + DEB_PLATFORM := i386 + DEB_MACHINE_DIR := $(DEB_CFG_I386_DIR) + DEB_MACHINE_FILES := $(DEB_CFG_I386_FILES) +endif +ALL_DEB_FILES = $(foreach f, $(DEB_CFG_CMN_FILES), $(DEB_BUILD_DIR)/$(f)) +ALL_DEB_FILES += $(foreach f, $(DEB_MACHINE_FILES), $(DEB_BUILD_DIR)/$(f)) + +DEB_PACKAGE_NAME := openpilot_$(VERSION_FULL)_$(DEB_PLATFORM) + +linux_deb_package: deb_build gcs + @echo $@ starting + cd .. && dpkg-buildpackage -b + $(V1)mv $(ROOT_DIR)/../$(DEB_PACKAGE_NAME).deb $(BUILD_DIR) + $(V1)mv $(ROOT_DIR)/../$(DEB_PACKAGE_NAME).changes $(BUILD_DIR) + $(V1)rm -rf $(DEB_BUILD_DIR) + +deb_build: | $(DEB_BUILD_DIR) $(ALL_DEB_FILES) $(BUILD_DIR)/build + @echo $@ starting + $(V1)$(shell echo $(PACKAGE_DIR) > $(BUILD_DIR)/package_dir) + $(V1)sed -i -e "$(SED_SCRIPT)" $(DEB_BUILD_DIR)/changelog + +$(BUILD_DIR)/build: package_flight + +$(DEB_BUILD_DIR): + @echo $@ starting + $(V1)mkdir -p $(DEB_BUILD_DIR) + +$(foreach cpfile, $(DEB_CFG_CMN_FILES), $(eval $(call CP_DEB_FILES_TEMPLATE,$(cpfile),$(DEB_BUILD_DIR),$(DEB_CFG_CMN)))) + +$(foreach cpfile, $(DEB_MACHINE_FILES), $(eval $(call CP_DEB_FILES_TEMPLATE,$(cpfile),$(DEB_BUILD_DIR),$(DEB_MACHINE_DIR)))) + gcs: uavobjects + @echo "Linux Package Make of GCS." $(V1) $(MAKE) -C $(ROOT_DIR) GCS_BUILD_CONF=release $@ -ground_package: | gcs +identify: + @echo "" + @echo "We are in the Linux Package Make system." + @echo "" -.PHONY: gcs ground_package +ground_package: | identify linux_deb_package + +.PHONY: identify gcs ground_package linux_deb_package deb_build $(DEB_BUILD_DIR) diff --git a/package/linux/45-openpilot-permissions.rules b/package/linux/45-openpilot-permissions.rules new file mode 100644 index 000000000..d04d31b7f --- /dev/null +++ b/package/linux/45-openpilot-permissions.rules @@ -0,0 +1,13 @@ + # OpenPilot openpilot flight control board + SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="4117", MODE="0664", GROUP="plugdev" + SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415a", MODE="0664", GROUP="plugdev" + # OpenPilot coptercontrol flight control board + SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415b", MODE="0664", GROUP="plugdev" + # OpenPilot Pipx radio modem board + SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415c", MODE="0664", GROUP="plugdev" + # unprogrammed openpilot flight control board + SUBSYSTEM=="usb", ATTRS{idVendor}=="0483", ATTRS{idProduct}=="5750", MODE="0664", GROUP="plugdev" + # FTDI FT2232C Dual USB-UART/FIFO IC + SUBSYSTEM=="usb", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6010", MODE="0664", GROUP="plugdev" + # Olimex Ltd. OpenOCD JTAG TINY + SUBSYSTEM=="usb", ATTRS{idVendor}=="15ba", ATTRS{idProduct}=="0004", MODE="0664", GROUP="plugdev" diff --git a/package/linux/deb_amd64/control b/package/linux/deb_amd64/control new file mode 100644 index 000000000..c2408ee21 --- /dev/null +++ b/package/linux/deb_amd64/control @@ -0,0 +1,15 @@ +Source: openpilot +Section: unknown +Priority: extra +Maintainer: naiiawah +Build-Depends: debhelper (>= 7.0.50~) +Standards-Version: 3.8.4 +Homepage: http://www.openpilot.org +Vcs-Git: git://git.openpilot.org/OpenPilot.git +Vcs-Browser: http://git.openpilot.org/changelog/OpenPilot + +Package: openpilot +Architecture: amd64 +Depends: ${shlibs:Depends}, ${misc:Depends} +Description: OpenPilot GCS & FW + OpenPilot GCS and Firmware for CopterControl (CC) board. diff --git a/package/linux/deb_common/changelog b/package/linux/deb_common/changelog new file mode 100644 index 000000000..c6f9e1519 --- /dev/null +++ b/package/linux/deb_common/changelog @@ -0,0 +1,5 @@ +openpilot () unstable; urgency=low + + * Initial release (testing - unstable) + + -- naiiawah diff --git a/package/linux/deb_common/compat b/package/linux/deb_common/compat new file mode 100644 index 000000000..7f8f011eb --- /dev/null +++ b/package/linux/deb_common/compat @@ -0,0 +1 @@ +7 diff --git a/package/linux/deb_common/copyright b/package/linux/deb_common/copyright new file mode 100644 index 000000000..561d0b327 --- /dev/null +++ b/package/linux/deb_common/copyright @@ -0,0 +1,37 @@ +This work was packaged for Debian by: + + naiiawah on Thu, 27 Oct 2011 01:35:37 -0600 + +It was downloaded from: + + + +Upstream Author(s): + + + + +Copyright: + + + + +License: + + + +The Debian packaging is: + + Copyright (C) 2011 naiiawah + +# Please chose a license for your packaging work. If the program you package +# uses a mainstream license, using the same license is the safest choice. +# Please avoid to pick license terms that are more restrictive than the +# packaged work, as it may make Debian's contributions unacceptable upstream. +# If you just want it to be GPL version 3, leave the following lines in. + +and is licensed under the GPL version 3, +see "/usr/share/common-licenses/GPL-3". + +# Please also look if there are files or directories which have a +# different copyright/license attached and list them here. diff --git a/package/linux/deb_common/docs b/package/linux/deb_common/docs new file mode 100644 index 000000000..e69de29bb diff --git a/package/linux/deb_common/init.d.ex b/package/linux/deb_common/init.d.ex new file mode 100644 index 000000000..fb3e26243 --- /dev/null +++ b/package/linux/deb_common/init.d.ex @@ -0,0 +1,154 @@ +#!/bin/sh +### BEGIN INIT INFO +# Provides: openpilot +# Required-Start: $network $local_fs +# Required-Stop: +# Default-Start: 2 3 4 5 +# Default-Stop: 0 1 6 +# Short-Description: +# Description: +# <...> +# <...> +### END INIT INFO + +# Author: naiiawah + +# PATH should only include /usr/* if it runs after the mountnfs.sh script +PATH=/sbin:/usr/sbin:/bin:/usr/bin +DESC=openpilot # Introduce a short description here +NAME=openpilot # Introduce the short server's name here +DAEMON=/usr/sbin/openpilot # Introduce the server's location here +DAEMON_ARGS="" # Arguments to run the daemon with +PIDFILE=/var/run/$NAME.pid +SCRIPTNAME=/etc/init.d/$NAME + +# Exit if the package is not installed +[ -x $DAEMON ] || exit 0 + +# Read configuration variable file if it is present +[ -r /etc/default/$NAME ] && . /etc/default/$NAME + +# Load the VERBOSE setting and other rcS variables +. /lib/init/vars.sh + +# Define LSB log_* functions. +# Depend on lsb-base (>= 3.0-6) to ensure that this file is present. +. /lib/lsb/init-functions + +# +# Function that starts the daemon/service +# +do_start() +{ + # Return + # 0 if daemon has been started + # 1 if daemon was already running + # 2 if daemon could not be started + start-stop-daemon --start --quiet --pidfile $PIDFILE --exec $DAEMON --test > /dev/null \ + || return 1 + start-stop-daemon --start --quiet --pidfile $PIDFILE --exec $DAEMON -- \ + $DAEMON_ARGS \ + || return 2 + # Add code here, if necessary, that waits for the process to be ready + # to handle requests from services started subsequently which depend + # on this one. As a last resort, sleep for some time. +} + +# +# Function that stops the daemon/service +# +do_stop() +{ + # Return + # 0 if daemon has been stopped + # 1 if daemon was already stopped + # 2 if daemon could not be stopped + # other if a failure occurred + start-stop-daemon --stop --quiet --retry=TERM/30/KILL/5 --pidfile $PIDFILE --name $NAME + RETVAL="$?" + [ "$RETVAL" = 2 ] && return 2 + # Wait for children to finish too if this is a daemon that forks + # and if the daemon is only ever run from this initscript. + # If the above conditions are not satisfied then add some other code + # that waits for the process to drop all resources that could be + # needed by services started subsequently. A last resort is to + # sleep for some time. + start-stop-daemon --stop --quiet --oknodo --retry=0/30/KILL/5 --exec $DAEMON + [ "$?" = 2 ] && return 2 + # Many daemons don't delete their pidfiles when they exit. + rm -f $PIDFILE + return "$RETVAL" +} + +# +# Function that sends a SIGHUP to the daemon/service +# +do_reload() { + # + # If the daemon can reload its configuration without + # restarting (for example, when it is sent a SIGHUP), + # then implement that here. + # + start-stop-daemon --stop --signal 1 --quiet --pidfile $PIDFILE --name $NAME + return 0 +} + +case "$1" in + start) + [ "$VERBOSE" != no ] && log_daemon_msg "Starting $DESC " "$NAME" + do_start + case "$?" in + 0|1) [ "$VERBOSE" != no ] && log_end_msg 0 ;; + 2) [ "$VERBOSE" != no ] && log_end_msg 1 ;; + esac + ;; + stop) + [ "$VERBOSE" != no ] && log_daemon_msg "Stopping $DESC" "$NAME" + do_stop + case "$?" in + 0|1) [ "$VERBOSE" != no ] && log_end_msg 0 ;; + 2) [ "$VERBOSE" != no ] && log_end_msg 1 ;; + esac + ;; + status) + status_of_proc "$DAEMON" "$NAME" && exit 0 || exit $? + ;; + #reload|force-reload) + # + # If do_reload() is not implemented then leave this commented out + # and leave 'force-reload' as an alias for 'restart'. + # + #log_daemon_msg "Reloading $DESC" "$NAME" + #do_reload + #log_end_msg $? + #;; + restart|force-reload) + # + # If the "reload" option is implemented then remove the + # 'force-reload' alias + # + log_daemon_msg "Restarting $DESC" "$NAME" + do_stop + case "$?" in + 0|1) + do_start + case "$?" in + 0) log_end_msg 0 ;; + 1) log_end_msg 1 ;; # Old process is still running + *) log_end_msg 1 ;; # Failed to start + esac + ;; + *) + # Failed to stop + log_end_msg 1 + ;; + esac + ;; + *) + #echo "Usage: $SCRIPTNAME {start|stop|restart|reload|force-reload}" >&2 + echo "Usage: $SCRIPTNAME {start|stop|status|restart|force-reload}" >&2 + exit 3 + ;; +esac + +: diff --git a/package/linux/deb_common/manpage.1.ex b/package/linux/deb_common/manpage.1.ex new file mode 100644 index 000000000..1d0199483 --- /dev/null +++ b/package/linux/deb_common/manpage.1.ex @@ -0,0 +1,59 @@ +.\" Hey, EMACS: -*- nroff -*- +.\" First parameter, NAME, should be all caps +.\" Second parameter, SECTION, should be 1-8, maybe w/ subsection +.\" other parameters are allowed: see man(7), man(1) +.TH OPENPILOT SECTION "October 27, 2011" +.\" Please adjust this date whenever revising the manpage. +.\" +.\" Some roff macros, for reference: +.\" .nh disable hyphenation +.\" .hy enable hyphenation +.\" .ad l left justify +.\" .ad b justify to both left and right margins +.\" .nf disable filling +.\" .fi enable filling +.\" .br insert line break +.\" .sp insert n+1 empty lines +.\" for manpage-specific macros, see man(7) +.SH NAME +openpilot \- program to do something +.SH SYNOPSIS +.B openpilot +.RI [ options ] " files" ... +.br +.B bar +.RI [ options ] " files" ... +.SH DESCRIPTION +This manual page documents briefly the +.B openpilot +and +.B bar +commands. +.PP +.\" TeX users may be more comfortable with the \fB\fP and +.\" \fI\fP escape sequences to invode bold face and italics, +.\" respectively. +\fBopenpilot\fP is a program that... +.SH OPTIONS +These programs follow the usual GNU command line syntax, with long +options starting with two dashes (`-'). +A summary of options is included below. +For a complete description, see the Info files. +.TP +.B \-h, \-\-help +Show summary of options. +.TP +.B \-v, \-\-version +Show version of program. +.SH SEE ALSO +.BR bar (1), +.BR baz (1). +.br +The programs are documented fully by +.IR "The Rise and Fall of a Fooish Bar" , +available via the Info system. +.SH AUTHOR +openpilot was written by . +.PP +This manual page was written by naiiawah , +for the Debian project (and may be used by others). diff --git a/package/linux/deb_common/manpage.sgml.ex b/package/linux/deb_common/manpage.sgml.ex new file mode 100644 index 000000000..76b474e3e --- /dev/null +++ b/package/linux/deb_common/manpage.sgml.ex @@ -0,0 +1,154 @@ + manpage.1'. You may view + the manual page with: `docbook-to-man manpage.sgml | nroff -man | + less'. A typical entry in a Makefile or Makefile.am is: + +manpage.1: manpage.sgml + docbook-to-man $< > $@ + + + The docbook-to-man binary is found in the docbook-to-man package. + Please remember that if you create the nroff version in one of the + debian/rules file targets (such as build), you will need to include + docbook-to-man in your Build-Depends control field. + + --> + + + FIRSTNAME"> + SURNAME"> + + October 27, 2011"> + + SECTION"> + naiiawah@none"> + + OPENPILOT"> + + + Debian"> + GNU"> + GPL"> +]> + + + +
+ &dhemail; +
+ + &dhfirstname; + &dhsurname; + + + 2003 + &dhusername; + + &dhdate; +
+ + &dhucpackage; + + &dhsection; + + + &dhpackage; + + program to do something + + + + &dhpackage; + + + + + + + + DESCRIPTION + + This manual page documents briefly the + &dhpackage; and bar + commands. + + This manual page was written for the &debian; distribution + because the original program does not have a manual page. + Instead, it has documentation in the &gnu; + Info format; see below. + + &dhpackage; is a program that... + + + + OPTIONS + + These programs follow the usual &gnu; command line syntax, + with long options starting with two dashes (`-'). A summary of + options is included below. For a complete description, see the + Info files. + + + + + + + + Show summary of options. + + + + + + + + Show version of program. + + + + + + SEE ALSO + + bar (1), baz (1). + + The programs are documented fully by The Rise and + Fall of a Fooish Bar available via the + Info system. + + + AUTHOR + + This manual page was written by &dhusername; &dhemail; for + the &debian; system (and may be used by others). Permission is + granted to copy, distribute and/or modify this document under + the terms of the &gnu; General Public License, Version 2 any + later version published by the Free Software Foundation. + + + On Debian systems, the complete text of the GNU General Public + License can be found in /usr/share/common-licenses/GPL. + + + +
+ + diff --git a/package/linux/deb_common/manpage.xml.ex b/package/linux/deb_common/manpage.xml.ex new file mode 100644 index 000000000..b8c0d8411 --- /dev/null +++ b/package/linux/deb_common/manpage.xml.ex @@ -0,0 +1,291 @@ + +.
will be generated. You may view the +manual page with: nroff -man .
| less'. A typical entry +in a Makefile or Makefile.am is: + +DB2MAN = /usr/share/sgml/docbook/stylesheet/xsl/docbook-xsl/manpages/docbook.xsl +XP = xsltproc -''-nonet -''-param man.charmap.use.subset "0" + +manpage.1: manpage.xml + $(XP) $(DB2MAN) $< + +The xsltproc binary is found in the xsltproc package. The XSL files are in +docbook-xsl. A description of the parameters you can use can be found in the +docbook-xsl-doc-* packages. Please remember that if you create the nroff +version in one of the debian/rules file targets (such as build), you will need +to include xsltproc and docbook-xsl in your Build-Depends control field. +Alternatively use the xmlto command/package. That will also automatically +pull in xsltproc and docbook-xsl. + +Notes for using docbook2x: docbook2x-man does not automatically create the +AUTHOR(S) and COPYRIGHT sections. In this case, please add them manually as + ... . + +To disable the automatic creation of the AUTHOR(S) and COPYRIGHT sections +read /usr/share/doc/docbook-xsl/doc/manpages/authors.html. This file can be +found in the docbook-xsl-doc-html package. + +Validation can be done using: `xmllint -''-noout -''-valid manpage.xml` + +General documentation about man-pages and man-page-formatting: +man(1), man(7), http://www.tldp.org/HOWTO/Man-Page/ + +--> + + + + + + + + + + + + + +]> + + + + &dhtitle; + &dhpackage; + + + &dhfirstname; + &dhsurname; + Wrote this manpage for the Debian system. +
+ &dhemail; +
+
+
+ + 2007 + &dhusername; + + + This manual page was written for the Debian system + (and may be used by others). + Permission is granted to copy, distribute and/or modify this + document under the terms of the GNU General Public License, + Version 2 or (at your option) any later version published by + the Free Software Foundation. + On Debian systems, the complete text of the GNU General Public + License can be found in + /usr/share/common-licenses/GPL. + +
+ + &dhucpackage; + &dhsection; + + + &dhpackage; + program to do something + + + + &dhpackage; + + + + + + + + + this + + + + + + + + this + that + + + + + &dhpackage; + + + + + + + + + + + + + + + + + + + DESCRIPTION + This manual page documents briefly the + &dhpackage; and bar + commands. + This manual page was written for the Debian distribution + because the original program does not have a manual page. + Instead, it has documentation in the GNU + info + 1 + format; see below. + &dhpackage; is a program that... + + + OPTIONS + The program follows the usual GNU command line syntax, + with long options starting with two dashes (`-'). A summary of + options is included below. For a complete description, see the + + info + 1 + files. + + + + + + + Does this and that. + + + + + + + Show summary of options. + + + + + + + Show version of program. + + + + + + FILES + + + /etc/foo.conf + + The system-wide configuration file to control the + behaviour of &dhpackage;. See + + foo.conf + 5 + for further details. + + + + ${HOME}/.foo.conf + + The per-user configuration file to control the + behaviour of &dhpackage;. See + + foo.conf + 5 + for further details. + + + + + + ENVIONMENT + + + FOO_CONF + + If used, the defined file is used as configuration + file (see also ). + + + + + + DIAGNOSTICS + The following diagnostics may be issued + on stderr: + + + Bad configuration file. Exiting. + + The configuration file seems to contain a broken configuration + line. Use the option, to get more info. + + + + + &dhpackage; provides some return codes, that can + be used in scripts: + + Code + Diagnostic + + 0 + Program exited successfully. + + + 1 + The configuration file seems to be broken. + + + + + + BUGS + The program is currently limited to only work + with the foobar library. + The upstreams BTS can be found + at . + + + SEE ALSO + + + bar + 1 + , + baz + 1 + , + foo.conf + 5 + + The programs are documented fully by The Rise and + Fall of a Fooish Bar available via the + info + 1 + system. + +
+ diff --git a/package/linux/deb_common/menu.ex b/package/linux/deb_common/menu.ex new file mode 100644 index 000000000..c5a80a7bc --- /dev/null +++ b/package/linux/deb_common/menu.ex @@ -0,0 +1,2 @@ +?package(openpilot):needs="X11|text|vc|wm" section="Applications/see-menu-manual"\ + title="openpilot" command="/usr/bin/openpilot" diff --git a/package/linux/deb_common/openpilot.cron.d.ex b/package/linux/deb_common/openpilot.cron.d.ex new file mode 100644 index 000000000..bc3507489 --- /dev/null +++ b/package/linux/deb_common/openpilot.cron.d.ex @@ -0,0 +1,4 @@ +# +# Regular cron jobs for the openpilot package +# +0 4 * * * root [ -x /usr/bin/openpilot_maintenance ] && /usr/bin/openpilot_maintenance diff --git a/package/linux/deb_common/openpilot.debhelper.log b/package/linux/deb_common/openpilot.debhelper.log new file mode 100644 index 000000000..34de80b19 --- /dev/null +++ b/package/linux/deb_common/openpilot.debhelper.log @@ -0,0 +1,15 @@ +dh_prep +dh_installdirs +dh_installchangelogs +dh_installdocs +dh_installexamples +dh_installman +dh_link +dh_strip +dh_compress +dh_fixperms +dh_installdeb +dh_shlibdeps +dh_gencontrol +dh_md5sums +dh_builddeb diff --git a/package/linux/deb_common/openpilot.default.ex b/package/linux/deb_common/openpilot.default.ex new file mode 100644 index 000000000..0b172a1fc --- /dev/null +++ b/package/linux/deb_common/openpilot.default.ex @@ -0,0 +1,10 @@ +# Defaults for openpilot initscript +# sourced by /etc/init.d/openpilot +# installed at /etc/default/openpilot by the maintainer scripts + +# +# This is a POSIX shell fragment +# + +# Additional options that are passed to the Daemon. +DAEMON_OPTS="" diff --git a/package/linux/deb_common/openpilot.dirs b/package/linux/deb_common/openpilot.dirs new file mode 100644 index 000000000..08bf6a7e1 --- /dev/null +++ b/package/linux/deb_common/openpilot.dirs @@ -0,0 +1,6 @@ +etc/xdg/menus/applications-merged +usr/share/applications +usr/share/pixmaps +usr/share/desktop-directories +usr/local/OpenPilot/firmware +usr/bin diff --git a/package/linux/deb_common/openpilot.doc-base.EX b/package/linux/deb_common/openpilot.doc-base.EX new file mode 100644 index 000000000..9e24da0dc --- /dev/null +++ b/package/linux/deb_common/openpilot.doc-base.EX @@ -0,0 +1,20 @@ +Document: openpilot +Title: Debian openpilot Manual +Author: +Abstract: This manual describes what openpilot is + and how it can be used to + manage online manuals on Debian systems. +Section: unknown + +Format: debiandoc-sgml +Files: /usr/share/doc/openpilot/openpilot.sgml.gz + +Format: postscript +Files: /usr/share/doc/openpilot/openpilot.ps.gz + +Format: text +Files: /usr/share/doc/openpilot/openpilot.text.gz + +Format: HTML +Index: /usr/share/doc/openpilot/html/index.html +Files: /usr/share/doc/openpilot/html/*.html diff --git a/package/linux/deb_common/openpilot.substvars b/package/linux/deb_common/openpilot.substvars new file mode 100644 index 000000000..39006599c --- /dev/null +++ b/package/linux/deb_common/openpilot.substvars @@ -0,0 +1,2 @@ +shlibs:Depends=libc6 (>= 2.3.6-6~), libc6 (>= 2.4), libgcc1 (>= 1:4.1.1), libgl1-mesa-glx | libgl1, libglu1-mesa | libglu1, libphonon4 (>= 4:4.3.0), libqt4-network (>= 4:4.6.1), libqt4-opengl (>= 4:4.6.1), libqt4-script (>= 4:4.5.3), libqt4-sql (>= 4:4.5.3), libqt4-svg (>= 4:4.5.3), libqt4-test (>= 4:4.5.3), libqt4-xml (>= 4:4.5.3), libqtcore4 (>= 4:4.7.0~beta1), libqtgui4 (>= 4:4.6.2), libsdl1.2debian (>= 1.2.10-1), libstdc++6 (>= 4.1.1), libudev0 (>= 147), libusb-0.1-4 (>= 2:0.1.12), phonon +misc:Depends= diff --git a/package/linux/deb_common/openpilot.udev b/package/linux/deb_common/openpilot.udev new file mode 100644 index 000000000..3d84dd426 --- /dev/null +++ b/package/linux/deb_common/openpilot.udev @@ -0,0 +1,18 @@ + # OpenPilot Flight Control board + SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="4117", MODE="0664", GROUP="plugdev" + # OpenPilot OP board + SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415a", MODE="0664", GROUP="plugdev" + # OpenPilot CopterControl flight control board + SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415b", MODE="0664", GROUP="plugdev" + # OpenPilot Pipx radio modem board + SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415c", MODE="0664", GROUP="plugdev" + # OpenPilot CopterControl3D flight control board + SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415d", MODE="0664", GROUP="plugdev" + # OpenPilot Revolution flight control board + SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415e", MODE="0664", GROUP="plugdev" + # unprogrammed openpilot flight control board + SUBSYSTEM=="usb", ATTRS{idVendor}=="0483", ATTRS{idProduct}=="5750", MODE="0664", GROUP="plugdev" + # FTDI FT2232C Dual USB-UART/FIFO IC + SUBSYSTEM=="usb", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6010", MODE="0664", GROUP="plugdev" + # Olimex Ltd. OpenOCD JTAG TINY + SUBSYSTEM=="usb", ATTRS{idVendor}=="15ba", ATTRS{idProduct}=="0004", MODE="0664", GROUP="plugdev" diff --git a/package/linux/deb_common/postinst b/package/linux/deb_common/postinst new file mode 100644 index 000000000..df8022075 --- /dev/null +++ b/package/linux/deb_common/postinst @@ -0,0 +1,40 @@ +#!/bin/sh +# postinst script for openpilot +# +# see: dh_installdeb(1) + +set -e + +# summary of how this script can be called: +# * `configure' +# * `abort-upgrade' +# * `abort-remove' `in-favour' +# +# * `abort-remove' +# * `abort-deconfigure' `in-favour' +# `removing' +# +# for details, see http://www.debian.org/doc/debian-policy/ or +# the debian-policy package + + +case "$1" in + configure) + sudo udevadm control --reload-rules >&2 + ;; + + abort-upgrade|abort-remove|abort-deconfigure) + ;; + + *) + echo "postinst called with unknown argument \`$1'" >&2 + exit 1 + ;; +esac + +# dh_installdeb will replace this with shell code automatically +# generated by other debhelper scripts. + +#DEBHELPER# + +exit 0 diff --git a/package/linux/deb_common/postinst.ex b/package/linux/deb_common/postinst.ex new file mode 100644 index 000000000..e8295471c --- /dev/null +++ b/package/linux/deb_common/postinst.ex @@ -0,0 +1,39 @@ +#!/bin/sh +# postinst script for openpilot +# +# see: dh_installdeb(1) + +set -e + +# summary of how this script can be called: +# * `configure' +# * `abort-upgrade' +# * `abort-remove' `in-favour' +# +# * `abort-remove' +# * `abort-deconfigure' `in-favour' +# `removing' +# +# for details, see http://www.debian.org/doc/debian-policy/ or +# the debian-policy package + + +case "$1" in + configure) + ;; + + abort-upgrade|abort-remove|abort-deconfigure) + ;; + + *) + echo "postinst called with unknown argument \`$1'" >&2 + exit 1 + ;; +esac + +# dh_installdeb will replace this with shell code automatically +# generated by other debhelper scripts. + +#DEBHELPER# + +exit 0 diff --git a/package/linux/deb_common/postrm.ex b/package/linux/deb_common/postrm.ex new file mode 100644 index 000000000..7494eff83 --- /dev/null +++ b/package/linux/deb_common/postrm.ex @@ -0,0 +1,37 @@ +#!/bin/sh +# postrm script for openpilot +# +# see: dh_installdeb(1) + +set -e + +# summary of how this script can be called: +# * `remove' +# * `purge' +# * `upgrade' +# * `failed-upgrade' +# * `abort-install' +# * `abort-install' +# * `abort-upgrade' +# * `disappear' +# +# for details, see http://www.debian.org/doc/debian-policy/ or +# the debian-policy package + + +case "$1" in + purge|remove|upgrade|failed-upgrade|abort-install|abort-upgrade|disappear) + ;; + + *) + echo "postrm called with unknown argument \`$1'" >&2 + exit 1 + ;; +esac + +# dh_installdeb will replace this with shell code automatically +# generated by other debhelper scripts. + +#DEBHELPER# + +exit 0 diff --git a/package/linux/deb_common/preinst.ex b/package/linux/deb_common/preinst.ex new file mode 100644 index 000000000..32ac40cc3 --- /dev/null +++ b/package/linux/deb_common/preinst.ex @@ -0,0 +1,35 @@ +#!/bin/sh +# preinst script for openpilot +# +# see: dh_installdeb(1) + +set -e + +# summary of how this script can be called: +# * `install' +# * `install' +# * `upgrade' +# * `abort-upgrade' +# for details, see http://www.debian.org/doc/debian-policy/ or +# the debian-policy package + + +case "$1" in + install|upgrade) + ;; + + abort-upgrade) + ;; + + *) + echo "preinst called with unknown argument \`$1'" >&2 + exit 1 + ;; +esac + +# dh_installdeb will replace this with shell code automatically +# generated by other debhelper scripts. + +#DEBHELPER# + +exit 0 diff --git a/package/linux/deb_common/prerm.ex b/package/linux/deb_common/prerm.ex new file mode 100644 index 000000000..a46c87175 --- /dev/null +++ b/package/linux/deb_common/prerm.ex @@ -0,0 +1,38 @@ +#!/bin/sh +# prerm script for openpilot +# +# see: dh_installdeb(1) + +set -e + +# summary of how this script can be called: +# * `remove' +# * `upgrade' +# * `failed-upgrade' +# * `remove' `in-favour' +# * `deconfigure' `in-favour' +# `removing' +# +# for details, see http://www.debian.org/doc/debian-policy/ or +# the debian-policy package + + +case "$1" in + remove|upgrade|deconfigure) + ;; + + failed-upgrade) + ;; + + *) + echo "prerm called with unknown argument \`$1'" >&2 + exit 1 + ;; +esac + +# dh_installdeb will replace this with shell code automatically +# generated by other debhelper scripts. + +#DEBHELPER# + +exit 0 diff --git a/package/linux/deb_common/rules b/package/linux/deb_common/rules new file mode 100755 index 000000000..c4a7d9bd9 --- /dev/null +++ b/package/linux/deb_common/rules @@ -0,0 +1,83 @@ +#!/usr/bin/make -f +# -*- makefile -*- +# Sample debian/rules that uses debhelper. +# +# This file was originally written by Joey Hess and Craig Small. +# As a special exception, when this file is copied by dh-make into a +# dh-make output file, you may use that output file without restriction. +# This special exception was added by Craig Small in version 0.37 of dh-make. +# +# Modified to make a template file for a multi-binary package with separated +# build-arch and build-indep targets by Bill Allombert 2001 + +# Uncomment this to turn on verbose mode. +# export DH_VERBOSE=1 + +# This has to be exported to make some magic below work. +export DH_OPTIONS=-v + +#%: +# dh $@ + +PACKAGE_DIR = $(shell cat build/package_dir) + +clean: + dh_testdir + dh_testroot + dh_clean + +install: + dh_testdir + dh_testroot + dh_prep + dh_installdirs + dh_installudev --priority=45 + # Add here commands to install the package into debian/ + cp -arp build/ground/openpilotgcs/bin debian/openpilot/usr/local/OpenPilot + cp -arp build/ground/openpilotgcs/lib debian/openpilot/usr/local/OpenPilot + cp -arp build/ground/openpilotgcs/share debian/openpilot/usr/local/OpenPilot + cp -arp build/ground/openpilotgcs/.obj debian/openpilot/usr/local/OpenPilot + cp -arp build/ground/openpilotgcs/gcsversioninfo.h debian/openpilot/usr/local/OpenPilot + cp -arp package/linux/openpilot.desktop debian/openpilot/usr/share/applications + cp -arp package/linux/openpilot.png debian/openpilot/usr/share/pixmaps + cp -arp package/linux/openpilot_menu.png debian/openpilot/usr/share/pixmaps + cp -arp package/linux/openpilot_menu.menu debian/openpilot/etc/xdg/menus/applications-merged + cp -arp package/linux/openpilot_menu.directory debian/openpilot/usr/share/desktop-directories +ifdef $(PACKAGE_DIR) + cp -ar $(PACKAGE_DIR)/* debian/openpilot/usr/local/OpenPilot/firmware/ +endif + ln -s /usr/local/OpenPilot/bin/openpilotgcs.bin `pwd`/debian/openpilot/usr/bin/openpilot-gcs + rm -rf debian/openpilot/usr/local/OpenPilot/share/openpilotgcs/sounds/sounds + rm -rf debian/openpilot/usr/local/OpenPilot/share/openpilotgcs/pfd/pfd + rm -rf debian/openpilot/usr/local/OpenPilot/share/openpilotgcs/models/models + rm -rf debian/openpilot/usr/local/OpenPilot/share/openpilotgcs/mapicons/mapicons + rm -rf debian/openpilot/usr/local/OpenPilot/share/openpilotgcs/dials/dials + rm -rf debian/openpilot/usr/local/OpenPilot/share/openpilotgcs/diagrams/diagrams + + +# Build architecture-independent files here. +binary-indep: install + +# We have nothing to build by default. Got taken care of by OPs build system +# Build architecture-dependent files here. +binary-arch: install + dh_testdir + dh_testroot + dh_installchangelogs + dh_installdocs + dh_installexamples + dh_installman + dh_link + dh_strip + dh_compress + dh_fixperms + dh_installdeb + dh_shlibdeps -l/usr/local/OpenPilot/lib/openpilotgcs --dpkg-shlibdeps-params="--ignore-missing-info -v" + dh_gencontrol + dh_md5sums + dh_builddeb + +binary: binary-indep binary-arch + +.PHONY: clean binary-indep binary-arch binary install + diff --git a/package/linux/deb_common/watch.ex b/package/linux/deb_common/watch.ex new file mode 100644 index 000000000..7e9872e99 --- /dev/null +++ b/package/linux/deb_common/watch.ex @@ -0,0 +1,23 @@ +# Example watch control file for uscan +# Rename this file to "watch" and then you can run the "uscan" command +# to check for upstream updates and more. +# See uscan(1) for format + +# Compulsory line, this is a version 3 file +version=3 + +# Uncomment to examine a Webpage +# +#http://www.example.com/downloads.php openpilot-(.*)\.tar\.gz + +# Uncomment to examine a Webserver directory +#http://www.example.com/pub/openpilot-(.*)\.tar\.gz + +# Uncommment to examine a FTP server +#ftp://ftp.example.com/pub/openpilot-(.*)\.tar\.gz debian uupdate + +# Uncomment to find new files on sourceforge, for devscripts >= 2.9 +# http://sf.net/openpilot/openpilot-(.*)\.tar\.gz + +# Uncomment to find new files on GooglePages +# http://example.googlepages.com/foo.html openpilot-(.*)\.tar\.gz diff --git a/package/linux/deb_i386/control b/package/linux/deb_i386/control new file mode 100644 index 000000000..e93d4f559 --- /dev/null +++ b/package/linux/deb_i386/control @@ -0,0 +1,15 @@ +Source: openpilot +Section: unknown +Priority: extra +Maintainer: naiiawah +Build-Depends: debhelper (>= 7.0.50~) +Standards-Version: 3.8.4 +Homepage: http://www.openpilot.org +Vcs-Git: git://git.openpilot.org/OpenPilot.git +Vcs-Browser: http://git.openpilot.org/changelog/OpenPilot + +Package: openpilot +Architecture: i386 +Depends: ${shlibs:Depends}, ${misc:Depends} +Description: OpenPilot GCS & FW + OpenPilot GCS and Firmware for CopterControl (CC) board. diff --git a/package/linux/openpilot.desktop b/package/linux/openpilot.desktop new file mode 100644 index 000000000..5ce67af5d --- /dev/null +++ b/package/linux/openpilot.desktop @@ -0,0 +1,12 @@ +[Desktop Entry] +Version=0.1.0 +Encoding=UTF-8 +Name=OpenPilot GCS +Exec=openpilot-gcs +TryExec=openpilot-gcs +Comment=Configure, Tune, Diagnose, Track, & Upgrade FW for OpenPilot solutions +Terminal=false +Categories=OpenPilotMenu;Qt;Other; +Icon=openpilot +Type=Application +MimeType=application/openpilot.snapshot; diff --git a/package/linux/openpilot.png b/package/linux/openpilot.png new file mode 100755 index 000000000..e9c4ee868 Binary files /dev/null and b/package/linux/openpilot.png differ diff --git a/package/linux/openpilot_menu.directory b/package/linux/openpilot_menu.directory new file mode 100644 index 000000000..7175a8915 --- /dev/null +++ b/package/linux/openpilot_menu.directory @@ -0,0 +1,5 @@ +[Desktop Entry] +Type=Directory +Encoding=UTF-8 +Name=OpenPilot +Icon=openpilot_menu.png diff --git a/package/linux/openpilot_menu.menu b/package/linux/openpilot_menu.menu new file mode 100644 index 000000000..9e35577ec --- /dev/null +++ b/package/linux/openpilot_menu.menu @@ -0,0 +1,12 @@ + + + Applications + + OpenPilot + openpilot_menu.directory + + OpenPilotMenu + + + diff --git a/package/linux/openpilot_menu.png b/package/linux/openpilot_menu.png new file mode 100755 index 000000000..b5e10befa Binary files /dev/null and b/package/linux/openpilot_menu.png differ diff --git a/package/osx/OpenPilot.dmg b/package/osx/OpenPilot.dmg index c8e1056fb..9d231cdf6 100644 Binary files a/package/osx/OpenPilot.dmg and b/package/osx/OpenPilot.dmg differ diff --git a/package/osx/package b/package/osx/package index e481353ff..8a4860b5d 100755 --- a/package/osx/package +++ b/package/osx/package @@ -30,8 +30,10 @@ cp "${ROOT_DIR}/HISTORY.txt" "/Volumes/${VOL_NAME}" hdiutil detach ${device} -echo "Resizing dmg" -hdiutil resize -size 250m ${TEMP_FILE} +min=`hdiutil resize ${TEMP_FILE} | awk \{print\ \$\1\}` +echo "Resizing dmg to ${min}" + +hdiutil resize -sectors ${min} ${TEMP_FILE} hdiutil convert "${TEMP_FILE}" -format UDZO -o "${OUT_FILE}" # cleanup diff --git a/shared/uavobjectdefinition/actuatorcommand.xml b/shared/uavobjectdefinition/actuatorcommand.xml index 0d7de05a6..c0b65bbbc 100644 --- a/shared/uavobjectdefinition/actuatorcommand.xml +++ b/shared/uavobjectdefinition/actuatorcommand.xml @@ -1,7 +1,7 @@ Contains the pulse duration sent to each of the channels. Set by @ref ActuatorModule - + diff --git a/shared/uavobjectdefinition/actuatorsettings.xml b/shared/uavobjectdefinition/actuatorsettings.xml index a4cf3bc76..1524797b4 100644 --- a/shared/uavobjectdefinition/actuatorsettings.xml +++ b/shared/uavobjectdefinition/actuatorsettings.xml @@ -1,27 +1,27 @@ Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + - - - - - + + + + + diff --git a/shared/uavobjectdefinition/attitudesettings.xml b/shared/uavobjectdefinition/attitudesettings.xml index 522fd6f3a..e60c2454b 100644 --- a/shared/uavobjectdefinition/attitudesettings.xml +++ b/shared/uavobjectdefinition/attitudesettings.xml @@ -5,11 +5,12 @@ - + + diff --git a/shared/uavobjectdefinition/cameradesired.xml b/shared/uavobjectdefinition/cameradesired.xml new file mode 100644 index 000000000..022728f7e --- /dev/null +++ b/shared/uavobjectdefinition/cameradesired.xml @@ -0,0 +1,12 @@ + + + Desired camera outputs. Comes from @ref CameraStabilization module. + + + + + + + + + diff --git a/shared/uavobjectdefinition/camerastabsettings.xml b/shared/uavobjectdefinition/camerastabsettings.xml new file mode 100644 index 000000000..09199b77a --- /dev/null +++ b/shared/uavobjectdefinition/camerastabsettings.xml @@ -0,0 +1,12 @@ + + + Settings for the @ref CameraStab mmodule + + + + + + + + + diff --git a/shared/uavobjectdefinition/gcsreceiver.xml b/shared/uavobjectdefinition/gcsreceiver.xml new file mode 100644 index 000000000..d21598e48 --- /dev/null +++ b/shared/uavobjectdefinition/gcsreceiver.xml @@ -0,0 +1,10 @@ + + + A receiver channel group carried over the telemetry link. + + + + + + + diff --git a/shared/uavobjectdefinition/hwsettings.xml b/shared/uavobjectdefinition/hwsettings.xml index a3494f820..9ec859fa3 100644 --- a/shared/uavobjectdefinition/hwsettings.xml +++ b/shared/uavobjectdefinition/hwsettings.xml @@ -1,11 +1,23 @@ - - Selection of optional hardware configurations. - - - - - - + + Selection of optional hardware configurations. + + + + + + + + + + + + + + + + + + diff --git a/shared/uavobjectdefinition/manualcontrolcommand.xml b/shared/uavobjectdefinition/manualcontrolcommand.xml index ef74c2576..d8dba78d6 100644 --- a/shared/uavobjectdefinition/manualcontrolcommand.xml +++ b/shared/uavobjectdefinition/manualcontrolcommand.xml @@ -2,11 +2,12 @@ The output from the @ref ManualControlModule which descodes the receiver inputs. Overriden by GCS for fly-by-wire control. - + + - - + + diff --git a/shared/uavobjectdefinition/manualcontrolsettings.xml b/shared/uavobjectdefinition/manualcontrolsettings.xml index bfd692f91..78f38011f 100644 --- a/shared/uavobjectdefinition/manualcontrolsettings.xml +++ b/shared/uavobjectdefinition/manualcontrolsettings.xml @@ -1,15 +1,18 @@ Settings to indicate how to decode receiver input by @ref ManualControlModule. - - - - - - - - - + + + + + + @@ -20,9 +23,6 @@ - - - diff --git a/shared/uavobjectdefinition/mixersettings.xml b/shared/uavobjectdefinition/mixersettings.xml index 02ff69013..e2df02ce0 100644 --- a/shared/uavobjectdefinition/mixersettings.xml +++ b/shared/uavobjectdefinition/mixersettings.xml @@ -5,25 +5,29 @@ - - + + - + - + - + - + - + - + - + - + + + + + diff --git a/shared/uavobjectdefinition/objectpersistence.xml b/shared/uavobjectdefinition/objectpersistence.xml index 94076de9a..aa7a58e8c 100644 --- a/shared/uavobjectdefinition/objectpersistence.xml +++ b/shared/uavobjectdefinition/objectpersistence.xml @@ -1,7 +1,7 @@ Someone who knows please enter this - + diff --git a/shared/uavobjectdefinition/receiveractivity.xml b/shared/uavobjectdefinition/receiveractivity.xml new file mode 100644 index 000000000..c2a741d7f --- /dev/null +++ b/shared/uavobjectdefinition/receiveractivity.xml @@ -0,0 +1,14 @@ + + + Monitors which receiver channels have been active within the last second. + + + + + + + + diff --git a/shared/uavobjectdefinition/stabilizationsettings.xml b/shared/uavobjectdefinition/stabilizationsettings.xml index b6668350d..e42f468bf 100644 --- a/shared/uavobjectdefinition/stabilizationsettings.xml +++ b/shared/uavobjectdefinition/stabilizationsettings.xml @@ -1,8 +1,8 @@ PID settings used by the Stabilization module to combine the @ref AttitudeActual and @ref AttitudeDesired to compute @ref ActuatorDesired - - + + @@ -16,7 +16,7 @@ - + diff --git a/shared/uavobjectdefinition/telemetrysettings.xml b/shared/uavobjectdefinition/telemetrysettings.xml deleted file mode 100644 index d19c03c55..000000000 --- a/shared/uavobjectdefinition/telemetrysettings.xml +++ /dev/null @@ -1,10 +0,0 @@ - - - Select baud rate of telemetry. Warning - this must match your modem. - - - - - - -