diff --git a/.gitignore b/.gitignore index 6751a0f21..5f12c3dfd 100644 --- a/.gitignore +++ b/.gitignore @@ -75,7 +75,13 @@ GTAGS plane quad -# Ignore auto generated java files +# Ignore intermediate files generated by command-line android builds +# Couldn't figure out how to force these files into the ./build directory +androidgcs/build.xml +androidgcs/local.properties +androidgcs/proguard-project.txt + +# Ignore build output from Eclipse android builds androidgcs/bin/ androidgcs/gen/ /.cproject diff --git a/CREDITS.txt b/CREDITS.txt index b6e6db727..2e5e8d0ad 100644 --- a/CREDITS.txt +++ b/CREDITS.txt @@ -1,5 +1,5 @@ -This is a credits file of people that are or have been key contributors to the OpenPilot project. -Without the work of the people in this file OpenPilot would not be what it is today. +This is a credits file of people that are or have been key contributors to the OpenPilot code base in this Git repository. +Without the work of the people in this file and many that are not who help the community, OpenPilot would not be what it is today. It is sorted alphabetically by name and formatted so that it allows for easy grepping and beautification by scripts. @@ -15,7 +15,6 @@ Current maintainer function (M) N: Connor Abbott E: connor (at) abbott (dot) cx D: Win32 OpenPilot port -M: SITL Win32 N: David Ankers E: david (at) openpilot (dot) org @@ -27,6 +26,11 @@ N: Pedro Assuncao E: pedro (dot) agda (plus) openpilot (at) gmail (dot) com D: Initial GCS Settings Gadget work +N: Fredrik Arvidsson +E: fredrik (at) arvidssons (dot) org +W: GCS Setup Wizard +M: GCS Setup Wizard + N: Werner Backes E: werner (at) bit-1 (dot) de D: Port of CopterControl to PS3 Move Controller (MoveCopter) @@ -34,30 +38,37 @@ D: Port of CopterControl to PS3 Move Controller (MoveCopter) N: Jose Barros E: josembarros (at) hotmail (dot) com D: Next-Gen OP Map Lib, Y-Modem Library, Uploader Plugin -D: OP Bootloader, AHRS Bootloader, OPUploadTool -M: Bootloader, OP MAP Lib +D: OP Bootloader, AHRS Bootloader, OPUploadTool and much else +M: Bootloader, OP MAP Lib N: David "Buzz" Carlson E: chebuzz (plus) openpilot (at) gmail (dot) com D: 3D ModelView GCS Plugin, sponsor of HITL merge work and XPlane addition -M: 3D Modelview N: James Cotton E: peabody124 (plus) openpilot (at) gmail (dot) com D: Multiplatform HID implementation (firmware & GCS), GCS Joystick control D: Posix OpenPilot work and Mac implementation D: Firmware implementation of Professor Schinstock's INS/GPS -M: Architecture co-lead +D: Android GCS and much else +M: Architecture co-lead, Android GCS Lead + +N: Steve Doll +E: speakfree07 (at) hotmail (dot) com +D: Much Artwork, Logo rework, Welcome page design N: Piotr Esden-Tempski E: esden (at) esden (dot) net D: Floss-JTAG Rev A, 4-layer initial design +N: Darren Furniss +E: furnibird (plus) openpilot (at) gmail (dot) com +W: GCS Artwork and Android GCS Artwork + N: Frederic Goddeeris E: fredericgoddeeris (at) hotmail (dot) com D: I2C work and FreeRTOS work, MK integration D: EagleTree OSD implementation -M: OSD Module N: Daniel Godin E: dgodin (at) dnsct (dot) com @@ -70,6 +81,7 @@ D: GCS Scope plugin N: Nuno Guedes E: muralha (plus) openpilot (at) gmail (dot) com D: 3D artwork, moving surfaces and work on ModelView +D: PFD Artwork N: Peter Gunnarsson E: peter (at) pyne (dot) se @@ -82,9 +94,13 @@ D: Creator of http://pythononachip.org N: Joe Hlebasko E: joe (dot) hlebasko(plus) openpilot (at) gmail (dot) com -D: Production Main Board & Production OP GPS +D: Early versions of Main Board & Production OP GPS M: Hardware Architecture Team +N: Andy Honecker +E: andywh (at) yahoo (dot) com +D: Hardware design review and optimisation + N: Mark James E: mjames (plus) openpilot (at) gmail (dot) com D: Some of Silk Icon set used in GCS - http://www.famfamfam.com/lab/icons/silk @@ -92,6 +108,7 @@ D: Some of Silk Icon set used in GCS - http://www.famfamfam.com/lab/icons/silk N: Sami Korhonen E: samik (dot) korhonen (plus) openpilot (at) gmail (dot) com D: GPS Module, Spektrum RC Module, OSD work +M: OpenPilot OSD N: Thorsten Klose E: thorsten (dot) klose (at) dmx (dot) de @@ -101,11 +118,14 @@ N: Hallvard Kristiansen E: hal (at) fleshmx (dot) com D: GCS Artwork, Quad layout diagrams +N: Mike Labranche +E: mdlabranche (plus) openpilot (at) gmail (dot) com +D: Tab bar Telem Monitor + N: Edouard Lafargue E: edouard (at) lafargue (dot) name D: GCS Dial Plugins, GCS PFD Plugin, GCS GPS plugin, GCS Config plugin D: Artwork including standard display dials -M: GCS Core N: Matt Lipski E: mattlipski (plus) openpilot (at) gmail (dot) com @@ -113,7 +133,7 @@ D: Deluxe Dials Set artwork, (Artificial Horizon, Compass, Turn Indicator) N: Les Newell E: les (dot) newell (at) fastmail (dot) co (dot) uk -D: Advanced mixer matrix, SPI protocol based on UAVObjects +D: Advanced mixer matrix, SPI protocol based on UAVObjects, feedforward N: Ken Northup E: helos360 (at) bellsouth (dot) net @@ -126,19 +146,22 @@ D: Artwork and design including work on the Deluxe Dial Set N: Cathy Moss E: cmoss296 (at) blueyonder (dot) co (dot) uk D: Hardware design Lead: Gen 2 Mainboard, PipXtreme, Current Sensor -D: Lead dev PipXtreme, creator OP Map Plugin -M: Hardware Architecture Team / PipX Modem +D: PipXtreme designer, creator OP Map Plugin N: Angus Peart E: gussy (at) openpilot (dot) org D: Co-founder, Principal hardware architect. -D: Hardware design of OpenPilot, AHRS, GPS and other hardware -D: Core developer embedded code +D: Hardware design of early OpenPilot, AHRS, GPS and other hardware + +N: Dmytro Poplavskiy +E: dmytro (dot) poplavskiy (plus) openpilot (at) gmail (dot) com +W: QML PFD, QML Welcome page +M: Qml plugins N: Eric Price E: corvus (dot) corax (at) cybertrench (dot) com D: IL2 HITL GCS Plugin, Posix OpenPilot, Advanced stabilisation module -M: SITL Posix +M: SITL Posix, SLAM work N: Richard Querin E: rfquerin (plus) openpilot (at) gmail (dot) com @@ -151,7 +174,6 @@ D: See: http://www.glc-lib.net/ N: Julien Rouviere E: julien (dot) rouviere (plus) openpilot (at) gmail (dot) com -D: GCS Core Developer D: GCS Framework and Plugins for the GCS N: Zik Saleeba @@ -163,6 +185,11 @@ E: dales (at) ksu (dot) edu D: Lead AHRS Developer D: Creator of the OpenPilot INS / EKF +N: Professor Kenn Sebesta +E: kenn (at) openpilot (dot) org +D: Lead Fixed Wing Developer +M: Fixed Wing support + N: Oleg Semyonov E: os-openpilot-org (at) os-propo (dot) info D: Core tester & Project organisation @@ -178,7 +205,6 @@ D: SPI protocol for AHRS, I2C rewrite and much core work N: Troy Schultz E: troy (dot) schultz (at) rogers (dot) com D: INS design review and optimisation -M: Hardware Architecture Team N: Dr. Erhard Siegl E: Erhard (dot) Siegl (at) zogazoga (dot) at @@ -202,8 +228,13 @@ N: Vassilis Varveropoulos E: vassilis (at) openpilot (dot) org D: Co-founder, Principal embedded software architect. D: Module architecture and UAVTalk/UAVObjects implementation. -M: Architecture co-lead N: Alex Vrubel E: alex (dot) vrubel (plus) openpilot (at) gmail (dot) com D: Russian translation of the GCS + +N: Brian Webb +E: webbbn (plus) openpilot (at) gmail (dot) com +W: Modem lead developer +M: OP Modems + diff --git a/HISTORY.txt b/HISTORY.txt index 54dc5c6d0..513b368a5 100644 --- a/HISTORY.txt +++ b/HISTORY.txt @@ -1,4 +1,9 @@ Short summary of changes. For a complete list see the git log. + +2012-10-06 +Receiver port can now be configured as PPM *and* PWM inputs. +Pin 1 is PPM, other pins are PWM inputs. + 2012-07-27 Added the ability to load stylesheets from external file according to operating system: macos.qss, linux.qss, windows.qss diff --git a/KNOWN_ISSUES.txt b/KNOWN_ISSUES.txt new file mode 100644 index 000000000..303e6319f --- /dev/null +++ b/KNOWN_ISSUES.txt @@ -0,0 +1,10 @@ ++ Halt/Reset buttons don't work if board is armed. But no way to use them if "Always armed". Use rescue as workaround. ++ Missing Translations, use English. ++ Radio Wizard confused by a reversed throttle, fix it on your transmitter before starting wizard. ++ [Windows 8] USB Driver is broken. ++ Firmware Update Instructions on Firmware Tab not entirely accurate for all upgrade paths. ++ Radio Wizard Throttle display does not show full range properly. ++ Tricopter's using Vehicle Wizard need to check servo does not need reversed manually. ++ XAircraft ESCs uses non-standard PPM range which may cause issues with Vehicle Wizard. ++ Spectrum Satellite Receivers setup in Radio Wizard may have wrong protocol set. ++ Old Intel 965 have an OpenGL bug that turns the QML PFD black and while. diff --git a/Makefile b/Makefile index f9df8d912..8b6cd4c20 100644 --- a/Makefile +++ b/Makefile @@ -7,6 +7,10 @@ TOOLS_DIR=$(ROOT_DIR)/tools BUILD_DIR=$(ROOT_DIR)/build DL_DIR=$(ROOT_DIR)/downloads +# Function for converting an absolute path to one relative +# to the top of the source tree. +toprel = $(subst $(realpath $(ROOT_DIR))/,,$(abspath $(1))) + # Clean out undesirable variables from the environment and command-line # to remove the chance that they will cause problems with our build define SANITIZE_VAR @@ -32,6 +36,7 @@ $(foreach var, $(SANITIZE_DEPRECATED_VARS), $(eval $(call SANITIZE_VAR,$(var),de QT_SPEC=win32-g++ UAVOBJGENERATOR="$(BUILD_DIR)/ground/uavobjgenerator/debug/uavobjgenerator.exe" UNAME := $(shell uname) +ARCH := $(shell uname -m) ifeq ($(UNAME), Linux) QT_SPEC=linux-g++ UAVOBJGENERATOR="$(BUILD_DIR)/ground/uavobjgenerator/uavobjgenerator" @@ -73,6 +78,7 @@ help: @echo " openocd_install - Install the OpenOCD JTAG daemon" @echo " stm32flash_install - Install the stm32flash tool for unbricking boards" @echo " dfuutil_install - Install the dfu-util tool for unbricking F4-based boards" + @echo " android_sdk_install - Install the Android SDK tools" @echo @echo " [Big Hammer]" @echo " all - Generate UAVObjects, build openpilot firmware and gcs" @@ -163,10 +169,16 @@ $(BUILD_DIR): QT_SDK_DIR := $(TOOLS_DIR)/qtsdk-v1.2.1 .PHONY: qt_sdk_install +# Choose the appropriate installer based on host architecture +ifneq (,$(filter $(ARCH), x86_64 amd64)) +# 64-bit +qt_sdk_install: QT_SDK_FILE := QtSdk-offline-linux-x86_64-v1.2.1.run +qt_sdk_install: QT_SDK_URL := http://www.developer.nokia.com/dp?uri=http://sw.nokia.com/id/14b2039c-0e1f-4774-a4f2-9aa60b6d5313/Qt_SDK_Lin64_offline +else +# 32-bit qt_sdk_install: QT_SDK_URL := http://www.developer.nokia.com/dp?uri=http://sw.nokia.com/id/8ea74da4-fec1-4277-8b26-c58cc82e204b/Qt_SDK_Lin32_offline qt_sdk_install: QT_SDK_FILE := QtSdk-offline-linux-x86-v1.2.1.run -#qt_sdk_install: QT_SDK_URL := http://www.developer.nokia.com/dp?uri=http://sw.nokia.com/id/c365bbf5-c2b9-4dda-9c1f-34b2c8d07785/Qt_SDK_Lin32_offline_v1_1_2 -#qt_sdk_install: QT_SDK_FILE := Qt_SDK_Lin32_offline_v1_1_2_en.run +endif # order-only prereq on directory existance: qt_sdk_install : | $(DL_DIR) $(TOOLS_DIR) qt_sdk_install: qt_sdk_clean @@ -428,6 +440,32 @@ dfuutil_clean: $(V0) @echo " CLEAN $(DFUUTIL_DIR)" $(V1) [ ! -d "$(DFUUTIL_DIR)" ] || $(RM) -r "$(DFUUTIL_DIR)" +# see http://developer.android.com/sdk/ for latest versions +ANDROID_SDK_DIR := $(TOOLS_DIR)/android-sdk-linux +.PHONY: android_sdk_install +android_sdk_install: ANDROID_SDK_URL := http://dl.google.com/android/android-sdk_r20.0.3-linux.tgz +android_sdk_install: ANDROID_SDK_FILE := $(notdir $(ANDROID_SDK_URL)) +# order-only prereq on directory existance: +android_sdk_install: | $(DL_DIR) $(TOOLS_DIR) +android_sdk_install: android_sdk_clean + # download the source only if it's newer than what we already have + $(V0) @echo " DOWNLOAD $(ANDROID_SDK_URL)" + $(V1) wget --no-check-certificate -N -P "$(DL_DIR)" "$(ANDROID_SDK_URL)" + + # binary only release so just extract it + $(V0) @echo " EXTRACT $(ANDROID_SDK_FILE)" + $(V1) tar -C $(TOOLS_DIR) -xf "$(DL_DIR)/$(ANDROID_SDK_FILE)" + +.PHONY: android_sdk_clean +android_sdk_clean: + $(V0) @echo " CLEAN $(ANDROID_SDK_DIR)" + $(V1) [ ! -d "$(ANDROID_SDK_DIR)" ] || $(RM) -r $(ANDROID_SDK_DIR) + +.PHONY: android_sdk_update +android_sdk_update: + $(V0) @echo " UPDATE $(ANDROID_SDK_DIR)" + $(ANDROID_SDK_DIR)/tools/android update sdk --no-ui -t platform-tools,android-16,addon-google_apis-google-16 + ############################## # # Set up paths to tools @@ -455,6 +493,15 @@ else OPENOCD ?= openocd endif +ifeq ($(shell [ -d "$(ANDROID_SDK_DIR)" ] && echo "exists"), exists) + ANDROID := $(ANDROID_SDK_DIR)/tools/android + ANDROID_DX := $(ANDROID_SDK_DIR)/platform-tools/dx +else + # not installed, hope it's in the path... + ANDROID ?= android + ANDROID_DX ?= dx +endif + ############################## # # GCS related components @@ -512,6 +559,154 @@ uavobjects_clean: $(V0) @echo " CLEAN $@" $(V1) [ ! -d "$(UAVOBJ_OUT_DIR)" ] || $(RM) -r "$(UAVOBJ_OUT_DIR)" +################################ +# +# Android GCS related components +# +################################ + + +# Build the output directory for the Android GCS build +ANDROIDGCS_OUT_DIR := $(BUILD_DIR)/androidgcs +$(ANDROIDGCS_OUT_DIR): + $(V1) mkdir -p $@ + +# Build the asset directory for the android assets +ANDROIDGCS_ASSETS_DIR := $(ANDROIDGCS_OUT_DIR)/assets +$(ANDROIDGCS_ASSETS_DIR)/uavos: + $(V1) mkdir -p $@ + +ifeq ($(V), 1) +ANT_QUIET := +ANDROID_SILENT := +else +ANT_QUIET := -q +ANDROID_SILENT := -s +endif +.PHONY: androidgcs +androidgcs: uavo-collections_java + $(V0) @echo " ANDROID $(call toprel, $(ANDROIDGCS_OUT_DIR))" + $(V1) mkdir -p $(ANDROIDGCS_OUT_DIR) + $(V1) $(ANDROID) $(ANDROID_SILENT) update project --target 'Google Inc.:Google APIs:16' --name androidgcs --path ./androidgcs + $(V1) ant -f ./androidgcs/build.xml \ + $(ANT_QUIET) \ + -Dout.dir="../$(call toprel, $(ANDROIDGCS_OUT_DIR)/bin)" \ + -Dgen.absolute.dir="$(ANDROIDGCS_OUT_DIR)/gen" \ + debug + +.PHONY: androidgcs_clean +androidgcs_clean: + $(V0) @echo " CLEAN $@" + $(V1) [ ! -d "$(ANDROIDGCS_OUT_DIR)" ] || $(RM) -r "$(ANDROIDGCS_OUT_DIR)" + +# We want to take snapshots of the UAVOs at each point that they change +# to allow the GCS to be compatible with as many versions as possible. +# +# Find the git hashes of each commit that changes uavobjects with: +# git log --format=%h -- shared/uavobjectdefinition/ | head -n 2 +UAVO_GIT_VERSIONS := 684620d 43f85d9 + +# All versions includes a pseudo collection called "working" which represents +# the UAVOs in the source tree +UAVO_ALL_VERSIONS := $(UAVO_GIT_VERSIONS) srctree + +# This is where the UAVO collections are stored +UAVO_COLLECTION_DIR := $(BUILD_DIR)/uavo-collections + +# $(1) git hash of a UAVO snapshot +define UAVO_COLLECTION_GIT_TEMPLATE + +# Make the output directory that will contain all of the synthetics for the +# uavo collection referenced by the git hash $(1) +$$(UAVO_COLLECTION_DIR)/$(1): + $$(V1) mkdir -p $$(UAVO_COLLECTION_DIR)/$(1) + +# Extract the snapshot of shared/uavobjectdefinition from git hash $(1) +$$(UAVO_COLLECTION_DIR)/$(1)/uavo-xml.tar: | $$(UAVO_COLLECTION_DIR)/$(1) +$$(UAVO_COLLECTION_DIR)/$(1)/uavo-xml.tar: + $$(V0) @echo " UAVOTAR $(1)" + $$(V1) git archive $(1) -o $$@ -- shared/uavobjectdefinition/ + +# Extract the uavo xml files from our snapshot +$$(UAVO_COLLECTION_DIR)/$(1)/uavo-xml: $$(UAVO_COLLECTION_DIR)/$(1)/uavo-xml.tar + $$(V0) @echo " UAVOUNTAR $(1)" + $$(V1) rm -rf $$@ + $$(V1) mkdir -p $$@ + $$(V1) tar -C $$(call toprel, $$@) -xf $$(call toprel, $$<) || rm -rf $$@ +endef + +# Map the current working directory into the set of UAVO collections +$(UAVO_COLLECTION_DIR)/srctree: + $(V1) mkdir -p $@ + +$(UAVO_COLLECTION_DIR)/srctree/uavo-xml: | $(UAVO_COLLECTION_DIR)/srctree +$(UAVO_COLLECTION_DIR)/srctree/uavo-xml: $(UAVOBJ_XML_DIR) + $(V1) ln -sf $(ROOT_DIR) $(UAVO_COLLECTION_DIR)/srctree/uavo-xml + +# $(1) git hash (or symbolic name) of a UAVO snapshot +define UAVO_COLLECTION_BUILD_TEMPLATE + +# This leaves us with a (broken) symlink that points to the full sha1sum of the collection +$$(UAVO_COLLECTION_DIR)/$(1)/uavohash: $$(UAVO_COLLECTION_DIR)/$(1)/uavo-xml + # Compute the sha1 hash for this UAVO collection + # The sed bit truncates the UAVO hash to 16 hex digits + $$(V1) python $$(ROOT_DIR)/make/scripts/version-info.py \ + --path=$$(ROOT_DIR) \ + --uavodir=$$(UAVO_COLLECTION_DIR)/$(1)/uavo-xml/shared/uavobjectdefinition \ + --format='$$$${UAVOSHA1TXT}' | \ + sed -e 's|\(................\).*|\1|' > $$@ + + $$(V0) @echo " UAVOHASH $(1) ->" $$$$(cat $$(UAVO_COLLECTION_DIR)/$(1)/uavohash) + +# Generate the java uavobjects for this UAVO collection +$$(UAVO_COLLECTION_DIR)/$(1)/java-build/java: $$(UAVO_COLLECTION_DIR)/$(1)/uavohash + $$(V0) @echo " UAVOJAVA $(1) " $$$$(cat $$(UAVO_COLLECTION_DIR)/$(1)/uavohash) + $$(V1) mkdir -p $$@ + $$(V1) ( \ + cd $$(UAVO_COLLECTION_DIR)/$(1)/java-build && \ + $$(UAVOBJGENERATOR) -java $$(UAVO_COLLECTION_DIR)/$(1)/uavo-xml/shared/uavobjectdefinition $$(ROOT_DIR) ; \ + ) + +# Build a jar file for this UAVO collection +$$(UAVO_COLLECTION_DIR)/$(1)/java-build/uavobjects.jar: | $$(ANDROIDGCS_ASSETS_DIR)/uavos +$$(UAVO_COLLECTION_DIR)/$(1)/java-build/uavobjects.jar: $$(UAVO_COLLECTION_DIR)/$(1)/java-build/java + $$(V0) @echo " UAVOJAR $(1) " $$$$(cat $$(UAVO_COLLECTION_DIR)/$(1)/uavohash) + $$(V1) ( \ + HASH=$$$$(cat $$(UAVO_COLLECTION_DIR)/$(1)/uavohash) && \ + cd $$(UAVO_COLLECTION_DIR)/$(1)/java-build && \ + javac java/*.java \ + $$(ROOT_DIR)/androidgcs/src/org/openpilot/uavtalk/UAVDataObject.java \ + $$(ROOT_DIR)/androidgcs/src/org/openpilot/uavtalk/UAVObject*.java \ + $$(ROOT_DIR)/androidgcs/src/org/openpilot/uavtalk/UAVMetaObject.java \ + -d . && \ + find ./org/openpilot/uavtalk/uavobjects -type f -name '*.class' > classlist.txt && \ + jar cf tmp_uavobjects.jar @classlist.txt && \ + $$(ANDROID_DX) \ + --dex \ + --output $$(ANDROIDGCS_ASSETS_DIR)/uavos/$$$${HASH}.jar \ + tmp_uavobjects.jar && \ + ln -sf $$(ANDROIDGCS_ASSETS_DIR)/uavos/$$$${HASH}.jar uavobjects.jar \ + ) + +endef + +# One of these for each element of UAVO_GIT_VERSIONS so we can extract the UAVOs from git +$(foreach githash, $(UAVO_GIT_VERSIONS), $(eval $(call UAVO_COLLECTION_GIT_TEMPLATE,$(githash)))) + +# One of these for each UAVO_ALL_VERSIONS which includes the ones in the srctree +$(foreach githash, $(UAVO_ALL_VERSIONS), $(eval $(call UAVO_COLLECTION_BUILD_TEMPLATE,$(githash)))) + +.PHONY: uavo-collections_java +uavo-collections_java: $(foreach githash, $(UAVO_ALL_VERSIONS), $(UAVO_COLLECTION_DIR)/$(githash)/java-build/uavobjects.jar) + +.PHONY: uavo-collections +uavo-collections: uavo-collections_java + +.PHONY: uavo-collections_clean +uavo-collections_clean: + $(V0) @echo " CLEAN $(UAVO_COLLECTION_DIR)" + $(V1) [ ! -d "$(UAVO_COLLECTION_DIR)" ] || $(RM) -r $(UAVO_COLLECTION_DIR) + ############################## # # Flight related components @@ -774,6 +969,11 @@ sim_osx_%: uavobjects_flight # Packaging components # ############################## + .PHONY: package package: $(V1) cd $@ && $(MAKE) --no-print-directory $@ + +.PHONY: package_resources +package_resources: + $(V1) cd package && $(MAKE) --no-print-directory opfw_resource diff --git a/androidgcs/.classpath b/androidgcs/.classpath index c88f96260..9e9c6b0d0 100644 --- a/androidgcs/.classpath +++ b/androidgcs/.classpath @@ -2,7 +2,6 @@ - diff --git a/androidgcs/AndroidManifest.xml b/androidgcs/AndroidManifest.xml index a6da85935..622c7f571 100644 --- a/androidgcs/AndroidManifest.xml +++ b/androidgcs/AndroidManifest.xml @@ -58,4 +58,4 @@ - \ No newline at end of file + diff --git a/androidgcs/assets/uavos b/androidgcs/assets/uavos new file mode 120000 index 000000000..913c42fb4 --- /dev/null +++ b/androidgcs/assets/uavos @@ -0,0 +1 @@ +../../build/androidgcs/assets/uavos \ No newline at end of file diff --git a/androidgcs/res/values/arrays.xml b/androidgcs/res/values/arrays.xml index d27dc7b11..4333bcc16 100644 --- a/androidgcs/res/values/arrays.xml +++ b/androidgcs/res/values/arrays.xml @@ -2,14 +2,12 @@ None - Fake Bluetooth Network HID 0 - 1 2 3 4 diff --git a/androidgcs/src/org/openpilot/androidgcs/CompassView.java b/androidgcs/src/org/openpilot/androidgcs/CompassView.java index b6b348588..01499011b 100644 --- a/androidgcs/src/org/openpilot/androidgcs/CompassView.java +++ b/androidgcs/src/org/openpilot/androidgcs/CompassView.java @@ -114,7 +114,7 @@ public class CompassView extends View { // Draw the background canvas.drawCircle(px, py, radius, circlePaint); - // Rotate our perspective so that the ÔtopÕ is + // Rotate our perspective so that the "top" is // facing the current bearing. canvas.save(); canvas.rotate((float) -bearing, px, py); diff --git a/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java b/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java index 8cd89e8d8..9d366a13a 100644 --- a/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java +++ b/androidgcs/src/org/openpilot/androidgcs/ObjectManagerActivity.java @@ -36,7 +36,6 @@ import java.util.Observable; import java.util.Observer; import java.util.Set; -import org.junit.Assert; import org.openpilot.androidgcs.fragments.ObjectManagerFragment; import org.openpilot.androidgcs.telemetry.OPTelemetryService; import org.openpilot.androidgcs.telemetry.OPTelemetryService.LocalBinder; @@ -206,7 +205,6 @@ public abstract class ObjectManagerActivity extends Activity { if (telemetryStatsConnected) { UAVObject stats = objMngr.getObject("GCSTelemetryStats"); - Assert.assertNotNull(stats); // Should not be null if we connected stats.removeUpdatedObserver(telemetryObserver); telemetryStatsConnected = false; diff --git a/androidgcs/src/org/openpilot/androidgcs/telemetry/OPTelemetryService.java b/androidgcs/src/org/openpilot/androidgcs/telemetry/OPTelemetryService.java index 69ab6e0d8..c03510a83 100644 --- a/androidgcs/src/org/openpilot/androidgcs/telemetry/OPTelemetryService.java +++ b/androidgcs/src/org/openpilot/androidgcs/telemetry/OPTelemetryService.java @@ -26,15 +26,22 @@ */ package org.openpilot.androidgcs.telemetry; +import java.io.File; +import java.io.FileOutputStream; +import java.io.IOException; +import java.io.InputStream; +import java.io.OutputStream; import java.lang.ref.WeakReference; +import java.lang.reflect.InvocationTargetException; +import java.lang.reflect.Method; -import org.openpilot.uavtalk.UAVDataObject; import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; import android.app.Service; +import android.content.Context; import android.content.Intent; import android.content.SharedPreferences; +import android.content.res.AssetManager; import android.os.Binder; import android.os.Handler; import android.os.HandlerThread; @@ -45,6 +52,7 @@ import android.os.Process; import android.preference.PreferenceManager; import android.util.Log; import android.widget.Toast; +import dalvik.system.DexClassLoader; public class OPTelemetryService extends Service { @@ -72,8 +80,6 @@ public class OPTelemetryService extends Service { static final int MSG_DISCONNECT = 3; static final int MSG_TOAST = 100; - private boolean terminate = false; - private Thread activeTelem; private TelemetryTask telemTask; @@ -103,7 +109,6 @@ public class OPTelemetryService extends Service { stopSelf(msg.arg2); break; case MSG_CONNECT: - terminate = false; int connection_type; SharedPreferences prefs = PreferenceManager.getDefaultSharedPreferences(OPTelemetryService.this); try { @@ -115,10 +120,6 @@ public class OPTelemetryService extends Service { switch(connection_type) { case 0: // No connection return; - case 1: - Toast.makeText(getApplicationContext(), "Attempting fake connection", Toast.LENGTH_SHORT).show(); - activeTelem = new FakeTelemetryThread(); - break; case 2: Toast.makeText(getApplicationContext(), "Attempting BT connection", Toast.LENGTH_SHORT).show(); telemTask = new BluetoothUAVTalk(this); @@ -142,7 +143,6 @@ public class OPTelemetryService extends Service { case MSG_DISCONNECT: Toast.makeText(getApplicationContext(), "Disconnect requested", Toast.LENGTH_SHORT).show(); if (DEBUG) Log.d(TAG, "Calling disconnect"); - terminate = true; if (telemTask != null) { telemTask.disconnect(); telemTask = null; @@ -277,148 +277,137 @@ public class OPTelemetryService extends Service { public UAVObjectManager getObjectManager(); }; - // Fake class for testing, simply emits periodic updates on - private class FakeTelemetryThread extends Thread implements TelemTask { - private final UAVObjectManager objMngr; - @Override - public UAVObjectManager getObjectManager() { return objMngr; }; - FakeTelemetryThread() { - objMngr = new UAVObjectManager(); - UAVObjectsInitialize.register(objMngr); - } + /************************************************************/ + /* Everything below here has to do with getting the UAVOs */ + /* from the package. This shouldn't really be in the telem */ + /* service class but needs to be in this context */ + /************************************************************/ - @Override - public void run() { - System.out.println("Running fake thread"); + private static void copyStream(InputStream inputStream, OutputStream outputStream) throws IOException + { + byte[] buffer = new byte[1024 * 10]; + int numRead = inputStream.read(buffer); + while (numRead > 0) + { + outputStream.write(buffer, 0, numRead); + numRead = inputStream.read(buffer); + } + } - Intent intent = new Intent(); - intent.setAction(INTENT_ACTION_CONNECTED); - sendBroadcast(intent,null); + private void copyAssets(String JAR_DIR, String JAR_NAME) + { + File jarsDir = getDir(JAR_DIR, MODE_WORLD_READABLE); + AssetManager assetManager = getAssets(); + try + { + InputStream inputStream = null; + OutputStream outputStream = null; + try + { + File outputFile = new File(jarsDir, JAR_NAME); + inputStream = assetManager.open("uavos/" + JAR_NAME); + outputStream = new FileOutputStream(outputFile); + copyStream(inputStream, outputStream); + } + finally + { + if (inputStream != null) + inputStream.close(); + if (outputStream != null) + outputStream.close(); + } + } + catch (IOException e) + { + Log.e(TAG, e.toString(), e); + String[] list; + try { + list = assetManager.list("uavos/"); + Log.i(TAG, "Listing found uavos"); + for(int i = 0; i < list.length; i++) { + Log.i(TAG, "Found: " + list[i]); + } - //toastMessage("Started fake telemetry thread"); - UAVDataObject systemStats = (UAVDataObject) objMngr.getObject("SystemStats"); - UAVDataObject attitudeActual = (UAVDataObject) objMngr.getObject("AttitudeActual"); - UAVDataObject homeLocation = (UAVDataObject) objMngr.getObject("HomeLocation"); - UAVDataObject positionActual = (UAVDataObject) objMngr.getObject("PositionActual"); - UAVDataObject systemAlarms = (UAVDataObject) objMngr.getObject("SystemAlarms"); + } catch (IOException e1) { + // TODO Auto-generated catch block + e1.printStackTrace(); + } - systemAlarms.getField("Alarm").setValue("Warning",0); - systemAlarms.getField("Alarm").setValue("OK",1); - systemAlarms.getField("Alarm").setValue("Critical",2); - systemAlarms.getField("Alarm").setValue("Error",3); - systemAlarms.updated(); + } + } - homeLocation.getField("Latitude").setDouble(379420315); - homeLocation.getField("Longitude").setDouble(-88330078); - homeLocation.getField("Be").setDouble(26702.78710938,0); - homeLocation.getField("Be").setDouble(-1468.33605957,1); - homeLocation.getField("Be").setDouble(34181.78515625,2); + /** + * Delete the files in a directories + * @param directory + */ + private static void deleteDirectoryContents(File directory) + { + File contents[] = directory.listFiles(); + if (contents != null) + { + for (File file : contents) + { + if (file.isDirectory()) + deleteDirectoryContents(file); - - double roll = 0; - double pitch = 0; - double yaw = 0; - double north = 0; - double east = 0; - while( !terminate ) { - attitudeActual.getField("Roll").setDouble(roll); - attitudeActual.getField("Pitch").setDouble(pitch); - attitudeActual.getField("Yaw").setDouble(yaw); - positionActual.getField("North").setDouble(north += 100); - positionActual.getField("East").setDouble(east += 100); - roll = (roll + 10) % 180; - pitch = (pitch + 10) % 180; - yaw = (yaw + 10) % 360; - - systemStats.updated(); - attitudeActual.updated(); - positionActual.updated(); - try { - Thread.sleep(1000); - } catch (InterruptedException e) { - break; - } + file.delete(); } } } - /* - private class BTTelemetryThread extends Thread implements TelemTask { + /** + * Load the UAVObjects from a JAR file. This method must be called in the + * service context. + * @return True if success, False otherwise + */ + public boolean loadUavobjects(String jar, UAVObjectManager objMngr) { + final String JAR_DIR = "jars"; + final String DEX_DIR = "optimized_dex"; - private final UAVObjectManager objMngr; - private UAVTalk uavTalk; - private Telemetry tel; - private TelemetryMonitor mon; + File jarsDir = getDir(JAR_DIR, MODE_WORLD_READABLE); + if (jarsDir.exists()) + deleteDirectoryContents(jarsDir); - @Override - public UAVObjectManager getObjectManager() { return objMngr; }; + copyAssets(JAR_DIR, jar); - BTTelemetryThread() { - objMngr = new UAVObjectManager(); - UAVObjectsInitialize.register(objMngr); + Log.d(TAG, "Starting dex loader"); + File dexDir = getDir(DEX_DIR, Context.MODE_WORLD_READABLE); + + // Necessary to get dexOpt to run + if (dexDir.exists()) + deleteDirectoryContents(dexDir); + + String classpath = new File(jarsDir, jar).getAbsolutePath(); + + DexClassLoader loader = new DexClassLoader(classpath, dexDir.getAbsolutePath(), null, getClassLoader()); + + try { + Class initClass = loader.loadClass("org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize"); + Method initMethod = initClass.getMethod("register", UAVObjectManager.class); + initMethod.invoke(null, objMngr); + } catch (ClassNotFoundException e1) { + // TODO Auto-generated catch block + e1.printStackTrace(); + return false; + } catch (IllegalAccessException e1) { + // TODO Auto-generated catch block + e1.printStackTrace(); + return false; + } catch (NoSuchMethodException e1) { + // TODO Auto-generated catch block + e1.printStackTrace(); + return false; + } catch (IllegalArgumentException e) { + // TODO Auto-generated catch block + e.printStackTrace(); + return false; + } catch (InvocationTargetException e) { + // TODO Auto-generated catch block + e.printStackTrace(); + return false; } - @Override - public void run() { - if (DEBUG) Log.d(TAG, "Telemetry Thread started"); - - Looper.prepare(); - - BluetoothUAVTalk bt = new BluetoothUAVTalk(OPTelemetryService.this); - for( int i = 0; i < 10; i++ ) { - if (DEBUG) Log.d(TAG, "Attempting Bluetooth Connection"); - - bt.connect(objMngr); - - if (DEBUG) Log.d(TAG, "Done attempting connection"); - if( bt.getConnected() ) - break; - - try { - Thread.sleep(1000); - } catch (InterruptedException e) { - Log.e(TAG, "Thread interrupted while trying to connect"); - e.printStackTrace(); - return; - } - } - if( ! bt.getConnected() ) { - toastMessage("BT connection failed"); - return; - } - toastMessage("BT Connected"); - - if (DEBUG) Log.d(TAG, "Connected via bluetooth"); - - uavTalk = bt.getUavtalk(); - tel = new Telemetry(uavTalk, objMngr); - mon = new TelemetryMonitor(objMngr,tel); - mon.addObserver(new Observer() { - @Override - public void update(Observable arg0, Object arg1) { - if (DEBUG) Log.d(TAG, "Mon updated. Connected: " + mon.getConnected() + " objects updated: " + mon.getObjectsUpdated()); - if(mon.getConnected() ) { - Intent intent = new Intent(); - intent.setAction(INTENT_ACTION_CONNECTED); - sendBroadcast(intent,null); - } - } - }); - - - if (DEBUG) Log.d(TAG, "Entering UAVTalk processing loop"); - while( !terminate ) { - try { - if( !uavTalk.processInputStream() ) - break; - } catch (IOException e) { - // This occurs when they communication stream fails - toastMessage("Connection dropped"); - break; - } - } - if (DEBUG) Log.d(TAG, "UAVTalk stream disconnected"); - } - };*/ + return true; + } } diff --git a/androidgcs/src/org/openpilot/androidgcs/telemetry/TelemetryTask.java b/androidgcs/src/org/openpilot/androidgcs/telemetry/TelemetryTask.java index c9a44d6e1..ad23b2e00 100644 --- a/androidgcs/src/org/openpilot/androidgcs/telemetry/TelemetryTask.java +++ b/androidgcs/src/org/openpilot/androidgcs/telemetry/TelemetryTask.java @@ -10,7 +10,7 @@ import org.openpilot.uavtalk.Telemetry; import org.openpilot.uavtalk.TelemetryMonitor; import org.openpilot.uavtalk.UAVObjectManager; import org.openpilot.uavtalk.UAVTalk; -import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; +import org.openpilot.uavtalk.uavobjects.TelemObjectsInitialize; import android.content.Intent; import android.os.Handler; @@ -103,7 +103,7 @@ public abstract class TelemetryTask implements Runnable { // be dependent on what is connected (e.g. board and // version number). objMngr = new UAVObjectManager(); - UAVObjectsInitialize.register(objMngr); + TelemObjectsInitialize.register(objMngr); // Create the required telemetry objects attached to this // data stream diff --git a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java index 6fcbb2491..efb5b2252 100644 --- a/androidgcs/src/org/openpilot/uavtalk/Telemetry.java +++ b/androidgcs/src/org/openpilot/uavtalk/Telemetry.java @@ -202,7 +202,7 @@ public class Telemetry { /** * Register a new object for periodic updates (if enabled) */ - private synchronized void registerObject(UAVObject obj) { + private void registerObject(UAVObject obj) { // Setup object for periodic updates addObject(obj); @@ -213,24 +213,27 @@ public class Telemetry { /** * Add an object in the list used for periodic updates */ - private synchronized void addObject(UAVObject obj) { - // Check if object type is already in the list - ListIterator li = objList.listIterator(); - while (li.hasNext()) { - ObjectTimeInfo n = li.next(); - if (n.obj.getObjID() == obj.getObjID()) { - // Object type (not instance!) is already in the list, do - // nothing - return; - } - } + private void addObject(UAVObject obj) { - // If this point is reached, then the object type is new, let's add it - ObjectTimeInfo timeInfo = new ObjectTimeInfo(); - timeInfo.obj = obj; - timeInfo.timeToNextUpdateMs = 0; - timeInfo.updatePeriodMs = 0; - objList.add(timeInfo); + synchronized (objList) { + // Check if object type is already in the list + ListIterator li = objList.listIterator(); + while (li.hasNext()) { + ObjectTimeInfo n = li.next(); + if (n.obj.getObjID() == obj.getObjID()) { + // Object type (not instance!) is already in the list, do + // nothing + return; + } + } + + // If this point is reached, then the object type is new, let's add it + ObjectTimeInfo timeInfo = new ObjectTimeInfo(); + timeInfo.obj = obj; + timeInfo.timeToNextUpdateMs = 0; + timeInfo.updatePeriodMs = 0; + objList.add(timeInfo); + } } /** @@ -281,7 +284,7 @@ public class Telemetry { * Connect to all instances of an object depending on the event mask * specified */ - private synchronized void connectToObjectInstances(UAVObject obj, + private void connectToObjectInstances(UAVObject obj, int eventMask) { List objs = objMngr.getObjectInstances(obj.getObjID()); ListIterator li = objs.listIterator(); @@ -312,43 +315,46 @@ public class Telemetry { * Update an object based on its metadata properties */ private void updateObject(UAVObject obj) { - // Get metadata - UAVObject.Metadata metadata = obj.getMetadata(); - // Setup object depending on update mode - int eventMask; - if (metadata.GetGcsTelemetryUpdateMode() == UAVObject.UpdateMode.UPDATEMODE_PERIODIC) { - // Set update period - setUpdatePeriod(obj, metadata.gcsTelemetryUpdatePeriod); - // Connect signals for all instances - eventMask = EV_UPDATED_MANUAL | EV_UPDATE_REQ; - if (obj.isMetadata()) - eventMask |= EV_UNPACKED; // we also need to act on remote - // updates (unpack events) + synchronized(obj) { + // Get metadata + UAVObject.Metadata metadata = obj.getMetadata(); - connectToObjectInstances(obj, eventMask); - } else if (metadata.GetGcsTelemetryUpdateMode() == UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) { - // Set update period - setUpdatePeriod(obj, 0); - // Connect signals for all instances - eventMask = EV_UPDATED | EV_UPDATED_MANUAL | EV_UPDATE_REQ; - if (obj.isMetadata()) - eventMask |= EV_UNPACKED; // we also need to act on remote - // updates (unpack events) + // Setup object depending on update mode + int eventMask; + if (metadata.GetGcsTelemetryUpdateMode() == UAVObject.UpdateMode.UPDATEMODE_PERIODIC) { + // Set update period + setUpdatePeriod(obj, metadata.gcsTelemetryUpdatePeriod); + // Connect signals for all instances + eventMask = EV_UPDATED_MANUAL | EV_UPDATE_REQ; + if (obj.isMetadata()) + eventMask |= EV_UNPACKED; // we also need to act on remote + // updates (unpack events) - connectToObjectInstances(obj, eventMask); - } else if (metadata.GetGcsTelemetryUpdateMode() == UAVObject.UpdateMode.UPDATEMODE_THROTTLED) { - // TODO - } else if (metadata.GetGcsTelemetryUpdateMode() == UAVObject.UpdateMode.UPDATEMODE_MANUAL) { - // Set update period - setUpdatePeriod(obj, 0); - // Connect signals for all instances - eventMask = EV_UPDATED_MANUAL | EV_UPDATE_REQ; - if (obj.isMetadata()) - eventMask |= EV_UNPACKED; // we also need to act on remote - // updates (unpack events) + connectToObjectInstances(obj, eventMask); + } else if (metadata.GetGcsTelemetryUpdateMode() == UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) { + // Set update period + setUpdatePeriod(obj, 0); + // Connect signals for all instances + eventMask = EV_UPDATED | EV_UPDATED_MANUAL | EV_UPDATE_REQ; + if (obj.isMetadata()) + eventMask |= EV_UNPACKED; // we also need to act on remote + // updates (unpack events) - connectToObjectInstances(obj, eventMask); + connectToObjectInstances(obj, eventMask); + } else if (metadata.GetGcsTelemetryUpdateMode() == UAVObject.UpdateMode.UPDATEMODE_THROTTLED) { + // TODO + } else if (metadata.GetGcsTelemetryUpdateMode() == UAVObject.UpdateMode.UPDATEMODE_MANUAL) { + // Set update period + setUpdatePeriod(obj, 0); + // Connect signals for all instances + eventMask = EV_UPDATED_MANUAL | EV_UPDATE_REQ; + if (obj.isMetadata()) + eventMask |= EV_UNPACKED; // we also need to act on remote + // updates (unpack events) + + connectToObjectInstances(obj, eventMask); + } } } @@ -448,7 +454,7 @@ public class Telemetry { registerObject(obj); } - private synchronized void newInstance(UAVObject obj) { + private void newInstance(UAVObject obj) { registerObject(obj); } @@ -632,11 +638,7 @@ public class Telemetry { return; } - // Store this as the active transaction - transPending = newTransactionPending; - transInfo = newTrans; - - if (DEBUG) Log.d(TAG, "Process Object transaction for " + transInfo.obj.getName()); + if (DEBUG) Log.d(TAG, "Process Object transaction for " + newTrans.obj.getName()); // Remove this one from the list of pending transactions handler.removeActivatedQueue(objInfo); @@ -644,12 +646,12 @@ public class Telemetry { try { // 3. Execute transaction by sending the appropriate UAVTalk command - if (transInfo.objRequest) { - if (DEBUG) Log.d(TAG, "Sending object request " + transInfo.obj.getName()); - utalk.sendObjectRequest(transInfo.obj, transInfo.allInstances); + if (newTrans.objRequest) { + if (DEBUG) Log.d(TAG, "Sending object request " + newTrans.obj.getName()); + utalk.sendObjectRequest(newTrans.obj, newTrans.allInstances); } else { - if (DEBUG) Log.d(TAG, "Sending object " + transInfo.obj.getName()); - utalk.sendObject(transInfo.obj, transInfo.acked, transInfo.allInstances); + if (DEBUG) Log.d(TAG, "Sending object " + newTrans.obj.getName()); + utalk.sendObject(newTrans.obj, newTrans.acked, newTrans.allInstances); } } catch (IOException e) { @@ -657,9 +659,17 @@ public class Telemetry { e.printStackTrace(); } - // Post a timeout timer if a response is epxected - if (transPending) + // Store this as the active transaction. However in the case + // of transPending && !newTransactionPending we need ot not + // override the previous pending transaction + if (!transPending && newTransactionPending) { + transPending = newTransactionPending; + transInfo = newTrans; + + // Post a timeout timer if a response is epxected handler.postDelayed(transactionTimeout, REQ_TIMEOUT_MS); + } + } } } @@ -744,7 +754,7 @@ public class Telemetry { //Send signal obj.transactionCompleted(result); } else { - if (ERROR) Log.e(TAG, "Error: received a transaction completed when did not expect it."); + if (ERROR) Log.e(TAG, "Error: received a transaction completed when did not expect it. " + obj.getName()); transPending = false; } } diff --git a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java index 121a5ebcc..47d5744a0 100644 --- a/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java +++ b/androidgcs/src/org/openpilot/uavtalk/TelemetryMonitor.java @@ -54,9 +54,12 @@ public class TelemetryMonitor extends Observable { private final UAVObjectManager objMngr; private final Telemetry tel; + + private boolean objectsRegistered; // private UAVObject objPending; private UAVObject gcsStatsObj; private UAVObject flightStatsObj; + private final UAVObject firmwareIapObj; private Timer periodicTask; private int currentPeriod; private long lastUpdateTime; @@ -74,7 +77,8 @@ public class TelemetryMonitor extends Observable { return objects_updated; }; - public TelemetryMonitor(UAVObjectManager objMngr, Telemetry tel, OPTelemetryService s) { + public TelemetryMonitor(UAVObjectManager objMngr, Telemetry tel, + OPTelemetryService s) { this(objMngr, tel); telemService = s; } @@ -85,9 +89,15 @@ public class TelemetryMonitor extends Observable { // this.objPending = null; queue = new ArrayList(); + objectsRegistered = false; + // Get stats objects gcsStatsObj = objMngr.getObject("GCSTelemetryStats"); flightStatsObj = objMngr.getObject("FlightTelemetryStats"); + firmwareIapObj = objMngr.getObject("FirmwareIAPObj"); + + // The first update of the firmwareIapObj will trigger registering the objects + firmwareIapObj.addUpdatedObserver(firmwareIapUpdated); flightStatsObj.addUpdatedObserver(new Observer() { @Override @@ -360,8 +370,13 @@ public class TelemetryMonitor extends Observable { setPeriod(STATS_UPDATE_PERIOD_MS); connected = true; objects_updated = false; - startRetrievingObjects(); - if (HANDSHAKE_IS_CONNECTED) setChanged(); // Enabling this line makes the opConnected signal occur whenever we get a handshake + if (objectsRegistered) + startRetrievingObjects(); + else + firmwareIapObj.updateRequested(); + if (HANDSHAKE_IS_CONNECTED) + setChanged(); // Enabling this line makes the opConnected signal + // occur whenever we get a handshake } if (gcsDisconnected && gcsStatusChanged) { if (DEBUG) @@ -405,4 +420,37 @@ public class TelemetryMonitor extends Observable { periodicTask = null; } + private final Observer firmwareIapUpdated = new Observer() { + @Override + public void update(Observable observable, Object data) { + if (DEBUG) Log.d(TAG, "Received firmware IAP Updated message"); + + UAVObjectField description = firmwareIapObj.getField("Description"); + if (description == null || description.getNumElements() < 100) { + telemService.toastMessage("Failed to determine UAVO set"); + } else { + final int HASH_SIZE_USED = 8; + String jarName = new String(); + for (int i = 0; i < HASH_SIZE_USED; i++) { + jarName += String.format("%02x", (int) description.getDouble(i + 60)); + } + jarName += ".jar"; + if (DEBUG) Log.d(TAG, "Attempting to load: " + jarName); + if (telemService.loadUavobjects(jarName, objMngr)) { + telemService.toastMessage("Loaded appropriate UAVO set"); + objectsRegistered = true; + try { + startRetrievingObjects(); + } catch (IOException e) { + // TODO Auto-generated catch block + e.printStackTrace(); + } + } else + telemService.toastMessage("Failed to load UAVO set: " + jarName); + } + + firmwareIapObj.removeUpdatedObserver(this); + } + }; + } diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java index 51cfeafd2..e61f78d67 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVObjectManager.java @@ -70,7 +70,6 @@ public class UAVObjectManager { */ public synchronized boolean registerObject(UAVDataObject obj) throws Exception { - // QMutexLocker locker(mutex); ListIterator> objIt = objects.listIterator(0); diff --git a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java index c996da845..fae619714 100644 --- a/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java +++ b/androidgcs/src/org/openpilot/uavtalk/UAVTalk.java @@ -269,16 +269,18 @@ public class UAVTalk { * it wants to give up on one (after a timeout) then it can cancel it * @return True if that object was pending, False otherwise */ - public synchronized boolean cancelPendingTransaction(UAVObject obj) { - if(respObj != null && respObj.getObjID() == obj.getObjID()) { - if(transactionListener != null) { - Log.d(TAG,"Canceling transaction: " + respObj.getName()); - transactionListener.TransactionFailed(respObj); - } - respObj = null; - return true; - } else - return false; + public boolean cancelPendingTransaction(UAVObject obj) { + synchronized (respObj) { + if(respObj != null && respObj.getObjID() == obj.getObjID()) { + if(transactionListener != null) { + Log.d(TAG,"Canceling transaction: " + respObj.getName()); + transactionListener.TransactionFailed(respObj); + } + respObj = null; + return true; + } else + return false; + } } /** @@ -296,15 +298,16 @@ public class UAVTalk { /** * This is the code that sets up a new UAVTalk packet that expects a response. */ - private synchronized void setupTransaction(UAVObject obj, boolean allInstances, int type) { + private void setupTransaction(UAVObject obj, boolean allInstances, int type) { + synchronized (this) { + // Only cancel if it is for a different object + if(respObj != null && respObj.getObjID() != obj.getObjID()) + cancelPendingTransaction(obj); - // Only cancel if it is for a different object - if(respObj != null && respObj.getObjID() != obj.getObjID()) - cancelPendingTransaction(obj); - - respObj = obj; - respAllInstances = allInstances; - respType = type; + respObj = obj; + respAllInstances = allInstances; + respType = type; + } } /** @@ -315,7 +318,7 @@ public class UAVTalk { * Success (true), Failure (false) * @throws IOException */ - private synchronized boolean objectTransaction(UAVObject obj, int type, boolean allInstances) throws IOException { + private boolean objectTransaction(UAVObject obj, int type, boolean allInstances) throws IOException { if (type == TYPE_OBJ_ACK || type == TYPE_OBJ_REQ || type == TYPE_OBJ) { return transmitObject(obj, type, allInstances); } else { @@ -415,7 +418,7 @@ public class UAVTalk { { UAVObject rxObj = objMngr.getObject(rxObjId); if (rxObj == null) { - if (DEBUG) Log.d(TAG, "Unknown ID: " + rxObjId); + if (WARN) Log.w(TAG, "Unknown ID: " + rxObjId); stats.rxErrors++; rxState = RxStateType.STATE_SYNC; break; @@ -429,17 +432,7 @@ public class UAVTalk { // Check length and determine next state if (rxLength >= MAX_PAYLOAD_LENGTH) { - stats.rxErrors++; - rxState = RxStateType.STATE_SYNC; - break; - } - - // Check the lengths match - if ((rxPacketLength + rxLength) != packetSize) { // packet error - // - - // mismatched - // packet - // size + if (WARN) Log.w(TAG, "Greater than max payload length"); stats.rxErrors++; rxState = RxStateType.STATE_SYNC; break; @@ -503,7 +496,7 @@ public class UAVTalk { rxCSPacket = rxbyte; if (rxCS != rxCSPacket) { // packet error - faulty CRC - if (DEBUG) Log.d(TAG,"Bad crc"); + if (WARN) Log.w(TAG,"Bad crc"); stats.rxErrors++; rxState = RxStateType.STATE_SYNC; break; @@ -512,7 +505,7 @@ public class UAVTalk { if (rxPacketLength != (packetSize + 1)) { // packet error - // mismatched packet // size - if (DEBUG) Log.d(TAG,"Bad size"); + if (WARN) Log.w(TAG,"Bad size"); stats.rxErrors++; rxState = RxStateType.STATE_SYNC; break; @@ -529,6 +522,7 @@ public class UAVTalk { break; default: + if (WARN) Log.w(TAG, "Bad state"); rxState = RxStateType.STATE_SYNC; stats.rxErrors++; } @@ -701,21 +695,30 @@ public class UAVTalk { * Called when an object is received to check if this completes * a UAVTalk transaction */ - private synchronized void updateObjReq(UAVObject obj) { + private void updateObjReq(UAVObject obj) { // Check if this is not a possible candidate Assert.assertNotNull(obj); - if(respObj != null && respType == TYPE_OBJ_REQ && respObj.getObjID() == obj.getObjID() && - ((respObj.getInstID() == obj.getInstID() || !respAllInstances))) { + boolean succeeded = false; - // Indicate complete - respObj = null; + // The lock on UAVTalk must be release before the transaction succeeded signal is sent + // because otherwise if a transaction timeout occurs at the same time we can get a + // deadlock: + // 1. processInputStream -> updateObjReq (locks uavtalk) -> tranactionCompleted (locks transInfo) + // 2. transactionTimeout (locks transInfo) -> sendObjectRequest -> É -> setupTransaction (locks uavtalk) + synchronized(this) { + if(respObj != null && respType == TYPE_OBJ_REQ && respObj.getObjID() == obj.getObjID() && + ((respObj.getInstID() == obj.getInstID() || !respAllInstances))) { - // Notify listener - if (transactionListener != null) - transactionListener.TransactionSucceeded(obj); + // Indicate complete + respObj = null; + succeeded = true; + } } + // Notify listener + if (succeeded && transactionListener != null) + transactionListener.TransactionSucceeded(obj); } /** diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/Accels.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/Accels.java deleted file mode 100644 index e3c386e30..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/Accels.java +++ /dev/null @@ -1,150 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * The accel data. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -The accel data. - -generated from accels.xml - **/ -public class Accels extends UAVDataObject { - - public Accels() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List xElemNames = new ArrayList(); - xElemNames.add("0"); - fields.add( new UAVObjectField("x", "m/s^2", UAVObjectField.FieldType.FLOAT32, xElemNames, null) ); - - List yElemNames = new ArrayList(); - yElemNames.add("0"); - fields.add( new UAVObjectField("y", "m/s^2", UAVObjectField.FieldType.FLOAT32, yElemNames, null) ); - - List zElemNames = new ArrayList(); - zElemNames.add("0"); - fields.add( new UAVObjectField("z", "m/s^2", UAVObjectField.FieldType.FLOAT32, zElemNames, null) ); - - List temperatureElemNames = new ArrayList(); - temperatureElemNames.add("0"); - fields.add( new UAVObjectField("temperature", "deg C", UAVObjectField.FieldType.FLOAT32, temperatureElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 1000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - Accels obj = new Accels(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public Accels GetInstance(UAVObjectManager objMngr, long instID) - { - return (Accels)(objMngr.getObject(Accels.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0xDD9D5FC0l; - protected static final String NAME = "Accels"; - protected static String DESCRIPTION = "The accel data."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AccessoryDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AccessoryDesired.java deleted file mode 100644 index 24da98961..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AccessoryDesired.java +++ /dev/null @@ -1,138 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Desired Auxillary actuator settings. Comes from @ref ManualControlModule. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Desired Auxillary actuator settings. Comes from @ref ManualControlModule. - -generated from accessorydesired.xml - **/ -public class AccessoryDesired extends UAVDataObject { - - public AccessoryDesired() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List AccessoryValElemNames = new ArrayList(); - AccessoryValElemNames.add("0"); - fields.add( new UAVObjectField("AccessoryVal", "", UAVObjectField.FieldType.FLOAT32, AccessoryValElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 1000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - AccessoryDesired obj = new AccessoryDesired(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public AccessoryDesired GetInstance(UAVObjectManager objMngr, long instID) - { - return (AccessoryDesired)(objMngr.getObject(AccessoryDesired.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0xC409985Al; - protected static final String NAME = "AccessoryDesired"; - protected static String DESCRIPTION = "Desired Auxillary actuator settings. Comes from @ref ManualControlModule."; - protected static final boolean ISSINGLEINST = 0 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java deleted file mode 100644 index 917095171..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorCommand.java +++ /dev/null @@ -1,159 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Contains the pulse duration sent to each of the channels. Set by @ref ActuatorModule - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Contains the pulse duration sent to each of the channels. Set by @ref ActuatorModule - -generated from actuatorcommand.xml - **/ -public class ActuatorCommand extends UAVDataObject { - - public ActuatorCommand() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List ChannelElemNames = new ArrayList(); - ChannelElemNames.add("0"); - ChannelElemNames.add("1"); - ChannelElemNames.add("2"); - ChannelElemNames.add("3"); - ChannelElemNames.add("4"); - ChannelElemNames.add("5"); - ChannelElemNames.add("6"); - ChannelElemNames.add("7"); - ChannelElemNames.add("8"); - ChannelElemNames.add("9"); - fields.add( new UAVObjectField("Channel", "us", UAVObjectField.FieldType.INT16, ChannelElemNames, null) ); - - List MaxUpdateTimeElemNames = new ArrayList(); - MaxUpdateTimeElemNames.add("0"); - fields.add( new UAVObjectField("MaxUpdateTime", "ms", UAVObjectField.FieldType.UINT16, MaxUpdateTimeElemNames, null) ); - - List UpdateTimeElemNames = new ArrayList(); - UpdateTimeElemNames.add("0"); - fields.add( new UAVObjectField("UpdateTime", "ms", UAVObjectField.FieldType.UINT8, UpdateTimeElemNames, null) ); - - List NumFailedUpdatesElemNames = new ArrayList(); - NumFailedUpdatesElemNames.add("0"); - fields.add( new UAVObjectField("NumFailedUpdates", "", UAVObjectField.FieldType.UINT8, NumFailedUpdatesElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 1000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - ActuatorCommand obj = new ActuatorCommand(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public ActuatorCommand GetInstance(UAVObjectManager objMngr, long instID) - { - return (ActuatorCommand)(objMngr.getObject(ActuatorCommand.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x5324CB8l; - protected static final String NAME = "ActuatorCommand"; - protected static String DESCRIPTION = "Contains the pulse duration sent to each of the channels. Set by @ref ActuatorModule"; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java deleted file mode 100644 index 8f7869ff9..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorDesired.java +++ /dev/null @@ -1,158 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Desired raw, pitch and yaw actuator settings. Comes from either @ref StabilizationModule or @ref ManualControlModule depending on FlightMode. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Desired raw, pitch and yaw actuator settings. Comes from either @ref StabilizationModule or @ref ManualControlModule depending on FlightMode. - -generated from actuatordesired.xml - **/ -public class ActuatorDesired extends UAVDataObject { - - public ActuatorDesired() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List RollElemNames = new ArrayList(); - RollElemNames.add("0"); - fields.add( new UAVObjectField("Roll", "%", UAVObjectField.FieldType.FLOAT32, RollElemNames, null) ); - - List PitchElemNames = new ArrayList(); - PitchElemNames.add("0"); - fields.add( new UAVObjectField("Pitch", "%", UAVObjectField.FieldType.FLOAT32, PitchElemNames, null) ); - - List YawElemNames = new ArrayList(); - YawElemNames.add("0"); - fields.add( new UAVObjectField("Yaw", "%", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); - - List ThrottleElemNames = new ArrayList(); - ThrottleElemNames.add("0"); - fields.add( new UAVObjectField("Throttle", "%", UAVObjectField.FieldType.FLOAT32, ThrottleElemNames, null) ); - - List UpdateTimeElemNames = new ArrayList(); - UpdateTimeElemNames.add("0"); - fields.add( new UAVObjectField("UpdateTime", "ms", UAVObjectField.FieldType.FLOAT32, UpdateTimeElemNames, null) ); - - List NumLongUpdatesElemNames = new ArrayList(); - NumLongUpdatesElemNames.add("0"); - fields.add( new UAVObjectField("NumLongUpdates", "ms", UAVObjectField.FieldType.FLOAT32, NumLongUpdatesElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 1000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - ActuatorDesired obj = new ActuatorDesired(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public ActuatorDesired GetInstance(UAVObjectManager objMngr, long instID) - { - return (ActuatorDesired)(objMngr.getObject(ActuatorDesired.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0xCA4BC4A4l; - protected static final String NAME = "ActuatorDesired"; - protected static String DESCRIPTION = "Desired raw, pitch and yaw actuator settings. Comes from either @ref StabilizationModule or @ref ManualControlModule depending on FlightMode."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java deleted file mode 100644 index b0e5a2e89..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ActuatorSettings.java +++ /dev/null @@ -1,273 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType - -generated from actuatorsettings.xml - **/ -public class ActuatorSettings extends UAVDataObject { - - public ActuatorSettings() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List ChannelUpdateFreqElemNames = new ArrayList(); - ChannelUpdateFreqElemNames.add("0"); - ChannelUpdateFreqElemNames.add("1"); - ChannelUpdateFreqElemNames.add("2"); - ChannelUpdateFreqElemNames.add("3"); - fields.add( new UAVObjectField("ChannelUpdateFreq", "Hz", UAVObjectField.FieldType.UINT16, ChannelUpdateFreqElemNames, null) ); - - List ChannelMaxElemNames = new ArrayList(); - ChannelMaxElemNames.add("0"); - ChannelMaxElemNames.add("1"); - ChannelMaxElemNames.add("2"); - ChannelMaxElemNames.add("3"); - ChannelMaxElemNames.add("4"); - ChannelMaxElemNames.add("5"); - ChannelMaxElemNames.add("6"); - ChannelMaxElemNames.add("7"); - ChannelMaxElemNames.add("8"); - ChannelMaxElemNames.add("9"); - fields.add( new UAVObjectField("ChannelMax", "us", UAVObjectField.FieldType.INT16, ChannelMaxElemNames, null) ); - - List ChannelNeutralElemNames = new ArrayList(); - ChannelNeutralElemNames.add("0"); - ChannelNeutralElemNames.add("1"); - ChannelNeutralElemNames.add("2"); - ChannelNeutralElemNames.add("3"); - ChannelNeutralElemNames.add("4"); - ChannelNeutralElemNames.add("5"); - ChannelNeutralElemNames.add("6"); - ChannelNeutralElemNames.add("7"); - ChannelNeutralElemNames.add("8"); - ChannelNeutralElemNames.add("9"); - fields.add( new UAVObjectField("ChannelNeutral", "us", UAVObjectField.FieldType.INT16, ChannelNeutralElemNames, null) ); - - List ChannelMinElemNames = new ArrayList(); - ChannelMinElemNames.add("0"); - ChannelMinElemNames.add("1"); - ChannelMinElemNames.add("2"); - ChannelMinElemNames.add("3"); - ChannelMinElemNames.add("4"); - ChannelMinElemNames.add("5"); - ChannelMinElemNames.add("6"); - ChannelMinElemNames.add("7"); - ChannelMinElemNames.add("8"); - ChannelMinElemNames.add("9"); - fields.add( new UAVObjectField("ChannelMin", "us", UAVObjectField.FieldType.INT16, ChannelMinElemNames, null) ); - - List ChannelTypeElemNames = new ArrayList(); - ChannelTypeElemNames.add("0"); - ChannelTypeElemNames.add("1"); - ChannelTypeElemNames.add("2"); - ChannelTypeElemNames.add("3"); - ChannelTypeElemNames.add("4"); - ChannelTypeElemNames.add("5"); - ChannelTypeElemNames.add("6"); - ChannelTypeElemNames.add("7"); - ChannelTypeElemNames.add("8"); - ChannelTypeElemNames.add("9"); - List ChannelTypeEnumOptions = new ArrayList(); - ChannelTypeEnumOptions.add("PWM"); - ChannelTypeEnumOptions.add("MK"); - ChannelTypeEnumOptions.add("ASTEC4"); - ChannelTypeEnumOptions.add("PWM Alarm Buzzer"); - fields.add( new UAVObjectField("ChannelType", "", UAVObjectField.FieldType.ENUM, ChannelTypeElemNames, ChannelTypeEnumOptions) ); - - List ChannelAddrElemNames = new ArrayList(); - ChannelAddrElemNames.add("0"); - ChannelAddrElemNames.add("1"); - ChannelAddrElemNames.add("2"); - ChannelAddrElemNames.add("3"); - ChannelAddrElemNames.add("4"); - ChannelAddrElemNames.add("5"); - ChannelAddrElemNames.add("6"); - ChannelAddrElemNames.add("7"); - ChannelAddrElemNames.add("8"); - ChannelAddrElemNames.add("9"); - fields.add( new UAVObjectField("ChannelAddr", "", UAVObjectField.FieldType.UINT8, ChannelAddrElemNames, null) ); - - List MotorsSpinWhileArmedElemNames = new ArrayList(); - MotorsSpinWhileArmedElemNames.add("0"); - List MotorsSpinWhileArmedEnumOptions = new ArrayList(); - MotorsSpinWhileArmedEnumOptions.add("FALSE"); - MotorsSpinWhileArmedEnumOptions.add("TRUE"); - fields.add( new UAVObjectField("MotorsSpinWhileArmed", "", UAVObjectField.FieldType.ENUM, MotorsSpinWhileArmedElemNames, MotorsSpinWhileArmedEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 0; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("ChannelUpdateFreq").setValue(50,0); - getField("ChannelUpdateFreq").setValue(50,1); - getField("ChannelUpdateFreq").setValue(50,2); - getField("ChannelUpdateFreq").setValue(50,3); - getField("ChannelMax").setValue(1000,0); - getField("ChannelMax").setValue(1000,1); - getField("ChannelMax").setValue(1000,2); - getField("ChannelMax").setValue(1000,3); - getField("ChannelMax").setValue(1000,4); - getField("ChannelMax").setValue(1000,5); - getField("ChannelMax").setValue(1000,6); - getField("ChannelMax").setValue(1000,7); - getField("ChannelMax").setValue(1000,8); - getField("ChannelMax").setValue(1000,9); - getField("ChannelNeutral").setValue(1000,0); - getField("ChannelNeutral").setValue(1000,1); - getField("ChannelNeutral").setValue(1000,2); - getField("ChannelNeutral").setValue(1000,3); - getField("ChannelNeutral").setValue(1000,4); - getField("ChannelNeutral").setValue(1000,5); - getField("ChannelNeutral").setValue(1000,6); - getField("ChannelNeutral").setValue(1000,7); - getField("ChannelNeutral").setValue(1000,8); - getField("ChannelNeutral").setValue(1000,9); - getField("ChannelMin").setValue(1000,0); - getField("ChannelMin").setValue(1000,1); - getField("ChannelMin").setValue(1000,2); - getField("ChannelMin").setValue(1000,3); - getField("ChannelMin").setValue(1000,4); - getField("ChannelMin").setValue(1000,5); - getField("ChannelMin").setValue(1000,6); - getField("ChannelMin").setValue(1000,7); - getField("ChannelMin").setValue(1000,8); - getField("ChannelMin").setValue(1000,9); - getField("ChannelType").setValue("PWM",0); - getField("ChannelType").setValue("PWM",1); - getField("ChannelType").setValue("PWM",2); - getField("ChannelType").setValue("PWM",3); - getField("ChannelType").setValue("PWM",4); - getField("ChannelType").setValue("PWM",5); - getField("ChannelType").setValue("PWM",6); - getField("ChannelType").setValue("PWM",7); - getField("ChannelType").setValue("PWM",8); - getField("ChannelType").setValue("PWM",9); - getField("ChannelAddr").setValue(0,0); - getField("ChannelAddr").setValue(1,1); - getField("ChannelAddr").setValue(2,2); - getField("ChannelAddr").setValue(3,3); - getField("ChannelAddr").setValue(4,4); - getField("ChannelAddr").setValue(5,5); - getField("ChannelAddr").setValue(6,6); - getField("ChannelAddr").setValue(7,7); - getField("ChannelAddr").setValue(8,8); - getField("ChannelAddr").setValue(9,9); - getField("MotorsSpinWhileArmed").setValue("FALSE"); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - ActuatorSettings obj = new ActuatorSettings(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public ActuatorSettings GetInstance(UAVObjectManager objMngr, long instID) - { - return (ActuatorSettings)(objMngr.getObject(ActuatorSettings.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x7D555646l; - protected static final String NAME = "ActuatorSettings"; - protected static String DESCRIPTION = "Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType"; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 1 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltHoldSmoothed.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltHoldSmoothed.java deleted file mode 100644 index 4a49c8a5d..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltHoldSmoothed.java +++ /dev/null @@ -1,146 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * The output on the kalman filter on altitude. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -The output on the kalman filter on altitude. - -generated from altholdsmoothed.xml - **/ -public class AltHoldSmoothed extends UAVDataObject { - - public AltHoldSmoothed() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List AltitudeElemNames = new ArrayList(); - AltitudeElemNames.add("0"); - fields.add( new UAVObjectField("Altitude", "m", UAVObjectField.FieldType.FLOAT32, AltitudeElemNames, null) ); - - List VelocityElemNames = new ArrayList(); - VelocityElemNames.add("0"); - fields.add( new UAVObjectField("Velocity", "m/s", UAVObjectField.FieldType.FLOAT32, VelocityElemNames, null) ); - - List AccelElemNames = new ArrayList(); - AccelElemNames.add("0"); - fields.add( new UAVObjectField("Accel", "m/s^2", UAVObjectField.FieldType.FLOAT32, AccelElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 1000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - AltHoldSmoothed obj = new AltHoldSmoothed(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public AltHoldSmoothed GetInstance(UAVObjectManager objMngr, long instID) - { - return (AltHoldSmoothed)(objMngr.getObject(AltHoldSmoothed.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x2BC6B9D2l; - protected static final String NAME = "AltHoldSmoothed"; - protected static String DESCRIPTION = "The output on the kalman filter on altitude."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltitudeHoldDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltitudeHoldDesired.java deleted file mode 100644 index 880a88f3f..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltitudeHoldDesired.java +++ /dev/null @@ -1,150 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Holds the desired altitude (from manual control) as well as the desired attitude to pass through - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Holds the desired altitude (from manual control) as well as the desired attitude to pass through - -generated from altitudeholddesired.xml - **/ -public class AltitudeHoldDesired extends UAVDataObject { - - public AltitudeHoldDesired() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List AltitudeElemNames = new ArrayList(); - AltitudeElemNames.add("0"); - fields.add( new UAVObjectField("Altitude", "m", UAVObjectField.FieldType.FLOAT32, AltitudeElemNames, null) ); - - List RollElemNames = new ArrayList(); - RollElemNames.add("0"); - fields.add( new UAVObjectField("Roll", "deg", UAVObjectField.FieldType.FLOAT32, RollElemNames, null) ); - - List PitchElemNames = new ArrayList(); - PitchElemNames.add("0"); - fields.add( new UAVObjectField("Pitch", "deg", UAVObjectField.FieldType.FLOAT32, PitchElemNames, null) ); - - List YawElemNames = new ArrayList(); - YawElemNames.add("0"); - fields.add( new UAVObjectField("Yaw", "deg/s", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 0; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 1000; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - AltitudeHoldDesired obj = new AltitudeHoldDesired(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public AltitudeHoldDesired GetInstance(UAVObjectManager objMngr, long instID) - { - return (AltitudeHoldDesired)(objMngr.getObject(AltitudeHoldDesired.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x495BAD6El; - protected static final String NAME = "AltitudeHoldDesired"; - protected static String DESCRIPTION = "Holds the desired altitude (from manual control) as well as the desired attitude to pass through"; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltitudeHoldSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltitudeHoldSettings.java deleted file mode 100644 index 6b5c6d2a6..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AltitudeHoldSettings.java +++ /dev/null @@ -1,169 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Settings for the @ref AltitudeHold module - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Settings for the @ref AltitudeHold module - -generated from altitudeholdsettings.xml - **/ -public class AltitudeHoldSettings extends UAVDataObject { - - public AltitudeHoldSettings() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List KpElemNames = new ArrayList(); - KpElemNames.add("0"); - fields.add( new UAVObjectField("Kp", "throttle/m", UAVObjectField.FieldType.FLOAT32, KpElemNames, null) ); - - List KiElemNames = new ArrayList(); - KiElemNames.add("0"); - fields.add( new UAVObjectField("Ki", "throttle/m", UAVObjectField.FieldType.FLOAT32, KiElemNames, null) ); - - List KdElemNames = new ArrayList(); - KdElemNames.add("0"); - fields.add( new UAVObjectField("Kd", "throttle/m", UAVObjectField.FieldType.FLOAT32, KdElemNames, null) ); - - List KaElemNames = new ArrayList(); - KaElemNames.add("0"); - fields.add( new UAVObjectField("Ka", "throttle/(m/s^2)", UAVObjectField.FieldType.FLOAT32, KaElemNames, null) ); - - List PressureNoiseElemNames = new ArrayList(); - PressureNoiseElemNames.add("0"); - fields.add( new UAVObjectField("PressureNoise", "m", UAVObjectField.FieldType.FLOAT32, PressureNoiseElemNames, null) ); - - List AccelNoiseElemNames = new ArrayList(); - AccelNoiseElemNames.add("0"); - fields.add( new UAVObjectField("AccelNoise", "m/s^2", UAVObjectField.FieldType.FLOAT32, AccelNoiseElemNames, null) ); - - List AccelDriftElemNames = new ArrayList(); - AccelDriftElemNames.add("0"); - fields.add( new UAVObjectField("AccelDrift", "m/s^2", UAVObjectField.FieldType.FLOAT32, AccelDriftElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 0; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("Kp").setValue(0.025); - getField("Ki").setValue(0.025); - getField("Kd").setValue(0.25); - getField("Ka").setValue(0); - getField("PressureNoise").setValue(0.01); - getField("AccelNoise").setValue(10); - getField("AccelDrift").setValue(0.001); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - AltitudeHoldSettings obj = new AltitudeHoldSettings(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public AltitudeHoldSettings GetInstance(UAVObjectManager objMngr, long instID) - { - return (AltitudeHoldSettings)(objMngr.getObject(AltitudeHoldSettings.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0xFEC55B42l; - protected static final String NAME = "AltitudeHoldSettings"; - protected static String DESCRIPTION = "Settings for the @ref AltitudeHold module"; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 1 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java deleted file mode 100644 index d62253d0e..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeActual.java +++ /dev/null @@ -1,162 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * The updated Attitude estimation from @ref AHRSCommsModule. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -The updated Attitude estimation from @ref AHRSCommsModule. - -generated from attitudeactual.xml - **/ -public class AttitudeActual extends UAVDataObject { - - public AttitudeActual() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List q1ElemNames = new ArrayList(); - q1ElemNames.add("0"); - fields.add( new UAVObjectField("q1", "", UAVObjectField.FieldType.FLOAT32, q1ElemNames, null) ); - - List q2ElemNames = new ArrayList(); - q2ElemNames.add("0"); - fields.add( new UAVObjectField("q2", "", UAVObjectField.FieldType.FLOAT32, q2ElemNames, null) ); - - List q3ElemNames = new ArrayList(); - q3ElemNames.add("0"); - fields.add( new UAVObjectField("q3", "", UAVObjectField.FieldType.FLOAT32, q3ElemNames, null) ); - - List q4ElemNames = new ArrayList(); - q4ElemNames.add("0"); - fields.add( new UAVObjectField("q4", "", UAVObjectField.FieldType.FLOAT32, q4ElemNames, null) ); - - List RollElemNames = new ArrayList(); - RollElemNames.add("0"); - fields.add( new UAVObjectField("Roll", "degrees", UAVObjectField.FieldType.FLOAT32, RollElemNames, null) ); - - List PitchElemNames = new ArrayList(); - PitchElemNames.add("0"); - fields.add( new UAVObjectField("Pitch", "degrees", UAVObjectField.FieldType.FLOAT32, PitchElemNames, null) ); - - List YawElemNames = new ArrayList(); - YawElemNames.add("0"); - fields.add( new UAVObjectField("Yaw", "degrees", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 100; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - AttitudeActual obj = new AttitudeActual(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public AttitudeActual GetInstance(UAVObjectManager objMngr, long instID) - { - return (AttitudeActual)(objMngr.getObject(AttitudeActual.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x33DAD5E6l; - protected static final String NAME = "AttitudeActual"; - protected static String DESCRIPTION = "The updated Attitude estimation from @ref AHRSCommsModule."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java deleted file mode 100644 index c43a2a993..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSettings.java +++ /dev/null @@ -1,206 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Settings for the @ref Attitude module used on CopterControl - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Settings for the @ref Attitude module used on CopterControl - -generated from attitudesettings.xml - **/ -public class AttitudeSettings extends UAVDataObject { - - public AttitudeSettings() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List GyroGainElemNames = new ArrayList(); - GyroGainElemNames.add("0"); - fields.add( new UAVObjectField("GyroGain", "(rad/s)/lsb", UAVObjectField.FieldType.FLOAT32, GyroGainElemNames, null) ); - - List AccelKpElemNames = new ArrayList(); - AccelKpElemNames.add("0"); - fields.add( new UAVObjectField("AccelKp", "channel", UAVObjectField.FieldType.FLOAT32, AccelKpElemNames, null) ); - - List AccelKiElemNames = new ArrayList(); - AccelKiElemNames.add("0"); - fields.add( new UAVObjectField("AccelKi", "channel", UAVObjectField.FieldType.FLOAT32, AccelKiElemNames, null) ); - - List YawBiasRateElemNames = new ArrayList(); - YawBiasRateElemNames.add("0"); - fields.add( new UAVObjectField("YawBiasRate", "channel", UAVObjectField.FieldType.FLOAT32, YawBiasRateElemNames, null) ); - - List AccelBiasElemNames = new ArrayList(); - AccelBiasElemNames.add("X"); - AccelBiasElemNames.add("Y"); - AccelBiasElemNames.add("Z"); - fields.add( new UAVObjectField("AccelBias", "lsb", UAVObjectField.FieldType.INT16, AccelBiasElemNames, null) ); - - List GyroBiasElemNames = new ArrayList(); - GyroBiasElemNames.add("X"); - GyroBiasElemNames.add("Y"); - GyroBiasElemNames.add("Z"); - fields.add( new UAVObjectField("GyroBias", "deg/s * 100", UAVObjectField.FieldType.INT16, GyroBiasElemNames, null) ); - - List BoardRotationElemNames = new ArrayList(); - BoardRotationElemNames.add("Roll"); - BoardRotationElemNames.add("Pitch"); - BoardRotationElemNames.add("Yaw"); - fields.add( new UAVObjectField("BoardRotation", "deg", UAVObjectField.FieldType.INT16, BoardRotationElemNames, null) ); - - List ZeroDuringArmingElemNames = new ArrayList(); - ZeroDuringArmingElemNames.add("0"); - List ZeroDuringArmingEnumOptions = new ArrayList(); - ZeroDuringArmingEnumOptions.add("FALSE"); - ZeroDuringArmingEnumOptions.add("TRUE"); - fields.add( new UAVObjectField("ZeroDuringArming", "channel", UAVObjectField.FieldType.ENUM, ZeroDuringArmingElemNames, ZeroDuringArmingEnumOptions) ); - - List BiasCorrectGyroElemNames = new ArrayList(); - BiasCorrectGyroElemNames.add("0"); - List BiasCorrectGyroEnumOptions = new ArrayList(); - BiasCorrectGyroEnumOptions.add("FALSE"); - BiasCorrectGyroEnumOptions.add("TRUE"); - fields.add( new UAVObjectField("BiasCorrectGyro", "channel", UAVObjectField.FieldType.ENUM, BiasCorrectGyroElemNames, BiasCorrectGyroEnumOptions) ); - - List TrimFlightElemNames = new ArrayList(); - TrimFlightElemNames.add("0"); - List TrimFlightEnumOptions = new ArrayList(); - TrimFlightEnumOptions.add("NORMAL"); - TrimFlightEnumOptions.add("START"); - TrimFlightEnumOptions.add("LOAD"); - fields.add( new UAVObjectField("TrimFlight", "channel", UAVObjectField.FieldType.ENUM, TrimFlightElemNames, TrimFlightEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 0; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("GyroGain").setValue(0.42); - getField("AccelKp").setValue(0.05); - getField("AccelKi").setValue(0.0001); - getField("YawBiasRate").setValue(1e-06); - getField("AccelBias").setValue(0,0); - getField("AccelBias").setValue(0,1); - getField("AccelBias").setValue(0,2); - getField("GyroBias").setValue(0,0); - getField("GyroBias").setValue(0,1); - getField("GyroBias").setValue(0,2); - getField("BoardRotation").setValue(0,0); - getField("BoardRotation").setValue(0,1); - getField("BoardRotation").setValue(0,2); - getField("ZeroDuringArming").setValue("TRUE"); - getField("BiasCorrectGyro").setValue("TRUE"); - getField("TrimFlight").setValue("NORMAL"); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - AttitudeSettings obj = new AttitudeSettings(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public AttitudeSettings GetInstance(UAVObjectManager objMngr, long instID) - { - return (AttitudeSettings)(objMngr.getObject(AttitudeSettings.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0xC307BC4Al; - protected static final String NAME = "AttitudeSettings"; - protected static String DESCRIPTION = "Settings for the @ref Attitude module used on CopterControl"; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 1 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSimulated.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSimulated.java deleted file mode 100644 index 2046d6add..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/AttitudeSimulated.java +++ /dev/null @@ -1,174 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * The simulated Attitude estimation from @ref Sensors. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -The simulated Attitude estimation from @ref Sensors. - -generated from attitudesimulated.xml - **/ -public class AttitudeSimulated extends UAVDataObject { - - public AttitudeSimulated() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List q1ElemNames = new ArrayList(); - q1ElemNames.add("0"); - fields.add( new UAVObjectField("q1", "", UAVObjectField.FieldType.FLOAT32, q1ElemNames, null) ); - - List q2ElemNames = new ArrayList(); - q2ElemNames.add("0"); - fields.add( new UAVObjectField("q2", "", UAVObjectField.FieldType.FLOAT32, q2ElemNames, null) ); - - List q3ElemNames = new ArrayList(); - q3ElemNames.add("0"); - fields.add( new UAVObjectField("q3", "", UAVObjectField.FieldType.FLOAT32, q3ElemNames, null) ); - - List q4ElemNames = new ArrayList(); - q4ElemNames.add("0"); - fields.add( new UAVObjectField("q4", "", UAVObjectField.FieldType.FLOAT32, q4ElemNames, null) ); - - List RollElemNames = new ArrayList(); - RollElemNames.add("0"); - fields.add( new UAVObjectField("Roll", "degrees", UAVObjectField.FieldType.FLOAT32, RollElemNames, null) ); - - List PitchElemNames = new ArrayList(); - PitchElemNames.add("0"); - fields.add( new UAVObjectField("Pitch", "degrees", UAVObjectField.FieldType.FLOAT32, PitchElemNames, null) ); - - List YawElemNames = new ArrayList(); - YawElemNames.add("0"); - fields.add( new UAVObjectField("Yaw", "degrees", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); - - List VelocityElemNames = new ArrayList(); - VelocityElemNames.add("North"); - VelocityElemNames.add("East"); - VelocityElemNames.add("Down"); - fields.add( new UAVObjectField("Velocity", "m/s", UAVObjectField.FieldType.FLOAT32, VelocityElemNames, null) ); - - List PositionElemNames = new ArrayList(); - PositionElemNames.add("North"); - PositionElemNames.add("East"); - PositionElemNames.add("Down"); - fields.add( new UAVObjectField("Position", "m", UAVObjectField.FieldType.FLOAT32, PositionElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 100; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - AttitudeSimulated obj = new AttitudeSimulated(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public AttitudeSimulated GetInstance(UAVObjectManager objMngr, long instID) - { - return (AttitudeSimulated)(objMngr.getObject(AttitudeSimulated.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x9266CE74l; - protected static final String NAME = "AttitudeSimulated"; - protected static String DESCRIPTION = "The simulated Attitude estimation from @ref Sensors."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAirspeed.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAirspeed.java deleted file mode 100644 index 3a9e306f4..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAirspeed.java +++ /dev/null @@ -1,153 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * The raw data from the dynamic pressure sensor with pressure, temperature and airspeed. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -The raw data from the dynamic pressure sensor with pressure, temperature and airspeed. - -generated from baroairspeed.xml - **/ -public class BaroAirspeed extends UAVDataObject { - - public BaroAirspeed() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List AirspeedElemNames = new ArrayList(); - AirspeedElemNames.add("0"); - fields.add( new UAVObjectField("Airspeed", "m/s", UAVObjectField.FieldType.FLOAT32, AirspeedElemNames, null) ); - - List SensorValueElemNames = new ArrayList(); - SensorValueElemNames.add("0"); - fields.add( new UAVObjectField("SensorValue", "raw", UAVObjectField.FieldType.UINT16, SensorValueElemNames, null) ); - - List ZeroPointElemNames = new ArrayList(); - ZeroPointElemNames.add("0"); - fields.add( new UAVObjectField("ZeroPoint", "raw", UAVObjectField.FieldType.UINT16, ZeroPointElemNames, null) ); - - List ConnectedElemNames = new ArrayList(); - ConnectedElemNames.add("0"); - List ConnectedEnumOptions = new ArrayList(); - ConnectedEnumOptions.add("False"); - ConnectedEnumOptions.add("True"); - fields.add( new UAVObjectField("Connected", "", UAVObjectField.FieldType.ENUM, ConnectedElemNames, ConnectedEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 1000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - BaroAirspeed obj = new BaroAirspeed(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public BaroAirspeed GetInstance(UAVObjectManager objMngr, long instID) - { - return (BaroAirspeed)(objMngr.getObject(BaroAirspeed.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x169EA4Al; - protected static final String NAME = "BaroAirspeed"; - protected static String DESCRIPTION = "The raw data from the dynamic pressure sensor with pressure, temperature and airspeed."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java deleted file mode 100644 index 505a42c5f..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/BaroAltitude.java +++ /dev/null @@ -1,146 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * The raw data from the barometric sensor with pressure, temperature and altitude estimate. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -The raw data from the barometric sensor with pressure, temperature and altitude estimate. - -generated from baroaltitude.xml - **/ -public class BaroAltitude extends UAVDataObject { - - public BaroAltitude() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List AltitudeElemNames = new ArrayList(); - AltitudeElemNames.add("0"); - fields.add( new UAVObjectField("Altitude", "m", UAVObjectField.FieldType.FLOAT32, AltitudeElemNames, null) ); - - List TemperatureElemNames = new ArrayList(); - TemperatureElemNames.add("0"); - fields.add( new UAVObjectField("Temperature", "C", UAVObjectField.FieldType.FLOAT32, TemperatureElemNames, null) ); - - List PressureElemNames = new ArrayList(); - PressureElemNames.add("0"); - fields.add( new UAVObjectField("Pressure", "kPa", UAVObjectField.FieldType.FLOAT32, PressureElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 1000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - BaroAltitude obj = new BaroAltitude(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public BaroAltitude GetInstance(UAVObjectManager objMngr, long instID) - { - return (BaroAltitude)(objMngr.getObject(BaroAltitude.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x99622E6Al; - protected static final String NAME = "BaroAltitude"; - protected static String DESCRIPTION = "The raw data from the barometric sensor with pressure, temperature and altitude estimate."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraDesired.java deleted file mode 100644 index caff64a0b..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraDesired.java +++ /dev/null @@ -1,146 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Desired camera outputs. Comes from @ref CameraStabilization module. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Desired camera outputs. Comes from @ref CameraStabilization module. - -generated from cameradesired.xml - **/ -public class CameraDesired extends UAVDataObject { - - public CameraDesired() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List RollElemNames = new ArrayList(); - RollElemNames.add("0"); - fields.add( new UAVObjectField("Roll", "", UAVObjectField.FieldType.FLOAT32, RollElemNames, null) ); - - List PitchElemNames = new ArrayList(); - PitchElemNames.add("0"); - fields.add( new UAVObjectField("Pitch", "", UAVObjectField.FieldType.FLOAT32, PitchElemNames, null) ); - - List YawElemNames = new ArrayList(); - YawElemNames.add("0"); - fields.add( new UAVObjectField("Yaw", "", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 1000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - CameraDesired obj = new CameraDesired(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public CameraDesired GetInstance(UAVObjectManager objMngr, long instID) - { - return (CameraDesired)(objMngr.getObject(CameraDesired.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x531F544El; - protected static final String NAME = "CameraDesired"; - protected static String DESCRIPTION = "Desired camera outputs. Comes from @ref CameraStabilization module."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraStabSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraStabSettings.java deleted file mode 100644 index 9ddb2116d..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/CameraStabSettings.java +++ /dev/null @@ -1,204 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Settings for the @ref CameraStab mmodule - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Settings for the @ref CameraStab mmodule - -generated from camerastabsettings.xml - **/ -public class CameraStabSettings extends UAVDataObject { - - public CameraStabSettings() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List MaxAxisLockRateElemNames = new ArrayList(); - MaxAxisLockRateElemNames.add("0"); - fields.add( new UAVObjectField("MaxAxisLockRate", "deg/s", UAVObjectField.FieldType.FLOAT32, MaxAxisLockRateElemNames, null) ); - - List ResponseTimeElemNames = new ArrayList(); - ResponseTimeElemNames.add("Roll"); - ResponseTimeElemNames.add("Pitch"); - ResponseTimeElemNames.add("Yaw"); - fields.add( new UAVObjectField("ResponseTime", "ms", UAVObjectField.FieldType.UINT16, ResponseTimeElemNames, null) ); - - List InputElemNames = new ArrayList(); - InputElemNames.add("Roll"); - InputElemNames.add("Pitch"); - InputElemNames.add("Yaw"); - List InputEnumOptions = new ArrayList(); - InputEnumOptions.add("Accessory0"); - InputEnumOptions.add("Accessory1"); - InputEnumOptions.add("Accessory2"); - InputEnumOptions.add("Accessory3"); - InputEnumOptions.add("Accessory4"); - InputEnumOptions.add("Accessory5"); - InputEnumOptions.add("None"); - fields.add( new UAVObjectField("Input", "channel", UAVObjectField.FieldType.ENUM, InputElemNames, InputEnumOptions) ); - - List InputRangeElemNames = new ArrayList(); - InputRangeElemNames.add("Roll"); - InputRangeElemNames.add("Pitch"); - InputRangeElemNames.add("Yaw"); - fields.add( new UAVObjectField("InputRange", "deg", UAVObjectField.FieldType.UINT8, InputRangeElemNames, null) ); - - List InputRateElemNames = new ArrayList(); - InputRateElemNames.add("Roll"); - InputRateElemNames.add("Pitch"); - InputRateElemNames.add("Yaw"); - fields.add( new UAVObjectField("InputRate", "deg/s", UAVObjectField.FieldType.UINT8, InputRateElemNames, null) ); - - List StabilizationModeElemNames = new ArrayList(); - StabilizationModeElemNames.add("Roll"); - StabilizationModeElemNames.add("Pitch"); - StabilizationModeElemNames.add("Yaw"); - List StabilizationModeEnumOptions = new ArrayList(); - StabilizationModeEnumOptions.add("Attitude"); - StabilizationModeEnumOptions.add("AxisLock"); - fields.add( new UAVObjectField("StabilizationMode", "", UAVObjectField.FieldType.ENUM, StabilizationModeElemNames, StabilizationModeEnumOptions) ); - - List OutputRangeElemNames = new ArrayList(); - OutputRangeElemNames.add("Roll"); - OutputRangeElemNames.add("Pitch"); - OutputRangeElemNames.add("Yaw"); - fields.add( new UAVObjectField("OutputRange", "deg", UAVObjectField.FieldType.UINT8, OutputRangeElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 0; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("MaxAxisLockRate").setValue(1); - getField("ResponseTime").setValue(150,0); - getField("ResponseTime").setValue(150,1); - getField("ResponseTime").setValue(150,2); - getField("Input").setValue("None",0); - getField("Input").setValue("None",1); - getField("Input").setValue("None",2); - getField("InputRange").setValue(20,0); - getField("InputRange").setValue(20,1); - getField("InputRange").setValue(20,2); - getField("InputRate").setValue(50,0); - getField("InputRate").setValue(50,1); - getField("InputRate").setValue(50,2); - getField("StabilizationMode").setValue("Attitude",0); - getField("StabilizationMode").setValue("Attitude",1); - getField("StabilizationMode").setValue("Attitude",2); - getField("OutputRange").setValue(20,0); - getField("OutputRange").setValue(20,1); - getField("OutputRange").setValue(20,2); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - CameraStabSettings obj = new CameraStabSettings(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public CameraStabSettings GetInstance(UAVObjectManager objMngr, long instID) - { - return (CameraStabSettings)(objMngr.getObject(CameraStabSettings.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x3B95DDBAl; - protected static final String NAME = "CameraStabSettings"; - protected static String DESCRIPTION = "Settings for the @ref CameraStab mmodule"; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 1 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FaultSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FaultSettings.java deleted file mode 100644 index 881a5c225..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FaultSettings.java +++ /dev/null @@ -1,146 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Allows testers to simulate various fault scenarios. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Allows testers to simulate various fault scenarios. - -generated from faultsettings.xml - **/ -public class FaultSettings extends UAVDataObject { - - public FaultSettings() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List ActivateFaultElemNames = new ArrayList(); - ActivateFaultElemNames.add("0"); - List ActivateFaultEnumOptions = new ArrayList(); - ActivateFaultEnumOptions.add("NoFault"); - ActivateFaultEnumOptions.add("ModuleInitAssert"); - ActivateFaultEnumOptions.add("InitOutOfMemory"); - ActivateFaultEnumOptions.add("InitBusError"); - ActivateFaultEnumOptions.add("RunawayTask"); - ActivateFaultEnumOptions.add("TaskOutOfMemory"); - fields.add( new UAVObjectField("ActivateFault", "fault", UAVObjectField.FieldType.ENUM, ActivateFaultElemNames, ActivateFaultEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 0; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("ActivateFault").setValue("NoFault"); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - FaultSettings obj = new FaultSettings(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public FaultSettings GetInstance(UAVObjectManager objMngr, long instID) - { - return (FaultSettings)(objMngr.getObject(FaultSettings.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x2778BA3Cl; - protected static final String NAME = "FaultSettings"; - protected static String DESCRIPTION = "Allows testers to simulate various fault scenarios."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 1 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java index 90a9e8893..ed79ad0b4 100644 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FirmwareIAPObj.java @@ -104,6 +104,66 @@ public class FirmwareIAPObj extends UAVDataObject { DescriptionElemNames.add("37"); DescriptionElemNames.add("38"); DescriptionElemNames.add("39"); + DescriptionElemNames.add("40"); + DescriptionElemNames.add("41"); + DescriptionElemNames.add("42"); + DescriptionElemNames.add("43"); + DescriptionElemNames.add("44"); + DescriptionElemNames.add("45"); + DescriptionElemNames.add("46"); + DescriptionElemNames.add("47"); + DescriptionElemNames.add("48"); + DescriptionElemNames.add("49"); + DescriptionElemNames.add("50"); + DescriptionElemNames.add("51"); + DescriptionElemNames.add("52"); + DescriptionElemNames.add("53"); + DescriptionElemNames.add("54"); + DescriptionElemNames.add("55"); + DescriptionElemNames.add("56"); + DescriptionElemNames.add("57"); + DescriptionElemNames.add("58"); + DescriptionElemNames.add("59"); + DescriptionElemNames.add("60"); + DescriptionElemNames.add("61"); + DescriptionElemNames.add("62"); + DescriptionElemNames.add("63"); + DescriptionElemNames.add("64"); + DescriptionElemNames.add("65"); + DescriptionElemNames.add("66"); + DescriptionElemNames.add("67"); + DescriptionElemNames.add("68"); + DescriptionElemNames.add("69"); + DescriptionElemNames.add("70"); + DescriptionElemNames.add("71"); + DescriptionElemNames.add("72"); + DescriptionElemNames.add("73"); + DescriptionElemNames.add("74"); + DescriptionElemNames.add("75"); + DescriptionElemNames.add("76"); + DescriptionElemNames.add("77"); + DescriptionElemNames.add("78"); + DescriptionElemNames.add("79"); + DescriptionElemNames.add("80"); + DescriptionElemNames.add("81"); + DescriptionElemNames.add("82"); + DescriptionElemNames.add("83"); + DescriptionElemNames.add("84"); + DescriptionElemNames.add("85"); + DescriptionElemNames.add("86"); + DescriptionElemNames.add("87"); + DescriptionElemNames.add("88"); + DescriptionElemNames.add("89"); + DescriptionElemNames.add("90"); + DescriptionElemNames.add("91"); + DescriptionElemNames.add("92"); + DescriptionElemNames.add("93"); + DescriptionElemNames.add("94"); + DescriptionElemNames.add("95"); + DescriptionElemNames.add("96"); + DescriptionElemNames.add("97"); + DescriptionElemNames.add("98"); + DescriptionElemNames.add("99"); fields.add( new UAVObjectField("Description", "", UAVObjectField.FieldType.UINT8, DescriptionElemNames, null) ); List CPUSerialElemNames = new ArrayList(); @@ -201,7 +261,7 @@ public class FirmwareIAPObj extends UAVDataObject { } // Constants - protected static final long OBJID = 0x3CCDFB68l; + protected static final long OBJID = 0x5E6E8FDCl; protected static final String NAME = "FirmwareIAPObj"; protected static String DESCRIPTION = "Queries board for SN, model, revision, and sends reset command"; protected static final boolean ISSINGLEINST = 1 > 0; diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FixedWingPathFollowerSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FixedWingPathFollowerSettings.java deleted file mode 100644 index 332873fe3..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FixedWingPathFollowerSettings.java +++ /dev/null @@ -1,239 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Settings for the @ref FixedWingPathFollowerModule - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Settings for the @ref FixedWingPathFollowerModule - -generated from fixedwingpathfollowersettings.xml - **/ -public class FixedWingPathFollowerSettings extends UAVDataObject { - - public FixedWingPathFollowerSettings() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List AirSpeedMaxElemNames = new ArrayList(); - AirSpeedMaxElemNames.add("0"); - fields.add( new UAVObjectField("AirSpeedMax", "m/s", UAVObjectField.FieldType.FLOAT32, AirSpeedMaxElemNames, null) ); - - List AirSpeedMinElemNames = new ArrayList(); - AirSpeedMinElemNames.add("0"); - fields.add( new UAVObjectField("AirSpeedMin", "m/s", UAVObjectField.FieldType.FLOAT32, AirSpeedMinElemNames, null) ); - - List VerticalVelMaxElemNames = new ArrayList(); - VerticalVelMaxElemNames.add("0"); - fields.add( new UAVObjectField("VerticalVelMax", "m/s", UAVObjectField.FieldType.FLOAT32, VerticalVelMaxElemNames, null) ); - - List HorizontalPosPElemNames = new ArrayList(); - HorizontalPosPElemNames.add("0"); - fields.add( new UAVObjectField("HorizontalPosP", "(m/s)/m", UAVObjectField.FieldType.FLOAT32, HorizontalPosPElemNames, null) ); - - List VerticalPosPElemNames = new ArrayList(); - VerticalPosPElemNames.add("0"); - fields.add( new UAVObjectField("VerticalPosP", "(m/s)/m", UAVObjectField.FieldType.FLOAT32, VerticalPosPElemNames, null) ); - - List CoursePIElemNames = new ArrayList(); - CoursePIElemNames.add("Kp"); - CoursePIElemNames.add("Ki"); - CoursePIElemNames.add("ILimit"); - fields.add( new UAVObjectField("CoursePI", "deg/deg", UAVObjectField.FieldType.FLOAT32, CoursePIElemNames, null) ); - - List SpeedPElemNames = new ArrayList(); - SpeedPElemNames.add("Kp"); - SpeedPElemNames.add("Max"); - fields.add( new UAVObjectField("SpeedP", "(m/s^2) / ((m/s)/(m/s)", UAVObjectField.FieldType.FLOAT32, SpeedPElemNames, null) ); - - List AccelPIElemNames = new ArrayList(); - AccelPIElemNames.add("Kp"); - AccelPIElemNames.add("Ki"); - AccelPIElemNames.add("ILimit"); - fields.add( new UAVObjectField("AccelPI", "deg / (m/s^2)", UAVObjectField.FieldType.FLOAT32, AccelPIElemNames, null) ); - - List VerticalToPitchCrossFeedElemNames = new ArrayList(); - VerticalToPitchCrossFeedElemNames.add("Kp"); - VerticalToPitchCrossFeedElemNames.add("Max"); - fields.add( new UAVObjectField("VerticalToPitchCrossFeed", "deg / ((m/s)/(m/s))", UAVObjectField.FieldType.FLOAT32, VerticalToPitchCrossFeedElemNames, null) ); - - List AirspeedToVerticalCrossFeedElemNames = new ArrayList(); - AirspeedToVerticalCrossFeedElemNames.add("Kp"); - AirspeedToVerticalCrossFeedElemNames.add("Max"); - fields.add( new UAVObjectField("AirspeedToVerticalCrossFeed", "(m/s) / ((m/s)/(m/s))", UAVObjectField.FieldType.FLOAT32, AirspeedToVerticalCrossFeedElemNames, null) ); - - List PowerPIElemNames = new ArrayList(); - PowerPIElemNames.add("Kp"); - PowerPIElemNames.add("Ki"); - PowerPIElemNames.add("ILimit"); - fields.add( new UAVObjectField("PowerPI", "1/(m/s)", UAVObjectField.FieldType.FLOAT32, PowerPIElemNames, null) ); - - List RollLimitElemNames = new ArrayList(); - RollLimitElemNames.add("Min"); - RollLimitElemNames.add("Neutral"); - RollLimitElemNames.add("Max"); - fields.add( new UAVObjectField("RollLimit", "deg", UAVObjectField.FieldType.FLOAT32, RollLimitElemNames, null) ); - - List PitchLimitElemNames = new ArrayList(); - PitchLimitElemNames.add("Min"); - PitchLimitElemNames.add("Neutral"); - PitchLimitElemNames.add("Max"); - fields.add( new UAVObjectField("PitchLimit", "deg", UAVObjectField.FieldType.FLOAT32, PitchLimitElemNames, null) ); - - List ThrottleLimitElemNames = new ArrayList(); - ThrottleLimitElemNames.add("Min"); - ThrottleLimitElemNames.add("Neutral"); - ThrottleLimitElemNames.add("Max"); - fields.add( new UAVObjectField("ThrottleLimit", "", UAVObjectField.FieldType.FLOAT32, ThrottleLimitElemNames, null) ); - - List UpdatePeriodElemNames = new ArrayList(); - UpdatePeriodElemNames.add("0"); - fields.add( new UAVObjectField("UpdatePeriod", "ms", UAVObjectField.FieldType.INT32, UpdatePeriodElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 0; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("AirSpeedMax").setValue(15); - getField("AirSpeedMin").setValue(10); - getField("VerticalVelMax").setValue(10); - getField("HorizontalPosP").setValue(0.05); - getField("VerticalPosP").setValue(0.05); - getField("CoursePI").setValue(0.2,0); - getField("CoursePI").setValue(0,1); - getField("CoursePI").setValue(0,2); - getField("SpeedP").setValue(10,0); - getField("SpeedP").setValue(10,1); - getField("AccelPI").setValue(1.5,0); - getField("AccelPI").setValue(1.5,1); - getField("AccelPI").setValue(20,2); - getField("VerticalToPitchCrossFeed").setValue(50,0); - getField("VerticalToPitchCrossFeed").setValue(5,1); - getField("AirspeedToVerticalCrossFeed").setValue(100,0); - getField("AirspeedToVerticalCrossFeed").setValue(100,1); - getField("PowerPI").setValue(0.01,0); - getField("PowerPI").setValue(0.01,1); - getField("PowerPI").setValue(0.8,2); - getField("RollLimit").setValue(-35,0); - getField("RollLimit").setValue(0,1); - getField("RollLimit").setValue(35,2); - getField("PitchLimit").setValue(-10,0); - getField("PitchLimit").setValue(5,1); - getField("PitchLimit").setValue(20,2); - getField("ThrottleLimit").setValue(0.1,0); - getField("ThrottleLimit").setValue(0.5,1); - getField("ThrottleLimit").setValue(0.9,2); - getField("UpdatePeriod").setValue(100); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - FixedWingPathFollowerSettings obj = new FixedWingPathFollowerSettings(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public FixedWingPathFollowerSettings GetInstance(UAVObjectManager objMngr, long instID) - { - return (FixedWingPathFollowerSettings)(objMngr.getObject(FixedWingPathFollowerSettings.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x8A3F1E02l; - protected static final String NAME = "FixedWingPathFollowerSettings"; - protected static String DESCRIPTION = "Settings for the @ref FixedWingPathFollowerModule"; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 1 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FixedWingPathFollowerStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FixedWingPathFollowerStatus.java deleted file mode 100644 index 7aac671a0..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FixedWingPathFollowerStatus.java +++ /dev/null @@ -1,164 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Object Storing Debugging Information on PID internals - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Object Storing Debugging Information on PID internals - -generated from fixedwingpathfollowerstatus.xml - **/ -public class FixedWingPathFollowerStatus extends UAVDataObject { - - public FixedWingPathFollowerStatus() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List EElemNames = new ArrayList(); - EElemNames.add("Course"); - EElemNames.add("Speed"); - EElemNames.add("Accel"); - EElemNames.add("Power"); - fields.add( new UAVObjectField("E", "", UAVObjectField.FieldType.FLOAT32, EElemNames, null) ); - - List AElemNames = new ArrayList(); - AElemNames.add("Course"); - AElemNames.add("Speed"); - AElemNames.add("Accel"); - AElemNames.add("Power"); - fields.add( new UAVObjectField("A", "", UAVObjectField.FieldType.FLOAT32, AElemNames, null) ); - - List CElemNames = new ArrayList(); - CElemNames.add("Course"); - CElemNames.add("Speed"); - CElemNames.add("Accel"); - CElemNames.add("Power"); - fields.add( new UAVObjectField("C", "", UAVObjectField.FieldType.FLOAT32, CElemNames, null) ); - - List ErrorsElemNames = new ArrayList(); - ErrorsElemNames.add("Wind"); - ErrorsElemNames.add("Lowspeed"); - ErrorsElemNames.add("Highspeed"); - ErrorsElemNames.add("Lowpower"); - ErrorsElemNames.add("Highpower"); - ErrorsElemNames.add("Pitchcontrol"); - fields.add( new UAVObjectField("Errors", "", UAVObjectField.FieldType.UINT8, ErrorsElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 500; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - FixedWingPathFollowerStatus obj = new FixedWingPathFollowerStatus(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public FixedWingPathFollowerStatus GetInstance(UAVObjectManager objMngr, long instID) - { - return (FixedWingPathFollowerStatus)(objMngr.getObject(FixedWingPathFollowerStatus.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0xA0D6F6D4l; - protected static final String NAME = "FixedWingPathFollowerStatus"; - protected static String DESCRIPTION = "Object Storing Debugging Information on PID internals"; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatterySettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatterySettings.java deleted file mode 100644 index 4baefffac..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatterySettings.java +++ /dev/null @@ -1,176 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Flight Battery configuration. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Flight Battery configuration. - -generated from flightbatterysettings.xml - **/ -public class FlightBatterySettings extends UAVDataObject { - - public FlightBatterySettings() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List CapacityElemNames = new ArrayList(); - CapacityElemNames.add("0"); - fields.add( new UAVObjectField("Capacity", "mAh", UAVObjectField.FieldType.UINT32, CapacityElemNames, null) ); - - List VoltageThresholdsElemNames = new ArrayList(); - VoltageThresholdsElemNames.add("Warning"); - VoltageThresholdsElemNames.add("Alarm"); - fields.add( new UAVObjectField("VoltageThresholds", "V", UAVObjectField.FieldType.FLOAT32, VoltageThresholdsElemNames, null) ); - - List SensorCalibrationsElemNames = new ArrayList(); - SensorCalibrationsElemNames.add("VoltageFactor"); - SensorCalibrationsElemNames.add("CurrentFactor"); - fields.add( new UAVObjectField("SensorCalibrations", "", UAVObjectField.FieldType.FLOAT32, SensorCalibrationsElemNames, null) ); - - List TypeElemNames = new ArrayList(); - TypeElemNames.add("0"); - List TypeEnumOptions = new ArrayList(); - TypeEnumOptions.add("LiPo"); - TypeEnumOptions.add("A123"); - TypeEnumOptions.add("LiCo"); - TypeEnumOptions.add("LiFeSO4"); - TypeEnumOptions.add("None"); - fields.add( new UAVObjectField("Type", "", UAVObjectField.FieldType.ENUM, TypeElemNames, TypeEnumOptions) ); - - List NbCellsElemNames = new ArrayList(); - NbCellsElemNames.add("0"); - fields.add( new UAVObjectField("NbCells", "", UAVObjectField.FieldType.UINT8, NbCellsElemNames, null) ); - - List SensorTypeElemNames = new ArrayList(); - SensorTypeElemNames.add("0"); - List SensorTypeEnumOptions = new ArrayList(); - SensorTypeEnumOptions.add("None"); - fields.add( new UAVObjectField("SensorType", "", UAVObjectField.FieldType.ENUM, SensorTypeElemNames, SensorTypeEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 0; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("Capacity").setValue(2200); - getField("VoltageThresholds").setValue(9.8,0); - getField("VoltageThresholds").setValue(9.2,1); - getField("SensorCalibrations").setValue(1,0); - getField("SensorCalibrations").setValue(1,1); - getField("Type").setValue("LiPo"); - getField("NbCells").setValue(3); - getField("SensorType").setValue("None"); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - FlightBatterySettings obj = new FlightBatterySettings(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public FlightBatterySettings GetInstance(UAVObjectManager objMngr, long instID) - { - return (FlightBatterySettings)(objMngr.getObject(FlightBatterySettings.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0xF172BB18l; - protected static final String NAME = "FlightBatterySettings"; - protected static String DESCRIPTION = "Flight Battery configuration."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 1 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java deleted file mode 100644 index 7a8f895f2..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightBatteryState.java +++ /dev/null @@ -1,164 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Battery status information. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Battery status information. - -generated from flightbatterystate.xml - **/ -public class FlightBatteryState extends UAVDataObject { - - public FlightBatteryState() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List VoltageElemNames = new ArrayList(); - VoltageElemNames.add("0"); - fields.add( new UAVObjectField("Voltage", "V", UAVObjectField.FieldType.FLOAT32, VoltageElemNames, null) ); - - List CurrentElemNames = new ArrayList(); - CurrentElemNames.add("0"); - fields.add( new UAVObjectField("Current", "A", UAVObjectField.FieldType.FLOAT32, CurrentElemNames, null) ); - - List PeakCurrentElemNames = new ArrayList(); - PeakCurrentElemNames.add("0"); - fields.add( new UAVObjectField("PeakCurrent", "A", UAVObjectField.FieldType.FLOAT32, PeakCurrentElemNames, null) ); - - List AvgCurrentElemNames = new ArrayList(); - AvgCurrentElemNames.add("0"); - fields.add( new UAVObjectField("AvgCurrent", "A", UAVObjectField.FieldType.FLOAT32, AvgCurrentElemNames, null) ); - - List ConsumedEnergyElemNames = new ArrayList(); - ConsumedEnergyElemNames.add("0"); - fields.add( new UAVObjectField("ConsumedEnergy", "mAh", UAVObjectField.FieldType.FLOAT32, ConsumedEnergyElemNames, null) ); - - List EstimatedFlightTimeElemNames = new ArrayList(); - EstimatedFlightTimeElemNames.add("0"); - fields.add( new UAVObjectField("EstimatedFlightTime", "sec", UAVObjectField.FieldType.FLOAT32, EstimatedFlightTimeElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READONLY) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 1000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("Voltage").setValue(0); - getField("Current").setValue(0); - getField("PeakCurrent").setValue(0); - getField("AvgCurrent").setValue(0); - getField("ConsumedEnergy").setValue(0); - getField("EstimatedFlightTime").setValue(0); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - FlightBatteryState obj = new FlightBatteryState(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public FlightBatteryState GetInstance(UAVObjectManager objMngr, long instID) - { - return (FlightBatteryState)(objMngr.getObject(FlightBatteryState.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x8C0D756l; - protected static final String NAME = "FlightBatteryState"; - protected static String DESCRIPTION = "Battery status information."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java deleted file mode 100644 index f7ed37fc2..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanControl.java +++ /dev/null @@ -1,143 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Control the flight plan script - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Control the flight plan script - -generated from flightplancontrol.xml - **/ -public class FlightPlanControl extends UAVDataObject { - - public FlightPlanControl() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List CommandElemNames = new ArrayList(); - CommandElemNames.add("0"); - List CommandEnumOptions = new ArrayList(); - CommandEnumOptions.add("Start"); - CommandEnumOptions.add("Stop"); - CommandEnumOptions.add("Kill"); - fields.add( new UAVObjectField("Command", "", UAVObjectField.FieldType.ENUM, CommandElemNames, CommandEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 0; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("Command").setValue("Start"); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - FlightPlanControl obj = new FlightPlanControl(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public FlightPlanControl GetInstance(UAVObjectManager objMngr, long instID) - { - return (FlightPlanControl)(objMngr.getObject(FlightPlanControl.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x53E3F180l; - protected static final String NAME = "FlightPlanControl"; - protected static String DESCRIPTION = "Control the flight plan script"; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java deleted file mode 100644 index a1c733686..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanSettings.java +++ /dev/null @@ -1,139 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Settings for the flight plan module, control the execution of the script - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Settings for the flight plan module, control the execution of the script - -generated from flightplansettings.xml - **/ -public class FlightPlanSettings extends UAVDataObject { - - public FlightPlanSettings() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List TestElemNames = new ArrayList(); - TestElemNames.add("0"); - fields.add( new UAVObjectField("Test", "", UAVObjectField.FieldType.FLOAT32, TestElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 0; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("Test").setValue(0); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - FlightPlanSettings obj = new FlightPlanSettings(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public FlightPlanSettings GetInstance(UAVObjectManager objMngr, long instID) - { - return (FlightPlanSettings)(objMngr.getObject(FlightPlanSettings.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x92E9FF76l; - protected static final String NAME = "FlightPlanSettings"; - protected static String DESCRIPTION = "Settings for the flight plan module, control the execution of the script"; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 1 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java deleted file mode 100644 index 49ffc7b49..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightPlanStatus.java +++ /dev/null @@ -1,183 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Status of the flight plan script - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Status of the flight plan script - -generated from flightplanstatus.xml - **/ -public class FlightPlanStatus extends UAVDataObject { - - public FlightPlanStatus() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List ErrorFileIDElemNames = new ArrayList(); - ErrorFileIDElemNames.add("0"); - fields.add( new UAVObjectField("ErrorFileID", "", UAVObjectField.FieldType.UINT32, ErrorFileIDElemNames, null) ); - - List ErrorLineNumElemNames = new ArrayList(); - ErrorLineNumElemNames.add("0"); - fields.add( new UAVObjectField("ErrorLineNum", "", UAVObjectField.FieldType.UINT32, ErrorLineNumElemNames, null) ); - - List DebugElemNames = new ArrayList(); - DebugElemNames.add("0"); - DebugElemNames.add("1"); - fields.add( new UAVObjectField("Debug", "", UAVObjectField.FieldType.FLOAT32, DebugElemNames, null) ); - - List StatusElemNames = new ArrayList(); - StatusElemNames.add("0"); - List StatusEnumOptions = new ArrayList(); - StatusEnumOptions.add("Stopped"); - StatusEnumOptions.add("Running"); - StatusEnumOptions.add("Error"); - fields.add( new UAVObjectField("Status", "", UAVObjectField.FieldType.ENUM, StatusElemNames, StatusEnumOptions) ); - - List ErrorTypeElemNames = new ArrayList(); - ErrorTypeElemNames.add("0"); - List ErrorTypeEnumOptions = new ArrayList(); - ErrorTypeEnumOptions.add("None"); - ErrorTypeEnumOptions.add("VMInitError"); - ErrorTypeEnumOptions.add("Exception"); - ErrorTypeEnumOptions.add("IOError"); - ErrorTypeEnumOptions.add("DivByZero"); - ErrorTypeEnumOptions.add("AssertError"); - ErrorTypeEnumOptions.add("AttributeError"); - ErrorTypeEnumOptions.add("ImportError"); - ErrorTypeEnumOptions.add("IndexError"); - ErrorTypeEnumOptions.add("KeyError"); - ErrorTypeEnumOptions.add("MemoryError"); - ErrorTypeEnumOptions.add("NameError"); - ErrorTypeEnumOptions.add("SyntaxError"); - ErrorTypeEnumOptions.add("SystemError"); - ErrorTypeEnumOptions.add("TypeError"); - ErrorTypeEnumOptions.add("ValueError"); - ErrorTypeEnumOptions.add("StopIteration"); - ErrorTypeEnumOptions.add("Warning"); - ErrorTypeEnumOptions.add("UnknownError"); - fields.add( new UAVObjectField("ErrorType", "", UAVObjectField.FieldType.ENUM, ErrorTypeElemNames, ErrorTypeEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 2000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("Debug").setValue(0,0); - getField("Debug").setValue(0,1); - getField("Status").setValue("Stopped"); - getField("ErrorType").setValue("None"); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - FlightPlanStatus obj = new FlightPlanStatus(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public FlightPlanStatus GetInstance(UAVObjectManager objMngr, long instID) - { - return (FlightPlanStatus)(objMngr.getObject(FlightPlanStatus.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x2206EE46l; - protected static final String NAME = "FlightPlanStatus"; - protected static String DESCRIPTION = "Status of the flight plan script"; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java deleted file mode 100644 index 97c0fafe5..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/FlightStatus.java +++ /dev/null @@ -1,156 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Contains major flight status information for other modules. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Contains major flight status information for other modules. - -generated from flightstatus.xml - **/ -public class FlightStatus extends UAVDataObject { - - public FlightStatus() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List ArmedElemNames = new ArrayList(); - ArmedElemNames.add("0"); - List ArmedEnumOptions = new ArrayList(); - ArmedEnumOptions.add("Disarmed"); - ArmedEnumOptions.add("Arming"); - ArmedEnumOptions.add("Armed"); - fields.add( new UAVObjectField("Armed", "", UAVObjectField.FieldType.ENUM, ArmedElemNames, ArmedEnumOptions) ); - - List FlightModeElemNames = new ArrayList(); - FlightModeElemNames.add("0"); - List FlightModeEnumOptions = new ArrayList(); - FlightModeEnumOptions.add("Manual"); - FlightModeEnumOptions.add("Stabilized1"); - FlightModeEnumOptions.add("Stabilized2"); - FlightModeEnumOptions.add("Stabilized3"); - FlightModeEnumOptions.add("Autotune"); - FlightModeEnumOptions.add("AltitudeHold"); - FlightModeEnumOptions.add("VelocityControl"); - FlightModeEnumOptions.add("PositionHold"); - fields.add( new UAVObjectField("FlightMode", "", UAVObjectField.FieldType.ENUM, FlightModeElemNames, FlightModeEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 5000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("Armed").setValue("Disarmed"); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - FlightStatus obj = new FlightStatus(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public FlightStatus GetInstance(UAVObjectManager objMngr, long instID) - { - return (FlightStatus)(objMngr.getObject(FlightStatus.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x9B6A127El; - protected static final String NAME = "FlightStatus"; - protected static String DESCRIPTION = "Contains major flight status information for other modules."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSReceiver.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSReceiver.java deleted file mode 100644 index dd4ad9d33..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GCSReceiver.java +++ /dev/null @@ -1,145 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * A receiver channel group carried over the telemetry link. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -A receiver channel group carried over the telemetry link. - -generated from gcsreceiver.xml - **/ -public class GCSReceiver extends UAVDataObject { - - public GCSReceiver() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List ChannelElemNames = new ArrayList(); - ChannelElemNames.add("0"); - ChannelElemNames.add("1"); - ChannelElemNames.add("2"); - ChannelElemNames.add("3"); - ChannelElemNames.add("4"); - ChannelElemNames.add("5"); - ChannelElemNames.add("6"); - ChannelElemNames.add("7"); - fields.add( new UAVObjectField("Channel", "us", UAVObjectField.FieldType.UINT16, ChannelElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 0; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - GCSReceiver obj = new GCSReceiver(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public GCSReceiver GetInstance(UAVObjectManager objMngr, long instID) - { - return (GCSReceiver)(objMngr.getObject(GCSReceiver.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0xCC7E1470l; - protected static final String NAME = "GCSReceiver"; - protected static String DESCRIPTION = "A receiver channel group carried over the telemetry link."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java deleted file mode 100644 index a13d11799..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSPosition.java +++ /dev/null @@ -1,183 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Raw GPS data from @ref GPSModule. Should only be used by @ref AHRSCommsModule. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Raw GPS data from @ref GPSModule. Should only be used by @ref AHRSCommsModule. - -generated from gpsposition.xml - **/ -public class GPSPosition extends UAVDataObject { - - public GPSPosition() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List LatitudeElemNames = new ArrayList(); - LatitudeElemNames.add("0"); - fields.add( new UAVObjectField("Latitude", "degrees x 10^-7", UAVObjectField.FieldType.INT32, LatitudeElemNames, null) ); - - List LongitudeElemNames = new ArrayList(); - LongitudeElemNames.add("0"); - fields.add( new UAVObjectField("Longitude", "degrees x 10^-7", UAVObjectField.FieldType.INT32, LongitudeElemNames, null) ); - - List AltitudeElemNames = new ArrayList(); - AltitudeElemNames.add("0"); - fields.add( new UAVObjectField("Altitude", "meters", UAVObjectField.FieldType.FLOAT32, AltitudeElemNames, null) ); - - List GeoidSeparationElemNames = new ArrayList(); - GeoidSeparationElemNames.add("0"); - fields.add( new UAVObjectField("GeoidSeparation", "meters", UAVObjectField.FieldType.FLOAT32, GeoidSeparationElemNames, null) ); - - List HeadingElemNames = new ArrayList(); - HeadingElemNames.add("0"); - fields.add( new UAVObjectField("Heading", "degrees", UAVObjectField.FieldType.FLOAT32, HeadingElemNames, null) ); - - List GroundspeedElemNames = new ArrayList(); - GroundspeedElemNames.add("0"); - fields.add( new UAVObjectField("Groundspeed", "m/s", UAVObjectField.FieldType.FLOAT32, GroundspeedElemNames, null) ); - - List PDOPElemNames = new ArrayList(); - PDOPElemNames.add("0"); - fields.add( new UAVObjectField("PDOP", "", UAVObjectField.FieldType.FLOAT32, PDOPElemNames, null) ); - - List HDOPElemNames = new ArrayList(); - HDOPElemNames.add("0"); - fields.add( new UAVObjectField("HDOP", "", UAVObjectField.FieldType.FLOAT32, HDOPElemNames, null) ); - - List VDOPElemNames = new ArrayList(); - VDOPElemNames.add("0"); - fields.add( new UAVObjectField("VDOP", "", UAVObjectField.FieldType.FLOAT32, VDOPElemNames, null) ); - - List StatusElemNames = new ArrayList(); - StatusElemNames.add("0"); - List StatusEnumOptions = new ArrayList(); - StatusEnumOptions.add("NoGPS"); - StatusEnumOptions.add("NoFix"); - StatusEnumOptions.add("Fix2D"); - StatusEnumOptions.add("Fix3D"); - fields.add( new UAVObjectField("Status", "", UAVObjectField.FieldType.ENUM, StatusElemNames, StatusEnumOptions) ); - - List SatellitesElemNames = new ArrayList(); - SatellitesElemNames.add("0"); - fields.add( new UAVObjectField("Satellites", "", UAVObjectField.FieldType.INT8, SatellitesElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 1000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 1000; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - GPSPosition obj = new GPSPosition(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public GPSPosition GetInstance(UAVObjectManager objMngr, long instID) - { - return (GPSPosition)(objMngr.getObject(GPSPosition.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0xE2A323B6l; - protected static final String NAME = "GPSPosition"; - protected static String DESCRIPTION = "Raw GPS data from @ref GPSModule. Should only be used by @ref AHRSCommsModule."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java deleted file mode 100644 index 0463bd4a1..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSatellites.java +++ /dev/null @@ -1,214 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Contains information about the GPS satellites in view from @ref GPSModule. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Contains information about the GPS satellites in view from @ref GPSModule. - -generated from gpssatellites.xml - **/ -public class GPSSatellites extends UAVDataObject { - - public GPSSatellites() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List ElevationElemNames = new ArrayList(); - ElevationElemNames.add("0"); - ElevationElemNames.add("1"); - ElevationElemNames.add("2"); - ElevationElemNames.add("3"); - ElevationElemNames.add("4"); - ElevationElemNames.add("5"); - ElevationElemNames.add("6"); - ElevationElemNames.add("7"); - ElevationElemNames.add("8"); - ElevationElemNames.add("9"); - ElevationElemNames.add("10"); - ElevationElemNames.add("11"); - ElevationElemNames.add("12"); - ElevationElemNames.add("13"); - ElevationElemNames.add("14"); - ElevationElemNames.add("15"); - fields.add( new UAVObjectField("Elevation", "degrees", UAVObjectField.FieldType.FLOAT32, ElevationElemNames, null) ); - - List AzimuthElemNames = new ArrayList(); - AzimuthElemNames.add("0"); - AzimuthElemNames.add("1"); - AzimuthElemNames.add("2"); - AzimuthElemNames.add("3"); - AzimuthElemNames.add("4"); - AzimuthElemNames.add("5"); - AzimuthElemNames.add("6"); - AzimuthElemNames.add("7"); - AzimuthElemNames.add("8"); - AzimuthElemNames.add("9"); - AzimuthElemNames.add("10"); - AzimuthElemNames.add("11"); - AzimuthElemNames.add("12"); - AzimuthElemNames.add("13"); - AzimuthElemNames.add("14"); - AzimuthElemNames.add("15"); - fields.add( new UAVObjectField("Azimuth", "degrees", UAVObjectField.FieldType.FLOAT32, AzimuthElemNames, null) ); - - List SatsInViewElemNames = new ArrayList(); - SatsInViewElemNames.add("0"); - fields.add( new UAVObjectField("SatsInView", "", UAVObjectField.FieldType.INT8, SatsInViewElemNames, null) ); - - List PRNElemNames = new ArrayList(); - PRNElemNames.add("0"); - PRNElemNames.add("1"); - PRNElemNames.add("2"); - PRNElemNames.add("3"); - PRNElemNames.add("4"); - PRNElemNames.add("5"); - PRNElemNames.add("6"); - PRNElemNames.add("7"); - PRNElemNames.add("8"); - PRNElemNames.add("9"); - PRNElemNames.add("10"); - PRNElemNames.add("11"); - PRNElemNames.add("12"); - PRNElemNames.add("13"); - PRNElemNames.add("14"); - PRNElemNames.add("15"); - fields.add( new UAVObjectField("PRN", "", UAVObjectField.FieldType.INT8, PRNElemNames, null) ); - - List SNRElemNames = new ArrayList(); - SNRElemNames.add("0"); - SNRElemNames.add("1"); - SNRElemNames.add("2"); - SNRElemNames.add("3"); - SNRElemNames.add("4"); - SNRElemNames.add("5"); - SNRElemNames.add("6"); - SNRElemNames.add("7"); - SNRElemNames.add("8"); - SNRElemNames.add("9"); - SNRElemNames.add("10"); - SNRElemNames.add("11"); - SNRElemNames.add("12"); - SNRElemNames.add("13"); - SNRElemNames.add("14"); - SNRElemNames.add("15"); - fields.add( new UAVObjectField("SNR", "", UAVObjectField.FieldType.INT8, SNRElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 10000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 30000; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - GPSSatellites obj = new GPSSatellites(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public GPSSatellites GetInstance(UAVObjectManager objMngr, long instID) - { - return (GPSSatellites)(objMngr.getObject(GPSSatellites.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x920D998l; - protected static final String NAME = "GPSSatellites"; - protected static String DESCRIPTION = "Contains information about the GPS satellites in view from @ref GPSModule."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSettings.java deleted file mode 100644 index 317d4d249..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSSettings.java +++ /dev/null @@ -1,142 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Settings for the GPS - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Settings for the GPS - -generated from gpssettings.xml - **/ -public class GPSSettings extends UAVDataObject { - - public GPSSettings() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List DataProtocolElemNames = new ArrayList(); - DataProtocolElemNames.add("0"); - List DataProtocolEnumOptions = new ArrayList(); - DataProtocolEnumOptions.add("NMEA"); - DataProtocolEnumOptions.add("UBX"); - fields.add( new UAVObjectField("DataProtocol", "", UAVObjectField.FieldType.ENUM, DataProtocolElemNames, DataProtocolEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 0; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("DataProtocol").setValue("UBX"); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - GPSSettings obj = new GPSSettings(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public GPSSettings GetInstance(UAVObjectManager objMngr, long instID) - { - return (GPSSettings)(objMngr.getObject(GPSSettings.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0xAC5F6370l; - protected static final String NAME = "GPSSettings"; - protected static String DESCRIPTION = "Settings for the GPS"; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 1 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java deleted file mode 100644 index 81fef701e..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSTime.java +++ /dev/null @@ -1,158 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Contains the GPS time from @ref GPSModule. Required to compute the world magnetic model correctly when setting the home location. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Contains the GPS time from @ref GPSModule. Required to compute the world magnetic model correctly when setting the home location. - -generated from gpstime.xml - **/ -public class GPSTime extends UAVDataObject { - - public GPSTime() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List YearElemNames = new ArrayList(); - YearElemNames.add("0"); - fields.add( new UAVObjectField("Year", "", UAVObjectField.FieldType.INT16, YearElemNames, null) ); - - List MonthElemNames = new ArrayList(); - MonthElemNames.add("0"); - fields.add( new UAVObjectField("Month", "", UAVObjectField.FieldType.INT8, MonthElemNames, null) ); - - List DayElemNames = new ArrayList(); - DayElemNames.add("0"); - fields.add( new UAVObjectField("Day", "", UAVObjectField.FieldType.INT8, DayElemNames, null) ); - - List HourElemNames = new ArrayList(); - HourElemNames.add("0"); - fields.add( new UAVObjectField("Hour", "", UAVObjectField.FieldType.INT8, HourElemNames, null) ); - - List MinuteElemNames = new ArrayList(); - MinuteElemNames.add("0"); - fields.add( new UAVObjectField("Minute", "", UAVObjectField.FieldType.INT8, MinuteElemNames, null) ); - - List SecondElemNames = new ArrayList(); - SecondElemNames.add("0"); - fields.add( new UAVObjectField("Second", "", UAVObjectField.FieldType.INT8, SecondElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 10000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 30000; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - GPSTime obj = new GPSTime(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public GPSTime GetInstance(UAVObjectManager objMngr, long instID) - { - return (GPSTime)(objMngr.getObject(GPSTime.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0xD4478084l; - protected static final String NAME = "GPSTime"; - protected static String DESCRIPTION = "Contains the GPS time from @ref GPSModule. Required to compute the world magnetic model correctly when setting the home location."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSVelocity.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSVelocity.java deleted file mode 100644 index 432f039a8..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GPSVelocity.java +++ /dev/null @@ -1,146 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Raw GPS data from @ref GPSModule. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Raw GPS data from @ref GPSModule. - -generated from gpsvelocity.xml - **/ -public class GPSVelocity extends UAVDataObject { - - public GPSVelocity() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List NorthElemNames = new ArrayList(); - NorthElemNames.add("0"); - fields.add( new UAVObjectField("North", "m/s", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); - - List EastElemNames = new ArrayList(); - EastElemNames.add("0"); - fields.add( new UAVObjectField("East", "m/s", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); - - List DownElemNames = new ArrayList(); - DownElemNames.add("0"); - fields.add( new UAVObjectField("Down", "m/s", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 1000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 1000; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - GPSVelocity obj = new GPSVelocity(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public GPSVelocity GetInstance(UAVObjectManager objMngr, long instID) - { - return (GPSVelocity)(objMngr.getObject(GPSVelocity.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x8245DC80l; - protected static final String NAME = "GPSVelocity"; - protected static String DESCRIPTION = "Raw GPS data from @ref GPSModule."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java deleted file mode 100644 index 7bf3f5a02..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GuidanceSettings.java +++ /dev/null @@ -1,210 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Settings for the @ref GuidanceModule - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Settings for the @ref GuidanceModule - -generated from guidancesettings.xml - **/ -public class GuidanceSettings extends UAVDataObject { - - public GuidanceSettings() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List HorizontalPosPIElemNames = new ArrayList(); - HorizontalPosPIElemNames.add("Kp"); - HorizontalPosPIElemNames.add("Ki"); - HorizontalPosPIElemNames.add("ILimit"); - fields.add( new UAVObjectField("HorizontalPosPI", "(m/s)/m", UAVObjectField.FieldType.FLOAT32, HorizontalPosPIElemNames, null) ); - - List HorizontalVelPIDElemNames = new ArrayList(); - HorizontalVelPIDElemNames.add("Kp"); - HorizontalVelPIDElemNames.add("Ki"); - HorizontalVelPIDElemNames.add("Kd"); - HorizontalVelPIDElemNames.add("ILimit"); - fields.add( new UAVObjectField("HorizontalVelPID", "deg/(m/s)", UAVObjectField.FieldType.FLOAT32, HorizontalVelPIDElemNames, null) ); - - List VerticalPosPIElemNames = new ArrayList(); - VerticalPosPIElemNames.add("Kp"); - VerticalPosPIElemNames.add("Ki"); - VerticalPosPIElemNames.add("ILimit"); - fields.add( new UAVObjectField("VerticalPosPI", "", UAVObjectField.FieldType.FLOAT32, VerticalPosPIElemNames, null) ); - - List VerticalVelPIDElemNames = new ArrayList(); - VerticalVelPIDElemNames.add("Kp"); - VerticalVelPIDElemNames.add("Ki"); - VerticalVelPIDElemNames.add("Kd"); - VerticalVelPIDElemNames.add("ILimit"); - fields.add( new UAVObjectField("VerticalVelPID", "", UAVObjectField.FieldType.FLOAT32, VerticalVelPIDElemNames, null) ); - - List MaxRollPitchElemNames = new ArrayList(); - MaxRollPitchElemNames.add("0"); - fields.add( new UAVObjectField("MaxRollPitch", "deg", UAVObjectField.FieldType.FLOAT32, MaxRollPitchElemNames, null) ); - - List UpdatePeriodElemNames = new ArrayList(); - UpdatePeriodElemNames.add("0"); - fields.add( new UAVObjectField("UpdatePeriod", "", UAVObjectField.FieldType.INT32, UpdatePeriodElemNames, null) ); - - List HorizontalVelMaxElemNames = new ArrayList(); - HorizontalVelMaxElemNames.add("0"); - fields.add( new UAVObjectField("HorizontalVelMax", "m/s", UAVObjectField.FieldType.UINT16, HorizontalVelMaxElemNames, null) ); - - List VerticalVelMaxElemNames = new ArrayList(); - VerticalVelMaxElemNames.add("0"); - fields.add( new UAVObjectField("VerticalVelMax", "m/s", UAVObjectField.FieldType.UINT16, VerticalVelMaxElemNames, null) ); - - List GuidanceModeElemNames = new ArrayList(); - GuidanceModeElemNames.add("0"); - List GuidanceModeEnumOptions = new ArrayList(); - GuidanceModeEnumOptions.add("DUAL_LOOP"); - GuidanceModeEnumOptions.add("VELOCITY_CONTROL"); - fields.add( new UAVObjectField("GuidanceMode", "", UAVObjectField.FieldType.ENUM, GuidanceModeElemNames, GuidanceModeEnumOptions) ); - - List ThrottleControlElemNames = new ArrayList(); - ThrottleControlElemNames.add("0"); - List ThrottleControlEnumOptions = new ArrayList(); - ThrottleControlEnumOptions.add("FALSE"); - ThrottleControlEnumOptions.add("TRUE"); - fields.add( new UAVObjectField("ThrottleControl", "", UAVObjectField.FieldType.ENUM, ThrottleControlElemNames, ThrottleControlEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 0; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("HorizontalPosPI").setValue(0.1,0); - getField("HorizontalPosPI").setValue(0.001,1); - getField("HorizontalPosPI").setValue(300,2); - getField("HorizontalVelPID").setValue(0.05,0); - getField("HorizontalVelPID").setValue(0.002,1); - getField("HorizontalVelPID").setValue(0,2); - getField("HorizontalVelPID").setValue(1000,3); - getField("VerticalPosPI").setValue(0.1,0); - getField("VerticalPosPI").setValue(0.001,1); - getField("VerticalPosPI").setValue(200,2); - getField("VerticalVelPID").setValue(0.1,0); - getField("VerticalVelPID").setValue(0,1); - getField("VerticalVelPID").setValue(0,2); - getField("VerticalVelPID").setValue(0,3); - getField("MaxRollPitch").setValue(10); - getField("UpdatePeriod").setValue(100); - getField("HorizontalVelMax").setValue(300); - getField("VerticalVelMax").setValue(150); - getField("GuidanceMode").setValue("DUAL_LOOP"); - getField("ThrottleControl").setValue("FALSE"); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - GuidanceSettings obj = new GuidanceSettings(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public GuidanceSettings GetInstance(UAVObjectManager objMngr, long instID) - { - return (GuidanceSettings)(objMngr.getObject(GuidanceSettings.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x6EA79FB4l; - protected static final String NAME = "GuidanceSettings"; - protected static String DESCRIPTION = "Settings for the @ref GuidanceModule"; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 1 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/Gyros.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/Gyros.java deleted file mode 100644 index b3de76547..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/Gyros.java +++ /dev/null @@ -1,150 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * The gyro data. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -The gyro data. - -generated from gyros.xml - **/ -public class Gyros extends UAVDataObject { - - public Gyros() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List xElemNames = new ArrayList(); - xElemNames.add("0"); - fields.add( new UAVObjectField("x", "deg/s", UAVObjectField.FieldType.FLOAT32, xElemNames, null) ); - - List yElemNames = new ArrayList(); - yElemNames.add("0"); - fields.add( new UAVObjectField("y", "deg/s", UAVObjectField.FieldType.FLOAT32, yElemNames, null) ); - - List zElemNames = new ArrayList(); - zElemNames.add("0"); - fields.add( new UAVObjectField("z", "deg/s", UAVObjectField.FieldType.FLOAT32, zElemNames, null) ); - - List temperatureElemNames = new ArrayList(); - temperatureElemNames.add("0"); - fields.add( new UAVObjectField("temperature", "deg C", UAVObjectField.FieldType.FLOAT32, temperatureElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 1000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - Gyros obj = new Gyros(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public Gyros GetInstance(UAVObjectManager objMngr, long instID) - { - return (Gyros)(objMngr.getObject(Gyros.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x4228AF6l; - protected static final String NAME = "Gyros"; - protected static String DESCRIPTION = "The gyro data."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GyrosBias.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/GyrosBias.java deleted file mode 100644 index 3a51fcdb3..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/GyrosBias.java +++ /dev/null @@ -1,146 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * The gyro data. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -The gyro data. - -generated from gyrosbias.xml - **/ -public class GyrosBias extends UAVDataObject { - - public GyrosBias() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List xElemNames = new ArrayList(); - xElemNames.add("0"); - fields.add( new UAVObjectField("x", "deg/s", UAVObjectField.FieldType.FLOAT32, xElemNames, null) ); - - List yElemNames = new ArrayList(); - yElemNames.add("0"); - fields.add( new UAVObjectField("y", "deg/s", UAVObjectField.FieldType.FLOAT32, yElemNames, null) ); - - List zElemNames = new ArrayList(); - zElemNames.add("0"); - fields.add( new UAVObjectField("z", "deg/s", UAVObjectField.FieldType.FLOAT32, zElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 1000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - GyrosBias obj = new GyrosBias(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public GyrosBias GetInstance(UAVObjectManager objMngr, long instID) - { - return (GyrosBias)(objMngr.getObject(GyrosBias.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0xE4B6F980l; - protected static final String NAME = "GyrosBias"; - protected static String DESCRIPTION = "The gyro data."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java deleted file mode 100644 index 1b340f64d..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HomeLocation.java +++ /dev/null @@ -1,201 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * HomeLocation setting which contains the constants to tranlate from longitutde and latitude to NED reference frame. Automatically set by @ref GPSModule after acquiring a 3D lock. Used by @ref AHRSCommsModule. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -HomeLocation setting which contains the constants to tranlate from longitutde and latitude to NED reference frame. Automatically set by @ref GPSModule after acquiring a 3D lock. Used by @ref AHRSCommsModule. - -generated from homelocation.xml - **/ -public class HomeLocation extends UAVDataObject { - - public HomeLocation() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List LatitudeElemNames = new ArrayList(); - LatitudeElemNames.add("0"); - fields.add( new UAVObjectField("Latitude", "deg * 10e6", UAVObjectField.FieldType.INT32, LatitudeElemNames, null) ); - - List LongitudeElemNames = new ArrayList(); - LongitudeElemNames.add("0"); - fields.add( new UAVObjectField("Longitude", "deg * 10e6", UAVObjectField.FieldType.INT32, LongitudeElemNames, null) ); - - List AltitudeElemNames = new ArrayList(); - AltitudeElemNames.add("0"); - fields.add( new UAVObjectField("Altitude", "m over geoid", UAVObjectField.FieldType.FLOAT32, AltitudeElemNames, null) ); - - List ECEFElemNames = new ArrayList(); - ECEFElemNames.add("0"); - ECEFElemNames.add("1"); - ECEFElemNames.add("2"); - fields.add( new UAVObjectField("ECEF", "cm", UAVObjectField.FieldType.INT32, ECEFElemNames, null) ); - - List RNEElemNames = new ArrayList(); - RNEElemNames.add("0"); - RNEElemNames.add("1"); - RNEElemNames.add("2"); - RNEElemNames.add("3"); - RNEElemNames.add("4"); - RNEElemNames.add("5"); - RNEElemNames.add("6"); - RNEElemNames.add("7"); - RNEElemNames.add("8"); - fields.add( new UAVObjectField("RNE", "", UAVObjectField.FieldType.FLOAT32, RNEElemNames, null) ); - - List BeElemNames = new ArrayList(); - BeElemNames.add("0"); - BeElemNames.add("1"); - BeElemNames.add("2"); - fields.add( new UAVObjectField("Be", "", UAVObjectField.FieldType.FLOAT32, BeElemNames, null) ); - - List g_eElemNames = new ArrayList(); - g_eElemNames.add("0"); - fields.add( new UAVObjectField("g_e", "m/s^2", UAVObjectField.FieldType.FLOAT32, g_eElemNames, null) ); - - List SetElemNames = new ArrayList(); - SetElemNames.add("0"); - List SetEnumOptions = new ArrayList(); - SetEnumOptions.add("FALSE"); - SetEnumOptions.add("TRUE"); - fields.add( new UAVObjectField("Set", "", UAVObjectField.FieldType.ENUM, SetElemNames, SetEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 0; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("Latitude").setValue(0); - getField("Longitude").setValue(0); - getField("Altitude").setValue(0); - getField("ECEF").setValue(0,0); - getField("ECEF").setValue(0,1); - getField("ECEF").setValue(0,2); - getField("RNE").setValue(0,0); - getField("RNE").setValue(0,1); - getField("RNE").setValue(0,2); - getField("RNE").setValue(0,3); - getField("RNE").setValue(0,4); - getField("RNE").setValue(0,5); - getField("RNE").setValue(0,6); - getField("RNE").setValue(0,7); - getField("RNE").setValue(0,8); - getField("Be").setValue(0,0); - getField("Be").setValue(0,1); - getField("Be").setValue(0,2); - getField("g_e").setValue(9.81); - getField("Set").setValue("FALSE"); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - HomeLocation obj = new HomeLocation(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public HomeLocation GetInstance(UAVObjectManager objMngr, long instID) - { - return (HomeLocation)(objMngr.getObject(HomeLocation.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x5BB3AEFCl; - protected static final String NAME = "HomeLocation"; - protected static String DESCRIPTION = "HomeLocation setting which contains the constants to tranlate from longitutde and latitude to NED reference frame. Automatically set by @ref GPSModule after acquiring a 3D lock. Used by @ref AHRSCommsModule."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 1 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java deleted file mode 100644 index a6716d209..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/HwSettings.java +++ /dev/null @@ -1,328 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Selection of optional hardware configurations. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Selection of optional hardware configurations. - -generated from hwsettings.xml - **/ -public class HwSettings extends UAVDataObject { - - public HwSettings() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List CC_RcvrPortElemNames = new ArrayList(); - CC_RcvrPortElemNames.add("0"); - List CC_RcvrPortEnumOptions = new ArrayList(); - CC_RcvrPortEnumOptions.add("Disabled"); - CC_RcvrPortEnumOptions.add("PWM"); - CC_RcvrPortEnumOptions.add("PPM"); - CC_RcvrPortEnumOptions.add("PPM+Outputs"); - CC_RcvrPortEnumOptions.add("Outputs"); - fields.add( new UAVObjectField("CC_RcvrPort", "function", UAVObjectField.FieldType.ENUM, CC_RcvrPortElemNames, CC_RcvrPortEnumOptions) ); - - List CC_MainPortElemNames = new ArrayList(); - CC_MainPortElemNames.add("0"); - List CC_MainPortEnumOptions = new ArrayList(); - CC_MainPortEnumOptions.add("Disabled"); - CC_MainPortEnumOptions.add("Telemetry"); - CC_MainPortEnumOptions.add("GPS"); - CC_MainPortEnumOptions.add("S.Bus"); - CC_MainPortEnumOptions.add("DSM2"); - CC_MainPortEnumOptions.add("DSMX (10bit)"); - CC_MainPortEnumOptions.add("DSMX (11bit)"); - CC_MainPortEnumOptions.add("ComAux"); - CC_MainPortEnumOptions.add("ComBridge"); - fields.add( new UAVObjectField("CC_MainPort", "function", UAVObjectField.FieldType.ENUM, CC_MainPortElemNames, CC_MainPortEnumOptions) ); - - List CC_FlexiPortElemNames = new ArrayList(); - CC_FlexiPortElemNames.add("0"); - List CC_FlexiPortEnumOptions = new ArrayList(); - CC_FlexiPortEnumOptions.add("Disabled"); - CC_FlexiPortEnumOptions.add("Telemetry"); - CC_FlexiPortEnumOptions.add("GPS"); - CC_FlexiPortEnumOptions.add("I2C"); - CC_FlexiPortEnumOptions.add("DSM2"); - CC_FlexiPortEnumOptions.add("DSMX (10bit)"); - CC_FlexiPortEnumOptions.add("DSMX (11bit)"); - CC_FlexiPortEnumOptions.add("ComAux"); - CC_FlexiPortEnumOptions.add("ComBridge"); - fields.add( new UAVObjectField("CC_FlexiPort", "function", UAVObjectField.FieldType.ENUM, CC_FlexiPortElemNames, CC_FlexiPortEnumOptions) ); - - List RV_RcvrPortElemNames = new ArrayList(); - RV_RcvrPortElemNames.add("0"); - List RV_RcvrPortEnumOptions = new ArrayList(); - RV_RcvrPortEnumOptions.add("Disabled"); - RV_RcvrPortEnumOptions.add("PWM"); - RV_RcvrPortEnumOptions.add("PPM"); - RV_RcvrPortEnumOptions.add("PPM+Outputs"); - RV_RcvrPortEnumOptions.add("Outputs"); - fields.add( new UAVObjectField("RV_RcvrPort", "function", UAVObjectField.FieldType.ENUM, RV_RcvrPortElemNames, RV_RcvrPortEnumOptions) ); - - List RV_AuxPortElemNames = new ArrayList(); - RV_AuxPortElemNames.add("0"); - List RV_AuxPortEnumOptions = new ArrayList(); - RV_AuxPortEnumOptions.add("Disabled"); - RV_AuxPortEnumOptions.add("Telemetry"); - RV_AuxPortEnumOptions.add("DSM2"); - RV_AuxPortEnumOptions.add("DSMX (10bit)"); - RV_AuxPortEnumOptions.add("DSMX (11bit)"); - RV_AuxPortEnumOptions.add("ComAux"); - RV_AuxPortEnumOptions.add("ComBridge"); - fields.add( new UAVObjectField("RV_AuxPort", "function", UAVObjectField.FieldType.ENUM, RV_AuxPortElemNames, RV_AuxPortEnumOptions) ); - - List RV_AuxSBusPortElemNames = new ArrayList(); - RV_AuxSBusPortElemNames.add("0"); - List RV_AuxSBusPortEnumOptions = new ArrayList(); - RV_AuxSBusPortEnumOptions.add("Disabled"); - RV_AuxSBusPortEnumOptions.add("S.Bus"); - RV_AuxSBusPortEnumOptions.add("DSM2"); - RV_AuxSBusPortEnumOptions.add("DSMX (10bit)"); - RV_AuxSBusPortEnumOptions.add("DSMX (11bit)"); - RV_AuxSBusPortEnumOptions.add("ComAux"); - RV_AuxSBusPortEnumOptions.add("ComBridge"); - fields.add( new UAVObjectField("RV_AuxSBusPort", "function", UAVObjectField.FieldType.ENUM, RV_AuxSBusPortElemNames, RV_AuxSBusPortEnumOptions) ); - - List RV_FlexiPortElemNames = new ArrayList(); - RV_FlexiPortElemNames.add("0"); - List RV_FlexiPortEnumOptions = new ArrayList(); - RV_FlexiPortEnumOptions.add("Disabled"); - RV_FlexiPortEnumOptions.add("I2C"); - RV_FlexiPortEnumOptions.add("DSM2"); - RV_FlexiPortEnumOptions.add("DSMX (10bit)"); - RV_FlexiPortEnumOptions.add("DSMX (11bit)"); - RV_FlexiPortEnumOptions.add("ComAux"); - RV_FlexiPortEnumOptions.add("ComBridge"); - fields.add( new UAVObjectField("RV_FlexiPort", "function", UAVObjectField.FieldType.ENUM, RV_FlexiPortElemNames, RV_FlexiPortEnumOptions) ); - - List RV_TelemetryPortElemNames = new ArrayList(); - RV_TelemetryPortElemNames.add("0"); - List RV_TelemetryPortEnumOptions = new ArrayList(); - RV_TelemetryPortEnumOptions.add("Disabled"); - RV_TelemetryPortEnumOptions.add("Telemetry"); - RV_TelemetryPortEnumOptions.add("ComAux"); - RV_TelemetryPortEnumOptions.add("ComBridge"); - fields.add( new UAVObjectField("RV_TelemetryPort", "function", UAVObjectField.FieldType.ENUM, RV_TelemetryPortElemNames, RV_TelemetryPortEnumOptions) ); - - List RV_GPSPortElemNames = new ArrayList(); - RV_GPSPortElemNames.add("0"); - List RV_GPSPortEnumOptions = new ArrayList(); - RV_GPSPortEnumOptions.add("Disabled"); - RV_GPSPortEnumOptions.add("Telemetry"); - RV_GPSPortEnumOptions.add("GPS"); - RV_GPSPortEnumOptions.add("ComAux"); - RV_GPSPortEnumOptions.add("ComBridge"); - fields.add( new UAVObjectField("RV_GPSPort", "function", UAVObjectField.FieldType.ENUM, RV_GPSPortElemNames, RV_GPSPortEnumOptions) ); - - List TelemetrySpeedElemNames = new ArrayList(); - TelemetrySpeedElemNames.add("0"); - List TelemetrySpeedEnumOptions = new ArrayList(); - TelemetrySpeedEnumOptions.add("2400"); - TelemetrySpeedEnumOptions.add("4800"); - TelemetrySpeedEnumOptions.add("9600"); - TelemetrySpeedEnumOptions.add("19200"); - TelemetrySpeedEnumOptions.add("38400"); - TelemetrySpeedEnumOptions.add("57600"); - TelemetrySpeedEnumOptions.add("115200"); - fields.add( new UAVObjectField("TelemetrySpeed", "bps", UAVObjectField.FieldType.ENUM, TelemetrySpeedElemNames, TelemetrySpeedEnumOptions) ); - - List GPSSpeedElemNames = new ArrayList(); - GPSSpeedElemNames.add("0"); - List GPSSpeedEnumOptions = new ArrayList(); - GPSSpeedEnumOptions.add("2400"); - GPSSpeedEnumOptions.add("4800"); - GPSSpeedEnumOptions.add("9600"); - GPSSpeedEnumOptions.add("19200"); - GPSSpeedEnumOptions.add("38400"); - GPSSpeedEnumOptions.add("57600"); - GPSSpeedEnumOptions.add("115200"); - fields.add( new UAVObjectField("GPSSpeed", "bps", UAVObjectField.FieldType.ENUM, GPSSpeedElemNames, GPSSpeedEnumOptions) ); - - List ComUsbBridgeSpeedElemNames = new ArrayList(); - ComUsbBridgeSpeedElemNames.add("0"); - List ComUsbBridgeSpeedEnumOptions = new ArrayList(); - ComUsbBridgeSpeedEnumOptions.add("2400"); - ComUsbBridgeSpeedEnumOptions.add("4800"); - ComUsbBridgeSpeedEnumOptions.add("9600"); - ComUsbBridgeSpeedEnumOptions.add("19200"); - ComUsbBridgeSpeedEnumOptions.add("38400"); - ComUsbBridgeSpeedEnumOptions.add("57600"); - ComUsbBridgeSpeedEnumOptions.add("115200"); - fields.add( new UAVObjectField("ComUsbBridgeSpeed", "bps", UAVObjectField.FieldType.ENUM, ComUsbBridgeSpeedElemNames, ComUsbBridgeSpeedEnumOptions) ); - - List USB_HIDPortElemNames = new ArrayList(); - USB_HIDPortElemNames.add("0"); - List USB_HIDPortEnumOptions = new ArrayList(); - USB_HIDPortEnumOptions.add("USBTelemetry"); - USB_HIDPortEnumOptions.add("RCTransmitter"); - USB_HIDPortEnumOptions.add("Disabled"); - fields.add( new UAVObjectField("USB_HIDPort", "function", UAVObjectField.FieldType.ENUM, USB_HIDPortElemNames, USB_HIDPortEnumOptions) ); - - List USB_VCPPortElemNames = new ArrayList(); - USB_VCPPortElemNames.add("0"); - List USB_VCPPortEnumOptions = new ArrayList(); - USB_VCPPortEnumOptions.add("USBTelemetry"); - USB_VCPPortEnumOptions.add("ComBridge"); - USB_VCPPortEnumOptions.add("Disabled"); - fields.add( new UAVObjectField("USB_VCPPort", "function", UAVObjectField.FieldType.ENUM, USB_VCPPortElemNames, USB_VCPPortEnumOptions) ); - - List OptionalModulesElemNames = new ArrayList(); - OptionalModulesElemNames.add("CameraStab"); - OptionalModulesElemNames.add("GPS"); - OptionalModulesElemNames.add("ComUsbBridge"); - OptionalModulesElemNames.add("Fault"); - OptionalModulesElemNames.add("Altitude"); - OptionalModulesElemNames.add("TxPID"); - OptionalModulesElemNames.add("Autotune"); - List OptionalModulesEnumOptions = new ArrayList(); - OptionalModulesEnumOptions.add("Disabled"); - OptionalModulesEnumOptions.add("Enabled"); - fields.add( new UAVObjectField("OptionalModules", "", UAVObjectField.FieldType.ENUM, OptionalModulesElemNames, OptionalModulesEnumOptions) ); - - List DSMxBindElemNames = new ArrayList(); - DSMxBindElemNames.add("0"); - fields.add( new UAVObjectField("DSMxBind", "", UAVObjectField.FieldType.UINT8, DSMxBindElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 0; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("CC_RcvrPort").setValue("PWM"); - getField("CC_MainPort").setValue("Telemetry"); - getField("CC_FlexiPort").setValue("Disabled"); - getField("RV_RcvrPort").setValue("PWM"); - getField("RV_AuxPort").setValue("Disabled"); - getField("RV_AuxSBusPort").setValue("Disabled"); - getField("RV_FlexiPort").setValue("Disabled"); - getField("RV_TelemetryPort").setValue("Telemetry"); - getField("RV_GPSPort").setValue("GPS"); - getField("TelemetrySpeed").setValue("57600"); - getField("GPSSpeed").setValue("57600"); - getField("ComUsbBridgeSpeed").setValue("57600"); - getField("USB_HIDPort").setValue("USBTelemetry"); - getField("USB_VCPPort").setValue("Disabled"); - getField("OptionalModules").setValue("Disabled",0); - getField("OptionalModules").setValue("Disabled",1); - getField("OptionalModules").setValue("Disabled",2); - getField("OptionalModules").setValue("Disabled",3); - getField("OptionalModules").setValue("Disabled",4); - getField("OptionalModules").setValue("Disabled",5); - getField("OptionalModules").setValue("Disabled",6); - getField("DSMxBind").setValue(0); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - HwSettings obj = new HwSettings(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public HwSettings GetInstance(UAVObjectManager objMngr, long instID) - { - return (HwSettings)(objMngr.getObject(HwSettings.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x428D4DCEl; - protected static final String NAME = "HwSettings"; - protected static String DESCRIPTION = "Selection of optional hardware configurations."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 1 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java deleted file mode 100644 index 4bc8701ce..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/I2CStats.java +++ /dev/null @@ -1,237 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Tracks statistics on the I2C bus. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Tracks statistics on the I2C bus. - -generated from i2cstats.xml - **/ -public class I2CStats extends UAVDataObject { - - public I2CStats() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List evirq_logElemNames = new ArrayList(); - evirq_logElemNames.add("0"); - evirq_logElemNames.add("1"); - evirq_logElemNames.add("2"); - evirq_logElemNames.add("3"); - evirq_logElemNames.add("4"); - fields.add( new UAVObjectField("evirq_log", "", UAVObjectField.FieldType.UINT32, evirq_logElemNames, null) ); - - List erirq_logElemNames = new ArrayList(); - erirq_logElemNames.add("0"); - erirq_logElemNames.add("1"); - erirq_logElemNames.add("2"); - erirq_logElemNames.add("3"); - erirq_logElemNames.add("4"); - fields.add( new UAVObjectField("erirq_log", "", UAVObjectField.FieldType.UINT32, erirq_logElemNames, null) ); - - List event_errorsElemNames = new ArrayList(); - event_errorsElemNames.add("0"); - fields.add( new UAVObjectField("event_errors", "", UAVObjectField.FieldType.UINT8, event_errorsElemNames, null) ); - - List fsm_errorsElemNames = new ArrayList(); - fsm_errorsElemNames.add("0"); - fields.add( new UAVObjectField("fsm_errors", "", UAVObjectField.FieldType.UINT8, fsm_errorsElemNames, null) ); - - List irq_errorsElemNames = new ArrayList(); - irq_errorsElemNames.add("0"); - fields.add( new UAVObjectField("irq_errors", "", UAVObjectField.FieldType.UINT8, irq_errorsElemNames, null) ); - - List nacksElemNames = new ArrayList(); - nacksElemNames.add("0"); - fields.add( new UAVObjectField("nacks", "", UAVObjectField.FieldType.UINT8, nacksElemNames, null) ); - - List timeoutsElemNames = new ArrayList(); - timeoutsElemNames.add("0"); - fields.add( new UAVObjectField("timeouts", "", UAVObjectField.FieldType.UINT8, timeoutsElemNames, null) ); - - List last_error_typeElemNames = new ArrayList(); - last_error_typeElemNames.add("0"); - List last_error_typeEnumOptions = new ArrayList(); - last_error_typeEnumOptions.add("EVENT"); - last_error_typeEnumOptions.add("FSM"); - last_error_typeEnumOptions.add("INTERRUPT"); - fields.add( new UAVObjectField("last_error_type", "", UAVObjectField.FieldType.ENUM, last_error_typeElemNames, last_error_typeEnumOptions) ); - - List event_logElemNames = new ArrayList(); - event_logElemNames.add("0"); - event_logElemNames.add("1"); - event_logElemNames.add("2"); - event_logElemNames.add("3"); - event_logElemNames.add("4"); - List event_logEnumOptions = new ArrayList(); - event_logEnumOptions.add("I2C_EVENT_BUS_ERROR"); - event_logEnumOptions.add("I2C_EVENT_START"); - event_logEnumOptions.add("I2C_EVENT_STARTED_MORE_TXN_READ"); - event_logEnumOptions.add("I2C_EVENT_STARTED_MORE_TXN_WRITE"); - event_logEnumOptions.add("I2C_EVENT_STARTED_LAST_TXN_READ"); - event_logEnumOptions.add("I2C_EVENT_STARTED_LAST_TXN_WRITE"); - event_logEnumOptions.add("I2C_EVENT_ADDR_SENT_LEN_EQ_0"); - event_logEnumOptions.add("I2C_EVENT_ADDR_SENT_LEN_EQ_1"); - event_logEnumOptions.add("I2C_EVENT_ADDR_SENT_LEN_EQ_2"); - event_logEnumOptions.add("I2C_EVENT_ADDR_SENT_LEN_GT_2"); - event_logEnumOptions.add("I2C_EVENT_TRANSFER_DONE_LEN_EQ_0"); - event_logEnumOptions.add("I2C_EVENT_TRANSFER_DONE_LEN_EQ_1"); - event_logEnumOptions.add("I2C_EVENT_TRANSFER_DONE_LEN_EQ_2"); - event_logEnumOptions.add("I2C_EVENT_TRANSFER_DONE_LEN_GT_2"); - event_logEnumOptions.add("I2C_EVENT_NACK"); - event_logEnumOptions.add("I2C_EVENT_STOPPED"); - event_logEnumOptions.add("I2C_EVENT_AUTO"); - fields.add( new UAVObjectField("event_log", "", UAVObjectField.FieldType.ENUM, event_logElemNames, event_logEnumOptions) ); - - List state_logElemNames = new ArrayList(); - state_logElemNames.add("0"); - state_logElemNames.add("1"); - state_logElemNames.add("2"); - state_logElemNames.add("3"); - state_logElemNames.add("4"); - List state_logEnumOptions = new ArrayList(); - state_logEnumOptions.add("I2C_STATE_FSM_FAULT"); - state_logEnumOptions.add("I2C_STATE_BUS_ERROR"); - state_logEnumOptions.add("I2C_STATE_STOPPED"); - state_logEnumOptions.add("I2C_STATE_STOPPING"); - state_logEnumOptions.add("I2C_STATE_STARTING"); - state_logEnumOptions.add("I2C_STATE_R_MORE_TXN_ADDR"); - state_logEnumOptions.add("I2C_STATE_R_MORE_TXN_PRE_ONE"); - state_logEnumOptions.add("I2C_STATE_R_MORE_TXN_PRE_FIRST"); - state_logEnumOptions.add("I2C_STATE_R_MORE_TXN_PRE_MIDDLE"); - state_logEnumOptions.add("I2C_STATE_R_MORE_TXN_LAST"); - state_logEnumOptions.add("I2C_STATE_R_MORE_TXN_POST_LAST"); - state_logEnumOptions.add("R_LAST_TXN_ADDR"); - state_logEnumOptions.add("I2C_STATE_R_LAST_TXN_PRE_ONE"); - state_logEnumOptions.add("I2C_STATE_R_LAST_TXN_PRE_FIRST"); - state_logEnumOptions.add("I2C_STATE_R_LAST_TXN_PRE_MIDDLE"); - state_logEnumOptions.add("I2C_STATE_R_LAST_TXN_PRE_LAST"); - state_logEnumOptions.add("I2C_STATE_R_LAST_TXN_POST_LAST"); - state_logEnumOptions.add("I2C_STATE_W_MORE_TXN_ADDR"); - state_logEnumOptions.add("I2C_STATE_W_MORE_TXN_MIDDLE"); - state_logEnumOptions.add("I2C_STATE_W_MORE_TXN_LAST"); - state_logEnumOptions.add("I2C_STATE_W_LAST_TXN_ADDR"); - state_logEnumOptions.add("I2C_STATE_W_LAST_TXN_MIDDLE"); - state_logEnumOptions.add("I2C_STATE_W_LAST_TXN_LAST"); - state_logEnumOptions.add("I2C_STATE_NACK"); - fields.add( new UAVObjectField("state_log", "", UAVObjectField.FieldType.ENUM, state_logElemNames, state_logEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 10000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 30000; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - I2CStats obj = new I2CStats(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public I2CStats GetInstance(UAVObjectManager objMngr, long instID) - { - return (I2CStats)(objMngr.getObject(I2CStats.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0xB714823El; - protected static final String NAME = "I2CStats"; - protected static String DESCRIPTION = "Tracks statistics on the I2C bus."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MagBias.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MagBias.java deleted file mode 100644 index 19a9913d7..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MagBias.java +++ /dev/null @@ -1,146 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * The gyro data. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -The gyro data. - -generated from magbias.xml - **/ -public class MagBias extends UAVDataObject { - - public MagBias() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List xElemNames = new ArrayList(); - xElemNames.add("0"); - fields.add( new UAVObjectField("x", "mGau", UAVObjectField.FieldType.FLOAT32, xElemNames, null) ); - - List yElemNames = new ArrayList(); - yElemNames.add("0"); - fields.add( new UAVObjectField("y", "mGau", UAVObjectField.FieldType.FLOAT32, yElemNames, null) ); - - List zElemNames = new ArrayList(); - zElemNames.add("0"); - fields.add( new UAVObjectField("z", "mGau", UAVObjectField.FieldType.FLOAT32, zElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 1000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - MagBias obj = new MagBias(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public MagBias GetInstance(UAVObjectManager objMngr, long instID) - { - return (MagBias)(objMngr.getObject(MagBias.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x5043E510l; - protected static final String NAME = "MagBias"; - protected static String DESCRIPTION = "The gyro data."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/Magnetometer.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/Magnetometer.java deleted file mode 100644 index da81db3dd..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/Magnetometer.java +++ /dev/null @@ -1,146 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * The mag data. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -The mag data. - -generated from magnetometer.xml - **/ -public class Magnetometer extends UAVDataObject { - - public Magnetometer() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List xElemNames = new ArrayList(); - xElemNames.add("0"); - fields.add( new UAVObjectField("x", "mGa", UAVObjectField.FieldType.FLOAT32, xElemNames, null) ); - - List yElemNames = new ArrayList(); - yElemNames.add("0"); - fields.add( new UAVObjectField("y", "mGa", UAVObjectField.FieldType.FLOAT32, yElemNames, null) ); - - List zElemNames = new ArrayList(); - zElemNames.add("0"); - fields.add( new UAVObjectField("z", "mGa", UAVObjectField.FieldType.FLOAT32, zElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 1000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - Magnetometer obj = new Magnetometer(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public Magnetometer GetInstance(UAVObjectManager objMngr, long instID) - { - return (Magnetometer)(objMngr.getObject(Magnetometer.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x813B55DEl; - protected static final String NAME = "Magnetometer"; - protected static String DESCRIPTION = "The mag data."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java deleted file mode 100644 index 63816ed52..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlCommand.java +++ /dev/null @@ -1,173 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * The output from the @ref ManualControlModule which descodes the receiver inputs. Overriden by GCS for fly-by-wire control. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -The output from the @ref ManualControlModule which descodes the receiver inputs. Overriden by GCS for fly-by-wire control. - -generated from manualcontrolcommand.xml - **/ -public class ManualControlCommand extends UAVDataObject { - - public ManualControlCommand() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List ThrottleElemNames = new ArrayList(); - ThrottleElemNames.add("0"); - fields.add( new UAVObjectField("Throttle", "%", UAVObjectField.FieldType.FLOAT32, ThrottleElemNames, null) ); - - List RollElemNames = new ArrayList(); - RollElemNames.add("0"); - fields.add( new UAVObjectField("Roll", "%", UAVObjectField.FieldType.FLOAT32, RollElemNames, null) ); - - List PitchElemNames = new ArrayList(); - PitchElemNames.add("0"); - fields.add( new UAVObjectField("Pitch", "%", UAVObjectField.FieldType.FLOAT32, PitchElemNames, null) ); - - List YawElemNames = new ArrayList(); - YawElemNames.add("0"); - fields.add( new UAVObjectField("Yaw", "%", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); - - List CollectiveElemNames = new ArrayList(); - CollectiveElemNames.add("0"); - fields.add( new UAVObjectField("Collective", "%", UAVObjectField.FieldType.FLOAT32, CollectiveElemNames, null) ); - - List ChannelElemNames = new ArrayList(); - ChannelElemNames.add("0"); - ChannelElemNames.add("1"); - ChannelElemNames.add("2"); - ChannelElemNames.add("3"); - ChannelElemNames.add("4"); - ChannelElemNames.add("5"); - ChannelElemNames.add("6"); - ChannelElemNames.add("7"); - ChannelElemNames.add("8"); - fields.add( new UAVObjectField("Channel", "us", UAVObjectField.FieldType.UINT16, ChannelElemNames, null) ); - - List ConnectedElemNames = new ArrayList(); - ConnectedElemNames.add("0"); - List ConnectedEnumOptions = new ArrayList(); - ConnectedEnumOptions.add("False"); - ConnectedEnumOptions.add("True"); - fields.add( new UAVObjectField("Connected", "", UAVObjectField.FieldType.ENUM, ConnectedElemNames, ConnectedEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 2000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - ManualControlCommand obj = new ManualControlCommand(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public ManualControlCommand GetInstance(UAVObjectManager objMngr, long instID) - { - return (ManualControlCommand)(objMngr.getObject(ManualControlCommand.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x1E82C2D2l; - protected static final String NAME = "ManualControlCommand"; - protected static String DESCRIPTION = "The output from the @ref ManualControlModule which descodes the receiver inputs. Overriden by GCS for fly-by-wire control."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java deleted file mode 100644 index be71d23f0..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ManualControlSettings.java +++ /dev/null @@ -1,354 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Settings to indicate how to decode receiver input by @ref ManualControlModule. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Settings to indicate how to decode receiver input by @ref ManualControlModule. - -generated from manualcontrolsettings.xml - **/ -public class ManualControlSettings extends UAVDataObject { - - public ManualControlSettings() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List DeadbandElemNames = new ArrayList(); - DeadbandElemNames.add("0"); - fields.add( new UAVObjectField("Deadband", "%", UAVObjectField.FieldType.FLOAT32, DeadbandElemNames, null) ); - - List ChannelMinElemNames = new ArrayList(); - ChannelMinElemNames.add("Throttle"); - ChannelMinElemNames.add("Roll"); - ChannelMinElemNames.add("Pitch"); - ChannelMinElemNames.add("Yaw"); - ChannelMinElemNames.add("FlightMode"); - ChannelMinElemNames.add("Collective"); - ChannelMinElemNames.add("Accessory0"); - ChannelMinElemNames.add("Accessory1"); - ChannelMinElemNames.add("Accessory2"); - fields.add( new UAVObjectField("ChannelMin", "us", UAVObjectField.FieldType.INT16, ChannelMinElemNames, null) ); - - List ChannelNeutralElemNames = new ArrayList(); - ChannelNeutralElemNames.add("Throttle"); - ChannelNeutralElemNames.add("Roll"); - ChannelNeutralElemNames.add("Pitch"); - ChannelNeutralElemNames.add("Yaw"); - ChannelNeutralElemNames.add("FlightMode"); - ChannelNeutralElemNames.add("Collective"); - ChannelNeutralElemNames.add("Accessory0"); - ChannelNeutralElemNames.add("Accessory1"); - ChannelNeutralElemNames.add("Accessory2"); - fields.add( new UAVObjectField("ChannelNeutral", "us", UAVObjectField.FieldType.INT16, ChannelNeutralElemNames, null) ); - - List ChannelMaxElemNames = new ArrayList(); - ChannelMaxElemNames.add("Throttle"); - ChannelMaxElemNames.add("Roll"); - ChannelMaxElemNames.add("Pitch"); - ChannelMaxElemNames.add("Yaw"); - ChannelMaxElemNames.add("FlightMode"); - ChannelMaxElemNames.add("Collective"); - ChannelMaxElemNames.add("Accessory0"); - ChannelMaxElemNames.add("Accessory1"); - ChannelMaxElemNames.add("Accessory2"); - fields.add( new UAVObjectField("ChannelMax", "us", UAVObjectField.FieldType.INT16, ChannelMaxElemNames, null) ); - - List ArmedTimeoutElemNames = new ArrayList(); - ArmedTimeoutElemNames.add("0"); - fields.add( new UAVObjectField("ArmedTimeout", "ms", UAVObjectField.FieldType.UINT16, ArmedTimeoutElemNames, null) ); - - List ChannelGroupsElemNames = new ArrayList(); - ChannelGroupsElemNames.add("Throttle"); - ChannelGroupsElemNames.add("Roll"); - ChannelGroupsElemNames.add("Pitch"); - ChannelGroupsElemNames.add("Yaw"); - ChannelGroupsElemNames.add("FlightMode"); - ChannelGroupsElemNames.add("Collective"); - ChannelGroupsElemNames.add("Accessory0"); - ChannelGroupsElemNames.add("Accessory1"); - ChannelGroupsElemNames.add("Accessory2"); - List ChannelGroupsEnumOptions = new ArrayList(); - ChannelGroupsEnumOptions.add("PWM"); - ChannelGroupsEnumOptions.add("PPM"); - ChannelGroupsEnumOptions.add("DSM (MainPort)"); - ChannelGroupsEnumOptions.add("DSM (FlexiPort)"); - ChannelGroupsEnumOptions.add("S.Bus"); - ChannelGroupsEnumOptions.add("GCS"); - ChannelGroupsEnumOptions.add("None"); - fields.add( new UAVObjectField("ChannelGroups", "Channel Group", UAVObjectField.FieldType.ENUM, ChannelGroupsElemNames, ChannelGroupsEnumOptions) ); - - List ChannelNumberElemNames = new ArrayList(); - ChannelNumberElemNames.add("Throttle"); - ChannelNumberElemNames.add("Roll"); - ChannelNumberElemNames.add("Pitch"); - ChannelNumberElemNames.add("Yaw"); - ChannelNumberElemNames.add("FlightMode"); - ChannelNumberElemNames.add("Collective"); - ChannelNumberElemNames.add("Accessory0"); - ChannelNumberElemNames.add("Accessory1"); - ChannelNumberElemNames.add("Accessory2"); - fields.add( new UAVObjectField("ChannelNumber", "channel", UAVObjectField.FieldType.UINT8, ChannelNumberElemNames, null) ); - - List ArmingElemNames = new ArrayList(); - ArmingElemNames.add("0"); - List ArmingEnumOptions = new ArrayList(); - ArmingEnumOptions.add("Always Disarmed"); - ArmingEnumOptions.add("Always Armed"); - ArmingEnumOptions.add("Roll Left"); - ArmingEnumOptions.add("Roll Right"); - ArmingEnumOptions.add("Pitch Forward"); - ArmingEnumOptions.add("Pitch Aft"); - ArmingEnumOptions.add("Yaw Left"); - ArmingEnumOptions.add("Yaw Right"); - fields.add( new UAVObjectField("Arming", "", UAVObjectField.FieldType.ENUM, ArmingElemNames, ArmingEnumOptions) ); - - List Stabilization1SettingsElemNames = new ArrayList(); - Stabilization1SettingsElemNames.add("Roll"); - Stabilization1SettingsElemNames.add("Pitch"); - Stabilization1SettingsElemNames.add("Yaw"); - List Stabilization1SettingsEnumOptions = new ArrayList(); - Stabilization1SettingsEnumOptions.add("None"); - Stabilization1SettingsEnumOptions.add("Rate"); - Stabilization1SettingsEnumOptions.add("Attitude"); - Stabilization1SettingsEnumOptions.add("AxisLock"); - Stabilization1SettingsEnumOptions.add("WeakLeveling"); - Stabilization1SettingsEnumOptions.add("VirtualBar"); - Stabilization1SettingsEnumOptions.add("RelayRate"); - Stabilization1SettingsEnumOptions.add("RelayAttitude"); - fields.add( new UAVObjectField("Stabilization1Settings", "", UAVObjectField.FieldType.ENUM, Stabilization1SettingsElemNames, Stabilization1SettingsEnumOptions) ); - - List Stabilization2SettingsElemNames = new ArrayList(); - Stabilization2SettingsElemNames.add("Roll"); - Stabilization2SettingsElemNames.add("Pitch"); - Stabilization2SettingsElemNames.add("Yaw"); - List Stabilization2SettingsEnumOptions = new ArrayList(); - Stabilization2SettingsEnumOptions.add("None"); - Stabilization2SettingsEnumOptions.add("Rate"); - Stabilization2SettingsEnumOptions.add("Attitude"); - Stabilization2SettingsEnumOptions.add("AxisLock"); - Stabilization2SettingsEnumOptions.add("WeakLeveling"); - Stabilization2SettingsEnumOptions.add("VirtualBar"); - Stabilization2SettingsEnumOptions.add("RelayRate"); - Stabilization2SettingsEnumOptions.add("RelayAttitude"); - fields.add( new UAVObjectField("Stabilization2Settings", "", UAVObjectField.FieldType.ENUM, Stabilization2SettingsElemNames, Stabilization2SettingsEnumOptions) ); - - List Stabilization3SettingsElemNames = new ArrayList(); - Stabilization3SettingsElemNames.add("Roll"); - Stabilization3SettingsElemNames.add("Pitch"); - Stabilization3SettingsElemNames.add("Yaw"); - List Stabilization3SettingsEnumOptions = new ArrayList(); - Stabilization3SettingsEnumOptions.add("None"); - Stabilization3SettingsEnumOptions.add("Rate"); - Stabilization3SettingsEnumOptions.add("Attitude"); - Stabilization3SettingsEnumOptions.add("AxisLock"); - Stabilization3SettingsEnumOptions.add("WeakLeveling"); - Stabilization3SettingsEnumOptions.add("VirtualBar"); - Stabilization3SettingsEnumOptions.add("RelayRate"); - Stabilization3SettingsEnumOptions.add("RelayAttitude"); - fields.add( new UAVObjectField("Stabilization3Settings", "", UAVObjectField.FieldType.ENUM, Stabilization3SettingsElemNames, Stabilization3SettingsEnumOptions) ); - - List FlightModeNumberElemNames = new ArrayList(); - FlightModeNumberElemNames.add("0"); - fields.add( new UAVObjectField("FlightModeNumber", "", UAVObjectField.FieldType.UINT8, FlightModeNumberElemNames, null) ); - - List FlightModePositionElemNames = new ArrayList(); - FlightModePositionElemNames.add("0"); - FlightModePositionElemNames.add("1"); - FlightModePositionElemNames.add("2"); - FlightModePositionElemNames.add("3"); - FlightModePositionElemNames.add("4"); - FlightModePositionElemNames.add("5"); - List FlightModePositionEnumOptions = new ArrayList(); - FlightModePositionEnumOptions.add("Manual"); - FlightModePositionEnumOptions.add("Stabilized1"); - FlightModePositionEnumOptions.add("Stabilized2"); - FlightModePositionEnumOptions.add("Stabilized3"); - FlightModePositionEnumOptions.add("Autotune"); - FlightModePositionEnumOptions.add("AltitudeHold"); - FlightModePositionEnumOptions.add("VelocityControl"); - FlightModePositionEnumOptions.add("PositionHold"); - fields.add( new UAVObjectField("FlightModePosition", "", UAVObjectField.FieldType.ENUM, FlightModePositionElemNames, FlightModePositionEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 0; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("Deadband").setValue(0); - getField("ChannelMin").setValue(1000,0); - getField("ChannelMin").setValue(1000,1); - getField("ChannelMin").setValue(1000,2); - getField("ChannelMin").setValue(1000,3); - getField("ChannelMin").setValue(1000,4); - getField("ChannelMin").setValue(1000,5); - getField("ChannelMin").setValue(1000,6); - getField("ChannelMin").setValue(1000,7); - getField("ChannelMin").setValue(1000,8); - getField("ChannelNeutral").setValue(1500,0); - getField("ChannelNeutral").setValue(1500,1); - getField("ChannelNeutral").setValue(1500,2); - getField("ChannelNeutral").setValue(1500,3); - getField("ChannelNeutral").setValue(1500,4); - getField("ChannelNeutral").setValue(1500,5); - getField("ChannelNeutral").setValue(1500,6); - getField("ChannelNeutral").setValue(1500,7); - getField("ChannelNeutral").setValue(1500,8); - getField("ChannelMax").setValue(2000,0); - getField("ChannelMax").setValue(2000,1); - getField("ChannelMax").setValue(2000,2); - getField("ChannelMax").setValue(2000,3); - getField("ChannelMax").setValue(2000,4); - getField("ChannelMax").setValue(2000,5); - getField("ChannelMax").setValue(2000,6); - getField("ChannelMax").setValue(2000,7); - getField("ChannelMax").setValue(2000,8); - getField("ArmedTimeout").setValue(30000); - getField("ChannelGroups").setValue("None",0); - getField("ChannelGroups").setValue("None",1); - getField("ChannelGroups").setValue("None",2); - getField("ChannelGroups").setValue("None",3); - getField("ChannelGroups").setValue("None",4); - getField("ChannelGroups").setValue("None",5); - getField("ChannelGroups").setValue("None",6); - getField("ChannelGroups").setValue("None",7); - getField("ChannelGroups").setValue("None",8); - getField("ChannelNumber").setValue(0,0); - getField("ChannelNumber").setValue(0,1); - getField("ChannelNumber").setValue(0,2); - getField("ChannelNumber").setValue(0,3); - getField("ChannelNumber").setValue(0,4); - getField("ChannelNumber").setValue(0,5); - getField("ChannelNumber").setValue(0,6); - getField("ChannelNumber").setValue(0,7); - getField("ChannelNumber").setValue(0,8); - getField("Arming").setValue("Always Disarmed"); - getField("Stabilization1Settings").setValue("Attitude",0); - getField("Stabilization1Settings").setValue("Attitude",1); - getField("Stabilization1Settings").setValue("Rate",2); - getField("Stabilization2Settings").setValue("Attitude",0); - getField("Stabilization2Settings").setValue("Attitude",1); - getField("Stabilization2Settings").setValue("Rate",2); - getField("Stabilization3Settings").setValue("Attitude",0); - getField("Stabilization3Settings").setValue("Attitude",1); - getField("Stabilization3Settings").setValue("Rate",2); - getField("FlightModeNumber").setValue(3); - getField("FlightModePosition").setValue("Manual",0); - getField("FlightModePosition").setValue("Stabilized1",1); - getField("FlightModePosition").setValue("Stabilized2",2); - getField("FlightModePosition").setValue("Stabilized3",3); - getField("FlightModePosition").setValue("Stabilized1",4); - getField("FlightModePosition").setValue("Stabilized2",5); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - ManualControlSettings obj = new ManualControlSettings(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public ManualControlSettings GetInstance(UAVObjectManager objMngr, long instID) - { - return (ManualControlSettings)(objMngr.getObject(ManualControlSettings.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0xA240D466l; - protected static final String NAME = "ManualControlSettings"; - protected static String DESCRIPTION = "Settings to indicate how to decode receiver input by @ref ManualControlModule."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 1 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java deleted file mode 100644 index f51a083b0..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerSettings.java +++ /dev/null @@ -1,507 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType - -generated from mixersettings.xml - **/ -public class MixerSettings extends UAVDataObject { - - public MixerSettings() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List MaxAccelElemNames = new ArrayList(); - MaxAccelElemNames.add("0"); - fields.add( new UAVObjectField("MaxAccel", "units/sec", UAVObjectField.FieldType.FLOAT32, MaxAccelElemNames, null) ); - - List FeedForwardElemNames = new ArrayList(); - FeedForwardElemNames.add("0"); - fields.add( new UAVObjectField("FeedForward", "", UAVObjectField.FieldType.FLOAT32, FeedForwardElemNames, null) ); - - List AccelTimeElemNames = new ArrayList(); - AccelTimeElemNames.add("0"); - fields.add( new UAVObjectField("AccelTime", "ms", UAVObjectField.FieldType.FLOAT32, AccelTimeElemNames, null) ); - - List DecelTimeElemNames = new ArrayList(); - DecelTimeElemNames.add("0"); - fields.add( new UAVObjectField("DecelTime", "ms", UAVObjectField.FieldType.FLOAT32, DecelTimeElemNames, null) ); - - List ThrottleCurve1ElemNames = new ArrayList(); - ThrottleCurve1ElemNames.add("0"); - ThrottleCurve1ElemNames.add("25"); - ThrottleCurve1ElemNames.add("50"); - ThrottleCurve1ElemNames.add("75"); - ThrottleCurve1ElemNames.add("100"); - fields.add( new UAVObjectField("ThrottleCurve1", "percent", UAVObjectField.FieldType.FLOAT32, ThrottleCurve1ElemNames, null) ); - - List ThrottleCurve2ElemNames = new ArrayList(); - ThrottleCurve2ElemNames.add("0"); - ThrottleCurve2ElemNames.add("25"); - ThrottleCurve2ElemNames.add("50"); - ThrottleCurve2ElemNames.add("75"); - ThrottleCurve2ElemNames.add("100"); - fields.add( new UAVObjectField("ThrottleCurve2", "percent", UAVObjectField.FieldType.FLOAT32, ThrottleCurve2ElemNames, null) ); - - List Curve2SourceElemNames = new ArrayList(); - Curve2SourceElemNames.add("0"); - List Curve2SourceEnumOptions = new ArrayList(); - Curve2SourceEnumOptions.add("Throttle"); - Curve2SourceEnumOptions.add("Roll"); - Curve2SourceEnumOptions.add("Pitch"); - Curve2SourceEnumOptions.add("Yaw"); - Curve2SourceEnumOptions.add("Collective"); - Curve2SourceEnumOptions.add("Accessory0"); - Curve2SourceEnumOptions.add("Accessory1"); - Curve2SourceEnumOptions.add("Accessory2"); - Curve2SourceEnumOptions.add("Accessory3"); - Curve2SourceEnumOptions.add("Accessory4"); - Curve2SourceEnumOptions.add("Accessory5"); - fields.add( new UAVObjectField("Curve2Source", "", UAVObjectField.FieldType.ENUM, Curve2SourceElemNames, Curve2SourceEnumOptions) ); - - List Mixer1TypeElemNames = new ArrayList(); - Mixer1TypeElemNames.add("0"); - List Mixer1TypeEnumOptions = new ArrayList(); - Mixer1TypeEnumOptions.add("Disabled"); - Mixer1TypeEnumOptions.add("Motor"); - Mixer1TypeEnumOptions.add("Servo"); - Mixer1TypeEnumOptions.add("CameraRoll"); - Mixer1TypeEnumOptions.add("CameraPitch"); - Mixer1TypeEnumOptions.add("CameraYaw"); - Mixer1TypeEnumOptions.add("Accessory0"); - Mixer1TypeEnumOptions.add("Accessory1"); - Mixer1TypeEnumOptions.add("Accessory2"); - Mixer1TypeEnumOptions.add("Accessory3"); - Mixer1TypeEnumOptions.add("Accessory4"); - Mixer1TypeEnumOptions.add("Accessory5"); - fields.add( new UAVObjectField("Mixer1Type", "", UAVObjectField.FieldType.ENUM, Mixer1TypeElemNames, Mixer1TypeEnumOptions) ); - - List Mixer1VectorElemNames = new ArrayList(); - Mixer1VectorElemNames.add("ThrottleCurve1"); - Mixer1VectorElemNames.add("ThrottleCurve2"); - Mixer1VectorElemNames.add("Roll"); - Mixer1VectorElemNames.add("Pitch"); - Mixer1VectorElemNames.add("Yaw"); - fields.add( new UAVObjectField("Mixer1Vector", "", UAVObjectField.FieldType.INT8, Mixer1VectorElemNames, null) ); - - List Mixer2TypeElemNames = new ArrayList(); - Mixer2TypeElemNames.add("0"); - List Mixer2TypeEnumOptions = new ArrayList(); - Mixer2TypeEnumOptions.add("Disabled"); - Mixer2TypeEnumOptions.add("Motor"); - Mixer2TypeEnumOptions.add("Servo"); - Mixer2TypeEnumOptions.add("CameraRoll"); - Mixer2TypeEnumOptions.add("CameraPitch"); - Mixer2TypeEnumOptions.add("CameraYaw"); - Mixer2TypeEnumOptions.add("Accessory0"); - Mixer2TypeEnumOptions.add("Accessory1"); - Mixer2TypeEnumOptions.add("Accessory2"); - Mixer2TypeEnumOptions.add("Accessory3"); - Mixer2TypeEnumOptions.add("Accessory4"); - Mixer2TypeEnumOptions.add("Accessory5"); - fields.add( new UAVObjectField("Mixer2Type", "", UAVObjectField.FieldType.ENUM, Mixer2TypeElemNames, Mixer2TypeEnumOptions) ); - - List Mixer2VectorElemNames = new ArrayList(); - Mixer2VectorElemNames.add("ThrottleCurve1"); - Mixer2VectorElemNames.add("ThrottleCurve2"); - Mixer2VectorElemNames.add("Roll"); - Mixer2VectorElemNames.add("Pitch"); - Mixer2VectorElemNames.add("Yaw"); - fields.add( new UAVObjectField("Mixer2Vector", "", UAVObjectField.FieldType.INT8, Mixer2VectorElemNames, null) ); - - List Mixer3TypeElemNames = new ArrayList(); - Mixer3TypeElemNames.add("0"); - List Mixer3TypeEnumOptions = new ArrayList(); - Mixer3TypeEnumOptions.add("Disabled"); - Mixer3TypeEnumOptions.add("Motor"); - Mixer3TypeEnumOptions.add("Servo"); - Mixer3TypeEnumOptions.add("CameraRoll"); - Mixer3TypeEnumOptions.add("CameraPitch"); - Mixer3TypeEnumOptions.add("CameraYaw"); - Mixer3TypeEnumOptions.add("Accessory0"); - Mixer3TypeEnumOptions.add("Accessory1"); - Mixer3TypeEnumOptions.add("Accessory2"); - Mixer3TypeEnumOptions.add("Accessory3"); - Mixer3TypeEnumOptions.add("Accessory4"); - Mixer3TypeEnumOptions.add("Accessory5"); - fields.add( new UAVObjectField("Mixer3Type", "", UAVObjectField.FieldType.ENUM, Mixer3TypeElemNames, Mixer3TypeEnumOptions) ); - - List Mixer3VectorElemNames = new ArrayList(); - Mixer3VectorElemNames.add("ThrottleCurve1"); - Mixer3VectorElemNames.add("ThrottleCurve2"); - Mixer3VectorElemNames.add("Roll"); - Mixer3VectorElemNames.add("Pitch"); - Mixer3VectorElemNames.add("Yaw"); - fields.add( new UAVObjectField("Mixer3Vector", "", UAVObjectField.FieldType.INT8, Mixer3VectorElemNames, null) ); - - List Mixer4TypeElemNames = new ArrayList(); - Mixer4TypeElemNames.add("0"); - List Mixer4TypeEnumOptions = new ArrayList(); - Mixer4TypeEnumOptions.add("Disabled"); - Mixer4TypeEnumOptions.add("Motor"); - Mixer4TypeEnumOptions.add("Servo"); - Mixer4TypeEnumOptions.add("CameraRoll"); - Mixer4TypeEnumOptions.add("CameraPitch"); - Mixer4TypeEnumOptions.add("CameraYaw"); - Mixer4TypeEnumOptions.add("Accessory0"); - Mixer4TypeEnumOptions.add("Accessory1"); - Mixer4TypeEnumOptions.add("Accessory2"); - Mixer4TypeEnumOptions.add("Accessory3"); - Mixer4TypeEnumOptions.add("Accessory4"); - Mixer4TypeEnumOptions.add("Accessory5"); - fields.add( new UAVObjectField("Mixer4Type", "", UAVObjectField.FieldType.ENUM, Mixer4TypeElemNames, Mixer4TypeEnumOptions) ); - - List Mixer4VectorElemNames = new ArrayList(); - Mixer4VectorElemNames.add("ThrottleCurve1"); - Mixer4VectorElemNames.add("ThrottleCurve2"); - Mixer4VectorElemNames.add("Roll"); - Mixer4VectorElemNames.add("Pitch"); - Mixer4VectorElemNames.add("Yaw"); - fields.add( new UAVObjectField("Mixer4Vector", "", UAVObjectField.FieldType.INT8, Mixer4VectorElemNames, null) ); - - List Mixer5TypeElemNames = new ArrayList(); - Mixer5TypeElemNames.add("0"); - List Mixer5TypeEnumOptions = new ArrayList(); - Mixer5TypeEnumOptions.add("Disabled"); - Mixer5TypeEnumOptions.add("Motor"); - Mixer5TypeEnumOptions.add("Servo"); - Mixer5TypeEnumOptions.add("CameraRoll"); - Mixer5TypeEnumOptions.add("CameraPitch"); - Mixer5TypeEnumOptions.add("CameraYaw"); - Mixer5TypeEnumOptions.add("Accessory0"); - Mixer5TypeEnumOptions.add("Accessory1"); - Mixer5TypeEnumOptions.add("Accessory2"); - Mixer5TypeEnumOptions.add("Accessory3"); - Mixer5TypeEnumOptions.add("Accessory4"); - Mixer5TypeEnumOptions.add("Accessory5"); - fields.add( new UAVObjectField("Mixer5Type", "", UAVObjectField.FieldType.ENUM, Mixer5TypeElemNames, Mixer5TypeEnumOptions) ); - - List Mixer5VectorElemNames = new ArrayList(); - Mixer5VectorElemNames.add("ThrottleCurve1"); - Mixer5VectorElemNames.add("ThrottleCurve2"); - Mixer5VectorElemNames.add("Roll"); - Mixer5VectorElemNames.add("Pitch"); - Mixer5VectorElemNames.add("Yaw"); - fields.add( new UAVObjectField("Mixer5Vector", "", UAVObjectField.FieldType.INT8, Mixer5VectorElemNames, null) ); - - List Mixer6TypeElemNames = new ArrayList(); - Mixer6TypeElemNames.add("0"); - List Mixer6TypeEnumOptions = new ArrayList(); - Mixer6TypeEnumOptions.add("Disabled"); - Mixer6TypeEnumOptions.add("Motor"); - Mixer6TypeEnumOptions.add("Servo"); - Mixer6TypeEnumOptions.add("CameraRoll"); - Mixer6TypeEnumOptions.add("CameraPitch"); - Mixer6TypeEnumOptions.add("CameraYaw"); - Mixer6TypeEnumOptions.add("Accessory0"); - Mixer6TypeEnumOptions.add("Accessory1"); - Mixer6TypeEnumOptions.add("Accessory2"); - Mixer6TypeEnumOptions.add("Accessory3"); - Mixer6TypeEnumOptions.add("Accessory4"); - Mixer6TypeEnumOptions.add("Accessory5"); - fields.add( new UAVObjectField("Mixer6Type", "", UAVObjectField.FieldType.ENUM, Mixer6TypeElemNames, Mixer6TypeEnumOptions) ); - - List Mixer6VectorElemNames = new ArrayList(); - Mixer6VectorElemNames.add("ThrottleCurve1"); - Mixer6VectorElemNames.add("ThrottleCurve2"); - Mixer6VectorElemNames.add("Roll"); - Mixer6VectorElemNames.add("Pitch"); - Mixer6VectorElemNames.add("Yaw"); - fields.add( new UAVObjectField("Mixer6Vector", "", UAVObjectField.FieldType.INT8, Mixer6VectorElemNames, null) ); - - List Mixer7TypeElemNames = new ArrayList(); - Mixer7TypeElemNames.add("0"); - List Mixer7TypeEnumOptions = new ArrayList(); - Mixer7TypeEnumOptions.add("Disabled"); - Mixer7TypeEnumOptions.add("Motor"); - Mixer7TypeEnumOptions.add("Servo"); - Mixer7TypeEnumOptions.add("CameraRoll"); - Mixer7TypeEnumOptions.add("CameraPitch"); - Mixer7TypeEnumOptions.add("CameraYaw"); - Mixer7TypeEnumOptions.add("Accessory0"); - Mixer7TypeEnumOptions.add("Accessory1"); - Mixer7TypeEnumOptions.add("Accessory2"); - Mixer7TypeEnumOptions.add("Accessory3"); - Mixer7TypeEnumOptions.add("Accessory4"); - Mixer7TypeEnumOptions.add("Accessory5"); - fields.add( new UAVObjectField("Mixer7Type", "", UAVObjectField.FieldType.ENUM, Mixer7TypeElemNames, Mixer7TypeEnumOptions) ); - - List Mixer7VectorElemNames = new ArrayList(); - Mixer7VectorElemNames.add("ThrottleCurve1"); - Mixer7VectorElemNames.add("ThrottleCurve2"); - Mixer7VectorElemNames.add("Roll"); - Mixer7VectorElemNames.add("Pitch"); - Mixer7VectorElemNames.add("Yaw"); - fields.add( new UAVObjectField("Mixer7Vector", "", UAVObjectField.FieldType.INT8, Mixer7VectorElemNames, null) ); - - List Mixer8TypeElemNames = new ArrayList(); - Mixer8TypeElemNames.add("0"); - List Mixer8TypeEnumOptions = new ArrayList(); - Mixer8TypeEnumOptions.add("Disabled"); - Mixer8TypeEnumOptions.add("Motor"); - Mixer8TypeEnumOptions.add("Servo"); - Mixer8TypeEnumOptions.add("CameraRoll"); - Mixer8TypeEnumOptions.add("CameraPitch"); - Mixer8TypeEnumOptions.add("CameraYaw"); - Mixer8TypeEnumOptions.add("Accessory0"); - Mixer8TypeEnumOptions.add("Accessory1"); - Mixer8TypeEnumOptions.add("Accessory2"); - Mixer8TypeEnumOptions.add("Accessory3"); - Mixer8TypeEnumOptions.add("Accessory4"); - Mixer8TypeEnumOptions.add("Accessory5"); - fields.add( new UAVObjectField("Mixer8Type", "", UAVObjectField.FieldType.ENUM, Mixer8TypeElemNames, Mixer8TypeEnumOptions) ); - - List Mixer8VectorElemNames = new ArrayList(); - Mixer8VectorElemNames.add("ThrottleCurve1"); - Mixer8VectorElemNames.add("ThrottleCurve2"); - Mixer8VectorElemNames.add("Roll"); - Mixer8VectorElemNames.add("Pitch"); - Mixer8VectorElemNames.add("Yaw"); - fields.add( new UAVObjectField("Mixer8Vector", "", UAVObjectField.FieldType.INT8, Mixer8VectorElemNames, null) ); - - List Mixer9TypeElemNames = new ArrayList(); - Mixer9TypeElemNames.add("0"); - List Mixer9TypeEnumOptions = new ArrayList(); - Mixer9TypeEnumOptions.add("Disabled"); - Mixer9TypeEnumOptions.add("Motor"); - Mixer9TypeEnumOptions.add("Servo"); - Mixer9TypeEnumOptions.add("CameraRoll"); - Mixer9TypeEnumOptions.add("CameraPitch"); - Mixer9TypeEnumOptions.add("CameraYaw"); - Mixer9TypeEnumOptions.add("Accessory0"); - Mixer9TypeEnumOptions.add("Accessory1"); - Mixer9TypeEnumOptions.add("Accessory2"); - Mixer9TypeEnumOptions.add("Accessory3"); - Mixer9TypeEnumOptions.add("Accessory4"); - Mixer9TypeEnumOptions.add("Accessory5"); - fields.add( new UAVObjectField("Mixer9Type", "", UAVObjectField.FieldType.ENUM, Mixer9TypeElemNames, Mixer9TypeEnumOptions) ); - - List Mixer9VectorElemNames = new ArrayList(); - Mixer9VectorElemNames.add("ThrottleCurve1"); - Mixer9VectorElemNames.add("ThrottleCurve2"); - Mixer9VectorElemNames.add("Roll"); - Mixer9VectorElemNames.add("Pitch"); - Mixer9VectorElemNames.add("Yaw"); - fields.add( new UAVObjectField("Mixer9Vector", "", UAVObjectField.FieldType.INT8, Mixer9VectorElemNames, null) ); - - List Mixer10TypeElemNames = new ArrayList(); - Mixer10TypeElemNames.add("0"); - List Mixer10TypeEnumOptions = new ArrayList(); - Mixer10TypeEnumOptions.add("Disabled"); - Mixer10TypeEnumOptions.add("Motor"); - Mixer10TypeEnumOptions.add("Servo"); - Mixer10TypeEnumOptions.add("CameraRoll"); - Mixer10TypeEnumOptions.add("CameraPitch"); - Mixer10TypeEnumOptions.add("CameraYaw"); - Mixer10TypeEnumOptions.add("Accessory0"); - Mixer10TypeEnumOptions.add("Accessory1"); - Mixer10TypeEnumOptions.add("Accessory2"); - Mixer10TypeEnumOptions.add("Accessory3"); - Mixer10TypeEnumOptions.add("Accessory4"); - Mixer10TypeEnumOptions.add("Accessory5"); - fields.add( new UAVObjectField("Mixer10Type", "", UAVObjectField.FieldType.ENUM, Mixer10TypeElemNames, Mixer10TypeEnumOptions) ); - - List Mixer10VectorElemNames = new ArrayList(); - Mixer10VectorElemNames.add("ThrottleCurve1"); - Mixer10VectorElemNames.add("ThrottleCurve2"); - Mixer10VectorElemNames.add("Roll"); - Mixer10VectorElemNames.add("Pitch"); - Mixer10VectorElemNames.add("Yaw"); - fields.add( new UAVObjectField("Mixer10Vector", "", UAVObjectField.FieldType.INT8, Mixer10VectorElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 0; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("MaxAccel").setValue(1000); - getField("FeedForward").setValue(0); - getField("AccelTime").setValue(0); - getField("DecelTime").setValue(0); - getField("ThrottleCurve1").setValue(0,0); - getField("ThrottleCurve1").setValue(0,1); - getField("ThrottleCurve1").setValue(0,2); - getField("ThrottleCurve1").setValue(0,3); - getField("ThrottleCurve1").setValue(0,4); - getField("ThrottleCurve2").setValue(0,0); - getField("ThrottleCurve2").setValue(0.25,1); - getField("ThrottleCurve2").setValue(0.5,2); - getField("ThrottleCurve2").setValue(0.75,3); - getField("ThrottleCurve2").setValue(1,4); - getField("Curve2Source").setValue("Throttle"); - getField("Mixer1Type").setValue("Disabled"); - getField("Mixer1Vector").setValue(0,0); - getField("Mixer1Vector").setValue(0,1); - getField("Mixer1Vector").setValue(0,2); - getField("Mixer1Vector").setValue(0,3); - getField("Mixer1Vector").setValue(0,4); - getField("Mixer2Type").setValue("Disabled"); - getField("Mixer2Vector").setValue(0,0); - getField("Mixer2Vector").setValue(0,1); - getField("Mixer2Vector").setValue(0,2); - getField("Mixer2Vector").setValue(0,3); - getField("Mixer2Vector").setValue(0,4); - getField("Mixer3Type").setValue("Disabled"); - getField("Mixer3Vector").setValue(0,0); - getField("Mixer3Vector").setValue(0,1); - getField("Mixer3Vector").setValue(0,2); - getField("Mixer3Vector").setValue(0,3); - getField("Mixer3Vector").setValue(0,4); - getField("Mixer4Type").setValue("Disabled"); - getField("Mixer4Vector").setValue(0,0); - getField("Mixer4Vector").setValue(0,1); - getField("Mixer4Vector").setValue(0,2); - getField("Mixer4Vector").setValue(0,3); - getField("Mixer4Vector").setValue(0,4); - getField("Mixer5Type").setValue("Disabled"); - getField("Mixer5Vector").setValue(0,0); - getField("Mixer5Vector").setValue(0,1); - getField("Mixer5Vector").setValue(0,2); - getField("Mixer5Vector").setValue(0,3); - getField("Mixer5Vector").setValue(0,4); - getField("Mixer6Type").setValue("Disabled"); - getField("Mixer6Vector").setValue(0,0); - getField("Mixer6Vector").setValue(0,1); - getField("Mixer6Vector").setValue(0,2); - getField("Mixer6Vector").setValue(0,3); - getField("Mixer6Vector").setValue(0,4); - getField("Mixer7Type").setValue("Disabled"); - getField("Mixer7Vector").setValue(0,0); - getField("Mixer7Vector").setValue(0,1); - getField("Mixer7Vector").setValue(0,2); - getField("Mixer7Vector").setValue(0,3); - getField("Mixer7Vector").setValue(0,4); - getField("Mixer8Type").setValue("Disabled"); - getField("Mixer8Vector").setValue(0,0); - getField("Mixer8Vector").setValue(0,1); - getField("Mixer8Vector").setValue(0,2); - getField("Mixer8Vector").setValue(0,3); - getField("Mixer8Vector").setValue(0,4); - getField("Mixer9Type").setValue("Disabled"); - getField("Mixer9Vector").setValue(0,0); - getField("Mixer9Vector").setValue(0,1); - getField("Mixer9Vector").setValue(0,2); - getField("Mixer9Vector").setValue(0,3); - getField("Mixer9Vector").setValue(0,4); - getField("Mixer10Type").setValue("Disabled"); - getField("Mixer10Vector").setValue(0,0); - getField("Mixer10Vector").setValue(0,1); - getField("Mixer10Vector").setValue(0,2); - getField("Mixer10Vector").setValue(0,3); - getField("Mixer10Vector").setValue(0,4); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - MixerSettings obj = new MixerSettings(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public MixerSettings GetInstance(UAVObjectManager objMngr, long instID) - { - return (MixerSettings)(objMngr.getObject(MixerSettings.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x5D16D6C4l; - protected static final String NAME = "MixerSettings"; - protected static String DESCRIPTION = "Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType"; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 1 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java deleted file mode 100644 index 8b7766a94..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/MixerStatus.java +++ /dev/null @@ -1,174 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Status for the matrix mixer showing the output of each mixer after all scaling - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Status for the matrix mixer showing the output of each mixer after all scaling - -generated from mixerstatus.xml - **/ -public class MixerStatus extends UAVDataObject { - - public MixerStatus() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List Mixer1ElemNames = new ArrayList(); - Mixer1ElemNames.add("0"); - fields.add( new UAVObjectField("Mixer1", "", UAVObjectField.FieldType.FLOAT32, Mixer1ElemNames, null) ); - - List Mixer2ElemNames = new ArrayList(); - Mixer2ElemNames.add("0"); - fields.add( new UAVObjectField("Mixer2", "", UAVObjectField.FieldType.FLOAT32, Mixer2ElemNames, null) ); - - List Mixer3ElemNames = new ArrayList(); - Mixer3ElemNames.add("0"); - fields.add( new UAVObjectField("Mixer3", "", UAVObjectField.FieldType.FLOAT32, Mixer3ElemNames, null) ); - - List Mixer4ElemNames = new ArrayList(); - Mixer4ElemNames.add("0"); - fields.add( new UAVObjectField("Mixer4", "", UAVObjectField.FieldType.FLOAT32, Mixer4ElemNames, null) ); - - List Mixer5ElemNames = new ArrayList(); - Mixer5ElemNames.add("0"); - fields.add( new UAVObjectField("Mixer5", "", UAVObjectField.FieldType.FLOAT32, Mixer5ElemNames, null) ); - - List Mixer6ElemNames = new ArrayList(); - Mixer6ElemNames.add("0"); - fields.add( new UAVObjectField("Mixer6", "", UAVObjectField.FieldType.FLOAT32, Mixer6ElemNames, null) ); - - List Mixer7ElemNames = new ArrayList(); - Mixer7ElemNames.add("0"); - fields.add( new UAVObjectField("Mixer7", "", UAVObjectField.FieldType.FLOAT32, Mixer7ElemNames, null) ); - - List Mixer8ElemNames = new ArrayList(); - Mixer8ElemNames.add("0"); - fields.add( new UAVObjectField("Mixer8", "", UAVObjectField.FieldType.FLOAT32, Mixer8ElemNames, null) ); - - List Mixer9ElemNames = new ArrayList(); - Mixer9ElemNames.add("0"); - fields.add( new UAVObjectField("Mixer9", "", UAVObjectField.FieldType.FLOAT32, Mixer9ElemNames, null) ); - - List Mixer10ElemNames = new ArrayList(); - Mixer10ElemNames.add("0"); - fields.add( new UAVObjectField("Mixer10", "", UAVObjectField.FieldType.FLOAT32, Mixer10ElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 1000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 1000; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - MixerStatus obj = new MixerStatus(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public MixerStatus GetInstance(UAVObjectManager objMngr, long instID) - { - return (MixerStatus)(objMngr.getObject(MixerStatus.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x124E28Al; - protected static final String NAME = "MixerStatus"; - protected static String DESCRIPTION = "Status for the matrix mixer showing the output of each mixer after all scaling"; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/NEDPosition.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/NEDPosition.java deleted file mode 100644 index 01bc062ff..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/NEDPosition.java +++ /dev/null @@ -1,146 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Contains the current position relative to @ref HomeLocation - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Contains the current position relative to @ref HomeLocation - -generated from nedposition.xml - **/ -public class NEDPosition extends UAVDataObject { - - public NEDPosition() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List NorthElemNames = new ArrayList(); - NorthElemNames.add("0"); - fields.add( new UAVObjectField("North", "m", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); - - List EastElemNames = new ArrayList(); - EastElemNames.add("0"); - fields.add( new UAVObjectField("East", "m", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); - - List DownElemNames = new ArrayList(); - DownElemNames.add("0"); - fields.add( new UAVObjectField("Down", "m", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 1000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 1000; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - NEDPosition obj = new NEDPosition(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public NEDPosition GetInstance(UAVObjectManager objMngr, long instID) - { - return (NEDPosition)(objMngr.getObject(NEDPosition.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x1FB15A00l; - protected static final String NAME = "NEDPosition"; - protected static String DESCRIPTION = "Contains the current position relative to @ref HomeLocation"; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java deleted file mode 100644 index 9520e65eb..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/NedAccel.java +++ /dev/null @@ -1,146 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * The projection of acceleration in the NED reference frame used by @ref Guidance. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -The projection of acceleration in the NED reference frame used by @ref Guidance. - -generated from nedaccel.xml - **/ -public class NedAccel extends UAVDataObject { - - public NedAccel() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List NorthElemNames = new ArrayList(); - NorthElemNames.add("0"); - fields.add( new UAVObjectField("North", "m/s^2", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); - - List EastElemNames = new ArrayList(); - EastElemNames.add("0"); - fields.add( new UAVObjectField("East", "m/s^2", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); - - List DownElemNames = new ArrayList(); - DownElemNames.add("0"); - fields.add( new UAVObjectField("Down", "m/s^2", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 10001; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - NedAccel obj = new NedAccel(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public NedAccel GetInstance(UAVObjectManager objMngr, long instID) - { - return (NedAccel)(objMngr.getObject(NedAccel.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x7C7F5BC0l; - protected static final String NAME = "NedAccel"; - protected static String DESCRIPTION = "The projection of acceleration in the NED reference frame used by @ref Guidance."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java deleted file mode 100644 index d856a3396..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ObjectPersistence.java +++ /dev/null @@ -1,163 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Someone who knows please enter this - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Someone who knows please enter this - -generated from objectpersistence.xml - **/ -public class ObjectPersistence extends UAVDataObject { - - public ObjectPersistence() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List ObjectIDElemNames = new ArrayList(); - ObjectIDElemNames.add("0"); - fields.add( new UAVObjectField("ObjectID", "", UAVObjectField.FieldType.UINT32, ObjectIDElemNames, null) ); - - List InstanceIDElemNames = new ArrayList(); - InstanceIDElemNames.add("0"); - fields.add( new UAVObjectField("InstanceID", "", UAVObjectField.FieldType.UINT32, InstanceIDElemNames, null) ); - - List OperationElemNames = new ArrayList(); - OperationElemNames.add("0"); - List OperationEnumOptions = new ArrayList(); - OperationEnumOptions.add("NOP"); - OperationEnumOptions.add("Load"); - OperationEnumOptions.add("Save"); - OperationEnumOptions.add("Delete"); - OperationEnumOptions.add("FullErase"); - OperationEnumOptions.add("Completed"); - OperationEnumOptions.add("Error"); - fields.add( new UAVObjectField("Operation", "", UAVObjectField.FieldType.ENUM, OperationElemNames, OperationEnumOptions) ); - - List SelectionElemNames = new ArrayList(); - SelectionElemNames.add("0"); - List SelectionEnumOptions = new ArrayList(); - SelectionEnumOptions.add("SingleObject"); - SelectionEnumOptions.add("AllSettings"); - SelectionEnumOptions.add("AllMetaObjects"); - SelectionEnumOptions.add("AllObjects"); - fields.add( new UAVObjectField("Selection", "", UAVObjectField.FieldType.ENUM, SelectionElemNames, SelectionEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 0; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - ObjectPersistence obj = new ObjectPersistence(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public ObjectPersistence GetInstance(UAVObjectManager objMngr, long instID) - { - return (ObjectPersistence)(objMngr.getObject(ObjectPersistence.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x99C63292l; - protected static final String NAME = "ObjectPersistence"; - protected static String DESCRIPTION = "Someone who knows please enter this"; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/OveroSyncSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/OveroSyncSettings.java deleted file mode 100644 index b312badfc..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/OveroSyncSettings.java +++ /dev/null @@ -1,143 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Settings to control the behavior of the overo sync module - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Settings to control the behavior of the overo sync module - -generated from overosyncsettings.xml - **/ -public class OveroSyncSettings extends UAVDataObject { - - public OveroSyncSettings() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List LogOnElemNames = new ArrayList(); - LogOnElemNames.add("0"); - List LogOnEnumOptions = new ArrayList(); - LogOnEnumOptions.add("Never"); - LogOnEnumOptions.add("Always"); - LogOnEnumOptions.add("Armed"); - fields.add( new UAVObjectField("LogOn", "", UAVObjectField.FieldType.ENUM, LogOnElemNames, LogOnEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 0; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 1000; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("LogOn").setValue("Armed"); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - OveroSyncSettings obj = new OveroSyncSettings(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public OveroSyncSettings GetInstance(UAVObjectManager objMngr, long instID) - { - return (OveroSyncSettings)(objMngr.getObject(OveroSyncSettings.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0xA1ABC278l; - protected static final String NAME = "OveroSyncSettings"; - protected static String DESCRIPTION = "Settings to control the behavior of the overo sync module"; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 1 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/OveroSyncStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/OveroSyncStats.java deleted file mode 100644 index 26985df6c..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/OveroSyncStats.java +++ /dev/null @@ -1,153 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Maintains statistics on transfer rate to and from over - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Maintains statistics on transfer rate to and from over - -generated from overosyncstats.xml - **/ -public class OveroSyncStats extends UAVDataObject { - - public OveroSyncStats() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List SendElemNames = new ArrayList(); - SendElemNames.add("0"); - fields.add( new UAVObjectField("Send", "B/s", UAVObjectField.FieldType.UINT32, SendElemNames, null) ); - - List ReceivedElemNames = new ArrayList(); - ReceivedElemNames.add("0"); - fields.add( new UAVObjectField("Received", "B/s", UAVObjectField.FieldType.UINT32, ReceivedElemNames, null) ); - - List DroppedUpdatesElemNames = new ArrayList(); - DroppedUpdatesElemNames.add("0"); - fields.add( new UAVObjectField("DroppedUpdates", "", UAVObjectField.FieldType.UINT32, DroppedUpdatesElemNames, null) ); - - List ConnectedElemNames = new ArrayList(); - ConnectedElemNames.add("0"); - List ConnectedEnumOptions = new ArrayList(); - ConnectedEnumOptions.add("False"); - ConnectedEnumOptions.add("True"); - fields.add( new UAVObjectField("Connected", "", UAVObjectField.FieldType.ENUM, ConnectedElemNames, ConnectedEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 1000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 1000; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - OveroSyncStats obj = new OveroSyncStats(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public OveroSyncStats GetInstance(UAVObjectManager objMngr, long instID) - { - return (OveroSyncStats)(objMngr.getObject(OveroSyncStats.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x388468B8l; - protected static final String NAME = "OveroSyncStats"; - protected static String DESCRIPTION = "Maintains statistics on transfer rate to and from over"; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PathAction.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PathAction.java deleted file mode 100644 index f21e301c3..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PathAction.java +++ /dev/null @@ -1,195 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * A waypoint command the pathplanner is to use at a certain waypoint - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -A waypoint command the pathplanner is to use at a certain waypoint - -generated from pathaction.xml - **/ -public class PathAction extends UAVDataObject { - - public PathAction() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List ModeParametersElemNames = new ArrayList(); - ModeParametersElemNames.add("0"); - ModeParametersElemNames.add("1"); - ModeParametersElemNames.add("2"); - ModeParametersElemNames.add("3"); - fields.add( new UAVObjectField("ModeParameters", "", UAVObjectField.FieldType.FLOAT32, ModeParametersElemNames, null) ); - - List ConditionParametersElemNames = new ArrayList(); - ConditionParametersElemNames.add("0"); - ConditionParametersElemNames.add("1"); - ConditionParametersElemNames.add("2"); - ConditionParametersElemNames.add("3"); - fields.add( new UAVObjectField("ConditionParameters", "", UAVObjectField.FieldType.FLOAT32, ConditionParametersElemNames, null) ); - - List ModeElemNames = new ArrayList(); - ModeElemNames.add("0"); - List ModeEnumOptions = new ArrayList(); - ModeEnumOptions.add("FlyEndpoint"); - ModeEnumOptions.add("FlyVector"); - ModeEnumOptions.add("FlyCircleRight"); - ModeEnumOptions.add("FlyCircleLeft"); - ModeEnumOptions.add("DriveEndpoint"); - ModeEnumOptions.add("DriveVector"); - ModeEnumOptions.add("DriveCircleLeft"); - ModeEnumOptions.add("DriveCircleRight"); - ModeEnumOptions.add("FixedAttitude"); - ModeEnumOptions.add("SetAccessory"); - ModeEnumOptions.add("DisarmAlarm"); - fields.add( new UAVObjectField("Mode", "", UAVObjectField.FieldType.ENUM, ModeElemNames, ModeEnumOptions) ); - - List EndConditionElemNames = new ArrayList(); - EndConditionElemNames.add("0"); - List EndConditionEnumOptions = new ArrayList(); - EndConditionEnumOptions.add("None"); - EndConditionEnumOptions.add("TimeOut"); - EndConditionEnumOptions.add("DistanceToTarget"); - EndConditionEnumOptions.add("LegRemaining"); - EndConditionEnumOptions.add("AboveAltitude"); - EndConditionEnumOptions.add("PointingTowardsNext"); - EndConditionEnumOptions.add("PythonScript"); - EndConditionEnumOptions.add("Immediate"); - fields.add( new UAVObjectField("EndCondition", "", UAVObjectField.FieldType.ENUM, EndConditionElemNames, EndConditionEnumOptions) ); - - List CommandElemNames = new ArrayList(); - CommandElemNames.add("0"); - List CommandEnumOptions = new ArrayList(); - CommandEnumOptions.add("OnConditionNextWaypoint"); - CommandEnumOptions.add("OnNotConditionNextWaypoint"); - CommandEnumOptions.add("OnConditionJumpWaypoint"); - CommandEnumOptions.add("OnNotConditionJumpWaypoint"); - CommandEnumOptions.add("IfConditionJumpWaypointElseNextWaypoint"); - fields.add( new UAVObjectField("Command", "", UAVObjectField.FieldType.ENUM, CommandElemNames, CommandEnumOptions) ); - - List JumpDestinationElemNames = new ArrayList(); - JumpDestinationElemNames.add("0"); - fields.add( new UAVObjectField("JumpDestination", "waypoint", UAVObjectField.FieldType.UINT8, JumpDestinationElemNames, null) ); - - List ErrorDestinationElemNames = new ArrayList(); - ErrorDestinationElemNames.add("0"); - fields.add( new UAVObjectField("ErrorDestination", "waypoint", UAVObjectField.FieldType.UINT8, ErrorDestinationElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 4000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 1000; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - PathAction obj = new PathAction(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public PathAction GetInstance(UAVObjectManager objMngr, long instID) - { - return (PathAction)(objMngr.getObject(PathAction.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x34595F1Cl; - protected static final String NAME = "PathAction"; - protected static String DESCRIPTION = "A waypoint command the pathplanner is to use at a certain waypoint"; - protected static final boolean ISSINGLEINST = 0 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PathDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PathDesired.java deleted file mode 100644 index f7a00a5da..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PathDesired.java +++ /dev/null @@ -1,162 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * The endpoint or path the craft is trying to achieve. Can come from @ref ManualControl or @ref PathPlanner - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -The endpoint or path the craft is trying to achieve. Can come from @ref ManualControl or @ref PathPlanner - -generated from pathdesired.xml - **/ -public class PathDesired extends UAVDataObject { - - public PathDesired() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List StartElemNames = new ArrayList(); - StartElemNames.add("North"); - StartElemNames.add("East"); - StartElemNames.add("Down"); - fields.add( new UAVObjectField("Start", "m", UAVObjectField.FieldType.FLOAT32, StartElemNames, null) ); - - List EndElemNames = new ArrayList(); - EndElemNames.add("North"); - EndElemNames.add("East"); - EndElemNames.add("Down"); - fields.add( new UAVObjectField("End", "m", UAVObjectField.FieldType.FLOAT32, EndElemNames, null) ); - - List StartingVelocityElemNames = new ArrayList(); - StartingVelocityElemNames.add("0"); - fields.add( new UAVObjectField("StartingVelocity", "m/s", UAVObjectField.FieldType.FLOAT32, StartingVelocityElemNames, null) ); - - List EndingVelocityElemNames = new ArrayList(); - EndingVelocityElemNames.add("0"); - fields.add( new UAVObjectField("EndingVelocity", "m/s", UAVObjectField.FieldType.FLOAT32, EndingVelocityElemNames, null) ); - - List ModeElemNames = new ArrayList(); - ModeElemNames.add("0"); - List ModeEnumOptions = new ArrayList(); - ModeEnumOptions.add("Endpoint"); - ModeEnumOptions.add("Path"); - ModeEnumOptions.add("Land"); - fields.add( new UAVObjectField("Mode", "", UAVObjectField.FieldType.ENUM, ModeElemNames, ModeEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 1000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - PathDesired obj = new PathDesired(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public PathDesired GetInstance(UAVObjectManager objMngr, long instID) - { - return (PathDesired)(objMngr.getObject(PathDesired.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x5A4DC71Al; - protected static final String NAME = "PathDesired"; - protected static String DESCRIPTION = "The endpoint or path the craft is trying to achieve. Can come from @ref ManualControl or @ref PathPlanner "; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PathPlannerSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PathPlannerSettings.java deleted file mode 100644 index d309130a7..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PathPlannerSettings.java +++ /dev/null @@ -1,151 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Settings for the @ref PathPlanner Module - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Settings for the @ref PathPlanner Module - -generated from pathplannersettings.xml - **/ -public class PathPlannerSettings extends UAVDataObject { - - public PathPlannerSettings() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List PathModeElemNames = new ArrayList(); - PathModeElemNames.add("0"); - List PathModeEnumOptions = new ArrayList(); - PathModeEnumOptions.add("ENDPOINT"); - PathModeEnumOptions.add("PATH"); - fields.add( new UAVObjectField("PathMode", "", UAVObjectField.FieldType.ENUM, PathModeElemNames, PathModeEnumOptions) ); - - List PreprogrammedPathElemNames = new ArrayList(); - PreprogrammedPathElemNames.add("0"); - List PreprogrammedPathEnumOptions = new ArrayList(); - PreprogrammedPathEnumOptions.add("NONE"); - PreprogrammedPathEnumOptions.add("10M_BOX"); - PreprogrammedPathEnumOptions.add("LOGO"); - fields.add( new UAVObjectField("PreprogrammedPath", "", UAVObjectField.FieldType.ENUM, PreprogrammedPathElemNames, PreprogrammedPathEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 0; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("PathMode").setValue("PATH"); - getField("PreprogrammedPath").setValue("NONE"); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - PathPlannerSettings obj = new PathPlannerSettings(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public PathPlannerSettings GetInstance(UAVObjectManager objMngr, long instID) - { - return (PathPlannerSettings)(objMngr.getObject(PathPlannerSettings.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x290E45DAl; - protected static final String NAME = "PathPlannerSettings"; - protected static String DESCRIPTION = "Settings for the @ref PathPlanner Module"; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 1 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXSettings.java deleted file mode 100644 index 46cd3a998..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXSettings.java +++ /dev/null @@ -1,326 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * PipXtreme configurations options. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -PipXtreme configurations options. - -generated from pipxsettings.xml - **/ -public class PipXSettings extends UAVDataObject { - - public PipXSettings() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List PairIDElemNames = new ArrayList(); - PairIDElemNames.add("0"); - fields.add( new UAVObjectField("PairID", "", UAVObjectField.FieldType.UINT32, PairIDElemNames, null) ); - - List FrequencyElemNames = new ArrayList(); - FrequencyElemNames.add("0"); - fields.add( new UAVObjectField("Frequency", "", UAVObjectField.FieldType.UINT32, FrequencyElemNames, null) ); - - List SendTimeoutElemNames = new ArrayList(); - SendTimeoutElemNames.add("0"); - fields.add( new UAVObjectField("SendTimeout", "ms", UAVObjectField.FieldType.UINT16, SendTimeoutElemNames, null) ); - - List TelemetryConfigElemNames = new ArrayList(); - TelemetryConfigElemNames.add("0"); - List TelemetryConfigEnumOptions = new ArrayList(); - TelemetryConfigEnumOptions.add("Disabled"); - TelemetryConfigEnumOptions.add("Serial"); - TelemetryConfigEnumOptions.add("UAVTalk"); - TelemetryConfigEnumOptions.add("GCS"); - TelemetryConfigEnumOptions.add("Debug"); - fields.add( new UAVObjectField("TelemetryConfig", "function", UAVObjectField.FieldType.ENUM, TelemetryConfigElemNames, TelemetryConfigEnumOptions) ); - - List TelemetrySpeedElemNames = new ArrayList(); - TelemetrySpeedElemNames.add("0"); - List TelemetrySpeedEnumOptions = new ArrayList(); - TelemetrySpeedEnumOptions.add("2400"); - TelemetrySpeedEnumOptions.add("4800"); - TelemetrySpeedEnumOptions.add("9600"); - TelemetrySpeedEnumOptions.add("19200"); - TelemetrySpeedEnumOptions.add("38400"); - TelemetrySpeedEnumOptions.add("57600"); - TelemetrySpeedEnumOptions.add("115200"); - fields.add( new UAVObjectField("TelemetrySpeed", "bps", UAVObjectField.FieldType.ENUM, TelemetrySpeedElemNames, TelemetrySpeedEnumOptions) ); - - List FlexiConfigElemNames = new ArrayList(); - FlexiConfigElemNames.add("0"); - List FlexiConfigEnumOptions = new ArrayList(); - FlexiConfigEnumOptions.add("Disabled"); - FlexiConfigEnumOptions.add("Serial"); - FlexiConfigEnumOptions.add("UAVTalk"); - FlexiConfigEnumOptions.add("GCS"); - FlexiConfigEnumOptions.add("PPM_In"); - FlexiConfigEnumOptions.add("PPM_Out"); - FlexiConfigEnumOptions.add("RSSI"); - FlexiConfigEnumOptions.add("Debug"); - fields.add( new UAVObjectField("FlexiConfig", "function", UAVObjectField.FieldType.ENUM, FlexiConfigElemNames, FlexiConfigEnumOptions) ); - - List FlexiSpeedElemNames = new ArrayList(); - FlexiSpeedElemNames.add("0"); - List FlexiSpeedEnumOptions = new ArrayList(); - FlexiSpeedEnumOptions.add("2400"); - FlexiSpeedEnumOptions.add("4800"); - FlexiSpeedEnumOptions.add("9600"); - FlexiSpeedEnumOptions.add("19200"); - FlexiSpeedEnumOptions.add("38400"); - FlexiSpeedEnumOptions.add("57600"); - FlexiSpeedEnumOptions.add("115200"); - fields.add( new UAVObjectField("FlexiSpeed", "bps", UAVObjectField.FieldType.ENUM, FlexiSpeedElemNames, FlexiSpeedEnumOptions) ); - - List VCPConfigElemNames = new ArrayList(); - VCPConfigElemNames.add("0"); - List VCPConfigEnumOptions = new ArrayList(); - VCPConfigEnumOptions.add("Disabled"); - VCPConfigEnumOptions.add("Serial"); - VCPConfigEnumOptions.add("Debug"); - fields.add( new UAVObjectField("VCPConfig", "function", UAVObjectField.FieldType.ENUM, VCPConfigElemNames, VCPConfigEnumOptions) ); - - List VCPSpeedElemNames = new ArrayList(); - VCPSpeedElemNames.add("0"); - List VCPSpeedEnumOptions = new ArrayList(); - VCPSpeedEnumOptions.add("2400"); - VCPSpeedEnumOptions.add("4800"); - VCPSpeedEnumOptions.add("9600"); - VCPSpeedEnumOptions.add("19200"); - VCPSpeedEnumOptions.add("38400"); - VCPSpeedEnumOptions.add("57600"); - VCPSpeedEnumOptions.add("115200"); - fields.add( new UAVObjectField("VCPSpeed", "bps", UAVObjectField.FieldType.ENUM, VCPSpeedElemNames, VCPSpeedEnumOptions) ); - - List RFSpeedElemNames = new ArrayList(); - RFSpeedElemNames.add("0"); - List RFSpeedEnumOptions = new ArrayList(); - RFSpeedEnumOptions.add("2400"); - RFSpeedEnumOptions.add("4800"); - RFSpeedEnumOptions.add("9600"); - RFSpeedEnumOptions.add("19200"); - RFSpeedEnumOptions.add("38400"); - RFSpeedEnumOptions.add("57600"); - RFSpeedEnumOptions.add("115200"); - fields.add( new UAVObjectField("RFSpeed", "bps", UAVObjectField.FieldType.ENUM, RFSpeedElemNames, RFSpeedEnumOptions) ); - - List MaxRFPowerElemNames = new ArrayList(); - MaxRFPowerElemNames.add("0"); - List MaxRFPowerEnumOptions = new ArrayList(); - MaxRFPowerEnumOptions.add("1.25"); - MaxRFPowerEnumOptions.add("1.6"); - MaxRFPowerEnumOptions.add("3.16"); - MaxRFPowerEnumOptions.add("6.3"); - MaxRFPowerEnumOptions.add("12.6"); - MaxRFPowerEnumOptions.add("25"); - MaxRFPowerEnumOptions.add("50"); - MaxRFPowerEnumOptions.add("100"); - fields.add( new UAVObjectField("MaxRFPower", "mW", UAVObjectField.FieldType.ENUM, MaxRFPowerElemNames, MaxRFPowerEnumOptions) ); - - List MinPacketSizeElemNames = new ArrayList(); - MinPacketSizeElemNames.add("0"); - fields.add( new UAVObjectField("MinPacketSize", "bytes", UAVObjectField.FieldType.UINT8, MinPacketSizeElemNames, null) ); - - List FrequencyCalibrationElemNames = new ArrayList(); - FrequencyCalibrationElemNames.add("0"); - fields.add( new UAVObjectField("FrequencyCalibration", "", UAVObjectField.FieldType.UINT8, FrequencyCalibrationElemNames, null) ); - - List AESKeyElemNames = new ArrayList(); - AESKeyElemNames.add("0"); - AESKeyElemNames.add("1"); - AESKeyElemNames.add("2"); - AESKeyElemNames.add("3"); - AESKeyElemNames.add("4"); - AESKeyElemNames.add("5"); - AESKeyElemNames.add("6"); - AESKeyElemNames.add("7"); - AESKeyElemNames.add("8"); - AESKeyElemNames.add("9"); - AESKeyElemNames.add("10"); - AESKeyElemNames.add("11"); - AESKeyElemNames.add("12"); - AESKeyElemNames.add("13"); - AESKeyElemNames.add("14"); - AESKeyElemNames.add("15"); - AESKeyElemNames.add("16"); - AESKeyElemNames.add("17"); - AESKeyElemNames.add("18"); - AESKeyElemNames.add("19"); - AESKeyElemNames.add("20"); - AESKeyElemNames.add("21"); - AESKeyElemNames.add("22"); - AESKeyElemNames.add("23"); - AESKeyElemNames.add("24"); - AESKeyElemNames.add("25"); - AESKeyElemNames.add("26"); - AESKeyElemNames.add("27"); - AESKeyElemNames.add("28"); - AESKeyElemNames.add("29"); - AESKeyElemNames.add("30"); - AESKeyElemNames.add("31"); - fields.add( new UAVObjectField("AESKey", "", UAVObjectField.FieldType.UINT8, AESKeyElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 0; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("PairID").setValue(0); - getField("Frequency").setValue(434000000); - getField("SendTimeout").setValue(50); - getField("TelemetryConfig").setValue("UAVTalk"); - getField("TelemetrySpeed").setValue("57600"); - getField("FlexiConfig").setValue("Disabled"); - getField("FlexiSpeed").setValue("57600"); - getField("VCPConfig").setValue("Disabled"); - getField("VCPSpeed").setValue("57600"); - getField("RFSpeed").setValue("115200"); - getField("MaxRFPower").setValue("100"); - getField("MinPacketSize").setValue(50); - getField("FrequencyCalibration").setValue(127); - getField("AESKey").setValue(0,0); - getField("AESKey").setValue(0,1); - getField("AESKey").setValue(0,2); - getField("AESKey").setValue(0,3); - getField("AESKey").setValue(0,4); - getField("AESKey").setValue(0,5); - getField("AESKey").setValue(0,6); - getField("AESKey").setValue(0,7); - getField("AESKey").setValue(0,8); - getField("AESKey").setValue(0,9); - getField("AESKey").setValue(0,10); - getField("AESKey").setValue(0,11); - getField("AESKey").setValue(0,12); - getField("AESKey").setValue(0,13); - getField("AESKey").setValue(0,14); - getField("AESKey").setValue(0,15); - getField("AESKey").setValue(0,16); - getField("AESKey").setValue(0,17); - getField("AESKey").setValue(0,18); - getField("AESKey").setValue(0,19); - getField("AESKey").setValue(0,20); - getField("AESKey").setValue(0,21); - getField("AESKey").setValue(0,22); - getField("AESKey").setValue(0,23); - getField("AESKey").setValue(0,24); - getField("AESKey").setValue(0,25); - getField("AESKey").setValue(0,26); - getField("AESKey").setValue(0,27); - getField("AESKey").setValue(0,28); - getField("AESKey").setValue(0,29); - getField("AESKey").setValue(0,30); - getField("AESKey").setValue(0,31); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - PipXSettings obj = new PipXSettings(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public PipXSettings GetInstance(UAVObjectManager objMngr, long instID) - { - return (PipXSettings)(objMngr.getObject(PipXSettings.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0xBA192BCAl; - protected static final String NAME = "PipXSettings"; - protected static String DESCRIPTION = "PipXtreme configurations options."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 1 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXStatus.java deleted file mode 100644 index 5525a21b6..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PipXStatus.java +++ /dev/null @@ -1,301 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * PipXtreme device status. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -PipXtreme device status. - -generated from pipxstatus.xml - **/ -public class PipXStatus extends UAVDataObject { - - public PipXStatus() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List MinFrequencyElemNames = new ArrayList(); - MinFrequencyElemNames.add("0"); - fields.add( new UAVObjectField("MinFrequency", "Hz", UAVObjectField.FieldType.UINT32, MinFrequencyElemNames, null) ); - - List MaxFrequencyElemNames = new ArrayList(); - MaxFrequencyElemNames.add("0"); - fields.add( new UAVObjectField("MaxFrequency", "Hz", UAVObjectField.FieldType.UINT32, MaxFrequencyElemNames, null) ); - - List FrequencyStepSizeElemNames = new ArrayList(); - FrequencyStepSizeElemNames.add("0"); - fields.add( new UAVObjectField("FrequencyStepSize", "", UAVObjectField.FieldType.FLOAT32, FrequencyStepSizeElemNames, null) ); - - List DeviceIDElemNames = new ArrayList(); - DeviceIDElemNames.add("0"); - fields.add( new UAVObjectField("DeviceID", "", UAVObjectField.FieldType.UINT32, DeviceIDElemNames, null) ); - - List AFCElemNames = new ArrayList(); - AFCElemNames.add("0"); - fields.add( new UAVObjectField("AFC", "", UAVObjectField.FieldType.INT32, AFCElemNames, null) ); - - List PairIDsElemNames = new ArrayList(); - PairIDsElemNames.add("0"); - PairIDsElemNames.add("1"); - PairIDsElemNames.add("2"); - PairIDsElemNames.add("3"); - fields.add( new UAVObjectField("PairIDs", "", UAVObjectField.FieldType.UINT32, PairIDsElemNames, null) ); - - List BoardRevisionElemNames = new ArrayList(); - BoardRevisionElemNames.add("0"); - fields.add( new UAVObjectField("BoardRevision", "", UAVObjectField.FieldType.UINT16, BoardRevisionElemNames, null) ); - - List RetriesElemNames = new ArrayList(); - RetriesElemNames.add("0"); - fields.add( new UAVObjectField("Retries", "", UAVObjectField.FieldType.UINT16, RetriesElemNames, null) ); - - List ErrorsElemNames = new ArrayList(); - ErrorsElemNames.add("0"); - fields.add( new UAVObjectField("Errors", "", UAVObjectField.FieldType.UINT16, ErrorsElemNames, null) ); - - List UAVTalkErrorsElemNames = new ArrayList(); - UAVTalkErrorsElemNames.add("0"); - fields.add( new UAVObjectField("UAVTalkErrors", "", UAVObjectField.FieldType.UINT16, UAVTalkErrorsElemNames, null) ); - - List DroppedElemNames = new ArrayList(); - DroppedElemNames.add("0"); - fields.add( new UAVObjectField("Dropped", "", UAVObjectField.FieldType.UINT16, DroppedElemNames, null) ); - - List ResetsElemNames = new ArrayList(); - ResetsElemNames.add("0"); - fields.add( new UAVObjectField("Resets", "", UAVObjectField.FieldType.UINT16, ResetsElemNames, null) ); - - List TXRateElemNames = new ArrayList(); - TXRateElemNames.add("0"); - fields.add( new UAVObjectField("TXRate", "Bps", UAVObjectField.FieldType.UINT16, TXRateElemNames, null) ); - - List RXRateElemNames = new ArrayList(); - RXRateElemNames.add("0"); - fields.add( new UAVObjectField("RXRate", "Bps", UAVObjectField.FieldType.UINT16, RXRateElemNames, null) ); - - List DescriptionElemNames = new ArrayList(); - DescriptionElemNames.add("0"); - DescriptionElemNames.add("1"); - DescriptionElemNames.add("2"); - DescriptionElemNames.add("3"); - DescriptionElemNames.add("4"); - DescriptionElemNames.add("5"); - DescriptionElemNames.add("6"); - DescriptionElemNames.add("7"); - DescriptionElemNames.add("8"); - DescriptionElemNames.add("9"); - DescriptionElemNames.add("10"); - DescriptionElemNames.add("11"); - DescriptionElemNames.add("12"); - DescriptionElemNames.add("13"); - DescriptionElemNames.add("14"); - DescriptionElemNames.add("15"); - DescriptionElemNames.add("16"); - DescriptionElemNames.add("17"); - DescriptionElemNames.add("18"); - DescriptionElemNames.add("19"); - DescriptionElemNames.add("20"); - DescriptionElemNames.add("21"); - DescriptionElemNames.add("22"); - DescriptionElemNames.add("23"); - DescriptionElemNames.add("24"); - DescriptionElemNames.add("25"); - DescriptionElemNames.add("26"); - DescriptionElemNames.add("27"); - DescriptionElemNames.add("28"); - DescriptionElemNames.add("29"); - DescriptionElemNames.add("30"); - DescriptionElemNames.add("31"); - DescriptionElemNames.add("32"); - DescriptionElemNames.add("33"); - DescriptionElemNames.add("34"); - DescriptionElemNames.add("35"); - DescriptionElemNames.add("36"); - DescriptionElemNames.add("37"); - DescriptionElemNames.add("38"); - DescriptionElemNames.add("39"); - fields.add( new UAVObjectField("Description", "", UAVObjectField.FieldType.UINT8, DescriptionElemNames, null) ); - - List CPUSerialElemNames = new ArrayList(); - CPUSerialElemNames.add("0"); - CPUSerialElemNames.add("1"); - CPUSerialElemNames.add("2"); - CPUSerialElemNames.add("3"); - CPUSerialElemNames.add("4"); - CPUSerialElemNames.add("5"); - CPUSerialElemNames.add("6"); - CPUSerialElemNames.add("7"); - CPUSerialElemNames.add("8"); - CPUSerialElemNames.add("9"); - CPUSerialElemNames.add("10"); - CPUSerialElemNames.add("11"); - fields.add( new UAVObjectField("CPUSerial", "", UAVObjectField.FieldType.UINT8, CPUSerialElemNames, null) ); - - List BoardTypeElemNames = new ArrayList(); - BoardTypeElemNames.add("0"); - fields.add( new UAVObjectField("BoardType", "", UAVObjectField.FieldType.UINT8, BoardTypeElemNames, null) ); - - List FrequencyBandElemNames = new ArrayList(); - FrequencyBandElemNames.add("0"); - fields.add( new UAVObjectField("FrequencyBand", "", UAVObjectField.FieldType.UINT8, FrequencyBandElemNames, null) ); - - List RSSIElemNames = new ArrayList(); - RSSIElemNames.add("0"); - fields.add( new UAVObjectField("RSSI", "dBm", UAVObjectField.FieldType.INT8, RSSIElemNames, null) ); - - List LinkStateElemNames = new ArrayList(); - LinkStateElemNames.add("0"); - List LinkStateEnumOptions = new ArrayList(); - LinkStateEnumOptions.add("Disconnected"); - LinkStateEnumOptions.add("Connecting"); - LinkStateEnumOptions.add("Connected"); - fields.add( new UAVObjectField("LinkState", "function", UAVObjectField.FieldType.ENUM, LinkStateElemNames, LinkStateEnumOptions) ); - - List PairSignalStrengthsElemNames = new ArrayList(); - PairSignalStrengthsElemNames.add("0"); - PairSignalStrengthsElemNames.add("1"); - PairSignalStrengthsElemNames.add("2"); - PairSignalStrengthsElemNames.add("3"); - fields.add( new UAVObjectField("PairSignalStrengths", "dBm", UAVObjectField.FieldType.INT8, PairSignalStrengthsElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READONLY) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 0; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 1000; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("MinFrequency").setValue(0); - getField("MaxFrequency").setValue(0); - getField("FrequencyStepSize").setValue(0); - getField("DeviceID").setValue(0); - getField("AFC").setValue(0); - getField("PairIDs").setValue(0,0); - getField("PairIDs").setValue(0,1); - getField("PairIDs").setValue(0,2); - getField("PairIDs").setValue(0,3); - getField("Retries").setValue(0); - getField("Errors").setValue(0); - getField("UAVTalkErrors").setValue(0); - getField("Dropped").setValue(0); - getField("Resets").setValue(0); - getField("TXRate").setValue(0); - getField("RXRate").setValue(0); - getField("FrequencyBand").setValue(0); - getField("RSSI").setValue(0); - getField("LinkState").setValue("Disconnected"); - getField("PairSignalStrengths").setValue(-127,0); - getField("PairSignalStrengths").setValue(-127,1); - getField("PairSignalStrengths").setValue(-127,2); - getField("PairSignalStrengths").setValue(-127,3); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - PipXStatus obj = new PipXStatus(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public PipXStatus GetInstance(UAVObjectManager objMngr, long instID) - { - return (PipXStatus)(objMngr.getObject(PipXStatus.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x3FC68A86l; - protected static final String NAME = "PipXStatus"; - protected static String DESCRIPTION = "PipXtreme device status."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java deleted file mode 100644 index bf8837ae9..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionActual.java +++ /dev/null @@ -1,146 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Contains the current position relative to @ref HomeLocation - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Contains the current position relative to @ref HomeLocation - -generated from positionactual.xml - **/ -public class PositionActual extends UAVDataObject { - - public PositionActual() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List NorthElemNames = new ArrayList(); - NorthElemNames.add("0"); - fields.add( new UAVObjectField("North", "m", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); - - List EastElemNames = new ArrayList(); - EastElemNames.add("0"); - fields.add( new UAVObjectField("East", "m", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); - - List DownElemNames = new ArrayList(); - DownElemNames.add("0"); - fields.add( new UAVObjectField("Down", "m", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 1000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 1000; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - PositionActual obj = new PositionActual(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public PositionActual GetInstance(UAVObjectManager objMngr, long instID) - { - return (PositionActual)(objMngr.getObject(PositionActual.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0xFA9E2D42l; - protected static final String NAME = "PositionActual"; - protected static String DESCRIPTION = "Contains the current position relative to @ref HomeLocation"; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java deleted file mode 100644 index 967e298e6..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/PositionDesired.java +++ /dev/null @@ -1,146 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * The position the craft is trying t achieve. Can come from GCS or @ref PathPlanner - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -The position the craft is trying t achieve. Can come from GCS or @ref PathPlanner - -generated from positiondesired.xml - **/ -public class PositionDesired extends UAVDataObject { - - public PositionDesired() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List NorthElemNames = new ArrayList(); - NorthElemNames.add("0"); - fields.add( new UAVObjectField("North", "m", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); - - List EastElemNames = new ArrayList(); - EastElemNames.add("0"); - fields.add( new UAVObjectField("East", "m", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); - - List DownElemNames = new ArrayList(); - DownElemNames.add("0"); - fields.add( new UAVObjectField("Down", "m", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 0; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 1000; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - PositionDesired obj = new PositionDesired(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public PositionDesired GetInstance(UAVObjectManager objMngr, long instID) - { - return (PositionDesired)(objMngr.getObject(PositionDesired.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x778DBE24l; - protected static final String NAME = "PositionDesired"; - protected static String DESCRIPTION = "The position the craft is trying t achieve. Can come from GCS or @ref PathPlanner "; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java deleted file mode 100644 index b15d368a0..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/RateDesired.java +++ /dev/null @@ -1,146 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Status for the matrix mixer showing the output of each mixer after all scaling - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Status for the matrix mixer showing the output of each mixer after all scaling - -generated from ratedesired.xml - **/ -public class RateDesired extends UAVDataObject { - - public RateDesired() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List RollElemNames = new ArrayList(); - RollElemNames.add("0"); - fields.add( new UAVObjectField("Roll", "deg/s", UAVObjectField.FieldType.FLOAT32, RollElemNames, null) ); - - List PitchElemNames = new ArrayList(); - PitchElemNames.add("0"); - fields.add( new UAVObjectField("Pitch", "deg/s", UAVObjectField.FieldType.FLOAT32, PitchElemNames, null) ); - - List YawElemNames = new ArrayList(); - YawElemNames.add("0"); - fields.add( new UAVObjectField("Yaw", "deg/s", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 1000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 1000; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - RateDesired obj = new RateDesired(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public RateDesired GetInstance(UAVObjectManager objMngr, long instID) - { - return (RateDesired)(objMngr.getObject(RateDesired.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0xCE8C826l; - protected static final String NAME = "RateDesired"; - protected static String DESCRIPTION = "Status for the matrix mixer showing the output of each mixer after all scaling"; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ReceiverActivity.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/ReceiverActivity.java deleted file mode 100644 index 4928d0913..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/ReceiverActivity.java +++ /dev/null @@ -1,152 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Monitors which receiver channels have been active within the last second. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Monitors which receiver channels have been active within the last second. - -generated from receiveractivity.xml - **/ -public class ReceiverActivity extends UAVDataObject { - - public ReceiverActivity() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List ActiveGroupElemNames = new ArrayList(); - ActiveGroupElemNames.add("0"); - List ActiveGroupEnumOptions = new ArrayList(); - ActiveGroupEnumOptions.add("PWM"); - ActiveGroupEnumOptions.add("PPM"); - ActiveGroupEnumOptions.add("DSM (MainPort)"); - ActiveGroupEnumOptions.add("DSM (FlexiPort)"); - ActiveGroupEnumOptions.add("S.Bus"); - ActiveGroupEnumOptions.add("GCS"); - ActiveGroupEnumOptions.add("None"); - fields.add( new UAVObjectField("ActiveGroup", "Channel Group", UAVObjectField.FieldType.ENUM, ActiveGroupElemNames, ActiveGroupEnumOptions) ); - - List ActiveChannelElemNames = new ArrayList(); - ActiveChannelElemNames.add("0"); - fields.add( new UAVObjectField("ActiveChannel", "channel", UAVObjectField.FieldType.UINT8, ActiveChannelElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READONLY) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 0; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("ActiveGroup").setValue("None"); - getField("ActiveChannel").setValue(255); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - ReceiverActivity obj = new ReceiverActivity(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public ReceiverActivity GetInstance(UAVObjectManager objMngr, long instID) - { - return (ReceiverActivity)(objMngr.getObject(ReceiverActivity.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x1E7C53DAl; - protected static final String NAME = "ReceiverActivity"; - protected static String DESCRIPTION = "Monitors which receiver channels have been active within the last second."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/RelayTuning.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RelayTuning.java deleted file mode 100644 index 741e024a7..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/RelayTuning.java +++ /dev/null @@ -1,146 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * The input to the relay tuning. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -The input to the relay tuning. - -generated from relaytuning.xml - **/ -public class RelayTuning extends UAVDataObject { - - public RelayTuning() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List PeriodElemNames = new ArrayList(); - PeriodElemNames.add("Roll"); - PeriodElemNames.add("Pitch"); - PeriodElemNames.add("Yaw"); - fields.add( new UAVObjectField("Period", "ms", UAVObjectField.FieldType.FLOAT32, PeriodElemNames, null) ); - - List GainElemNames = new ArrayList(); - GainElemNames.add("Roll"); - GainElemNames.add("Pitch"); - GainElemNames.add("Yaw"); - fields.add( new UAVObjectField("Gain", "(deg/s)/output", UAVObjectField.FieldType.FLOAT32, GainElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 1000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - RelayTuning obj = new RelayTuning(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public RelayTuning GetInstance(UAVObjectManager objMngr, long instID) - { - return (RelayTuning)(objMngr.getObject(RelayTuning.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0xF6EE61BEl; - protected static final String NAME = "RelayTuning"; - protected static String DESCRIPTION = "The input to the relay tuning."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/RelayTuningSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RelayTuningSettings.java deleted file mode 100644 index 9dfa78654..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/RelayTuningSettings.java +++ /dev/null @@ -1,171 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Setting to run a relay tuning algorithm - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Setting to run a relay tuning algorithm - -generated from relaytuningsettings.xml - **/ -public class RelayTuningSettings extends UAVDataObject { - - public RelayTuningSettings() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List RateGainElemNames = new ArrayList(); - RateGainElemNames.add("0"); - fields.add( new UAVObjectField("RateGain", "", UAVObjectField.FieldType.FLOAT32, RateGainElemNames, null) ); - - List AttitudeGainElemNames = new ArrayList(); - AttitudeGainElemNames.add("0"); - fields.add( new UAVObjectField("AttitudeGain", "", UAVObjectField.FieldType.FLOAT32, AttitudeGainElemNames, null) ); - - List AmplitudeElemNames = new ArrayList(); - AmplitudeElemNames.add("0"); - fields.add( new UAVObjectField("Amplitude", "", UAVObjectField.FieldType.FLOAT32, AmplitudeElemNames, null) ); - - List HysteresisThreshElemNames = new ArrayList(); - HysteresisThreshElemNames.add("0"); - fields.add( new UAVObjectField("HysteresisThresh", "deg/s", UAVObjectField.FieldType.UINT8, HysteresisThreshElemNames, null) ); - - List ModeElemNames = new ArrayList(); - ModeElemNames.add("0"); - List ModeEnumOptions = new ArrayList(); - ModeEnumOptions.add("Rate"); - ModeEnumOptions.add("Attitude"); - fields.add( new UAVObjectField("Mode", "", UAVObjectField.FieldType.ENUM, ModeElemNames, ModeEnumOptions) ); - - List BehaviorElemNames = new ArrayList(); - BehaviorElemNames.add("0"); - List BehaviorEnumOptions = new ArrayList(); - BehaviorEnumOptions.add("Measure"); - BehaviorEnumOptions.add("Compute"); - BehaviorEnumOptions.add("Save"); - fields.add( new UAVObjectField("Behavior", "", UAVObjectField.FieldType.ENUM, BehaviorElemNames, BehaviorEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 0; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("RateGain").setValue(0.3333); - getField("AttitudeGain").setValue(0.2); - getField("Amplitude").setValue(0.25); - getField("HysteresisThresh").setValue(5); - getField("Mode").setValue("Attitude"); - getField("Behavior").setValue("Compute"); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - RelayTuningSettings obj = new RelayTuningSettings(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public RelayTuningSettings GetInstance(UAVObjectManager objMngr, long instID) - { - return (RelayTuningSettings)(objMngr.getObject(RelayTuningSettings.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0xEA358166l; - protected static final String NAME = "RelayTuningSettings"; - protected static String DESCRIPTION = "Setting to run a relay tuning algorithm"; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 1 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/RevoCalibration.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RevoCalibration.java deleted file mode 100644 index 41ce4a4b6..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/RevoCalibration.java +++ /dev/null @@ -1,232 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Settings for the INS to control the algorithm and what is updated - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Settings for the INS to control the algorithm and what is updated - -generated from revocalibration.xml - **/ -public class RevoCalibration extends UAVDataObject { - - public RevoCalibration() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List accel_biasElemNames = new ArrayList(); - accel_biasElemNames.add("X"); - accel_biasElemNames.add("Y"); - accel_biasElemNames.add("Z"); - fields.add( new UAVObjectField("accel_bias", "m/s", UAVObjectField.FieldType.FLOAT32, accel_biasElemNames, null) ); - - List accel_scaleElemNames = new ArrayList(); - accel_scaleElemNames.add("X"); - accel_scaleElemNames.add("Y"); - accel_scaleElemNames.add("Z"); - fields.add( new UAVObjectField("accel_scale", "gain", UAVObjectField.FieldType.FLOAT32, accel_scaleElemNames, null) ); - - List accel_varElemNames = new ArrayList(); - accel_varElemNames.add("X"); - accel_varElemNames.add("Y"); - accel_varElemNames.add("Z"); - fields.add( new UAVObjectField("accel_var", "(m/s)^2", UAVObjectField.FieldType.FLOAT32, accel_varElemNames, null) ); - - List gyro_biasElemNames = new ArrayList(); - gyro_biasElemNames.add("X"); - gyro_biasElemNames.add("Y"); - gyro_biasElemNames.add("Z"); - fields.add( new UAVObjectField("gyro_bias", "deg/s", UAVObjectField.FieldType.FLOAT32, gyro_biasElemNames, null) ); - - List gyro_scaleElemNames = new ArrayList(); - gyro_scaleElemNames.add("X"); - gyro_scaleElemNames.add("Y"); - gyro_scaleElemNames.add("Z"); - fields.add( new UAVObjectField("gyro_scale", "gain", UAVObjectField.FieldType.FLOAT32, gyro_scaleElemNames, null) ); - - List gyro_varElemNames = new ArrayList(); - gyro_varElemNames.add("X"); - gyro_varElemNames.add("Y"); - gyro_varElemNames.add("Z"); - fields.add( new UAVObjectField("gyro_var", "(deg/s)^2", UAVObjectField.FieldType.FLOAT32, gyro_varElemNames, null) ); - - List gyro_tempcoeffElemNames = new ArrayList(); - gyro_tempcoeffElemNames.add("X"); - gyro_tempcoeffElemNames.add("Y"); - gyro_tempcoeffElemNames.add("Z"); - fields.add( new UAVObjectField("gyro_tempcoeff", "(deg/s)/deg", UAVObjectField.FieldType.FLOAT32, gyro_tempcoeffElemNames, null) ); - - List mag_biasElemNames = new ArrayList(); - mag_biasElemNames.add("X"); - mag_biasElemNames.add("Y"); - mag_biasElemNames.add("Z"); - fields.add( new UAVObjectField("mag_bias", "mGau", UAVObjectField.FieldType.FLOAT32, mag_biasElemNames, null) ); - - List mag_scaleElemNames = new ArrayList(); - mag_scaleElemNames.add("X"); - mag_scaleElemNames.add("Y"); - mag_scaleElemNames.add("Z"); - fields.add( new UAVObjectField("mag_scale", "gain", UAVObjectField.FieldType.FLOAT32, mag_scaleElemNames, null) ); - - List mag_varElemNames = new ArrayList(); - mag_varElemNames.add("X"); - mag_varElemNames.add("Y"); - mag_varElemNames.add("Z"); - fields.add( new UAVObjectField("mag_var", "mGau^2", UAVObjectField.FieldType.FLOAT32, mag_varElemNames, null) ); - - List BiasCorrectedRawElemNames = new ArrayList(); - BiasCorrectedRawElemNames.add("0"); - List BiasCorrectedRawEnumOptions = new ArrayList(); - BiasCorrectedRawEnumOptions.add("TRUE"); - BiasCorrectedRawEnumOptions.add("FALSE"); - fields.add( new UAVObjectField("BiasCorrectedRaw", "", UAVObjectField.FieldType.ENUM, BiasCorrectedRawElemNames, BiasCorrectedRawEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 0; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("accel_bias").setValue(0,0); - getField("accel_bias").setValue(0,1); - getField("accel_bias").setValue(0,2); - getField("accel_scale").setValue(1,0); - getField("accel_scale").setValue(1,1); - getField("accel_scale").setValue(1,2); - getField("accel_var").setValue(1,0); - getField("accel_var").setValue(1,1); - getField("accel_var").setValue(1,2); - getField("gyro_bias").setValue(0,0); - getField("gyro_bias").setValue(0,1); - getField("gyro_bias").setValue(0,2); - getField("gyro_scale").setValue(1,0); - getField("gyro_scale").setValue(1,1); - getField("gyro_scale").setValue(1,2); - getField("gyro_var").setValue(1,0); - getField("gyro_var").setValue(1,1); - getField("gyro_var").setValue(1,2); - getField("gyro_tempcoeff").setValue(1,0); - getField("gyro_tempcoeff").setValue(1,1); - getField("gyro_tempcoeff").setValue(1,2); - getField("mag_bias").setValue(0,0); - getField("mag_bias").setValue(0,1); - getField("mag_bias").setValue(0,2); - getField("mag_scale").setValue(1,0); - getField("mag_scale").setValue(1,1); - getField("mag_scale").setValue(1,2); - getField("mag_var").setValue(50,0); - getField("mag_var").setValue(50,1); - getField("mag_var").setValue(50,2); - getField("BiasCorrectedRaw").setValue("TRUE"); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - RevoCalibration obj = new RevoCalibration(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public RevoCalibration GetInstance(UAVObjectManager objMngr, long instID) - { - return (RevoCalibration)(objMngr.getObject(RevoCalibration.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0xC26D37B2l; - protected static final String NAME = "RevoCalibration"; - protected static String DESCRIPTION = "Settings for the INS to control the algorithm and what is updated"; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 1 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/RevoSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/RevoSettings.java deleted file mode 100644 index 0147f72c1..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/RevoSettings.java +++ /dev/null @@ -1,143 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Settings for the revo to control the algorithm and what is updated - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Settings for the revo to control the algorithm and what is updated - -generated from revosettings.xml - **/ -public class RevoSettings extends UAVDataObject { - - public RevoSettings() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List FusionAlgorithmElemNames = new ArrayList(); - FusionAlgorithmElemNames.add("0"); - List FusionAlgorithmEnumOptions = new ArrayList(); - FusionAlgorithmEnumOptions.add("Complimentary"); - FusionAlgorithmEnumOptions.add("INSIndoor"); - FusionAlgorithmEnumOptions.add("INSOutdoor"); - fields.add( new UAVObjectField("FusionAlgorithm", "", UAVObjectField.FieldType.ENUM, FusionAlgorithmElemNames, FusionAlgorithmEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 0; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("FusionAlgorithm").setValue("Complimentary"); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - RevoSettings obj = new RevoSettings(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public RevoSettings GetInstance(UAVObjectManager objMngr, long instID) - { - return (RevoSettings)(objMngr.getObject(RevoSettings.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0xE2DA70EAl; - protected static final String NAME = "RevoSettings"; - protected static String DESCRIPTION = "Settings for the revo to control the algorithm and what is updated"; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 1 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java deleted file mode 100644 index 00a711775..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SonarAltitude.java +++ /dev/null @@ -1,138 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * The raw data from the ultrasound sonar sensor with altitude estimate. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -The raw data from the ultrasound sonar sensor with altitude estimate. - -generated from sonaraltitude.xml - **/ -public class SonarAltitude extends UAVDataObject { - - public SonarAltitude() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List AltitudeElemNames = new ArrayList(); - AltitudeElemNames.add("0"); - fields.add( new UAVObjectField("Altitude", "m", UAVObjectField.FieldType.FLOAT32, AltitudeElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 1000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - SonarAltitude obj = new SonarAltitude(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public SonarAltitude GetInstance(UAVObjectManager objMngr, long instID) - { - return (SonarAltitude)(objMngr.getObject(SonarAltitude.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x6C5A0CBCl; - protected static final String NAME = "SonarAltitude"; - protected static String DESCRIPTION = "The raw data from the ultrasound sonar sensor with altitude estimate."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java deleted file mode 100644 index 31ca2e901..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationDesired.java +++ /dev/null @@ -1,165 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * The desired attitude that @ref StabilizationModule will try and achieve if FlightMode is Stabilized. Comes from @ref ManaulControlModule. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -The desired attitude that @ref StabilizationModule will try and achieve if FlightMode is Stabilized. Comes from @ref ManaulControlModule. - -generated from stabilizationdesired.xml - **/ -public class StabilizationDesired extends UAVDataObject { - - public StabilizationDesired() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List RollElemNames = new ArrayList(); - RollElemNames.add("0"); - fields.add( new UAVObjectField("Roll", "degrees", UAVObjectField.FieldType.FLOAT32, RollElemNames, null) ); - - List PitchElemNames = new ArrayList(); - PitchElemNames.add("0"); - fields.add( new UAVObjectField("Pitch", "degrees", UAVObjectField.FieldType.FLOAT32, PitchElemNames, null) ); - - List YawElemNames = new ArrayList(); - YawElemNames.add("0"); - fields.add( new UAVObjectField("Yaw", "degrees", UAVObjectField.FieldType.FLOAT32, YawElemNames, null) ); - - List ThrottleElemNames = new ArrayList(); - ThrottleElemNames.add("0"); - fields.add( new UAVObjectField("Throttle", "%", UAVObjectField.FieldType.FLOAT32, ThrottleElemNames, null) ); - - List StabilizationModeElemNames = new ArrayList(); - StabilizationModeElemNames.add("Roll"); - StabilizationModeElemNames.add("Pitch"); - StabilizationModeElemNames.add("Yaw"); - List StabilizationModeEnumOptions = new ArrayList(); - StabilizationModeEnumOptions.add("None"); - StabilizationModeEnumOptions.add("Rate"); - StabilizationModeEnumOptions.add("Attitude"); - StabilizationModeEnumOptions.add("AxisLock"); - StabilizationModeEnumOptions.add("WeakLeveling"); - StabilizationModeEnumOptions.add("VirtualBar"); - StabilizationModeEnumOptions.add("RelayRate"); - StabilizationModeEnumOptions.add("RelayAttitude"); - fields.add( new UAVObjectField("StabilizationMode", "", UAVObjectField.FieldType.ENUM, StabilizationModeElemNames, StabilizationModeEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 1000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - StabilizationDesired obj = new StabilizationDesired(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public StabilizationDesired GetInstance(UAVObjectManager objMngr, long instID) - { - return (StabilizationDesired)(objMngr.getObject(StabilizationDesired.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x4FDBFEEAl; - protected static final String NAME = "StabilizationDesired"; - protected static String DESCRIPTION = "The desired attitude that @ref StabilizationModule will try and achieve if FlightMode is Stabilized. Comes from @ref ManaulControlModule."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java deleted file mode 100644 index 99cfcd830..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/StabilizationSettings.java +++ /dev/null @@ -1,323 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * PID settings used by the Stabilization module to combine the @ref AttitudeActual and @ref AttitudeDesired to compute @ref ActuatorDesired - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -PID settings used by the Stabilization module to combine the @ref AttitudeActual and @ref AttitudeDesired to compute @ref ActuatorDesired - -generated from stabilizationsettings.xml - **/ -public class StabilizationSettings extends UAVDataObject { - - public StabilizationSettings() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List ManualRateElemNames = new ArrayList(); - ManualRateElemNames.add("Roll"); - ManualRateElemNames.add("Pitch"); - ManualRateElemNames.add("Yaw"); - fields.add( new UAVObjectField("ManualRate", "degrees/sec", UAVObjectField.FieldType.FLOAT32, ManualRateElemNames, null) ); - - List MaximumRateElemNames = new ArrayList(); - MaximumRateElemNames.add("Roll"); - MaximumRateElemNames.add("Pitch"); - MaximumRateElemNames.add("Yaw"); - fields.add( new UAVObjectField("MaximumRate", "degrees/sec", UAVObjectField.FieldType.FLOAT32, MaximumRateElemNames, null) ); - - List RollRatePIDElemNames = new ArrayList(); - RollRatePIDElemNames.add("Kp"); - RollRatePIDElemNames.add("Ki"); - RollRatePIDElemNames.add("Kd"); - RollRatePIDElemNames.add("ILimit"); - fields.add( new UAVObjectField("RollRatePID", "", UAVObjectField.FieldType.FLOAT32, RollRatePIDElemNames, null) ); - - List PitchRatePIDElemNames = new ArrayList(); - PitchRatePIDElemNames.add("Kp"); - PitchRatePIDElemNames.add("Ki"); - PitchRatePIDElemNames.add("Kd"); - PitchRatePIDElemNames.add("ILimit"); - fields.add( new UAVObjectField("PitchRatePID", "", UAVObjectField.FieldType.FLOAT32, PitchRatePIDElemNames, null) ); - - List YawRatePIDElemNames = new ArrayList(); - YawRatePIDElemNames.add("Kp"); - YawRatePIDElemNames.add("Ki"); - YawRatePIDElemNames.add("Kd"); - YawRatePIDElemNames.add("ILimit"); - fields.add( new UAVObjectField("YawRatePID", "", UAVObjectField.FieldType.FLOAT32, YawRatePIDElemNames, null) ); - - List RollPIElemNames = new ArrayList(); - RollPIElemNames.add("Kp"); - RollPIElemNames.add("Ki"); - RollPIElemNames.add("ILimit"); - fields.add( new UAVObjectField("RollPI", "", UAVObjectField.FieldType.FLOAT32, RollPIElemNames, null) ); - - List PitchPIElemNames = new ArrayList(); - PitchPIElemNames.add("Kp"); - PitchPIElemNames.add("Ki"); - PitchPIElemNames.add("ILimit"); - fields.add( new UAVObjectField("PitchPI", "", UAVObjectField.FieldType.FLOAT32, PitchPIElemNames, null) ); - - List YawPIElemNames = new ArrayList(); - YawPIElemNames.add("Kp"); - YawPIElemNames.add("Ki"); - YawPIElemNames.add("ILimit"); - fields.add( new UAVObjectField("YawPI", "", UAVObjectField.FieldType.FLOAT32, YawPIElemNames, null) ); - - List VbarSensitivityElemNames = new ArrayList(); - VbarSensitivityElemNames.add("Roll"); - VbarSensitivityElemNames.add("Pitch"); - VbarSensitivityElemNames.add("Yaw"); - fields.add( new UAVObjectField("VbarSensitivity", "frac", UAVObjectField.FieldType.FLOAT32, VbarSensitivityElemNames, null) ); - - List VbarRollPIElemNames = new ArrayList(); - VbarRollPIElemNames.add("Kp"); - VbarRollPIElemNames.add("Ki"); - fields.add( new UAVObjectField("VbarRollPI", "1/(deg/s)", UAVObjectField.FieldType.FLOAT32, VbarRollPIElemNames, null) ); - - List VbarPitchPIElemNames = new ArrayList(); - VbarPitchPIElemNames.add("Kp"); - VbarPitchPIElemNames.add("Ki"); - fields.add( new UAVObjectField("VbarPitchPI", "1/(deg/s)", UAVObjectField.FieldType.FLOAT32, VbarPitchPIElemNames, null) ); - - List VbarYawPIElemNames = new ArrayList(); - VbarYawPIElemNames.add("Kp"); - VbarYawPIElemNames.add("Ki"); - fields.add( new UAVObjectField("VbarYawPI", "1/(deg/s)", UAVObjectField.FieldType.FLOAT32, VbarYawPIElemNames, null) ); - - List VbarTauElemNames = new ArrayList(); - VbarTauElemNames.add("0"); - fields.add( new UAVObjectField("VbarTau", "sec", UAVObjectField.FieldType.FLOAT32, VbarTauElemNames, null) ); - - List GyroTauElemNames = new ArrayList(); - GyroTauElemNames.add("0"); - fields.add( new UAVObjectField("GyroTau", "", UAVObjectField.FieldType.FLOAT32, GyroTauElemNames, null) ); - - List DerivativeGammaElemNames = new ArrayList(); - DerivativeGammaElemNames.add("0"); - fields.add( new UAVObjectField("DerivativeGamma", "", UAVObjectField.FieldType.FLOAT32, DerivativeGammaElemNames, null) ); - - List WeakLevelingKpElemNames = new ArrayList(); - WeakLevelingKpElemNames.add("0"); - fields.add( new UAVObjectField("WeakLevelingKp", "(deg/s)/deg", UAVObjectField.FieldType.FLOAT32, WeakLevelingKpElemNames, null) ); - - List RollMaxElemNames = new ArrayList(); - RollMaxElemNames.add("0"); - fields.add( new UAVObjectField("RollMax", "degrees", UAVObjectField.FieldType.UINT8, RollMaxElemNames, null) ); - - List PitchMaxElemNames = new ArrayList(); - PitchMaxElemNames.add("0"); - fields.add( new UAVObjectField("PitchMax", "degrees", UAVObjectField.FieldType.UINT8, PitchMaxElemNames, null) ); - - List YawMaxElemNames = new ArrayList(); - YawMaxElemNames.add("0"); - fields.add( new UAVObjectField("YawMax", "degrees", UAVObjectField.FieldType.UINT8, YawMaxElemNames, null) ); - - List VbarGyroSuppressElemNames = new ArrayList(); - VbarGyroSuppressElemNames.add("0"); - fields.add( new UAVObjectField("VbarGyroSuppress", "%", UAVObjectField.FieldType.INT8, VbarGyroSuppressElemNames, null) ); - - List VbarPiroCompElemNames = new ArrayList(); - VbarPiroCompElemNames.add("0"); - List VbarPiroCompEnumOptions = new ArrayList(); - VbarPiroCompEnumOptions.add("FALSE"); - VbarPiroCompEnumOptions.add("TRUE"); - fields.add( new UAVObjectField("VbarPiroComp", "", UAVObjectField.FieldType.ENUM, VbarPiroCompElemNames, VbarPiroCompEnumOptions) ); - - List VbarMaxAngleElemNames = new ArrayList(); - VbarMaxAngleElemNames.add("0"); - fields.add( new UAVObjectField("VbarMaxAngle", "deg", UAVObjectField.FieldType.UINT8, VbarMaxAngleElemNames, null) ); - - List DerivativeCutoffElemNames = new ArrayList(); - DerivativeCutoffElemNames.add("0"); - fields.add( new UAVObjectField("DerivativeCutoff", "Hz", UAVObjectField.FieldType.UINT8, DerivativeCutoffElemNames, null) ); - - List MaxAxisLockElemNames = new ArrayList(); - MaxAxisLockElemNames.add("0"); - fields.add( new UAVObjectField("MaxAxisLock", "deg", UAVObjectField.FieldType.UINT8, MaxAxisLockElemNames, null) ); - - List MaxAxisLockRateElemNames = new ArrayList(); - MaxAxisLockRateElemNames.add("0"); - fields.add( new UAVObjectField("MaxAxisLockRate", "deg/s", UAVObjectField.FieldType.UINT8, MaxAxisLockRateElemNames, null) ); - - List MaxWeakLevelingRateElemNames = new ArrayList(); - MaxWeakLevelingRateElemNames.add("0"); - fields.add( new UAVObjectField("MaxWeakLevelingRate", "deg/s", UAVObjectField.FieldType.UINT8, MaxWeakLevelingRateElemNames, null) ); - - List LowThrottleZeroIntegralElemNames = new ArrayList(); - LowThrottleZeroIntegralElemNames.add("0"); - List LowThrottleZeroIntegralEnumOptions = new ArrayList(); - LowThrottleZeroIntegralEnumOptions.add("FALSE"); - LowThrottleZeroIntegralEnumOptions.add("TRUE"); - fields.add( new UAVObjectField("LowThrottleZeroIntegral", "", UAVObjectField.FieldType.ENUM, LowThrottleZeroIntegralElemNames, LowThrottleZeroIntegralEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 0; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("ManualRate").setValue(150,0); - getField("ManualRate").setValue(150,1); - getField("ManualRate").setValue(150,2); - getField("MaximumRate").setValue(300,0); - getField("MaximumRate").setValue(300,1); - getField("MaximumRate").setValue(300,2); - getField("RollRatePID").setValue(0.002,0); - getField("RollRatePID").setValue(0,1); - getField("RollRatePID").setValue(0,2); - getField("RollRatePID").setValue(0.3,3); - getField("PitchRatePID").setValue(0.002,0); - getField("PitchRatePID").setValue(0,1); - getField("PitchRatePID").setValue(0,2); - getField("PitchRatePID").setValue(0.3,3); - getField("YawRatePID").setValue(0.0035,0); - getField("YawRatePID").setValue(0.0035,1); - getField("YawRatePID").setValue(0,2); - getField("YawRatePID").setValue(0.3,3); - getField("RollPI").setValue(2,0); - getField("RollPI").setValue(0,1); - getField("RollPI").setValue(50,2); - getField("PitchPI").setValue(2,0); - getField("PitchPI").setValue(0,1); - getField("PitchPI").setValue(50,2); - getField("YawPI").setValue(2,0); - getField("YawPI").setValue(0,1); - getField("YawPI").setValue(50,2); - getField("VbarSensitivity").setValue(0.5,0); - getField("VbarSensitivity").setValue(0.5,1); - getField("VbarSensitivity").setValue(0.5,2); - getField("VbarRollPI").setValue(0.005,0); - getField("VbarRollPI").setValue(0.002,1); - getField("VbarPitchPI").setValue(0.005,0); - getField("VbarPitchPI").setValue(0.002,1); - getField("VbarYawPI").setValue(0.005,0); - getField("VbarYawPI").setValue(0.002,1); - getField("VbarTau").setValue(0.5); - getField("GyroTau").setValue(0.005); - getField("DerivativeGamma").setValue(1); - getField("WeakLevelingKp").setValue(0.1); - getField("RollMax").setValue(55); - getField("PitchMax").setValue(55); - getField("YawMax").setValue(35); - getField("VbarGyroSuppress").setValue(30); - getField("VbarPiroComp").setValue("FALSE"); - getField("VbarMaxAngle").setValue(10); - getField("DerivativeCutoff").setValue(20); - getField("MaxAxisLock").setValue(15); - getField("MaxAxisLockRate").setValue(2); - getField("MaxWeakLevelingRate").setValue(5); - getField("LowThrottleZeroIntegral").setValue("TRUE"); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - StabilizationSettings obj = new StabilizationSettings(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public StabilizationSettings GetInstance(UAVObjectManager objMngr, long instID) - { - return (StabilizationSettings)(objMngr.getObject(StabilizationSettings.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x3D03DE86l; - protected static final String NAME = "StabilizationSettings"; - protected static String DESCRIPTION = "PID settings used by the Stabilization module to combine the @ref AttitudeActual and @ref AttitudeDesired to compute @ref ActuatorDesired"; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 1 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java deleted file mode 100644 index bb5d098a4..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemAlarms.java +++ /dev/null @@ -1,175 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules. - -generated from systemalarms.xml - **/ -public class SystemAlarms extends UAVDataObject { - - public SystemAlarms() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List AlarmElemNames = new ArrayList(); - AlarmElemNames.add("OutOfMemory"); - AlarmElemNames.add("StackOverflow"); - AlarmElemNames.add("CPUOverload"); - AlarmElemNames.add("EventSystem"); - AlarmElemNames.add("Telemetry"); - AlarmElemNames.add("ManualControl"); - AlarmElemNames.add("Actuator"); - AlarmElemNames.add("Attitude"); - AlarmElemNames.add("Sensors"); - AlarmElemNames.add("Stabilization"); - AlarmElemNames.add("Guidance"); - AlarmElemNames.add("Battery"); - AlarmElemNames.add("FlightTime"); - AlarmElemNames.add("I2C"); - AlarmElemNames.add("GPS"); - AlarmElemNames.add("BootFault"); - List AlarmEnumOptions = new ArrayList(); - AlarmEnumOptions.add("Uninitialised"); - AlarmEnumOptions.add("OK"); - AlarmEnumOptions.add("Warning"); - AlarmEnumOptions.add("Error"); - AlarmEnumOptions.add("Critical"); - fields.add( new UAVObjectField("Alarm", "", UAVObjectField.FieldType.ENUM, AlarmElemNames, AlarmEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 0; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 1000; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("Alarm").setValue("Uninitialised",0); - getField("Alarm").setValue("Uninitialised",1); - getField("Alarm").setValue("Uninitialised",2); - getField("Alarm").setValue("Uninitialised",3); - getField("Alarm").setValue("Uninitialised",4); - getField("Alarm").setValue("Uninitialised",5); - getField("Alarm").setValue("Uninitialised",6); - getField("Alarm").setValue("Uninitialised",7); - getField("Alarm").setValue("Uninitialised",8); - getField("Alarm").setValue("Uninitialised",9); - getField("Alarm").setValue("Uninitialised",10); - getField("Alarm").setValue("Uninitialised",11); - getField("Alarm").setValue("Uninitialised",12); - getField("Alarm").setValue("Uninitialised",13); - getField("Alarm").setValue("Uninitialised",14); - getField("Alarm").setValue("Uninitialised",15); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - SystemAlarms obj = new SystemAlarms(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public SystemAlarms GetInstance(UAVObjectManager objMngr, long instID) - { - return (SystemAlarms)(objMngr.getObject(SystemAlarms.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x7BD9C77Al; - protected static final String NAME = "SystemAlarms"; - protected static String DESCRIPTION = "Alarms from OpenPilot to indicate failure conditions or warnings. Set by various modules."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java deleted file mode 100644 index aa4fad376..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemSettings.java +++ /dev/null @@ -1,170 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Select airframe type. Currently used by @ref ActuatorModule to choose mixing from @ref ActuatorDesired to @ref ActuatorCommand - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Select airframe type. Currently used by @ref ActuatorModule to choose mixing from @ref ActuatorDesired to @ref ActuatorCommand - -generated from systemsettings.xml - **/ -public class SystemSettings extends UAVDataObject { - - public SystemSettings() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List GUIConfigDataElemNames = new ArrayList(); - GUIConfigDataElemNames.add("0"); - GUIConfigDataElemNames.add("1"); - GUIConfigDataElemNames.add("2"); - GUIConfigDataElemNames.add("3"); - fields.add( new UAVObjectField("GUIConfigData", "bits", UAVObjectField.FieldType.UINT32, GUIConfigDataElemNames, null) ); - - List AirframeTypeElemNames = new ArrayList(); - AirframeTypeElemNames.add("0"); - List AirframeTypeEnumOptions = new ArrayList(); - AirframeTypeEnumOptions.add("FixedWing"); - AirframeTypeEnumOptions.add("FixedWingElevon"); - AirframeTypeEnumOptions.add("FixedWingVtail"); - AirframeTypeEnumOptions.add("VTOL"); - AirframeTypeEnumOptions.add("HeliCP"); - AirframeTypeEnumOptions.add("QuadX"); - AirframeTypeEnumOptions.add("QuadP"); - AirframeTypeEnumOptions.add("Hexa"); - AirframeTypeEnumOptions.add("Octo"); - AirframeTypeEnumOptions.add("Custom"); - AirframeTypeEnumOptions.add("HexaX"); - AirframeTypeEnumOptions.add("OctoV"); - AirframeTypeEnumOptions.add("OctoCoaxP"); - AirframeTypeEnumOptions.add("OctoCoaxX"); - AirframeTypeEnumOptions.add("HexaCoax"); - AirframeTypeEnumOptions.add("Tri"); - AirframeTypeEnumOptions.add("GroundVehicleCar"); - AirframeTypeEnumOptions.add("GroundVehicleDifferential"); - AirframeTypeEnumOptions.add("GroundVehicleMotorcycle"); - fields.add( new UAVObjectField("AirframeType", "", UAVObjectField.FieldType.ENUM, AirframeTypeElemNames, AirframeTypeEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 0; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("GUIConfigData").setValue(0,0); - getField("GUIConfigData").setValue(0,1); - getField("GUIConfigData").setValue(0,2); - getField("GUIConfigData").setValue(0,3); - getField("AirframeType").setValue("QuadX"); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - SystemSettings obj = new SystemSettings(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public SystemSettings GetInstance(UAVObjectManager objMngr, long instID) - { - return (SystemSettings)(objMngr.getObject(SystemSettings.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0xC72A326El; - protected static final String NAME = "SystemSettings"; - protected static String DESCRIPTION = "Select airframe type. Currently used by @ref ActuatorModule to choose mixing from @ref ActuatorDesired to @ref ActuatorCommand"; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 1 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java deleted file mode 100644 index 113bc8c25..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/SystemStats.java +++ /dev/null @@ -1,166 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * CPU and memory usage from OpenPilot computer. - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -CPU and memory usage from OpenPilot computer. - -generated from systemstats.xml - **/ -public class SystemStats extends UAVDataObject { - - public SystemStats() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List FlightTimeElemNames = new ArrayList(); - FlightTimeElemNames.add("0"); - fields.add( new UAVObjectField("FlightTime", "ms", UAVObjectField.FieldType.UINT32, FlightTimeElemNames, null) ); - - List EventSystemWarningIDElemNames = new ArrayList(); - EventSystemWarningIDElemNames.add("0"); - fields.add( new UAVObjectField("EventSystemWarningID", "uavoid", UAVObjectField.FieldType.UINT32, EventSystemWarningIDElemNames, null) ); - - List ObjectManagerCallbackIDElemNames = new ArrayList(); - ObjectManagerCallbackIDElemNames.add("0"); - fields.add( new UAVObjectField("ObjectManagerCallbackID", "uavoid", UAVObjectField.FieldType.UINT32, ObjectManagerCallbackIDElemNames, null) ); - - List ObjectManagerQueueIDElemNames = new ArrayList(); - ObjectManagerQueueIDElemNames.add("0"); - fields.add( new UAVObjectField("ObjectManagerQueueID", "uavoid", UAVObjectField.FieldType.UINT32, ObjectManagerQueueIDElemNames, null) ); - - List HeapRemainingElemNames = new ArrayList(); - HeapRemainingElemNames.add("0"); - fields.add( new UAVObjectField("HeapRemaining", "bytes", UAVObjectField.FieldType.UINT16, HeapRemainingElemNames, null) ); - - List IRQStackRemainingElemNames = new ArrayList(); - IRQStackRemainingElemNames.add("0"); - fields.add( new UAVObjectField("IRQStackRemaining", "bytes", UAVObjectField.FieldType.UINT16, IRQStackRemainingElemNames, null) ); - - List CPULoadElemNames = new ArrayList(); - CPULoadElemNames.add("0"); - fields.add( new UAVObjectField("CPULoad", "%", UAVObjectField.FieldType.UINT8, CPULoadElemNames, null) ); - - List CPUTempElemNames = new ArrayList(); - CPUTempElemNames.add("0"); - fields.add( new UAVObjectField("CPUTemp", "C", UAVObjectField.FieldType.INT8, CPUTempElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 1000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 1000; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - SystemStats obj = new SystemStats(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public SystemStats GetInstance(UAVObjectManager objMngr, long instID) - { - return (SystemStats)(objMngr.getObject(SystemStats.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x364D1406l; - protected static final String NAME = "SystemStats"; - protected static String DESCRIPTION = "CPU and memory usage from OpenPilot computer. "; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java deleted file mode 100644 index 8a62efc66..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TaskInfo.java +++ /dev/null @@ -1,203 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Task information - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Task information - -generated from taskinfo.xml - **/ -public class TaskInfo extends UAVDataObject { - - public TaskInfo() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List StackRemainingElemNames = new ArrayList(); - StackRemainingElemNames.add("System"); - StackRemainingElemNames.add("Actuator"); - StackRemainingElemNames.add("Attitude"); - StackRemainingElemNames.add("Sensors"); - StackRemainingElemNames.add("TelemetryTx"); - StackRemainingElemNames.add("TelemetryTxPri"); - StackRemainingElemNames.add("TelemetryRx"); - StackRemainingElemNames.add("GPS"); - StackRemainingElemNames.add("ManualControl"); - StackRemainingElemNames.add("Altitude"); - StackRemainingElemNames.add("Stabilization"); - StackRemainingElemNames.add("AltitudeHold"); - StackRemainingElemNames.add("Guidance"); - StackRemainingElemNames.add("FlightPlan"); - StackRemainingElemNames.add("Com2UsbBridge"); - StackRemainingElemNames.add("Usb2ComBridge"); - StackRemainingElemNames.add("OveroSync"); - StackRemainingElemNames.add("Autotune"); - StackRemainingElemNames.add("EventDispatcher"); - fields.add( new UAVObjectField("StackRemaining", "bytes", UAVObjectField.FieldType.UINT16, StackRemainingElemNames, null) ); - - List RunningElemNames = new ArrayList(); - RunningElemNames.add("System"); - RunningElemNames.add("Actuator"); - RunningElemNames.add("Attitude"); - RunningElemNames.add("Sensors"); - RunningElemNames.add("TelemetryTx"); - RunningElemNames.add("TelemetryTxPri"); - RunningElemNames.add("TelemetryRx"); - RunningElemNames.add("GPS"); - RunningElemNames.add("ManualControl"); - RunningElemNames.add("Altitude"); - RunningElemNames.add("Stabilization"); - RunningElemNames.add("AltitudeHold"); - RunningElemNames.add("Guidance"); - RunningElemNames.add("FlightPlan"); - RunningElemNames.add("Com2UsbBridge"); - RunningElemNames.add("Usb2ComBridge"); - RunningElemNames.add("OveroSync"); - RunningElemNames.add("Autotune"); - RunningElemNames.add("EventDispatcher"); - List RunningEnumOptions = new ArrayList(); - RunningEnumOptions.add("False"); - RunningEnumOptions.add("True"); - fields.add( new UAVObjectField("Running", "bool", UAVObjectField.FieldType.ENUM, RunningElemNames, RunningEnumOptions) ); - - List RunningTimeElemNames = new ArrayList(); - RunningTimeElemNames.add("System"); - RunningTimeElemNames.add("Actuator"); - RunningTimeElemNames.add("Attitude"); - RunningTimeElemNames.add("Sensors"); - RunningTimeElemNames.add("TelemetryTx"); - RunningTimeElemNames.add("TelemetryTxPri"); - RunningTimeElemNames.add("TelemetryRx"); - RunningTimeElemNames.add("GPS"); - RunningTimeElemNames.add("ManualControl"); - RunningTimeElemNames.add("Altitude"); - RunningTimeElemNames.add("Stabilization"); - RunningTimeElemNames.add("AltitudeHold"); - RunningTimeElemNames.add("Guidance"); - RunningTimeElemNames.add("FlightPlan"); - RunningTimeElemNames.add("Com2UsbBridge"); - RunningTimeElemNames.add("Usb2ComBridge"); - RunningTimeElemNames.add("OveroSync"); - RunningTimeElemNames.add("Autotune"); - RunningTimeElemNames.add("EventDispatcher"); - fields.add( new UAVObjectField("RunningTime", "%", UAVObjectField.FieldType.UINT8, RunningTimeElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 10000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 1000; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - TaskInfo obj = new TaskInfo(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public TaskInfo GetInstance(UAVObjectManager objMngr, long instID) - { - return (TaskInfo)(objMngr.getObject(TaskInfo.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0xB81CD2AEl; - protected static final String NAME = "TaskInfo"; - protected static String DESCRIPTION = "Task information"; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemObjectsInitialize.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemObjectsInitialize.java new file mode 100644 index 000000000..f177cf3ef --- /dev/null +++ b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TelemObjectsInitialize.java @@ -0,0 +1,44 @@ +/** + ****************************************************************************** + * + * + * @file uavobjectsinittemplate.java + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief the template for the uavobjects init part + * $(GENERATEDWARNING) + * + * @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 + */ + +package org.openpilot.uavtalk.uavobjects; + +import org.openpilot.uavtalk.UAVObjectManager; + +public class TelemObjectsInitialize { + + public static void register(UAVObjectManager objMngr) { + try { + objMngr.registerObject( new FirmwareIAPObj() ); + objMngr.registerObject( new FlightTelemetryStats() ); + objMngr.registerObject( new GCSTelemetryStats() ); + } catch (Exception e) { + e.printStackTrace(); + } + } +} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TxPIDSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/TxPIDSettings.java deleted file mode 100644 index 3f2264bf5..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/TxPIDSettings.java +++ /dev/null @@ -1,225 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Settings used by @ref TxPID optional module to tune PID settings using R/C transmitter - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Settings used by @ref TxPID optional module to tune PID settings using R/C transmitter - -generated from txpidsettings.xml - **/ -public class TxPIDSettings extends UAVDataObject { - - public TxPIDSettings() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List ThrottleRangeElemNames = new ArrayList(); - ThrottleRangeElemNames.add("Min"); - ThrottleRangeElemNames.add("Max"); - fields.add( new UAVObjectField("ThrottleRange", "%", UAVObjectField.FieldType.FLOAT32, ThrottleRangeElemNames, null) ); - - List MinPIDElemNames = new ArrayList(); - MinPIDElemNames.add("Instance1"); - MinPIDElemNames.add("Instance2"); - MinPIDElemNames.add("Instance3"); - fields.add( new UAVObjectField("MinPID", "", UAVObjectField.FieldType.FLOAT32, MinPIDElemNames, null) ); - - List MaxPIDElemNames = new ArrayList(); - MaxPIDElemNames.add("Instance1"); - MaxPIDElemNames.add("Instance2"); - MaxPIDElemNames.add("Instance3"); - fields.add( new UAVObjectField("MaxPID", "", UAVObjectField.FieldType.FLOAT32, MaxPIDElemNames, null) ); - - List UpdateModeElemNames = new ArrayList(); - UpdateModeElemNames.add("0"); - List UpdateModeEnumOptions = new ArrayList(); - UpdateModeEnumOptions.add("Never"); - UpdateModeEnumOptions.add("When Armed"); - UpdateModeEnumOptions.add("Always"); - fields.add( new UAVObjectField("UpdateMode", "option", UAVObjectField.FieldType.ENUM, UpdateModeElemNames, UpdateModeEnumOptions) ); - - List InputsElemNames = new ArrayList(); - InputsElemNames.add("Instance1"); - InputsElemNames.add("Instance2"); - InputsElemNames.add("Instance3"); - List InputsEnumOptions = new ArrayList(); - InputsEnumOptions.add("Throttle"); - InputsEnumOptions.add("Accessory0"); - InputsEnumOptions.add("Accessory1"); - InputsEnumOptions.add("Accessory2"); - InputsEnumOptions.add("Accessory3"); - InputsEnumOptions.add("Accessory4"); - InputsEnumOptions.add("Accessory5"); - fields.add( new UAVObjectField("Inputs", "channel", UAVObjectField.FieldType.ENUM, InputsElemNames, InputsEnumOptions) ); - - List PIDsElemNames = new ArrayList(); - PIDsElemNames.add("Instance1"); - PIDsElemNames.add("Instance2"); - PIDsElemNames.add("Instance3"); - List PIDsEnumOptions = new ArrayList(); - PIDsEnumOptions.add("Disabled"); - PIDsEnumOptions.add("Roll Rate.Kp"); - PIDsEnumOptions.add("Pitch Rate.Kp"); - PIDsEnumOptions.add("Roll+Pitch Rate.Kp"); - PIDsEnumOptions.add("Yaw Rate.Kp"); - PIDsEnumOptions.add("Roll Rate.Ki"); - PIDsEnumOptions.add("Pitch Rate.Ki"); - PIDsEnumOptions.add("Roll+Pitch Rate.Ki"); - PIDsEnumOptions.add("Yaw Rate.Ki"); - PIDsEnumOptions.add("Roll Rate.Kd"); - PIDsEnumOptions.add("Pitch Rate.Kd"); - PIDsEnumOptions.add("Roll+Pitch Rate.Kd"); - PIDsEnumOptions.add("Yaw Rate.Kd"); - PIDsEnumOptions.add("Roll Rate.ILimit"); - PIDsEnumOptions.add("Pitch Rate.ILimit"); - PIDsEnumOptions.add("Roll+Pitch Rate.ILimit"); - PIDsEnumOptions.add("Yaw Rate.ILimit"); - PIDsEnumOptions.add("Roll Attitude.Kp"); - PIDsEnumOptions.add("Pitch Attitude.Kp"); - PIDsEnumOptions.add("Roll+Pitch Attitude.Kp"); - PIDsEnumOptions.add("Yaw Attitude.Kp"); - PIDsEnumOptions.add("Roll Attitude.Ki"); - PIDsEnumOptions.add("Pitch Attitude.Ki"); - PIDsEnumOptions.add("Roll+Pitch Attitude.Ki"); - PIDsEnumOptions.add("Yaw Attitude.Ki"); - PIDsEnumOptions.add("Roll Attitude.ILimit"); - PIDsEnumOptions.add("Pitch Attitude.ILimit"); - PIDsEnumOptions.add("Roll+Pitch Attitude.ILimit"); - PIDsEnumOptions.add("Yaw Attitude.ILimit"); - PIDsEnumOptions.add("GyroTau"); - fields.add( new UAVObjectField("PIDs", "option", UAVObjectField.FieldType.ENUM, PIDsElemNames, PIDsEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 0; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("ThrottleRange").setValue(0.2,0); - getField("ThrottleRange").setValue(0.8,1); - getField("MinPID").setValue(0,0); - getField("MinPID").setValue(0,1); - getField("MinPID").setValue(0,2); - getField("MaxPID").setValue(0,0); - getField("MaxPID").setValue(0,1); - getField("MaxPID").setValue(0,2); - getField("UpdateMode").setValue("When Armed"); - getField("Inputs").setValue("Throttle",0); - getField("Inputs").setValue("Accessory0",1); - getField("Inputs").setValue("Accessory1",2); - getField("PIDs").setValue("Disabled",0); - getField("PIDs").setValue("Disabled",1); - getField("PIDs").setValue("Disabled",2); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - TxPIDSettings obj = new TxPIDSettings(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public TxPIDSettings GetInstance(UAVObjectManager objMngr, long instID) - { - return (TxPIDSettings)(objMngr.getObject(TxPIDSettings.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x42B2D2AEl; - protected static final String NAME = "TxPIDSettings"; - protected static String DESCRIPTION = "Settings used by @ref TxPID optional module to tune PID settings using R/C transmitter"; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 1 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java deleted file mode 100644 index f8bd73662..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/UAVObjectsInitialize.java +++ /dev/null @@ -1,108 +0,0 @@ -/** - ****************************************************************************** - * - * - * @file uavobjectsinittemplate.java - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief the template for the uavobjects init part - * $(GENERATEDWARNING) - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import org.openpilot.uavtalk.UAVObjectManager; - -public class UAVObjectsInitialize { - - public static void register(UAVObjectManager objMngr) { - try { - objMngr.registerObject( new Accels() ); - objMngr.registerObject( new AccessoryDesired() ); - objMngr.registerObject( new ActuatorCommand() ); - objMngr.registerObject( new ActuatorDesired() ); - objMngr.registerObject( new ActuatorSettings() ); - objMngr.registerObject( new AltHoldSmoothed() ); - objMngr.registerObject( new AltitudeHoldDesired() ); - objMngr.registerObject( new AltitudeHoldSettings() ); - objMngr.registerObject( new AttitudeActual() ); - objMngr.registerObject( new AttitudeSettings() ); - objMngr.registerObject( new BaroAltitude() ); - objMngr.registerObject( new CameraDesired() ); - objMngr.registerObject( new CameraStabSettings() ); - objMngr.registerObject( new FaultSettings() ); - objMngr.registerObject( new FirmwareIAPObj() ); - objMngr.registerObject( new FlightBatterySettings() ); - objMngr.registerObject( new FlightBatteryState() ); - objMngr.registerObject( new FlightPlanControl() ); - objMngr.registerObject( new FlightPlanSettings() ); - objMngr.registerObject( new FlightPlanStatus() ); - objMngr.registerObject( new FlightStatus() ); - objMngr.registerObject( new FlightTelemetryStats() ); - objMngr.registerObject( new GCSReceiver() ); - objMngr.registerObject( new GCSTelemetryStats() ); - objMngr.registerObject( new GPSPosition() ); - objMngr.registerObject( new GPSSatellites() ); - objMngr.registerObject( new GPSSettings() ); - objMngr.registerObject( new GPSTime() ); - objMngr.registerObject( new GPSVelocity() ); - objMngr.registerObject( new GuidanceSettings() ); - objMngr.registerObject( new Gyros() ); - objMngr.registerObject( new GyrosBias() ); - objMngr.registerObject( new HomeLocation() ); - objMngr.registerObject( new HwSettings() ); - objMngr.registerObject( new I2CStats() ); - objMngr.registerObject( new Magnetometer() ); - objMngr.registerObject( new ManualControlCommand() ); - objMngr.registerObject( new ManualControlSettings() ); - objMngr.registerObject( new MixerSettings() ); - objMngr.registerObject( new MixerStatus() ); - objMngr.registerObject( new NedAccel() ); - objMngr.registerObject( new ObjectPersistence() ); - objMngr.registerObject( new OveroSyncStats() ); - objMngr.registerObject( new PathAction() ); - objMngr.registerObject( new PipXSettings() ); - objMngr.registerObject( new PipXStatus() ); - objMngr.registerObject( new PositionActual() ); - objMngr.registerObject( new PositionDesired() ); - objMngr.registerObject( new RateDesired() ); - objMngr.registerObject( new ReceiverActivity() ); - objMngr.registerObject( new RelayTuning() ); - objMngr.registerObject( new RelayTuningSettings() ); - objMngr.registerObject( new RevoCalibration() ); - objMngr.registerObject( new SonarAltitude() ); - objMngr.registerObject( new StabilizationDesired() ); - objMngr.registerObject( new StabilizationSettings() ); - objMngr.registerObject( new SystemAlarms() ); - objMngr.registerObject( new SystemSettings() ); - objMngr.registerObject( new SystemStats() ); - objMngr.registerObject( new TaskInfo() ); - objMngr.registerObject( new TxPIDSettings() ); - objMngr.registerObject( new VelocityActual() ); - objMngr.registerObject( new VelocityDesired() ); - objMngr.registerObject( new WatchdogStatus() ); - objMngr.registerObject( new Waypoint() ); - objMngr.registerObject( new WaypointActive() ); - - } catch (Exception e) { - e.printStackTrace(); - } - } -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java deleted file mode 100644 index 96ac3d72d..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityActual.java +++ /dev/null @@ -1,146 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Updated by @ref AHRSCommsModule and used within @ref GuidanceModule for velocity control - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Updated by @ref AHRSCommsModule and used within @ref GuidanceModule for velocity control - -generated from velocityactual.xml - **/ -public class VelocityActual extends UAVDataObject { - - public VelocityActual() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List NorthElemNames = new ArrayList(); - NorthElemNames.add("0"); - fields.add( new UAVObjectField("North", "m/s", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); - - List EastElemNames = new ArrayList(); - EastElemNames.add("0"); - fields.add( new UAVObjectField("East", "m/s", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); - - List DownElemNames = new ArrayList(); - DownElemNames.add("0"); - fields.add( new UAVObjectField("Down", "m/s", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 1000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 1000; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - VelocityActual obj = new VelocityActual(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public VelocityActual GetInstance(UAVObjectManager objMngr, long instID) - { - return (VelocityActual)(objMngr.getObject(VelocityActual.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x5A08F61Al; - protected static final String NAME = "VelocityActual"; - protected static String DESCRIPTION = "Updated by @ref AHRSCommsModule and used within @ref GuidanceModule for velocity control"; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java deleted file mode 100644 index 1746c978a..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VelocityDesired.java +++ /dev/null @@ -1,146 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Used within @ref GuidanceModule to communicate between the task computing the desired velocity and the PID loop to achieve it (running at different rates). - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Used within @ref GuidanceModule to communicate between the task computing the desired velocity and the PID loop to achieve it (running at different rates). - -generated from velocitydesired.xml - **/ -public class VelocityDesired extends UAVDataObject { - - public VelocityDesired() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List NorthElemNames = new ArrayList(); - NorthElemNames.add("0"); - fields.add( new UAVObjectField("North", "m/s", UAVObjectField.FieldType.FLOAT32, NorthElemNames, null) ); - - List EastElemNames = new ArrayList(); - EastElemNames.add("0"); - fields.add( new UAVObjectField("East", "m/s", UAVObjectField.FieldType.FLOAT32, EastElemNames, null) ); - - List DownElemNames = new ArrayList(); - DownElemNames.add("0"); - fields.add( new UAVObjectField("Down", "m/s", UAVObjectField.FieldType.FLOAT32, DownElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 1000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 1000; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - VelocityDesired obj = new VelocityDesired(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public VelocityDesired GetInstance(UAVObjectManager objMngr, long instID) - { - return (VelocityDesired)(objMngr.getObject(VelocityDesired.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x9E946992l; - protected static final String NAME = "VelocityDesired"; - protected static String DESCRIPTION = "Used within @ref GuidanceModule to communicate between the task computing the desired velocity and the PID loop to achieve it (running at different rates)."; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VtolPathFollowerSettings.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/VtolPathFollowerSettings.java deleted file mode 100644 index fa51e4512..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/VtolPathFollowerSettings.java +++ /dev/null @@ -1,232 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Settings for the @ref VtolPathFollower module - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Settings for the @ref VtolPathFollower module - -generated from vtolpathfollowersettings.xml - **/ -public class VtolPathFollowerSettings extends UAVDataObject { - - public VtolPathFollowerSettings() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List HorizontalPosPIElemNames = new ArrayList(); - HorizontalPosPIElemNames.add("Kp"); - HorizontalPosPIElemNames.add("Ki"); - HorizontalPosPIElemNames.add("ILimit"); - fields.add( new UAVObjectField("HorizontalPosPI", "(m/s)/m", UAVObjectField.FieldType.FLOAT32, HorizontalPosPIElemNames, null) ); - - List HorizontalVelPIDElemNames = new ArrayList(); - HorizontalVelPIDElemNames.add("Kp"); - HorizontalVelPIDElemNames.add("Ki"); - HorizontalVelPIDElemNames.add("Kd"); - HorizontalVelPIDElemNames.add("ILimit"); - fields.add( new UAVObjectField("HorizontalVelPID", "deg/(m/s)", UAVObjectField.FieldType.FLOAT32, HorizontalVelPIDElemNames, null) ); - - List VerticalPosPIElemNames = new ArrayList(); - VerticalPosPIElemNames.add("Kp"); - VerticalPosPIElemNames.add("Ki"); - VerticalPosPIElemNames.add("ILimit"); - fields.add( new UAVObjectField("VerticalPosPI", "", UAVObjectField.FieldType.FLOAT32, VerticalPosPIElemNames, null) ); - - List VerticalVelPIDElemNames = new ArrayList(); - VerticalVelPIDElemNames.add("Kp"); - VerticalVelPIDElemNames.add("Ki"); - VerticalVelPIDElemNames.add("Kd"); - VerticalVelPIDElemNames.add("ILimit"); - fields.add( new UAVObjectField("VerticalVelPID", "", UAVObjectField.FieldType.FLOAT32, VerticalVelPIDElemNames, null) ); - - List VelocityFeedforwardElemNames = new ArrayList(); - VelocityFeedforwardElemNames.add("0"); - fields.add( new UAVObjectField("VelocityFeedforward", "deg/(m/s)", UAVObjectField.FieldType.FLOAT32, VelocityFeedforwardElemNames, null) ); - - List MaxRollPitchElemNames = new ArrayList(); - MaxRollPitchElemNames.add("0"); - fields.add( new UAVObjectField("MaxRollPitch", "deg", UAVObjectField.FieldType.FLOAT32, MaxRollPitchElemNames, null) ); - - List UpdatePeriodElemNames = new ArrayList(); - UpdatePeriodElemNames.add("0"); - fields.add( new UAVObjectField("UpdatePeriod", "ms", UAVObjectField.FieldType.INT32, UpdatePeriodElemNames, null) ); - - List HorizontalVelMaxElemNames = new ArrayList(); - HorizontalVelMaxElemNames.add("0"); - fields.add( new UAVObjectField("HorizontalVelMax", "m/s", UAVObjectField.FieldType.UINT16, HorizontalVelMaxElemNames, null) ); - - List VerticalVelMaxElemNames = new ArrayList(); - VerticalVelMaxElemNames.add("0"); - fields.add( new UAVObjectField("VerticalVelMax", "m/s", UAVObjectField.FieldType.UINT16, VerticalVelMaxElemNames, null) ); - - List GuidanceModeElemNames = new ArrayList(); - GuidanceModeElemNames.add("0"); - List GuidanceModeEnumOptions = new ArrayList(); - GuidanceModeEnumOptions.add("DUAL_LOOP"); - GuidanceModeEnumOptions.add("VELOCITY_CONTROL"); - fields.add( new UAVObjectField("GuidanceMode", "", UAVObjectField.FieldType.ENUM, GuidanceModeElemNames, GuidanceModeEnumOptions) ); - - List ThrottleControlElemNames = new ArrayList(); - ThrottleControlElemNames.add("0"); - List ThrottleControlEnumOptions = new ArrayList(); - ThrottleControlEnumOptions.add("FALSE"); - ThrottleControlEnumOptions.add("TRUE"); - fields.add( new UAVObjectField("ThrottleControl", "", UAVObjectField.FieldType.ENUM, ThrottleControlElemNames, ThrottleControlEnumOptions) ); - - List VelocitySourceElemNames = new ArrayList(); - VelocitySourceElemNames.add("0"); - List VelocitySourceEnumOptions = new ArrayList(); - VelocitySourceEnumOptions.add("EKF"); - VelocitySourceEnumOptions.add("NEDVEL"); - VelocitySourceEnumOptions.add("GPSPOS"); - fields.add( new UAVObjectField("VelocitySource", "", UAVObjectField.FieldType.ENUM, VelocitySourceElemNames, VelocitySourceEnumOptions) ); - - List PositionSourceElemNames = new ArrayList(); - PositionSourceElemNames.add("0"); - List PositionSourceEnumOptions = new ArrayList(); - PositionSourceEnumOptions.add("EKF"); - PositionSourceEnumOptions.add("GPSPOS"); - fields.add( new UAVObjectField("PositionSource", "", UAVObjectField.FieldType.ENUM, PositionSourceElemNames, PositionSourceEnumOptions) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 1 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 1 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 0; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 0; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - getField("HorizontalPosPI").setValue(1,0); - getField("HorizontalPosPI").setValue(0,1); - getField("HorizontalPosPI").setValue(0,2); - getField("HorizontalVelPID").setValue(5,0); - getField("HorizontalVelPID").setValue(0,1); - getField("HorizontalVelPID").setValue(1,2); - getField("HorizontalVelPID").setValue(0,3); - getField("VerticalPosPI").setValue(0.1,0); - getField("VerticalPosPI").setValue(0.001,1); - getField("VerticalPosPI").setValue(200,2); - getField("VerticalVelPID").setValue(0.1,0); - getField("VerticalVelPID").setValue(0,1); - getField("VerticalVelPID").setValue(0,2); - getField("VerticalVelPID").setValue(0,3); - getField("VelocityFeedforward").setValue(0); - getField("MaxRollPitch").setValue(20); - getField("UpdatePeriod").setValue(100); - getField("HorizontalVelMax").setValue(10); - getField("VerticalVelMax").setValue(1); - getField("GuidanceMode").setValue("DUAL_LOOP"); - getField("ThrottleControl").setValue("FALSE"); - getField("VelocitySource").setValue("EKF"); - getField("PositionSource").setValue("EKF"); - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - VtolPathFollowerSettings obj = new VtolPathFollowerSettings(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public VtolPathFollowerSettings GetInstance(UAVObjectManager objMngr, long instID) - { - return (VtolPathFollowerSettings)(objMngr.getObject(VtolPathFollowerSettings.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x973991F6l; - protected static final String NAME = "VtolPathFollowerSettings"; - protected static String DESCRIPTION = "Settings for the @ref VtolPathFollower module"; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 1 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java deleted file mode 100644 index 722006943..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/WatchdogStatus.java +++ /dev/null @@ -1,142 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * For monitoring the flags in the watchdog and especially the bootup flags - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -For monitoring the flags in the watchdog and especially the bootup flags - -generated from watchdogstatus.xml - **/ -public class WatchdogStatus extends UAVDataObject { - - public WatchdogStatus() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List BootupFlagsElemNames = new ArrayList(); - BootupFlagsElemNames.add("0"); - fields.add( new UAVObjectField("BootupFlags", "", UAVObjectField.FieldType.UINT16, BootupFlagsElemNames, null) ); - - List ActiveFlagsElemNames = new ArrayList(); - ActiveFlagsElemNames.add("0"); - fields.add( new UAVObjectField("ActiveFlags", "", UAVObjectField.FieldType.UINT16, ActiveFlagsElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 5000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 5000; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - WatchdogStatus obj = new WatchdogStatus(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public WatchdogStatus GetInstance(UAVObjectManager objMngr, long instID) - { - return (WatchdogStatus)(objMngr.getObject(WatchdogStatus.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0xA207FA7Cl; - protected static final String NAME = "WatchdogStatus"; - protected static String DESCRIPTION = "For monitoring the flags in the watchdog and especially the bootup flags"; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/Waypoint.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/Waypoint.java deleted file mode 100644 index 017b274f5..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/Waypoint.java +++ /dev/null @@ -1,148 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * A waypoint the aircraft can try and hit. Used by the @ref PathPlanner module - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -A waypoint the aircraft can try and hit. Used by the @ref PathPlanner module - -generated from waypoint.xml - **/ -public class Waypoint extends UAVDataObject { - - public Waypoint() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List PositionElemNames = new ArrayList(); - PositionElemNames.add("North"); - PositionElemNames.add("East"); - PositionElemNames.add("Down"); - fields.add( new UAVObjectField("Position", "m", UAVObjectField.FieldType.FLOAT32, PositionElemNames, null) ); - - List VelocityElemNames = new ArrayList(); - VelocityElemNames.add("0"); - fields.add( new UAVObjectField("Velocity", "m/s", UAVObjectField.FieldType.FLOAT32, VelocityElemNames, null) ); - - List ActionElemNames = new ArrayList(); - ActionElemNames.add("0"); - fields.add( new UAVObjectField("Action", "", UAVObjectField.FieldType.UINT8, ActionElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_PERIODIC) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 4000; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 1000; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - Waypoint obj = new Waypoint(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public Waypoint GetInstance(UAVObjectManager objMngr, long instID) - { - return (Waypoint)(objMngr.getObject(Waypoint.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0xD23852DCl; - protected static final String NAME = "Waypoint"; - protected static String DESCRIPTION = "A waypoint the aircraft can try and hit. Used by the @ref PathPlanner module"; - protected static final boolean ISSINGLEINST = 0 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/src/org/openpilot/uavtalk/uavobjects/WaypointActive.java b/androidgcs/src/org/openpilot/uavtalk/uavobjects/WaypointActive.java deleted file mode 100644 index cb4717dbc..000000000 --- a/androidgcs/src/org/openpilot/uavtalk/uavobjects/WaypointActive.java +++ /dev/null @@ -1,138 +0,0 @@ -/** - ****************************************************************************** - * - * @file uavobjecttemplate.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @brief Template for an uavobject in java - * This is a autogenerated file!! Do not modify and expect a result. - * Indicates the currently active waypoint - * - * @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 - */ - -package org.openpilot.uavtalk.uavobjects; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; -import java.util.ListIterator; - -import org.openpilot.uavtalk.UAVObjectManager; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.UAVDataObject; -import org.openpilot.uavtalk.UAVObjectField; - -/** -Indicates the currently active waypoint - -generated from waypointactive.xml - **/ -public class WaypointActive extends UAVDataObject { - - public WaypointActive() { - super(OBJID, ISSINGLEINST, ISSETTINGS, NAME); - - List fields = new ArrayList(); - - - List IndexElemNames = new ArrayList(); - IndexElemNames.add("0"); - fields.add( new UAVObjectField("Index", "", UAVObjectField.FieldType.UINT8, IndexElemNames, null) ); - - - // Compute the number of bytes for this object - int numBytes = 0; - ListIterator li = fields.listIterator(); - while(li.hasNext()) { - numBytes += li.next().getNumBytes(); - } - NUMBYTES = numBytes; - - // Initialize object - initializeFields(fields, ByteBuffer.allocate(NUMBYTES), NUMBYTES); - // Set the default field values - setDefaultFieldValues(); - // Set the object description - setDescription(DESCRIPTION); - } - - /** - * Create a Metadata object filled with default values for this object - * @return Metadata object with default values - */ - public Metadata getDefaultMetadata() { - UAVObject.Metadata metadata = new UAVObject.Metadata(); - metadata.flags = - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_ACCESS_SHIFT | - UAVObject.Metadata.AccessModeNum(UAVObject.AccessMode.ACCESS_READWRITE) << UAVOBJ_GCS_ACCESS_SHIFT | - 0 << UAVOBJ_TELEMETRY_ACKED_SHIFT | - 0 << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_ONCHANGE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - UAVObject.Metadata.UpdateModeNum(UAVObject.UpdateMode.UPDATEMODE_MANUAL) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.flightTelemetryUpdatePeriod = 0; - metadata.gcsTelemetryUpdatePeriod = 0; - metadata.loggingUpdatePeriod = 1000; - - return metadata; - } - - /** - * Initialize object fields with the default values. - * If a default value is not specified the object fields - * will be initialized to zero. - */ - public void setDefaultFieldValues() - { - - } - - /** - * Create a clone of this object, a new instance ID must be specified. - * Do not use this function directly to create new instances, the - * UAVObjectManager should be used instead. - */ - public UAVDataObject clone(long instID) { - // TODO: Need to get specific instance to clone - try { - WaypointActive obj = new WaypointActive(); - obj.initialize(instID, this.getMetaObject()); - return obj; - } catch (Exception e) { - return null; - } - } - - /** - * Static function to retrieve an instance of the object. - */ - public WaypointActive GetInstance(UAVObjectManager objMngr, long instID) - { - return (WaypointActive)(objMngr.getObject(WaypointActive.OBJID, instID)); - } - - // Constants - protected static final long OBJID = 0x1EA5B192l; - protected static final String NAME = "WaypointActive"; - protected static String DESCRIPTION = "Indicates the currently active waypoint"; - protected static final boolean ISSINGLEINST = 1 > 0; - protected static final boolean ISSETTINGS = 0 > 0; - protected static int NUMBYTES = 0; - - -} diff --git a/androidgcs/tests/org/openpilot/uavtalk/DataObjectTest.java b/androidgcs/tests/org/openpilot/uavtalk/DataObjectTest.java deleted file mode 100644 index 3efa7d300..000000000 --- a/androidgcs/tests/org/openpilot/uavtalk/DataObjectTest.java +++ /dev/null @@ -1,93 +0,0 @@ -package org.openpilot.uavtalk; - -import static org.junit.Assert.*; - -import java.nio.ByteBuffer; -import java.util.Observer; - -import org.junit.BeforeClass; -import org.junit.Test; -import org.openpilot.uavtalk.uavobjects.ActuatorCommand; -import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; - -public class DataObjectTest { - - boolean succeed = false; - - @BeforeClass - public static void setUpBeforeClass() throws Exception { - } - - @Test - public void testUpdatedObserver() { - - succeed = false; - - UAVObject obj = new ActuatorCommand(); - obj.addUpdatedObserver( new Observer() { - - public void update(java.util.Observable observable, Object data) { - System.out.println("Updated: " + data.toString()); - succeed = true; - } - }); - obj.updated(); - - if(!succeed) - fail("No callback"); - - System.out.println("Done"); - - } - - @Test - public void testUpdatedViaObjMngr() { - succeed = false; - - UAVObjectManager objMngr = new UAVObjectManager(); - UAVObjectsInitialize.register(objMngr); - - UAVObject obj = objMngr.getObject("FlightTelemetryStats"); - obj.addUpdatedObserver( new Observer() { - - public void update(java.util.Observable observable, Object data) { - System.out.println("Updated: " + data.toString()); - succeed = true; - } - }); - objMngr.getObject("FlightTelemetryStats").updated(); - - if(!succeed) - fail("No callback"); - System.out.println("Done"); - - } - - @Test - public void testUnpackedViaObjMngr() { - succeed = false; - - UAVObjectManager objMngr = new UAVObjectManager(); - UAVObjectsInitialize.register(objMngr); - - UAVObject obj = objMngr.getObject("FlightTelemetryStats"); - obj.addUnpackedObserver( new Observer() { - - public void update(java.util.Observable observable, Object data) { - System.out.println("Updated: " + data.toString()); - succeed = true; - } - }); - - ByteBuffer bbuf = ByteBuffer.allocate(obj.getNumBytes()); - objMngr.getObject("FlightTelemetryStats").unpack(bbuf); - - if(!succeed) - fail("No callback"); - - System.out.println("Done"); - - } - - -} diff --git a/androidgcs/tests/org/openpilot/uavtalk/FieldTest.java b/androidgcs/tests/org/openpilot/uavtalk/FieldTest.java deleted file mode 100644 index 2d161fc25..000000000 --- a/androidgcs/tests/org/openpilot/uavtalk/FieldTest.java +++ /dev/null @@ -1,121 +0,0 @@ -package org.openpilot.uavtalk; - -import static org.junit.Assert.*; - -import java.nio.ByteBuffer; -import java.util.ArrayList; -import java.util.List; - -import org.junit.BeforeClass; -import org.junit.Test; - -import org.openpilot.uavtalk.UAVObjectField; -import org.openpilot.uavtalk.UAVObject; -import org.openpilot.uavtalk.uavobjects.*; - -public class FieldTest { - - @BeforeClass - public static void setUpBeforeClass() throws Exception { - } - - @Test - public void testPackUint16() { - // Need an object initialized to the field to provide metadata - UAVObject obj = null; - try { - obj = new ActuatorCommand(); - } catch (Exception e) { - // TODO Auto-generated catch block - e.printStackTrace(); - } - UAVObjectField field = new UAVObjectField("TestField", "No Units", UAVObjectField.FieldType.UINT16, 3, null); - field.initialize(obj); - field.setValue(3,0); - field.setValue(-50,1); - field.setValue(5003585,2); - - ByteBuffer bbuf = ByteBuffer.allocate(field.getNumBytes()); - - try { - field.pack(bbuf); - } catch (Exception e) { - // TODO Auto-generated catch block - e.printStackTrace(); - fail("Buffer size incorrect"); - } - - // Expect data to come out as little endian - byte[] expected = {3,0,0,0,(byte) 0xff,(byte) 0xff}; - for(int i = 0; i < expected.length && i < bbuf.array().length; i++) { - System.out.println("Expected: " + expected[i] + " (" + i + ")"); - System.out.println("Received: " + bbuf.array()[i] + " (" + i + ")"); - assertEquals(bbuf.array()[i],expected[i]); - } - } - - @Test - public void testUnpackUint16() { - // Need an object initialized to the field to provide metadata - UAVObject obj = null; - obj = new ActuatorCommand(); - UAVObjectField field = new UAVObjectField("TestField", "No Units", UAVObjectField.FieldType.UINT16, 3, null); - field.initialize(obj); - - ByteBuffer bbuf = ByteBuffer.allocate(field.getNumBytes()); - byte[] expected = {3,0,0,0,(byte) 0xff,(byte) 0xff}; - bbuf.put(expected); - bbuf.position(0); - field.unpack(bbuf); - - assertEquals(field.getValue(0), 3); - assertEquals(field.getValue(1), 0); - assertEquals(field.getValue(2), 65535); - } - - @Test - public void testEnumSetGetValue() { - List options = new ArrayList(); - options.add("Opt1"); - options.add("Opt2"); - options.add("Opt3"); - - // Need an object initialized to the field to provide metadata - UAVObject obj = null; - try { - obj = new ActuatorCommand(); - } catch (Exception e) { - // TODO Auto-generated catch block - e.printStackTrace(); - } - UAVObjectField field = new UAVObjectField("TestField", "No Units", UAVObjectField.FieldType.ENUM, 3, options); - field.initialize(obj); - field.setValue("Opt1",0); - field.setValue("Opt2",1); - field.setValue("Opt3",2); - assertEquals(field.getValue(0), "Opt1"); - assertEquals(field.getValue(1), "Opt2"); - assertEquals(field.getValue(2), "Opt3"); - } - - @Test - public void testUint16SetGetValue() { - - // Need an object initialized to the field to provide metadata - UAVObject obj = null; - try { - obj = new ActuatorCommand(); - } catch (Exception e) { - // TODO Auto-generated catch block - e.printStackTrace(); - } - UAVObjectField field = new UAVObjectField("TestField", "No Units", UAVObjectField.FieldType.UINT16, 3, null); - field.initialize(obj); - field.setValue(3,0); - field.setValue(-50,1); - field.setValue(5003585,2); - assertEquals(field.getValue(0), 3); - assertEquals(field.getValue(1), 0); - assertEquals(field.getValue(2), 65535); - } -} diff --git a/androidgcs/tests/org/openpilot/uavtalk/ObjMngrTest.java b/androidgcs/tests/org/openpilot/uavtalk/ObjMngrTest.java deleted file mode 100644 index 57e641c96..000000000 --- a/androidgcs/tests/org/openpilot/uavtalk/ObjMngrTest.java +++ /dev/null @@ -1,20 +0,0 @@ -package org.openpilot.uavtalk; - -import org.junit.BeforeClass; -import org.junit.Test; -import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; - -public class ObjMngrTest { - - @BeforeClass - public static void setUpBeforeClass() throws Exception { - } - - @Test - public void testGetObjects() { - UAVObjectManager objMngr = new UAVObjectManager(); - UAVObjectsInitialize.register(objMngr); -// System.out.println(objMngr.getObject("ActuatorSettings", 0)); - } - -} diff --git a/androidgcs/tests/org/openpilot/uavtalk/SettingsTest.java b/androidgcs/tests/org/openpilot/uavtalk/SettingsTest.java deleted file mode 100644 index 5a805ae88..000000000 --- a/androidgcs/tests/org/openpilot/uavtalk/SettingsTest.java +++ /dev/null @@ -1,34 +0,0 @@ -package org.openpilot.uavtalk; - -import static org.junit.Assert.*; - -import org.junit.BeforeClass; -import org.junit.Test; - -public class SettingsTest { - - @BeforeClass - public static void setUpBeforeClass() throws Exception { - } - - @Test - public void testGetDefaultMetadata() { - fail("Not yet implemented"); - } - - @Test - public void testSetDefaultFieldValues() { - fail("Not yet implemented"); - } - - @Test - public void testIsSettings() { - fail("Not yet implemented"); - } - - @Test - public void testGetField() { - fail("Not yet implemented"); - } - -} diff --git a/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java b/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java deleted file mode 100644 index 5e6186442..000000000 --- a/androidgcs/tests/org/openpilot/uavtalk/TalkTest.java +++ /dev/null @@ -1,133 +0,0 @@ -package org.openpilot.uavtalk; -import static org.junit.Assert.*; - -import java.io.ByteArrayInputStream; -import java.io.ByteArrayOutputStream; -import java.io.IOException; -import java.net.InetAddress; -import java.net.Socket; -import java.util.Observable; -import java.util.Observer; - -import org.junit.BeforeClass; -import org.junit.Test; -import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; -import org.openpilot.uavtalk.UAVTalk; - - -public class TalkTest { - - static UAVObjectManager objMngr; - static final String IP_ADDRDESS = new String("127.0.0.1"); - static final int PORT_NUM = 7777; - boolean succeed = false; - - byte[] flightStatsConnected = - {0x3c,0x20,0x1d,0x00, - (byte) 0x5e,(byte) 0x26,(byte) 0x0c,(byte) 0x66, - 0x03,0x00,0x00,0x00, - 0x00,0x00,0x00,0x00, - 0x00,0x00,0x00,0x00, - 0x00,0x00,0x00,0x00, - 0x00,0x00,0x00,0x00, - 0x00,(byte) 0xAE}; - - @BeforeClass - public static void setUpBeforeClass() throws Exception { - objMngr = new UAVObjectManager(); - UAVObjectsInitialize.register(objMngr); - } - - //@Test - public void testGetFlightStatus() { - Socket connection = null; - UAVTalk talk = null; - try{ - InetAddress ip = InetAddress.getByName(IP_ADDRDESS); - connection = new Socket(ip, PORT_NUM); - } catch (Exception e) { - e.printStackTrace(); - fail("Couldn't connect to test platform"); - } - - try { - talk = new UAVTalk(connection.getInputStream(), connection.getOutputStream(), objMngr); - } catch (IOException e) { - // TODO Auto-generated catch block - e.printStackTrace(); - fail("Couldn't construct UAVTalk object"); - } - - Thread inputStream = talk.getInputProcessThread(); - inputStream.start(); - - succeed = false; - - UAVObject obj = objMngr.getObject("FlightTelemetryStats"); - - obj.addUpdatedObserver( new Observer() { - public void update(Observable observable, Object data) { - // TODO Auto-generated method stub - System.out.println("Updated: " + data.toString()); - succeed = true; - } - }); - - try { - Thread.sleep(1000); - } catch (InterruptedException e1) { - } - - if(!succeed) - fail("Never received a FlightTelemetryStats update"); - - } - - @Test - public void testSendObjectRequest() throws IOException { - ByteArrayInputStream is = new ByteArrayInputStream(new byte[0], 0, 0); - ByteArrayOutputStream os = new ByteArrayOutputStream(100); - - UAVTalk talk = new UAVTalk(is,os,objMngr); - UAVObject obj = objMngr.getObject("FlightTelemetryStats"); - obj.getField("Status").setValue("Connected"); - - talk.sendObject(obj, false, false); - - System.out.println("Size: " + os.size()); - byte [] array = os.toByteArray(); - for(int i = 0; i < array.length; i++) { - System.out.print("0x" + Integer.toHexString((int) array[i] & 0xff)); - System.out.print("/0x" + Integer.toHexString((int) flightStatsConnected[i] & 0xff)); - if(i != array.length-1) - System.out.print("\n"); - } - System.out.print("\n"); - for(int i = 0; i < array.length; i++) - assertEquals(os.toByteArray()[i], flightStatsConnected[i]); - } - - @Test - public void testReceiveObject() throws InterruptedException { - ByteArrayInputStream is = new ByteArrayInputStream(flightStatsConnected, 0, flightStatsConnected.length); - ByteArrayOutputStream os = new ByteArrayOutputStream(100); - - // Make the Status wrong initially - UAVObject obj = objMngr.getObject("FlightTelemetryStats"); - obj.getField("Status").setValue("Disconnected"); - - // Test receiving from that stream - UAVTalk talk = new UAVTalk(is,os,objMngr); - Thread inputStream = talk.getInputProcessThread(); - inputStream.start(); - - Thread.sleep(1000); - - System.out.println("Should be FlightTelemetry Stats:"); - System.out.println(objMngr.getObject("FlightTelemetryStats").toString()); - - assertEquals(obj.getField("Status").getValue(), new String("Connected")); - } - - -} diff --git a/androidgcs/tests/org/openpilot/uavtalk/TelemetryMonitorTest.java b/androidgcs/tests/org/openpilot/uavtalk/TelemetryMonitorTest.java deleted file mode 100644 index 6ddcfe03e..000000000 --- a/androidgcs/tests/org/openpilot/uavtalk/TelemetryMonitorTest.java +++ /dev/null @@ -1,59 +0,0 @@ -package org.openpilot.uavtalk; - -import static org.junit.Assert.fail; - -import java.io.IOException; -import java.net.InetAddress; -import java.net.Socket; - -import org.junit.Test; -import org.openpilot.uavtalk.uavobjects.UAVObjectsInitialize; - -import android.os.Looper; - - -public class TelemetryMonitorTest { - - static UAVObjectManager objMngr; - static UAVTalk talk; - static final String IP_ADDRDESS = new String("127.0.0.1"); - static final int PORT_NUM = 7777; - static Socket connection = null; - boolean succeed = false; - - @Test - public void testTelemetry() throws Exception { - objMngr = new UAVObjectManager(); - UAVObjectsInitialize.register(objMngr); - talk = null; - try{ - InetAddress ip = InetAddress.getByName(IP_ADDRDESS); - connection = new Socket(ip, PORT_NUM); - } catch (Exception e) { - e.printStackTrace(); - fail("Couldn't connect to test platform"); - } - - try { - talk = new UAVTalk(connection.getInputStream(), connection.getOutputStream(), objMngr); - } catch (IOException e) { - // TODO Auto-generated catch block - e.printStackTrace(); - fail("Couldn't construct UAVTalk object"); - } - - Thread inputStream = talk.getInputProcessThread(); - inputStream.start(); - - Looper.prepare(); - Telemetry tel = new Telemetry(talk, objMngr, Looper.myLooper()); - @SuppressWarnings("unused") - TelemetryMonitor mon = new TelemetryMonitor(objMngr,tel); - - Thread.sleep(10000); - - System.out.println("Done"); - } - - -} diff --git a/flight/CopterControl/Makefile b/flight/CopterControl/Makefile index 8687defef..ce5f75f61 100644 --- a/flight/CopterControl/Makefile +++ b/flight/CopterControl/Makefile @@ -38,9 +38,15 @@ OUTDIR := $(TOP)/build/$(TARGET) DEBUG ?= NO # Include objects that are just nice information to show -DIAGNOSTICS ?= NO +STACK_DIAGNOSTICS ?= NO +MIXERSTATUS_DIAGNOSTICS ?= NO +RATEDESIRED_DIAGNOSTICS ?= NO +I2C_WDG_STATS_DIAGNOSTICS ?= NO DIAG_TASKS ?= NO +#Or just turn on all the above diagnostics. WARNING: This consumes massive amounts of memory. +ALL_DIGNOSTICS ?=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 @@ -217,6 +223,7 @@ SRC += $(OPUAVSYNTHDIR)/mixerstatus.c SRC += $(OPUAVSYNTHDIR)/ratedesired.c SRC += $(OPUAVSYNTHDIR)/baroaltitude.c SRC += $(OPUAVSYNTHDIR)/txpidsettings.c +SRC += $(OPUAVSYNTHDIR)/airspeedactual.c endif @@ -438,8 +445,8 @@ CDEFS += -DUSE_$(BOARD) ifeq ($(ENABLE_DEBUG_PINS), YES) CDEFS += -DPIOS_ENABLE_DEBUG_PINS endif -ifeq ($(ENABLE_AUX_UART), YES) -CDEFS += -DPIOS_ENABLE_AUX_UART +ifeq ($(ENABLE_DEBUG_CONSOLE), YES) +CDEFS += -DPIOS_INCLUDE_DEBUG_CONSOLE endif ifeq ($(ERASE_FLASH), YES) CDEFS += -DERASE_FLASH @@ -485,11 +492,25 @@ ifeq ($(DEBUG),YES) CFLAGS += -DDEBUG endif -ifeq ($(DIAGNOSTICS),YES) -CFLAGS += -DDIAGNOSTICS +#The following Makefile command, ifneq (, $(filter) $(A), $(B) $(C)) is equivalent +# to the pseudocode `if(A== B || A==C)` +ifneq (,$(filter YES,$(STACK_DIAGNOSTICS) $(ALL_DIGNOSTICS))) +CFLAGS += -DSTACK_DIAGNOSTICS endif -ifeq ($(DIAG_TASKS),YES) +ifneq (,$(filter YES,$(MIXERSTATUS_DIAGNOSTICS) $(ALL_DIGNOSTICS))) +CFLAGS += -DMIXERSTATUS_DIAGNOSTICS +endif + +ifneq (,$(filter YES,$(RATEDESIRED_DIAGNOSTICS) $(ALL_DIGNOSTICS))) +CFLAGS += -DRATEDESIRED_DIAGNOSTICS +endif + +ifneq (,$(filter YES,$(I2C_WDG_STATS_DIAGNOSTICS) $(ALL_DIGNOSTICS))) +CFLAGS += -DI2C_WDG_STATS_DIAGNOSTICS +endif + +ifneq (,$(filter YES,$(DIAG_TASKS) $(ALL_DIGNOSTICS))) CFLAGS += -DDIAG_TASKS endif diff --git a/flight/CopterControl/System/pios_board.c b/flight/CopterControl/System/pios_board.c index f59e7335a..9231aa727 100644 --- a/flight/CopterControl/System/pios_board.c +++ b/flight/CopterControl/System/pios_board.c @@ -61,6 +61,11 @@ uint32_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE]; #define PIOS_COM_BRIDGE_RX_BUF_LEN 65 #define PIOS_COM_BRIDGE_TX_BUF_LEN 12 +#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) +#define PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN 40 +uint32_t pios_com_debug_id; +#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ + uint32_t pios_com_telem_rf_id; uint32_t pios_com_telem_usb_id; uint32_t pios_com_vcp_id; @@ -323,6 +328,25 @@ void PIOS_Board_Init(void) { PIOS_Assert(0); } } +#endif /* PIOS_INCLUDE_COM */ + break; + case HWSETTINGS_USB_VCPPORT_DEBUGCONSOLE: +#if defined(PIOS_INCLUDE_COM) +#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) + { + uint32_t pios_usb_cdc_id; + if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) { + PIOS_Assert(0); + } + uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_debug_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, + NULL, 0, + tx_buffer, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN)) { + PIOS_Assert(0); + } + } +#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ #endif /* PIOS_INCLUDE_COM */ break; } @@ -487,7 +511,25 @@ void PIOS_Board_Init(void) { } #endif /* PIOS_INCLUDE_DSM */ break; - case HWSETTINGS_CC_MAINPORT_COMAUX: + case HWSETTINGS_CC_MAINPORT_DEBUGCONSOLE: +#if defined(PIOS_INCLUDE_COM) +#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) + { + uint32_t pios_usart_generic_id; + if (PIOS_USART_Init(&pios_usart_generic_id, &pios_usart_generic_main_cfg)) { + PIOS_Assert(0); + } + + uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_debug_id, &pios_usart_com_driver, pios_usart_generic_id, + NULL, 0, + tx_buffer, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN)) { + PIOS_Assert(0); + } + } +#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ +#endif /* PIOS_INCLUDE_COM */ break; case HWSETTINGS_CC_MAINPORT_COMBRIDGE: { @@ -613,7 +655,25 @@ void PIOS_Board_Init(void) { } #endif /* PIOS_INCLUDE_DSM */ break; - case HWSETTINGS_CC_FLEXIPORT_COMAUX: + case HWSETTINGS_CC_FLEXIPORT_DEBUGCONSOLE: +#if defined(PIOS_INCLUDE_COM) +#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) + { + uint32_t pios_usart_generic_id; + if (PIOS_USART_Init(&pios_usart_generic_id, &pios_usart_generic_flexi_cfg)) { + PIOS_Assert(0); + } + + uint8_t * tx_buffer = (uint8_t *) pvPortMalloc(PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_debug_id, &pios_usart_com_driver, pios_usart_generic_id, + NULL, 0, + tx_buffer, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN)) { + PIOS_Assert(0); + } + } +#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ +#endif /* PIOS_INCLUDE_COM */ break; case HWSETTINGS_CC_FLEXIPORT_I2C: #if defined(PIOS_INCLUDE_I2C) @@ -662,6 +722,33 @@ void PIOS_Board_Init(void) { } #endif /* PIOS_INCLUDE_PPM */ break; + case HWSETTINGS_CC_RCVRPORT_PPMPWM: + /* This is a combination of PPM and PWM inputs */ +#if defined(PIOS_INCLUDE_PPM) + { + 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 */ +#if defined(PIOS_INCLUDE_PWM) + { + uint32_t pios_pwm_id; + PIOS_PWM_Init(&pios_pwm_id, &pios_pwm_with_ppm_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; } #if defined(PIOS_INCLUDE_GCSRCVR) @@ -683,6 +770,7 @@ void PIOS_Board_Init(void) { case HWSETTINGS_CC_RCVRPORT_DISABLED: case HWSETTINGS_CC_RCVRPORT_PWM: case HWSETTINGS_CC_RCVRPORT_PPM: + case HWSETTINGS_CC_RCVRPORT_PPMPWM: PIOS_Servo_Init(&pios_servo_cfg); break; case HWSETTINGS_CC_RCVRPORT_PPMOUTPUTS: diff --git a/flight/Modules/Actuator/actuator.c b/flight/Modules/Actuator/actuator.c index e59d50957..6bd471666 100644 --- a/flight/Modules/Actuator/actuator.c +++ b/flight/Modules/Actuator/actuator.c @@ -126,7 +126,7 @@ int32_t ActuatorInitialize() // Primary output of this module ActuatorCommandInitialize(); -#if defined(DIAGNOSTICS) +#if defined(MIXERSTATUS_DIAGNOSTICS) // UAVO only used for inspecting the internal status of the mixer during debug MixerStatusInitialize(); #endif @@ -212,7 +212,7 @@ static void actuatorTask(void* parameters) ActuatorDesiredGet(&desired); ActuatorCommandGet(&command); -#if defined(DIAGNOSTICS) +#if defined(MIXERSTATUS_DIAGNOSTICS) MixerStatusGet(&mixerStatus); #endif int nMixers = 0; @@ -362,7 +362,7 @@ static void actuatorTask(void* parameters) // Update in case read only (eg. during servo configuration) ActuatorCommandGet(&command); -#if defined(DIAGNOSTICS) +#if defined(MIXERSTATUS_DIAGNOSTICS) MixerStatusSet(&mixerStatus); #endif diff --git a/flight/Modules/OveroSync/overosync.c b/flight/Modules/OveroSync/overosync.c index 7ca362dd5..d09ff779a 100644 --- a/flight/Modules/OveroSync/overosync.c +++ b/flight/Modules/OveroSync/overosync.c @@ -84,7 +84,7 @@ struct overosync { struct overosync *overosync; -static void PIOS_OVERO_IRQHandler(); +static bool PIOS_OVERO_IRQHandler(); static const struct pios_exti_cfg pios_exti_overo_cfg __exti_config = { .vector = PIOS_OVERO_IRQHandler, @@ -123,7 +123,7 @@ static const struct pios_exti_cfg pios_exti_overo_cfg __exti_config = { * Overo deasserting the CS line. We don't want to spin that long in an * isr */ -void PIOS_OVERO_IRQHandler() +bool PIOS_OVERO_IRQHandler() { // transmitData must not block to get semaphore for when we get out of // frame and transaction is still running here. -1 indicates the transaction @@ -131,6 +131,8 @@ void PIOS_OVERO_IRQHandler() // error occurred. This shouldn't happen. Race condition? if(transmitData() == -1) overosync->framesync_error++; + + return false; } /** diff --git a/flight/Modules/Stabilization/stabilization.c b/flight/Modules/Stabilization/stabilization.c index fc4a5dcc5..a43162e71 100644 --- a/flight/Modules/Stabilization/stabilization.c +++ b/flight/Modules/Stabilization/stabilization.c @@ -119,7 +119,7 @@ int32_t StabilizationInitialize() // Initialize variables StabilizationSettingsInitialize(); ActuatorDesiredInitialize(); -#if defined(DIAGNOSTICS) +#if defined(RATEDESIRED_DIAGNOSTICS) RateDesiredInitialize(); #endif @@ -172,8 +172,7 @@ static void stabilizationTask(void* parameters) StabilizationDesiredGet(&stabDesired); AttitudeActualGet(&attitudeActual); GyrosGet(&gyrosData); - -#if defined(DIAGNOSTICS) +#if defined(RATEDESIRED_DIAGNOSTICS) RateDesiredGet(&rateDesired); #endif @@ -350,7 +349,7 @@ static void stabilizationTask(void* parameters) if (settings.VbarPiroComp == STABILIZATIONSETTINGS_VBARPIROCOMP_TRUE) stabilization_virtual_flybar_pirocomp(gyro_filtered[2], dT); -#if defined(DIAGNOSTICS) +#if defined(RATEDESIRED_DIAGNOSTICS) RateDesiredSet(&rateDesired); #endif diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index 715c26d72..fa3be09e2 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -49,6 +49,14 @@ #include "watchdogstatus.h" #include "taskmonitor.h" +//#define DEBUG_THIS_FILE + +#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) && defined(DEBUG_THIS_FILE) +#define DEBUG_MSG(format, ...) PIOS_COM_SendFormattedString(PIOS_COM_DEBUG, format, ## __VA_ARGS__) +#else +#define DEBUG_MSG(format, ...) +#endif + // Private constants #define SYSTEM_UPDATE_PERIOD_MS 1000 #define LED_BLINK_RATE_HZ 5 @@ -82,7 +90,7 @@ static void objectUpdatedCb(UAVObjEvent * ev); static void updateStats(); static void updateSystemAlarms(); static void systemTask(void *parameters); -#if defined(DIAGNOSTICS) +#if defined(I2C_WDG_STATS_DIAGNOSTICS) static void updateI2Cstats(); static void updateWDGstats(); #endif @@ -118,7 +126,7 @@ int32_t SystemModInitialize(void) #if defined(DIAG_TASKS) TaskInfoInitialize(); #endif -#if defined(DIAGNOSTICS) +#if defined(I2C_WDG_STATS_DIAGNOSTICS) I2CStatsInitialize(); WatchdogStatusInitialize(); #endif @@ -168,7 +176,7 @@ static void systemTask(void *parameters) // Update the system alarms updateSystemAlarms(); -#if defined(DIAGNOSTICS) +#if defined(I2C_WDG_STATS_DIAGNOSTICS) updateI2Cstats(); updateWDGstats(); #endif @@ -181,6 +189,7 @@ static void systemTask(void *parameters) // Flash the heartbeat LED #if defined(PIOS_LED_HEARTBEAT) PIOS_LED_Toggle(PIOS_LED_HEARTBEAT); + DEBUG_MSG("+ 0x%08x\r\n", 0xDEADBEEF); #endif /* PIOS_LED_HEARTBEAT */ // Turn on the error LED if an alarm is set @@ -301,7 +310,7 @@ static void objectUpdatedCb(UAVObjEvent * ev) /** * Called periodically to update the I2C statistics */ -#if defined(DIAGNOSTICS) +#if defined(I2C_WDG_STATS_DIAGNOSTICS) static void updateI2Cstats() { #if defined(PIOS_INCLUDE_I2C) diff --git a/flight/PiOS/Boards/STM32103CB_CC_Rev1.h b/flight/PiOS/Boards/STM32103CB_CC_Rev1.h index 85143fc17..292594ee9 100644 --- a/flight/PiOS/Boards/STM32103CB_CC_Rev1.h +++ b/flight/PiOS/Boards/STM32103CB_CC_Rev1.h @@ -136,7 +136,6 @@ extern uint32_t pios_i2c_flexi_adapter_id; extern uint32_t pios_com_telem_rf_id; #define PIOS_COM_TELEM_RF (pios_com_telem_rf_id) -#define PIOS_COM_DEBUG PIOS_COM_TELEM_RF #if defined(PIOS_INCLUDE_GPS) extern uint32_t pios_com_gps_id; @@ -152,6 +151,11 @@ extern uint32_t pios_com_vcp_id; extern uint32_t pios_com_telem_usb_id; #define PIOS_COM_TELEM_USB (pios_com_telem_usb_id) +#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) +extern uint32_t pios_com_debug_id; +#define PIOS_COM_DEBUG (pios_com_debug_id) +#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ + //------------------------- // ADC // PIOS_ADC_PinGet(0) = Gyro Z diff --git a/flight/PiOS/Common/pios_bma180.c b/flight/PiOS/Common/pios_bma180.c index 2a578dd5d..3a2e32d95 100644 --- a/flight/PiOS/Common/pios_bma180.c +++ b/flight/PiOS/Common/pios_bma180.c @@ -434,7 +434,7 @@ int32_t PIOS_BMA180_Test() * @brief IRQ Handler. Read data from the BMA180 FIFO and push onto a local fifo. */ int32_t bma180_irqs = 0; -void PIOS_BMA180_IRQHandler(void) +bool PIOS_BMA180_IRQHandler(void) { bma180_irqs++; @@ -443,7 +443,7 @@ void PIOS_BMA180_IRQHandler(void) // If we can't get the bus then just move on for efficiency if(PIOS_BMA180_ClaimBusISR() != 0) { - return; // Something else is using bus, miss this data + return false; // Something else is using bus, miss this data } PIOS_SPI_TransferBlock(dev->spi_id,pios_bma180_req_buf,(uint8_t *) pios_bma180_dmabuf, @@ -457,7 +457,7 @@ void PIOS_BMA180_IRQHandler(void) // Must not return before releasing bus if(fifoBuf_getFree(&dev->fifo) < sizeof(data)) - return; + return false; // Bottom two bits indicate new data and are constant zeros. Don't right // shift because it drops sign bit @@ -470,7 +470,8 @@ void PIOS_BMA180_IRQHandler(void) data.temperature = pios_bma180_dmabuf[7]; fifoBuf_putData(&dev->fifo, (uint8_t *) &data, sizeof(data)); - + + return false; } #endif /* PIOS_INCLUDE_BMA180 */ diff --git a/flight/PiOS/Common/pios_hmc5883.c b/flight/PiOS/Common/pios_hmc5883.c index 87db6e74d..0eb14e28a 100644 --- a/flight/PiOS/Common/pios_hmc5883.c +++ b/flight/PiOS/Common/pios_hmc5883.c @@ -393,9 +393,11 @@ int32_t PIOS_HMC5883_Test(void) /** * @brief IRQ Handler */ -void PIOS_HMC5883_IRQHandler(void) +bool PIOS_HMC5883_IRQHandler(void) { pios_hmc5883_data_ready = true; + + return false; } #endif /* PIOS_INCLUDE_HMC5883 */ diff --git a/flight/PiOS/Common/pios_l3gd20.c b/flight/PiOS/Common/pios_l3gd20.c index 3151d26e2..6876db16d 100644 --- a/flight/PiOS/Common/pios_l3gd20.c +++ b/flight/PiOS/Common/pios_l3gd20.c @@ -353,7 +353,7 @@ uint8_t PIOS_L3GD20_Test(void) /** * @brief IRQ Handler. Read all the data from onboard buffer */ -void PIOS_L3GD20_IRQHandler(void) +bool PIOS_L3GD20_IRQHandler(void) { l3gd20_irq++; @@ -363,11 +363,11 @@ void PIOS_L3GD20_IRQHandler(void) /* This code duplicates ReadGyros above but uses ClaimBusIsr */ if(PIOS_L3GD20_ClaimBusIsr() != 0) - return; + return false; if(PIOS_SPI_TransferBlock(dev->spi_id, &buf[0], &rec[0], sizeof(buf), NULL) < 0) { PIOS_L3GD20_ReleaseBus(); - return; + return false; } PIOS_L3GD20_ReleaseBus(); @@ -375,7 +375,10 @@ void PIOS_L3GD20_IRQHandler(void) memcpy((uint8_t *) &(data.gyro_x), &rec[1], 6); data.temperature = PIOS_L3GD20_GetReg(PIOS_L3GD20_OUT_TEMP); - xQueueSend(dev->queue, (void *) &data, 0); + portBASE_TYPE xHigherPriorityTaskWoken; + xQueueSendToBackFromISR(dev->queue, (void *) &data, &xHigherPriorityTaskWoken); + + return xHigherPriorityTaskWoken == pdTRUE; } #endif /* L3GD20 */ diff --git a/flight/PiOS/Common/pios_mpu6000.c b/flight/PiOS/Common/pios_mpu6000.c index 428d28370..4cb864fb3 100644 --- a/flight/PiOS/Common/pios_mpu6000.c +++ b/flight/PiOS/Common/pios_mpu6000.c @@ -404,21 +404,21 @@ uint32_t mpu6000_interval_us; uint32_t mpu6000_time_us; uint32_t mpu6000_transfer_size; -void PIOS_MPU6000_IRQHandler(void) +bool PIOS_MPU6000_IRQHandler(void) { static uint32_t timeval; mpu6000_interval_us = PIOS_DELAY_DiffuS(timeval); timeval = PIOS_DELAY_GetRaw(); if(!mpu6000_configured) - return; + return false; mpu6000_count = PIOS_MPU6000_FifoDepth(); if(mpu6000_count < sizeof(struct pios_mpu6000_data)) - return; + return false; if(PIOS_MPU6000_ClaimBus() != 0) - return; + return false; uint8_t mpu6000_send_buf[1+sizeof(struct pios_mpu6000_data)] = {PIOS_MPU6000_FIFO_REG | 0x80, 0, 0, 0, 0, 0, 0, 0, 0}; uint8_t mpu6000_rec_buf[1+sizeof(struct pios_mpu6000_data)]; @@ -426,7 +426,7 @@ void PIOS_MPU6000_IRQHandler(void) if(PIOS_SPI_TransferBlock(dev->spi_id, &mpu6000_send_buf[0], &mpu6000_rec_buf[0], sizeof(mpu6000_send_buf), NULL) < 0) { PIOS_MPU6000_ReleaseBus(); mpu6000_fails++; - return; + return false; } PIOS_MPU6000_ReleaseBus(); @@ -437,12 +437,12 @@ void PIOS_MPU6000_IRQHandler(void) if (mpu6000_count >= (sizeof(data) * 2)) { mpu6000_fifo_backup++; if(PIOS_MPU6000_ClaimBus() != 0) - return; + return false; if(PIOS_SPI_TransferBlock(dev->spi_id, &mpu6000_send_buf[0], &mpu6000_rec_buf[0], sizeof(mpu6000_send_buf), NULL) < 0) { PIOS_MPU6000_ReleaseBus(); mpu6000_fails++; - return; + return false; } PIOS_MPU6000_ReleaseBus(); @@ -462,12 +462,15 @@ void PIOS_MPU6000_IRQHandler(void) data.gyro_y = mpu6000_rec_buf[5] << 8 | mpu6000_rec_buf[6]; data.gyro_z = mpu6000_rec_buf[7] << 8 | mpu6000_rec_buf[8]; #endif - - xQueueSend(dev->queue, (void *) &data, 0); + + portBASE_TYPE xHigherPriorityTaskWoken; + xQueueSendToBackFromISR(dev->queue, (void *) &data, &xHigherPriorityTaskWoken); mpu6000_irq++; mpu6000_time_us = PIOS_DELAY_DiffuS(timeval); + + return xHigherPriorityTaskWoken == pdTRUE; } #endif diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index 1f65748ee..74230c7a1 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -172,7 +172,7 @@ uint32_t random32 = 0x459ab8d8; /* Local function forwared declarations */ static void PIOS_RFM22B_Supervisor(uint32_t ppm_id); static void rfm22_processInt(void); -static void PIOS_RFM22_EXT_Int(void); +static bool PIOS_RFM22_EXT_Int(void); static void rfm22_setTxMode(uint8_t mode); // SPI read/write functions @@ -751,12 +751,13 @@ uint8_t rfm22_read(uint8_t addr) // external interrupt -static void PIOS_RFM22_EXT_Int(void) +static bool PIOS_RFM22_EXT_Int(void) { rfm22_setDebug("Ext Int"); if (!exec_using_spi) rfm22_processInt(); rfm22_setDebug("Ext Done"); + return false; } void rfm22_disableExtInt(void) diff --git a/flight/PiOS/Common/pios_video.c b/flight/PiOS/Common/pios_video.c index 859274909..22e6060ce 100644 --- a/flight/PiOS/Common/pios_video.c +++ b/flight/PiOS/Common/pios_video.c @@ -85,7 +85,7 @@ void swap_buffers() SWAP_BUFFS(tmp, disp_buffer_level, draw_buffer_level); } -void PIOS_Hsync_ISR() { +bool PIOS_Hsync_ISR() { if(dev_cfg->hsync->pin.gpio->IDR & dev_cfg->hsync->pin.init.GPIO_Pin) { //rising @@ -117,9 +117,11 @@ void PIOS_Hsync_ISR() { DMA_SetCurrDataCounter(dev_cfg->mask.dma.tx.channel,BUFFER_LINE_LENGTH); } } + + return false; } -void PIOS_Vsync_ISR() { +bool PIOS_Vsync_ISR() { static portBASE_TYPE xHigherPriorityTaskWoken; //PIOS_LED_Toggle(LED3); @@ -137,6 +139,8 @@ void PIOS_Vsync_ISR() { } } portEND_SWITCHING_ISR(xHigherPriorityTaskWoken); //portEND_SWITCHING_ISR(xHigherPriorityTaskWoken); + + return xHigherPriorityTaskWoken == pdTRUE; } uint16_t PIOS_Video_GetOSDLines(void) { diff --git a/flight/PiOS/STM32F10x/pios_dsm.c b/flight/PiOS/STM32F10x/pios_dsm.c index cb838b56b..b35560d5d 100644 --- a/flight/PiOS/STM32F10x/pios_dsm.c +++ b/flight/PiOS/STM32F10x/pios_dsm.c @@ -128,7 +128,7 @@ static void PIOS_DSM_Bind(struct pios_dsm_dev *dsm_dev, uint8_t bind) 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); + PIOS_DELAY_WaitmS(20); for (int i = 0; i < bind ; i++) { /* RX line, drive low for 120us */ diff --git a/flight/PiOS/STM32F10x/pios_exti.c b/flight/PiOS/STM32F10x/pios_exti.c index 65a651f6f..9b8221bbe 100644 --- a/flight/PiOS/STM32F10x/pios_exti.c +++ b/flight/PiOS/STM32F10x/pios_exti.c @@ -149,7 +149,7 @@ out_fail: return -1; } -static void PIOS_EXTI_generic_irq_handler(uint8_t line_index) +static bool PIOS_EXTI_generic_irq_handler(uint8_t line_index) { uint8_t cfg_index = pios_exti_line_to_cfg_map[line_index]; @@ -158,69 +158,133 @@ static void PIOS_EXTI_generic_irq_handler(uint8_t line_index) if (cfg_index > NELEMENTS(pios_exti_line_to_cfg_map) || cfg_index == PIOS_EXTI_INVALID) { /* Unconfigured interrupt just fired! */ - return; + return false; } struct pios_exti_cfg * cfg = &__start__exti + cfg_index; - cfg->vector(); + return cfg->vector(); } -/* Bind Interrupt Handlers */ - -#define PIOS_EXTI_HANDLE_LINE(line) \ +#ifdef PIOS_INCLUDE_FREERTOS +#define PIOS_EXTI_HANDLE_LINE(line, woken) \ + if (EXTI_GetITStatus(EXTI_Line##line) != RESET) { \ + EXTI_ClearITPendingBit(EXTI_Line##line); \ + woken = PIOS_EXTI_generic_irq_handler(line) ? pdTRUE : woken; \ + } +#else +#define PIOS_EXTI_HANDLE_LINE(line, woken) \ if (EXTI_GetITStatus(EXTI_Line##line) != RESET) { \ EXTI_ClearITPendingBit(EXTI_Line##line); \ PIOS_EXTI_generic_irq_handler(line); \ } +#endif + +/* Bind Interrupt Handlers */ static void PIOS_EXTI_0_irq_handler (void) { - PIOS_EXTI_HANDLE_LINE(0); +#ifdef PIOS_INCLUDE_FREERTOS + portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; +#else + bool xHigherPriorityTaskWoken; // dummy variable +#endif + PIOS_EXTI_HANDLE_LINE(0, xHigherPriorityTaskWoken); +#ifdef PIOS_INCLUDE_FREERTOS + portEND_SWITCHING_ISR(xHigherPriorityTaskWoken); +#endif } void EXTI0_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_0_irq_handler"))); static void PIOS_EXTI_1_irq_handler (void) { - PIOS_EXTI_HANDLE_LINE(1); +#ifdef PIOS_INCLUDE_FREERTOS + portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; +#else + bool xHigherPriorityTaskWoken; // dummy variable +#endif + PIOS_EXTI_HANDLE_LINE(1, xHigherPriorityTaskWoken); +#ifdef PIOS_INCLUDE_FREERTOS + portEND_SWITCHING_ISR(xHigherPriorityTaskWoken); +#endif } void EXTI1_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_1_irq_handler"))); static void PIOS_EXTI_2_irq_handler (void) { - PIOS_EXTI_HANDLE_LINE(2); +#ifdef PIOS_INCLUDE_FREERTOS + portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; +#else + bool xHigherPriorityTaskWoken; // dummy variable +#endif + PIOS_EXTI_HANDLE_LINE(2, xHigherPriorityTaskWoken); +#ifdef PIOS_INCLUDE_FREERTOS + portEND_SWITCHING_ISR(xHigherPriorityTaskWoken); +#endif } void EXTI2_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_2_irq_handler"))); static void PIOS_EXTI_3_irq_handler (void) { - PIOS_EXTI_HANDLE_LINE(3); +#ifdef PIOS_INCLUDE_FREERTOS + portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; +#else + bool xHigherPriorityTaskWoken; // dummy variable +#endif + PIOS_EXTI_HANDLE_LINE(3, xHigherPriorityTaskWoken); +#ifdef PIOS_INCLUDE_FREERTOS + portEND_SWITCHING_ISR(xHigherPriorityTaskWoken); +#endif } void EXTI3_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_3_irq_handler"))); static void PIOS_EXTI_4_irq_handler (void) { - PIOS_EXTI_HANDLE_LINE(4); +#ifdef PIOS_INCLUDE_FREERTOS + portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; +#else + bool xHigherPriorityTaskWoken; // dummy variable +#endif + PIOS_EXTI_HANDLE_LINE(4, xHigherPriorityTaskWoken); +#ifdef PIOS_INCLUDE_FREERTOS + portEND_SWITCHING_ISR(xHigherPriorityTaskWoken); +#endif } void EXTI4_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_4_irq_handler"))); static void PIOS_EXTI_9_5_irq_handler (void) { - PIOS_EXTI_HANDLE_LINE(5); - PIOS_EXTI_HANDLE_LINE(6); - PIOS_EXTI_HANDLE_LINE(7); - PIOS_EXTI_HANDLE_LINE(8); - PIOS_EXTI_HANDLE_LINE(9); +#ifdef PIOS_INCLUDE_FREERTOS + portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; +#else + bool xHigherPriorityTaskWoken; // dummy variable +#endif + PIOS_EXTI_HANDLE_LINE(5, xHigherPriorityTaskWoken); + PIOS_EXTI_HANDLE_LINE(6, xHigherPriorityTaskWoken); + PIOS_EXTI_HANDLE_LINE(7, xHigherPriorityTaskWoken); + PIOS_EXTI_HANDLE_LINE(8, xHigherPriorityTaskWoken); + PIOS_EXTI_HANDLE_LINE(9, xHigherPriorityTaskWoken); +#ifdef PIOS_INCLUDE_FREERTOS + portEND_SWITCHING_ISR(xHigherPriorityTaskWoken); +#endif } void EXTI9_5_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_9_5_irq_handler"))); static void PIOS_EXTI_15_10_irq_handler (void) { - PIOS_EXTI_HANDLE_LINE(10); - PIOS_EXTI_HANDLE_LINE(11); - PIOS_EXTI_HANDLE_LINE(12); - PIOS_EXTI_HANDLE_LINE(13); - PIOS_EXTI_HANDLE_LINE(14); - PIOS_EXTI_HANDLE_LINE(15); +#ifdef PIOS_INCLUDE_FREERTOS + portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; +#else + bool xHigherPriorityTaskWoken; // dummy variable +#endif + PIOS_EXTI_HANDLE_LINE(10, xHigherPriorityTaskWoken); + PIOS_EXTI_HANDLE_LINE(11, xHigherPriorityTaskWoken); + PIOS_EXTI_HANDLE_LINE(12, xHigherPriorityTaskWoken); + PIOS_EXTI_HANDLE_LINE(13, xHigherPriorityTaskWoken); + PIOS_EXTI_HANDLE_LINE(14, xHigherPriorityTaskWoken); + PIOS_EXTI_HANDLE_LINE(15, xHigherPriorityTaskWoken); +#ifdef PIOS_INCLUDE_FREERTOS + portEND_SWITCHING_ISR(xHigherPriorityTaskWoken); +#endif } void EXTI15_10_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_15_10_irq_handler"))); diff --git a/flight/PiOS/STM32F4xx/pios_exti.c b/flight/PiOS/STM32F4xx/pios_exti.c index 9f9567d51..45efb2ae5 100644 --- a/flight/PiOS/STM32F4xx/pios_exti.c +++ b/flight/PiOS/STM32F4xx/pios_exti.c @@ -149,7 +149,7 @@ out_fail: return -1; } -static void PIOS_EXTI_generic_irq_handler(uint8_t line_index) +static bool PIOS_EXTI_generic_irq_handler(uint8_t line_index) { uint8_t cfg_index = pios_exti_line_to_cfg_map[line_index]; @@ -158,69 +158,133 @@ static void PIOS_EXTI_generic_irq_handler(uint8_t line_index) if (cfg_index > NELEMENTS(pios_exti_line_to_cfg_map) || cfg_index == PIOS_EXTI_INVALID) { /* Unconfigured interrupt just fired! */ - return; + return false; } struct pios_exti_cfg * cfg = &__start__exti + cfg_index; - cfg->vector(); + return cfg->vector(); } /* Bind Interrupt Handlers */ -#define PIOS_EXTI_HANDLE_LINE(line) \ +#ifdef PIOS_INCLUDE_FREERTOS +#define PIOS_EXTI_HANDLE_LINE(line, woken) \ + if (EXTI_GetITStatus(EXTI_Line##line) != RESET) { \ + EXTI_ClearITPendingBit(EXTI_Line##line); \ + woken = PIOS_EXTI_generic_irq_handler(line) ? pdTRUE : woken; \ + } +#else +#define PIOS_EXTI_HANDLE_LINE(line, woken) \ if (EXTI_GetITStatus(EXTI_Line##line) != RESET) { \ EXTI_ClearITPendingBit(EXTI_Line##line); \ PIOS_EXTI_generic_irq_handler(line); \ } +#endif static void PIOS_EXTI_0_irq_handler (void) { - PIOS_EXTI_HANDLE_LINE(0); +#ifdef PIOS_INCLUDE_FREERTOS + portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; +#else + bool xHigherPriorityTaskWoken; +#endif + PIOS_EXTI_HANDLE_LINE(0, xHigherPriorityTaskWoken); +#ifdef PIOS_INCLUDE_FREERTOS + portEND_SWITCHING_ISR(xHigherPriorityTaskWoken); +#endif } void EXTI0_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_0_irq_handler"))); static void PIOS_EXTI_1_irq_handler (void) { - PIOS_EXTI_HANDLE_LINE(1); +#ifdef PIOS_INCLUDE_FREERTOS + portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; +#else + bool xHigherPriorityTaskWoken; +#endif + PIOS_EXTI_HANDLE_LINE(1, xHigherPriorityTaskWoken); +#ifdef PIOS_INCLUDE_FREERTOS + portEND_SWITCHING_ISR(xHigherPriorityTaskWoken); +#endif } void EXTI1_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_1_irq_handler"))); static void PIOS_EXTI_2_irq_handler (void) { - PIOS_EXTI_HANDLE_LINE(2); +#ifdef PIOS_INCLUDE_FREERTOS + portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; +#else + bool xHigherPriorityTaskWoken; +#endif + PIOS_EXTI_HANDLE_LINE(2, xHigherPriorityTaskWoken); +#ifdef PIOS_INCLUDE_FREERTOS + portEND_SWITCHING_ISR(xHigherPriorityTaskWoken); +#endif } void EXTI2_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_2_irq_handler"))); static void PIOS_EXTI_3_irq_handler (void) { - PIOS_EXTI_HANDLE_LINE(3); +#ifdef PIOS_INCLUDE_FREERTOS + portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; +#else + bool xHigherPriorityTaskWoken; +#endif + PIOS_EXTI_HANDLE_LINE(3, xHigherPriorityTaskWoken); +#ifdef PIOS_INCLUDE_FREERTOS + portEND_SWITCHING_ISR(xHigherPriorityTaskWoken); +#endif } void EXTI3_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_3_irq_handler"))); static void PIOS_EXTI_4_irq_handler (void) { - PIOS_EXTI_HANDLE_LINE(4); +#ifdef PIOS_INCLUDE_FREERTOS + portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; +#else + bool xHigherPriorityTaskWoken; +#endif + PIOS_EXTI_HANDLE_LINE(4, xHigherPriorityTaskWoken); +#ifdef PIOS_INCLUDE_FREERTOS + portEND_SWITCHING_ISR(xHigherPriorityTaskWoken); +#endif } void EXTI4_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_4_irq_handler"))); static void PIOS_EXTI_9_5_irq_handler (void) { - PIOS_EXTI_HANDLE_LINE(5); - PIOS_EXTI_HANDLE_LINE(6); - PIOS_EXTI_HANDLE_LINE(7); - PIOS_EXTI_HANDLE_LINE(8); - PIOS_EXTI_HANDLE_LINE(9); +#ifdef PIOS_INCLUDE_FREERTOS + portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; +#else + bool xHigherPriorityTaskWoken; +#endif + PIOS_EXTI_HANDLE_LINE(5, xHigherPriorityTaskWoken); + PIOS_EXTI_HANDLE_LINE(6, xHigherPriorityTaskWoken); + PIOS_EXTI_HANDLE_LINE(7, xHigherPriorityTaskWoken); + PIOS_EXTI_HANDLE_LINE(8, xHigherPriorityTaskWoken); + PIOS_EXTI_HANDLE_LINE(9, xHigherPriorityTaskWoken); +#ifdef PIOS_INCLUDE_FREERTOS + portEND_SWITCHING_ISR(xHigherPriorityTaskWoken); +#endif } void EXTI9_5_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_9_5_irq_handler"))); static void PIOS_EXTI_15_10_irq_handler (void) { - PIOS_EXTI_HANDLE_LINE(10); - PIOS_EXTI_HANDLE_LINE(11); - PIOS_EXTI_HANDLE_LINE(12); - PIOS_EXTI_HANDLE_LINE(13); - PIOS_EXTI_HANDLE_LINE(14); - PIOS_EXTI_HANDLE_LINE(15); +#ifdef PIOS_INCLUDE_FREERTOS + portBASE_TYPE xHigherPriorityTaskWoken = pdFALSE; +#else + bool xHigherPriorityTaskWoken; +#endif + PIOS_EXTI_HANDLE_LINE(10, xHigherPriorityTaskWoken); + PIOS_EXTI_HANDLE_LINE(11, xHigherPriorityTaskWoken); + PIOS_EXTI_HANDLE_LINE(12, xHigherPriorityTaskWoken); + PIOS_EXTI_HANDLE_LINE(13, xHigherPriorityTaskWoken); + PIOS_EXTI_HANDLE_LINE(14, xHigherPriorityTaskWoken); + PIOS_EXTI_HANDLE_LINE(15, xHigherPriorityTaskWoken); +#ifdef PIOS_INCLUDE_FREERTOS + portEND_SWITCHING_ISR(xHigherPriorityTaskWoken); +#endif } void EXTI15_10_IRQHandler(void) __attribute__ ((alias ("PIOS_EXTI_15_10_irq_handler"))); diff --git a/flight/PiOS/inc/pios_bma180.h b/flight/PiOS/inc/pios_bma180.h index ef9627f00..51e65a6ec 100644 --- a/flight/PiOS/inc/pios_bma180.h +++ b/flight/PiOS/inc/pios_bma180.h @@ -103,7 +103,7 @@ extern float PIOS_BMA180_GetScale(); extern int32_t PIOS_BMA180_ReadFifo(struct pios_bma180_data * buffer); extern int32_t PIOS_BMA180_ReadAccels(struct pios_bma180_data * data); extern int32_t PIOS_BMA180_Test(); -extern void PIOS_BMA180_IRQHandler(); +extern bool PIOS_BMA180_IRQHandler(); #endif /* PIOS_BMA180_H */ diff --git a/flight/PiOS/inc/pios_exti.h b/flight/PiOS/inc/pios_exti.h index 73a3bb556..4b1203aa2 100644 --- a/flight/PiOS/inc/pios_exti.h +++ b/flight/PiOS/inc/pios_exti.h @@ -36,7 +36,7 @@ #include struct pios_exti_cfg { - void (* vector)(void); + bool (* vector)(void); uint32_t line; /* use EXTI_LineN macros */ struct stm32_gpio pin; struct stm32_irq irq; diff --git a/flight/PiOS/inc/pios_hmc5883.h b/flight/PiOS/inc/pios_hmc5883.h index 6487fcf5c..19e71eb54 100644 --- a/flight/PiOS/inc/pios_hmc5883.h +++ b/flight/PiOS/inc/pios_hmc5883.h @@ -109,7 +109,7 @@ extern bool PIOS_HMC5883_NewDataAvailable(void); extern int32_t PIOS_HMC5883_ReadMag(int16_t out[3]); extern uint8_t PIOS_HMC5883_ReadID(uint8_t out[4]); extern int32_t PIOS_HMC5883_Test(void); -extern void PIOS_HMC5883_IRQHandler(); +bool PIOS_HMC5883_IRQHandler(); #endif /* PIOS_HMC5883_H */ /** diff --git a/flight/PiOS/inc/pios_l3gd20.h b/flight/PiOS/inc/pios_l3gd20.h index 83b2070b6..c41730c2f 100644 --- a/flight/PiOS/inc/pios_l3gd20.h +++ b/flight/PiOS/inc/pios_l3gd20.h @@ -141,7 +141,7 @@ extern int32_t PIOS_L3GD20_SetRange(enum pios_l3gd20_range range); extern float PIOS_L3GD20_GetScale(); extern int32_t PIOS_L3GD20_ReadID(); extern uint8_t PIOS_L3GD20_Test(); -extern void PIOS_L3GD20_IRQHandler(); +bool PIOS_L3GD20_IRQHandler(); #endif /* PIOS_L3GD20_H */ diff --git a/flight/PiOS/inc/pios_mpu6000.h b/flight/PiOS/inc/pios_mpu6000.h index 191b69ed5..782010648 100644 --- a/flight/PiOS/inc/pios_mpu6000.h +++ b/flight/PiOS/inc/pios_mpu6000.h @@ -157,7 +157,7 @@ extern int32_t PIOS_MPU6000_ReadID(); extern uint8_t PIOS_MPU6000_Test(); extern float PIOS_MPU6000_GetScale(); extern float PIOS_MPU6000_GetAccelScale(); -extern void PIOS_MPU6000_IRQHandler(void); +extern bool PIOS_MPU6000_IRQHandler(void); #endif /* PIOS_MPU6000_H */ diff --git a/flight/PiOS/inc/pios_video.h b/flight/PiOS/inc/pios_video.h index 1273bff01..029a19fbf 100644 --- a/flight/PiOS/inc/pios_video.h +++ b/flight/PiOS/inc/pios_video.h @@ -66,8 +66,8 @@ extern TTime timex; extern void PIOS_Video_Init(const struct pios_video_cfg * cfg); uint16_t PIOS_Video_GetOSDLines(void); -extern void PIOS_Hsync_ISR(); -extern void PIOS_Vsync_ISR(); +extern bool PIOS_Hsync_ISR(); +extern bool PIOS_Vsync_ISR(); // First OSD line #define GRAPHICS_LINE 32 diff --git a/flight/PipXtreme/Makefile b/flight/PipXtreme/Makefile index 63f2e7907..2aa57825a 100644 --- a/flight/PipXtreme/Makefile +++ b/flight/PipXtreme/Makefile @@ -38,7 +38,14 @@ OUTDIR := $(TOP)/build/$(TARGET) DEBUG ?= NO # Include objects that are just nice information to show -DIAGNOSTICS ?= NO +STACK_DIAGNOSTICS ?= NO +MIXERSTATUS_DIAGNOSTICS ?= NO +RATEDESIRED_DIAGNOSTICS ?= NO +I2C_WDG_STATS_DIAGNOSTICS ?= NO +DIAG_TASKS ?= NO + +#Or just turn on all the above diagnostics. WARNING: This consumes massive amounts of memory. +ALL_DIGNOSTICS ?=NO # Set to YES to build a FW version that will erase all flash memory ERASE_FLASH ?= NO @@ -378,8 +385,24 @@ ifeq ($(DEBUG),YES) CFLAGS = -DDEBUG endif -ifeq ($(DIAGNOSTICS),YES) -CFLAGS = -DDIAGNOSTICS +ifneq (,$(filter YES,$(STACK_DIAGNOSTICS) $(ALL_DIGNOSTICS))) +CFLAGS += -DSTACK_DIAGNOSTICS +endif + +ifneq (,$(filter YES,$(MIXERSTATUS_DIAGNOSTICS) $(ALL_DIGNOSTICS))) +CFLAGS += -DMIXERSTATUS_DIAGNOSTICS +endif + +ifneq (,$(filter YES,$(RATEDESIRED_DIAGNOSTICS) $(ALL_DIGNOSTICS))) +CFLAGS += -DRATEDESIRED_DIAGNOSTICS +endif + +ifneq (,$(filter YES,$(I2C_WDG_STATS_DIAGNOSTICS) $(ALL_DIGNOSTICS))) +CFLAGS += -DI2C_WDG_STATS_DIAGNOSTICS +endif + +ifneq (,$(filter YES,$(DIAG_TASKS) $(ALL_DIGNOSTICS))) +CFLAGS += -DDIAG_TASKS endif CFLAGS += -g$(DEBUGF) diff --git a/flight/PipXtreme/System/inc/FreeRTOSConfig.h b/flight/PipXtreme/System/inc/FreeRTOSConfig.h index 994956008..0c515b7f7 100755 --- a/flight/PipXtreme/System/inc/FreeRTOSConfig.h +++ b/flight/PipXtreme/System/inc/FreeRTOSConfig.h @@ -76,7 +76,7 @@ NVIC value of 255. */ #endif /* Enable run time stats collection */ -#if defined(DIAGNOSTICS) +#if defined(STACK_DIAGNOSTICS) #define configCHECK_FOR_STACK_OVERFLOW 2 #define configGENERATE_RUN_TIME_STATS 1 diff --git a/flight/Revolution/Makefile b/flight/Revolution/Makefile index fcc03f189..00ee453af 100644 --- a/flight/Revolution/Makefile +++ b/flight/Revolution/Makefile @@ -326,7 +326,10 @@ endif # common architecture-specific flags from the device-specific library makefile CFLAGS += $(ARCHFLAGS) -CFLAGS += -DDIAGNOSTICS +CFLAGS += -DSTACK_DIAGNOSTICS +CFLAGS += -DMIXERSTATUS_DIAGNOSTICS +CFLAGS += -DRATEDESIRED_DIAGNOSTICS +CFLAGS += -DI2C_WDG_STATS_DIAGNOSTICS CFLAGS += -DDIAG_TASKS # This is not the best place for these. Really should abstract out diff --git a/flight/SimPosix/Makefile b/flight/SimPosix/Makefile index 4b4b97ebf..3d0e8d710 100644 --- a/flight/SimPosix/Makefile +++ b/flight/SimPosix/Makefile @@ -260,7 +260,11 @@ endif CFLAGS += $(ARCHFLAGS) CFLAGS += $(UAVOBJDEFINE) -CFLAGS += -DDIAGNOSTICS + +CFLAGS += -DSTACK_DIAGNOSTICS +CFLAGS += -DMIXERSTATUS_DIAGNOSTICS +CFLAGS += -DRATEDESIRED_DIAGNOSTICS +CFLAGS += -DI2C_WDG_STATS_DIAGNOSTICS CFLAGS += -DDIAG_TASKS # This is not the best place for these. Really should abstract out diff --git a/flight/board_hw_defs/coptercontrol/board_hw_defs.c b/flight/board_hw_defs/coptercontrol/board_hw_defs.c index cc6ec4552..403657199 100644 --- a/flight/board_hw_defs/coptercontrol/board_hw_defs.c +++ b/flight/board_hw_defs/coptercontrol/board_hw_defs.c @@ -1134,6 +1134,19 @@ const struct pios_pwm_cfg pios_pwm_cfg = { .channels = pios_tim_rcvrport_all_channels, .num_channels = NELEMENTS(pios_tim_rcvrport_all_channels), }; + +const struct pios_pwm_cfg pios_pwm_with_ppm_cfg = { + .tim_ic_init = { + .TIM_ICPolarity = TIM_ICPolarity_Rising, + .TIM_ICSelection = TIM_ICSelection_DirectTI, + .TIM_ICPrescaler = TIM_ICPSC_DIV1, + .TIM_ICFilter = 0x0, + }, + /* Leave the first channel for PPM use and use the rest for PWM */ + .channels = &pios_tim_rcvrport_all_channels[1], + .num_channels = NELEMENTS(pios_tim_rcvrport_all_channels) - 1, +}; + #endif #if defined(PIOS_INCLUDE_I2C) diff --git a/ground/openpilotgcs/share/openpilotgcs/default_configurations/OpenPilotGCS.xml b/ground/openpilotgcs/share/openpilotgcs/default_configurations/OpenPilotGCS.xml index cab264e14..f8ffa2fd6 100644 --- a/ground/openpilotgcs/share/openpilotgcs/default_configurations/OpenPilotGCS.xml +++ b/ground/openpilotgcs/share/openpilotgcs/default_configurations/OpenPilotGCS.xml @@ -8,6 +8,8 @@ false en_AU true + 700 + 800 default false @@ -37,30 +39,49 @@ - - + default + FlightStatus 0 false - + Armed 0 0 0 - + armed - - + %%DATAPATH%%sounds + Armed 0 1 - false + true - 0 + + default + FlightStatus + 15 + false + Armed + 0 + 0 + 0 + armed + + + %%DATAPATH%%sounds + Armed + 0 + + 1 + + 57600 + @@ -925,39 +946,113 @@ - + false - 0.0.0 - - - \usr\games\fgfs - \usr\share\games\FlightGear - 127.0.0.1 - 9009 - false - 9010 - 127.0.0.1 - FG - true - + 0.0.0 + + + false + false + false + true + true + true + 20 + 50 + false + + + true + 100 + false + true + 100 + 0.0.0.0 + 40100 + true + + + false + false + 40 + 40200 + 127.0.0.1 + ASimRC + false + + + + + false + 0.0.0 + + + false + false + false + true + true + true + 20 + 50 + false + \usr\games\fgfs + \usr\share\games\FlightGear + false + 100 + false + true + 100 + 127.0.0.1 + 9009 + true + + + true + false + 40 + 9010 + 127.0.0.1 + FG + true + - - - false - 0.0.0 - - - \home\lafargue\X-Plane 9\X-Plane-i686 - \usr\share\games\FlightGear - 127.0.0.3 - 6756 - false - 49000 - 127.0.0.1 - X-Plane - false - + + + false + 0.0.0 + + + false + false + false + true + true + true + 20 + 50 + false + + + false + 100 + false + true + 100 + 0.0.0.0 + 6756 + true + + + true + false + 40 + 49000 + 127.0.0.1 + X-Plane + false + @@ -1683,7 +1778,7 @@ false mapquad.png true - false + true @@ -1703,7 +1798,7 @@ false airplanepip.png true - false + true @@ -1723,7 +1818,7 @@ false mapquad.png true - false + true @@ -1766,6 +1861,7 @@ %%DATAPATH%%pfd/default/readymap.earth 46.6715 10.1589 + true %%DATAPATH%%pfd/default/Pfd.qml false @@ -1782,6 +1878,7 @@ %%DATAPATH%%pfd/default/readymap.earth 46.6715 10.1589 + true %%DATAPATH%%pfd/default/Pfd.qml false @@ -2636,7 +2733,7 @@ uavGadget 2 - @Variant(AAAACQAAAAIAAAACAAAClQAAAAIAAAB3) + @Variant(AAAACQAAAAIAAAACAAABhAAAAAIAAAGE) splitter 1 @@ -2669,8 +2766,20 @@ - EmptyGadget - uavGadget + + PfdQmlGadget + + NoTerrain + + uavGadget + + + MagicWaypointGadget + uavGadget + + 1 + @Variant(AAAACQAAAAIAAAACAAAB7wAAAAIAAAGU) + splitter GCSControlGadget @@ -2680,7 +2789,7 @@ uavGadget 1 - @Variant(AAAACQAAAAIAAAACAAAB6AAAAAIAAADC) + @Variant(AAAACQAAAAIAAAACAAADhAAAAAIAAAIX) splitter 2 @@ -2739,7 +2848,7 @@ false - :\core\images\ah.png + :/core/images/ah.png :/core/images/openpilot_logo_64.png :/core/images/config.png :/core/images/cog.png diff --git a/ground/openpilotgcs/share/openpilotgcs/default_configurations/OpenPilotGCS_wide.xml b/ground/openpilotgcs/share/openpilotgcs/default_configurations/OpenPilotGCS_wide.xml index 960c10355..57d287c63 100644 --- a/ground/openpilotgcs/share/openpilotgcs/default_configurations/OpenPilotGCS_wide.xml +++ b/ground/openpilotgcs/share/openpilotgcs/default_configurations/OpenPilotGCS_wide.xml @@ -6,22 +6,13 @@ Notify Plugin settings true - 600 + 700 800 false Wide configuration
Default configuration built for wide screens (17"up)
wide - - - - 1 - 0 - - 1 - - 0 @@ -955,19 +946,74 @@ + + + false + 0.0.0 + + + false + false + false + true + true + true + 20 + 50 + false + + + true + 100 + false + true + 100 + 0.0.0.0 + 40100 + true + + + false + false + 40 + 40200 + 127.0.0.1 + ASimRC + false + + false 0.0.0 + false + false + false + true + true + true + 20 + 50 + false \usr\games\fgfs \usr\share\games\FlightGear + false + 100 + false + true + 100 127.0.0.1 9009 - false + true + + + true + false + 40 9010 - 127.0.0.1 + 127.0.0.1 FG true @@ -978,51 +1024,37 @@ 0.0.0 - \home\lafargue\X-Plane 9\X-Plane-i686 - \usr\share\games\FlightGear - 127.0.0.3 + false + false + false + true + true + true + 20 + 50 + false + + + false + 100 + false + true + 100 + 0.0.0.0 6756 - false + true + + + true + false + 40 49000 - 127.0.0.1 + 127.0.0.1 X-Plane false - - - - false - 0.0.0 - - - false - false - true - true - true - 20 - true - 200 - true - 0 - true - 127.0.0.1 - 40100 - true - false - false - 40200 - 20 - 127.0.0.1 - ASimRC - 50 - false - @Variant(AAAAh0CgAAA=) - - - @@ -1474,6 +1506,17 @@ false + + + false + 0.0.0 + + + %%DATAPATH%%models/boards/CC3D/CC3D.3ds + %%DATAPATH%%models/backgrounds/default_background.png + false + + false @@ -1485,6 +1528,17 @@ false + + + false + 0.0.0 + + + %%DATAPATH%%models/multi/dankers_quad/dankers_quad.3ds + %%DATAPATH%%models/backgrounds/default_background.png + false + + false @@ -1606,6 +1660,17 @@ false + + + false + 0.0.0 + + + %%DATAPATH%%models/multi/mattL_Y6/mattL_Y6.3ds + %%DATAPATH%%models/backgrounds/default_background.png + false + + false @@ -1676,10 +1741,11 @@ 2 GoogleSatellite 2000 + 1 false mapquad.png true - false + true @@ -1695,10 +1761,11 @@ 2 GoogleMap 2000 + 1 false airplanepip.png true - false + true @@ -1714,10 +1781,11 @@ 2 GoogleMap 2000 + 1 false mapquad.png true - false + true @@ -1760,6 +1828,7 @@ %%DATAPATH%%pfd/default/readymap.earth 46.6715 10.1589 + true %%DATAPATH%%pfd/default/Pfd.qml false @@ -1776,6 +1845,7 @@ %%DATAPATH%%pfd/default/readymap.earth 46.6715 10.1589 + true %%DATAPATH%%pfd/default/Pfd.qml false @@ -2162,7 +2232,7 @@ 4294901760 None - X + x Magnetometer 0 1 @@ -2172,7 +2242,7 @@ 4283782655 None - Y + y Magnetometer 0 1 @@ -2182,7 +2252,7 @@ 4283804160 None - Z + z Magnetometer 0 1 @@ -2486,11 +2556,11 @@ uavGadget 1 - @Variant(AAAACQAAAAIAAAACAAAAsQAAAAIAAAEV) + @Variant(AAAACQAAAAIAAAACAAAAYwAAAAIAAAB7) splitter 1 - @Variant(AAAACQAAAAIAAAACAAAArgAAAAIAAAHH) + @Variant(AAAACQAAAAIAAAACAAAAZgAAAAIAAADf) splitter @@ -2520,11 +2590,11 @@ uavGadget 1 - @Variant(AAAACQAAAAIAAAACAAABIAAAAAIAAAFV) + @Variant(AAAACQAAAAIAAAACAAAB1AAAAAIAAAGI) splitter 2 - @Variant(AAAACQAAAAIAAAACAAAB7wAAAAIAAAEf) + @Variant(AAAACQAAAAIAAAACAAACegAAAAIAAAFC) splitter @@ -2535,7 +2605,7 @@ uavGadget 1 - @Variant(AAAACQAAAAIAAAACAAACdgAAAAIAAAMp) + @Variant(AAAACQAAAAIAAAACAAADXgAAAAIAAAQd) splitter UAVGadgetManagerV1 @@ -2543,11 +2613,23 @@ false - ConfigGadget - - default - - uavGadget + + ConfigGadget + + default + + uavGadget + + + UAVObjectBrowser + + default + + uavGadget + + 1 + @Variant(AAAACQAAAAIAAAACAAAEeQAAAAIAAAMC) + splitter UAVGadgetManagerV1 @@ -2555,36 +2637,39 @@ false + UAVObjectBrowser + + default + + uavGadget + + - UAVObjectBrowser - - default - - uavGadget + + LoggingGadget + uavGadget + + + GpsDisplayGadget + + Flight GPS + + uavGadget + + 2 + @Variant(AAAACQAAAAIAAAACAAAAcAAAAAIAAAHo) + splitter DebugGadget uavGadget - 1 - @Variant(AAAACQAAAAA=) - splitter - - - - EmptyGadget - uavGadget - - - EmptyGadget - uavGadget - - 1 - @Variant(AAAACQAAAAA=) + 2 + @Variant(AAAACQAAAAIAAAACAAAB3wAAAAIAAAEp) splitter - 2 - @Variant(AAAACQAAAAIAAAACAAACJgAAAAIAAADo) + 1 + @Variant(AAAACQAAAAIAAAACAAAEvwAAAAIAAAK8) splitter UAVGadgetManagerV1 @@ -2613,30 +2698,21 @@ - - ScopeGadget - - Attitude - - uavGadget - - - ScopeGadget - - Uptimes - - uavGadget - - 2 - @Variant(AAAACQAAAAIAAAACAAABhgAAAAIAAAEO) - splitter + ScopeGadget + + Attitude + + uavGadget - LoggingGadget + ScopeGadget + + Uptimes + uavGadget 2 - @Variant(AAAACQAAAAIAAAACAAAClQAAAAIAAAB3) + @Variant(AAAACQAAAAIAAAACAAABhAAAAAIAAAGE) splitter 1 @@ -2669,8 +2745,20 @@ - EmptyGadget - uavGadget + + PfdQmlGadget + + NoTerrain + + uavGadget + + + MagicWaypointGadget + uavGadget + + 1 + @Variant(AAAACQAAAAIAAAACAAAB7wAAAAIAAAGU) + splitter GCSControlGadget @@ -2680,7 +2768,7 @@ uavGadget 1 - @Variant(AAAACQAAAAIAAAACAAAB6AAAAAIAAADC) + @Variant(AAAACQAAAAIAAAACAAADhAAAAAIAAAIX) splitter 2 @@ -2739,7 +2827,7 @@ false - :\core\images\ah.png + :/core/images/ah.png :/core/images/openpilot_logo_64.png :/core/images/config.png :/core/images/cog.png diff --git a/ground/openpilotgcs/share/openpilotgcs/stylesheets/default_linux.qss b/ground/openpilotgcs/share/openpilotgcs/stylesheets/default_linux.qss index 558054cc1..97844c95a 100644 --- a/ground/openpilotgcs/share/openpilotgcs/stylesheets/default_linux.qss +++ b/ground/openpilotgcs/share/openpilotgcs/stylesheets/default_linux.qss @@ -66,6 +66,8 @@ Utils--StyledBar { background-color: qlineargradient(spread:pad, x1:0, y1:0, x2: width: 6px; border-radius: 2px; margin 0px -10px; + margin-top: 5px; + margin-bottom: 5px; } QSlider::sub-page:vertical { background: #fff; diff --git a/ground/openpilotgcs/share/openpilotgcs/stylesheets/default_macos.qss b/ground/openpilotgcs/share/openpilotgcs/stylesheets/default_macos.qss index 035fa5633..430d04d67 100644 --- a/ground/openpilotgcs/share/openpilotgcs/stylesheets/default_macos.qss +++ b/ground/openpilotgcs/share/openpilotgcs/stylesheets/default_macos.qss @@ -65,6 +65,8 @@ Utils--StyledBar { background-color: qlineargradient(spread:pad, x1:0, y1:0, x2: width: 6px; border-radius: 2px; margin 0px -10px; + margin-top: 5px; + margin-bottom: 5px; } QSlider::sub-page:vertical { background: #fff; diff --git a/ground/openpilotgcs/share/openpilotgcs/stylesheets/default_windows.qss b/ground/openpilotgcs/share/openpilotgcs/stylesheets/default_windows.qss index 035fa5633..430d04d67 100644 --- a/ground/openpilotgcs/share/openpilotgcs/stylesheets/default_windows.qss +++ b/ground/openpilotgcs/share/openpilotgcs/stylesheets/default_windows.qss @@ -65,6 +65,8 @@ Utils--StyledBar { background-color: qlineargradient(spread:pad, x1:0, y1:0, x2: width: 6px; border-radius: 2px; margin 0px -10px; + margin-top: 5px; + margin-bottom: 5px; } QSlider::sub-page:vertical { background: #fff; diff --git a/ground/openpilotgcs/share/openpilotgcs/stylesheets/wide_linux.qss b/ground/openpilotgcs/share/openpilotgcs/stylesheets/wide_linux.qss index 558054cc1..97844c95a 100644 --- a/ground/openpilotgcs/share/openpilotgcs/stylesheets/wide_linux.qss +++ b/ground/openpilotgcs/share/openpilotgcs/stylesheets/wide_linux.qss @@ -66,6 +66,8 @@ Utils--StyledBar { background-color: qlineargradient(spread:pad, x1:0, y1:0, x2: width: 6px; border-radius: 2px; margin 0px -10px; + margin-top: 5px; + margin-bottom: 5px; } QSlider::sub-page:vertical { background: #fff; diff --git a/ground/openpilotgcs/share/openpilotgcs/stylesheets/wide_macos.qss b/ground/openpilotgcs/share/openpilotgcs/stylesheets/wide_macos.qss index 035fa5633..430d04d67 100644 --- a/ground/openpilotgcs/share/openpilotgcs/stylesheets/wide_macos.qss +++ b/ground/openpilotgcs/share/openpilotgcs/stylesheets/wide_macos.qss @@ -65,6 +65,8 @@ Utils--StyledBar { background-color: qlineargradient(spread:pad, x1:0, y1:0, x2: width: 6px; border-radius: 2px; margin 0px -10px; + margin-top: 5px; + margin-bottom: 5px; } QSlider::sub-page:vertical { background: #fff; diff --git a/ground/openpilotgcs/share/openpilotgcs/stylesheets/wide_windows.qss b/ground/openpilotgcs/share/openpilotgcs/stylesheets/wide_windows.qss index 035fa5633..430d04d67 100644 --- a/ground/openpilotgcs/share/openpilotgcs/stylesheets/wide_windows.qss +++ b/ground/openpilotgcs/share/openpilotgcs/stylesheets/wide_windows.qss @@ -65,6 +65,8 @@ Utils--StyledBar { background-color: qlineargradient(spread:pad, x1:0, y1:0, x2: width: 6px; border-radius: 2px; margin 0px -10px; + margin-top: 5px; + margin-bottom: 5px; } QSlider::sub-page:vertical { background: #fff; diff --git a/ground/openpilotgcs/share/share.pro b/ground/openpilotgcs/share/share.pro index 31b545e71..3c2a517b8 100644 --- a/ground/openpilotgcs/share/share.pro +++ b/ground/openpilotgcs/share/share.pro @@ -6,13 +6,14 @@ SUBDIRS = openpilotgcs/translations DATACOLLECTIONS = dials models pfd sounds diagrams mapicons stylesheets default_configurations equals(copydata, 1) { - for(dir, DATACOLLECTIONS) { - exists($$GCS_SOURCE_TREE/share/openpilotgcs/$$dir) { - macx:data_copy.commands += $(COPY_DIR) $$targetPath(\"$$GCS_SOURCE_TREE/share/openpilotgcs/$$dir\") $$targetPath(\"$$GCS_DATA_PATH/\") $$addNewline() - !macx:data_copy.commands += $(MKDIR) $$targetPath(\"$$GCS_DATA_PATH/$$dir\") $$addNewline() - !macx:data_copy.commands += $(COPY_DIR) $$targetPath(\"$$GCS_SOURCE_TREE/share/openpilotgcs/$$dir\") $$targetPath(\"$$GCS_DATA_PATH/\") $$addNewline() - } - } + for(dir, DATACOLLECTIONS) { + exists($$GCS_SOURCE_TREE/share/openpilotgcs/$$dir) { + macx:data_copy.commands += $(COPY_DIR) $$targetPath(\"$$GCS_SOURCE_TREE/share/openpilotgcs/$$dir\") $$targetPath(\"$$GCS_DATA_PATH/\") $$addNewline() + win32:data_copy.commands += $(COPY_DIR) $$targetPath(\"$$GCS_SOURCE_TREE/share/openpilotgcs/$$dir\") $$targetPath(\"$$GCS_DATA_PATH/$$dir\") $$addNewline() + unix:data_copy.commands += $(MKDIR) $$targetPath(\"$$GCS_DATA_PATH/$$dir\") $$addNewline() + unix:data_copy.commands += $(COPY_DIR) $$targetPath(\"$$GCS_SOURCE_TREE/share/openpilotgcs/$$dir\") $$targetPath(\"$$GCS_DATA_PATH/\") $$addNewline() + } + } data_copy.target = FORCE QMAKE_EXTRA_TARGETS += data_copy diff --git a/ground/openpilotgcs/src/app/main.cpp b/ground/openpilotgcs/src/app/main.cpp index 88eacd532..9d4010165 100644 --- a/ground/openpilotgcs/src/app/main.cpp +++ b/ground/openpilotgcs/src/app/main.cpp @@ -252,7 +252,7 @@ int main(int argc, char **argv) QCoreApplication::applicationDirPath()+QLatin1String(SHARE_PATH)); // keep this in sync with the MainWindow ctor in coreplugin/mainwindow.cpp QSettings settings(XmlConfig::XmlSettingsFormat, QSettings::UserScope, - QLatin1String("OpenPilot"), QLatin1String("OpenPilotGCS")); + QLatin1String("OpenPilot"), QLatin1String("OpenPilotGCS_config")); overrideSettings(settings, argc, argv); locale = settings.value("General/OverrideLanguage", locale).toString(); diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/opmaps.cpp b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/opmaps.cpp index 3b858d82f..86660fd3e 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/core/opmaps.cpp +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/core/opmaps.cpp @@ -43,8 +43,6 @@ namespace core { LanguageStr=LanguageType().toShortString(Language); Cache::Instance(); -// OPMaps::MemoryCache(); - } diff --git a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/lks94projection.h b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/lks94projection.h index 66581c694..d3e09b868 100644 --- a/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/lks94projection.h +++ b/ground/openpilotgcs/src/libs/opmapcontrol/src/internals/projections/lks94projection.h @@ -3,25 +3,25 @@ * * @file lks94projection.h * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. -* @brief +* @brief * @see The GNU Public License (GPL) Version 3 * @defgroup OPMapWidget * @{ -* +* *****************************************************************************/ -/* -* This program is free software; you can redistribute it and/or modify -* it under the terms of the GNU General Public License as published by -* the Free Software Foundation; either version 3 of the License, or +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or * (at your option) any later version. -* -* This program is distributed in the hope that it will be useful, but -* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License * for more details. -* -* You should have received a copy of the GNU General Public License along -* with this program; if not, write to the Free Software Foundation, Inc., +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ #ifndef LKS94PROJECTION_H @@ -30,7 +30,7 @@ #include "cmath" #include "../pureprojection.h" - + namespace projections { class LKS94Projection:public internals::PureProjection { diff --git a/ground/openpilotgcs/src/libs/sdlgamepad/sdlgamepad.cpp b/ground/openpilotgcs/src/libs/sdlgamepad/sdlgamepad.cpp index 2293c49ba..cbaa87453 100644 --- a/ground/openpilotgcs/src/libs/sdlgamepad/sdlgamepad.cpp +++ b/ground/openpilotgcs/src/libs/sdlgamepad/sdlgamepad.cpp @@ -93,8 +93,18 @@ bool SDLGamepad::setGamepad(qint16 index) { buttons = SDL_JoystickNumButtons(gamepad); axes = SDL_JoystickNumAxes(gamepad); - this->index = index; - return true; + + if (axes >= 4) { + this->index = index; + return true; + } + else + { + buttons = -1; + axes = -1; + this->index = -1; + qCritical("Gamepad has less than 4 axes"); + } } else { diff --git a/ground/openpilotgcs/src/libs/utils/coordinateconversions.cpp b/ground/openpilotgcs/src/libs/utils/coordinateconversions.cpp index a7f7117b1..bf5b987e8 100644 --- a/ground/openpilotgcs/src/libs/utils/coordinateconversions.cpp +++ b/ground/openpilotgcs/src/libs/utils/coordinateconversions.cpp @@ -257,5 +257,26 @@ void CoordinateConversions::Quaternion2R(const float q[4], float Rbe[3][3]) Rbe[2][2] = q0s - q1s - q2s + q3s; } +//** Find quaternion vector from a rotation matrix, Rbe, a matrix which rotates a vector from earth frame to body frame ** +void CoordinateConversions::R2Quaternion(float const Rbe[3][3], float q[4]) +{ + qreal w, x, y, z; + + // w always >= 0 + w = sqrt(std::max(0.0, 1.0 + Rbe[0][0] + Rbe[1][1] + Rbe[2][2])) / 2.0; + x = sqrt(std::max(0.0, 1.0 + Rbe[0][0] - Rbe[1][1] - Rbe[2][2])) / 2.0; + y = sqrt(std::max(0.0, 1.0 - Rbe[0][0] + Rbe[1][1] - Rbe[2][2])) / 2.0; + z = sqrt(std::max(0.0, 1.0 - Rbe[0][0] - Rbe[1][1] + Rbe[2][2])) / 2.0; + + x = copysign(x, (Rbe[1][2] - Rbe[2][1])); + y = copysign(y, (Rbe[2][0] - Rbe[0][2])); + z = copysign(z, (Rbe[0][1] - Rbe[1][0])); + + q[0]=w; + q[1]=x; + q[2]=y; + q[3]=z; +} + } diff --git a/ground/openpilotgcs/src/libs/utils/coordinateconversions.h b/ground/openpilotgcs/src/libs/utils/coordinateconversions.h index ca077a0c4..5f515c147 100644 --- a/ground/openpilotgcs/src/libs/utils/coordinateconversions.h +++ b/ground/openpilotgcs/src/libs/utils/coordinateconversions.h @@ -50,6 +50,7 @@ public: void Quaternion2RPY(const float q[4], float rpy[3]); void RPY2Quaternion(const float rpy[3], float q[4]); void Quaternion2R(const float q[4], float Rbe[3][3]); + void R2Quaternion(float const Rbe[3][3], float q[4]); }; } diff --git a/ground/openpilotgcs/src/libs/utils/mylistwidget.h b/ground/openpilotgcs/src/libs/utils/mylistwidget.h index 40059927e..176063681 100644 --- a/ground/openpilotgcs/src/libs/utils/mylistwidget.h +++ b/ground/openpilotgcs/src/libs/utils/mylistwidget.h @@ -42,7 +42,7 @@ class QTCREATOR_UTILS_EXPORT MyListWidget : public QListWidget { Q_OBJECT public: - MyListWidget(QWidget *parent) : QListWidget(parent), m_iconAbove(false) { } + MyListWidget(QWidget *parent) : QListWidget(parent), m_iconAbove(false) {} void setIconAbove(bool iconAbove) { m_iconAbove = iconAbove; } protected: QStyleOptionViewItem viewOptions() const; diff --git a/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.cpp b/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.cpp index 3db71a316..639052e57 100644 --- a/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.cpp +++ b/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.cpp @@ -48,20 +48,24 @@ MyTabbedStackWidget::MyTabbedStackWidget(QWidget *parent, bool isVertical, bool toplevelLayout->addWidget(m_stackWidget); m_listWidget->setFlow(QListView::TopToBottom); m_listWidget->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Expanding); + m_listWidget->setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); } else { toplevelLayout = new QVBoxLayout; toplevelLayout->addWidget(m_stackWidget); toplevelLayout->addWidget(m_listWidget); m_listWidget->setFlow(QListView::LeftToRight); m_listWidget->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Fixed); + m_listWidget->setVerticalScrollBarPolicy(Qt::ScrollBarAlwaysOff); } - if (m_iconAbove && m_vertical) + + if (m_iconAbove && m_vertical) { m_listWidget->setFixedWidth(90); // this should be computed instead + } toplevelLayout->setSpacing(0); toplevelLayout->setContentsMargins(0, 0, 0, 0); - m_listWidget->setSpacing(0); m_listWidget->setContentsMargins(0, 0, 0, 0); + m_listWidget->setSpacing(0); m_stackWidget->setContentsMargins(0, 0, 0, 0); setLayout(toplevelLayout); diff --git a/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.h b/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.h index f32524ce5..5faad8222 100644 --- a/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.h +++ b/ground/openpilotgcs/src/libs/utils/mytabbedstackwidget.h @@ -52,6 +52,7 @@ public: void insertCornerWidget(int index, QWidget *widget); int cornerWidgetCount() { return m_cornerWidgetCount; } QWidget * currentWidget(){return m_stackWidget->currentWidget();} + QWidget * getWidget(int index) {return m_stackWidget->widget(index);} signals: void currentAboutToShow(int index,bool * proceed); diff --git a/ground/openpilotgcs/src/libs/utils/pathutils.cpp b/ground/openpilotgcs/src/libs/utils/pathutils.cpp index 0ecdd3c85..3c06cd497 100644 --- a/ground/openpilotgcs/src/libs/utils/pathutils.cpp +++ b/ground/openpilotgcs/src/libs/utils/pathutils.cpp @@ -98,7 +98,7 @@ QString PathUtils::GetStoragePath() { // This routine works with "/" as the standard: // Work out where the settings are stored on the machine - QSettings set(XmlConfig::XmlSettingsFormat, QSettings::UserScope,QLatin1String("OpenPilot"), QLatin1String("OpenPilotGCS")); + QSettings set(XmlConfig::XmlSettingsFormat, QSettings::UserScope,QLatin1String("OpenPilot"), QLatin1String("OpenPilotGCS_config")); QFileInfo f(set.fileName()); QDir dir(f.absoluteDir()); diff --git a/ground/openpilotgcs/src/plugins/config/Config.pluginspec b/ground/openpilotgcs/src/plugins/config/Config.pluginspec index 1ba1c8f76..f9ce7a7e5 100644 --- a/ground/openpilotgcs/src/plugins/config/Config.pluginspec +++ b/ground/openpilotgcs/src/plugins/config/Config.pluginspec @@ -1,4 +1,4 @@ - + The OpenPilot Project (C) 2010 OpenPilot Project GNU Public License (GPL) Version 3 diff --git a/ground/openpilotgcs/src/plugins/config/airframe.ui b/ground/openpilotgcs/src/plugins/config/airframe.ui index c5ee92452..dda3534d4 100755 --- a/ground/openpilotgcs/src/plugins/config/airframe.ui +++ b/ground/openpilotgcs/src/plugins/config/airframe.ui @@ -6,17 +6,14 @@ 0 0 - 965 - 637 + 880 + 608 Form - - 6 - 12 @@ -131,8 +128,8 @@ 0 0 - 935 - 554 + 850 + 508 @@ -145,9 +142,6 @@ - - 6 - 12 @@ -705,12 +699,12 @@ margin:1px; - - 24 - 0 + + -1 + @@ -853,7 +847,7 @@ margin:1px;
- + 0 0 @@ -1098,7 +1092,7 @@ margin:1px;
Typical value is 50% for + or X configuration on quads.
- -100 + 0 100 @@ -1191,7 +1185,7 @@ margin:1px;
- + 0 0 @@ -1456,7 +1450,7 @@ font: bold 12px; margin:1px;
- Multirotor Yaw Direction + Multirotor Motor Direction Qt::AlignCenter @@ -1512,9 +1506,9 @@ margin:1px;
- + - Reverse Yaw Mix + Reverse all motors @@ -1550,487 +1544,506 @@ margin:1px;
false - + - - - + + + true + + + + + 0 + 0 + 800 + 386 + + + - - - - 0 - 0 - - - - - 75 - true - - - - Vehicle type: - - - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - - - - 75 - true - - - - Channel Assignment - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - - - - 0 - 0 - - - - - 0 - 100 - - - - Output channel asignmets - - - - - - - 77 - 0 - - - - Engine - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Select output channel for the engine - - - - - - - - 60 - 0 - - - - Aileron 1 - - - - - - - Select output channel for the first aileron (or elevon) - - - - - - - false - - - - 60 - 0 - - - - Aileron 2 - - - - - - - false - - - Select output channel for the second aileron (or elevon) - - - - - - - - 0 - 0 - - - - Motor - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Select output channel for the first motor - - - - - - - false - - - - 47 - 0 - - - - Motor 2 - - - - - - - false - - - Select output channel for a second motor - - - - - - - Front Steering - - - - - - - Select output channel for the first steering actuator - - - - - - - Rear Steering - - - - - - - Select output channel for a second steering actuator - - - - - - - - - - true - - - - 0 - 0 - - - - Differential Steering Mix - - - - - - - - + + + + + + + + 0 + 0 + + + + + 75 + true + + + + Vehicle type: + + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + + + + 75 + true + + + + Channel Assignment + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + + + + 0 + 0 + + + + + 0 + 100 + + + + Output channel asignmets + + + + - 65 + 77 0 - Left % + Engine + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - 100 - - - 50 - - - Qt::Vertical + + + + Select output channel for the engine - - - - 50 - - - - - - - - - + + - 50 + 60 0 - Right % + Aileron 1 - - - - 100 - - - 50 - - - Qt::Vertical + + + + Select output channel for the first aileron (or elevon) - - + + + + false + + + + 60 + 0 + + - 50 + Aileron 2 + + + + + + + false + + + Select output channel for the second aileron (or elevon) + + + + + + + + 0 + 0 + + + + Motor + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Select output channel for the first motor + + + + + + + false + + + + 47 + 0 + + + + Motor 2 + + + + + + + false + + + Select output channel for a second motor + + + + + + + Front Steering + + + + + + + Select output channel for the first steering actuator + + + + + + + Rear Steering + + + + + + + Select output channel for a second steering actuator - - - - - - - - - - - 0 - 100 - - - - Front throttle curve - - - - - - - 0 - 0 - - - - - 0 - 0 - - - - - 500 - 500 - - - - - 10 - 10 - - - - - 300 - 350 - - - - - - - - - - - - 0 - 0 - - - - Rear throttle curve - - - - - - - 0 - 0 - - - - - 0 - 0 - - - - - 500 - 500 - - - - - 10 - 10 - - - - - 300 - 350 - - - - - - + + + + + + true + + + + 0 + 0 + + + + Differential Steering Mix + + + + + + + + + + + 65 + 0 + + + + Left % + + + + + + + 100 + + + 50 + + + Qt::Vertical + + + + + + + 50 + + + + + + + + + + + + 50 + 0 + + + + Right % + + + + + + + 100 + + + 50 + + + Qt::Vertical + + + + + + + 50 + + + + + + + + + + + + + + + 0 + 100 + + + + Front throttle curve + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 500 + 500 + + + + + 10 + 10 + + + + + 300 + 350 + + + + + + + + + + + + 0 + 0 + + + + Rear throttle curve + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 500 + 500 + + + + + 10 + 10 + + + + + 300 + 350 + + + + + + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 75 + true + + + + Mixer OK + + + + + + - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 75 - true - - - - Mixer OK - - - - - - + + @@ -2819,8 +2832,8 @@ margin:1px;
0 0 - 935 - 554 + 287 + 326 @@ -2836,9 +2849,6 @@ margin:1px;
12 - - 6 - @@ -3206,14 +3216,15 @@ p, li { white-space: pre-wrap; } <!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:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> +</style></head><body style=" font-family:'Lucida Grande'; font-size:13pt; font-weight:400; font-style:normal;"> <table border="0" style="-qt-table-type: root; margin-top:4px; margin-bottom:4px; margin-left:4px; margin-right:4px;"> <tr> <td style="border: none;"> <p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:14pt; font-weight:600; color:#ff0000;">SETTING UP FEED FORWARD REQUIRES CAUTION</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:13pt;">Beware: Feed Forward Tuning will launch all engines around mid-throttle, you have been warned!</span></p> -<p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:13pt;">Remove your props initially, and for fine-tuning, make sure your airframe is safely held in place. Wear glasses and protect your face and body.</span></p></td></tr></table></body></html> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"><br /></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;"><br /></span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Beware: Feed Forward Tuning will launch all engines around mid-throttle, you have been warned!</p> +<p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Remove your props initially, and for fine-tuning, make sure your airframe is safely held in place. Wear glasses and protect your face and body.</p></td></tr></table></body></html>
@@ -3264,7 +3275,7 @@ p, li { white-space: pre-wrap; } - + :/core/images/helpicon.svg:/core/images/helpicon.svg @@ -3317,7 +3328,7 @@ p, li { white-space: pre-wrap; } - + diff --git a/ground/openpilotgcs/src/plugins/config/autotune.ui b/ground/openpilotgcs/src/plugins/config/autotune.ui index 4d7653c0b..647e7b166 100644 --- a/ground/openpilotgcs/src/plugins/config/autotune.ui +++ b/ground/openpilotgcs/src/plugins/config/autotune.ui @@ -6,1078 +6,687 @@ 0 0 - 443 - 575 + 739 + 688 + + + 0 + 0 + + Form - - - - 20 - 10 - 401 - 131 - + + + 6 - - Tuning Aggressiveness + + 12 - - - - - Rate Tuning: - + + + + 0 + + + + Pre-Autotune + + + + 12 + + + + + QFrame::StyledPanel + + + QFrame::Sunken + + + <!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:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;"> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:20pt; font-weight:600; color:#ff0000;">WARNING:</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Lucida Grande'; font-size:13pt;"><br /></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:13pt;"><br /></span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:13pt;">This is an experimental plugin for the GCS that is going to make your aircraft shake, etc, so test with lots of space and be </span><span style=" font-family:'Lucida Grande'; font-size:13pt; font-weight:600;">very very wary</span><span style=" font-family:'Lucida Grande'; font-size:13pt;"> for it creating bad tuning values.  Basically there is no reason to think this will work at all.<br /><br />To use autotuning, here are the steps:<br /></span></p> +<ul style="margin-top: 0px; margin-bottom: 0px; margin-left: 0px; margin-right: 0px; -qt-list-indent: 1;"><li style=" font-family:'Lucida Grande'; font-size:13pt;" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">On the <span style=" font-style:italic;">Input configuration</span> tab, <span style=" font-style:italic;">Flight Mode Switch Settings</span>, set one of your flight modes to &quot;Autotune&quot;.<br /></li> +<li style=" font-family:'Lucida Grande'; font-size:13pt;" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Take off, change flight mode to autotune, keep it in the air while it's shaking.<br /></li> +<li style=" font-family:'Lucida Grande'; font-size:13pt;" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Land and disarm.  (note - you <span style=" font-weight:600;">MUST</span> stay in autotune mode through this point, leaving autotune before disarming aborts the process)<br /></li> +<li style=" font-family:'Lucida Grande'; font-size:13pt;" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">We'd recommend checking your stabilization settings before trying them out (ie: compare to what you currently use, if they are VASTLY different, probably a good indication bad things will happen).<br /></li> +<li style=" font-family:'Lucida Grande'; font-size:13pt;" style=" margin-top:0px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">Test fly the new settings.</li> +<li style=" font-family:'Lucida Grande'; font-size:13pt;" style=" margin-top:0px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">If you're ready to proceed, click the <span style=" font-style:italic;">Enable Autotune Module</span> checkbox above this text, click <span style=" font-style:italic;">save</span> and go to the next tab.</li></ul></body></html> + + + + + + + Module Control + + + + + + Enable Autotune Module + + + true + + + + + + + Qt::Horizontal + + + + 454 + 20 + + + + + + horizontalSpacer_5 + enableAutoTune + horizontalSpacer_4 + enableAutoTune + horizontalSpacer_5 + + + - - - - - Attitude Tuning: - + + + Autotune Setup + + + + 0 + + + + + + + + + + 255 + 255 + 255 + + + + + + + 232 + 232 + 232 + + + + + + + + + 255 + 255 + 255 + + + + + + + 232 + 232 + 232 + + + + + + + + + 232 + 232 + 232 + + + + + + + 232 + 232 + 232 + + + + + + + + QFrame::NoFrame + + + QFrame::Plain + + + true + + + + + 0 + 0 + 711 + 596 + + + + + 0 + 0 + + + + true + + + + 12 + + + 12 + + + + + Tuning Aggressiveness + + + + + + Rate Tuning: + + + + + + + Attitude Tuning: + + + + + + + 100 + + + Qt::Horizontal + + + + objname:RelayTuningSettings + fieldname:RateGain + scale:0.01 + haslimits:no + + + + + + + + 100 + + + Qt::Horizontal + + + + objname:RelayTuningSettings + fieldname:AttitudeGain + scale:0.01 + haslimits:no + + + + + + + + + + + Measured Properties + + + + + + Roll: + + + + + + + 0 + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + objname:RelayTuning + fieldname:Period + element:Roll + + + + + + + + 0 + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + objname:RelayTuning + fieldname:Gain + element:Roll + + + + + + + + Period (ms) + + + + + + + Gain (deg/s) / output + + + + + + + Pitch + + + + + + + 0 + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + objname:RelayTuning + fieldname:Period + element:Pitch + + + + + + + + 0 + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + objname:RelayTuning + fieldname:Gain + element:Pitch + + + + + + + + + + + Computed Values + + + + + + RateKi + + + + + + + AttitudeKp + + + + + + + 0 + + + + + + + Pitch + + + + + + + RateKp + + + + + + + 0 + + + + + + + AttitudeKi + + + + + + + Roll + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + 0 + + + + + + + + + + + + + + + + + + + + + Apply Computed Values + + + + + + + Step Size + + + Qt::AlignCenter + + + + + + + Qt::Horizontal + + + + objname:RelayTuningSettings + fieldname:Amplitude + scale:0.01 + haslimits:no + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + The Apply and Save buttons below save the autotuning settings which +will alter settings for the next autotuning flight + + + Qt::AlignCenter + + + + + + + + + + + + Qt::Vertical + + + + 20 + 77 + + + + + + + + + - - - - - 100 - - - Qt::Horizontal - - - - objname:RelayTuningSettings - fieldname:RateGain - scale:0.01 - haslimits:no - - - - - - - - 100 - - - Qt::Horizontal - - - - objname:RelayTuningSettings - fieldname:AttitudeGain - scale:0.01 - haslimits:no - - - - - - - - - - 20 - 250 - 401 - 121 - - - - Computed Values - - - - - - RateKp - - - - - - - Roll - - - - - - - RateKi - - - - - - - AttitudeKp - - - - - - - AttitudeKi - - - - - - - Pitch - - - - - - - 0 - - - - - - - 0 - - - - - - - 0 - - - - - - - 0 - - - - - - - 0 - - - - - - - 0 - - - - - - - 0 - - - - - - - 0 - - - - - - - - - 20 - 140 - 401 - 111 - - - - Measured Properties - - - - - - Roll: - - - - - - - 0 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - objname:RelayTuning - fieldname:Period - element:Roll - - - - - - - - 0 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - objname:RelayTuning - fieldname:Gain - element:Roll - - - - - - - - Period (ms) - - - - - - - Gain (deg/s) / output - - - - - - - Pitch - - - - - - - 0 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - objname:RelayTuning - fieldname:Period - element:Pitch - - - - - - - - 0 - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - objname:RelayTuning - fieldname:Gain - element:Pitch - - - - - - - - - - 20 - 480 - 401 - 79 - - - - - 0 - 0 - - - - - 0 - 79 - - - - - 16777215 - 79 - - - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - false - - - - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - - - - Qt::Horizontal - - - - 111 - 10 - - - - - - - - - 120 - 28 - - - - Reloads the saved settings into GCS. + + + + + + 4 + + + + + Qt::Horizontal + + + QSizePolicy::Expanding + + + + 13 + 25 + + + + + + + + + 0 + 0 + + + + Reloads the saved settings into GCS. Useful if you have accidentally changed some settings. - - - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } - - - Reload Board Data - - - - button:reload - buttongroup:10 - - - - - - - - - 60 - 28 - - - - Send settings to the board but do not save to the non-volatile memory - - - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } - - - Apply - - - - button:apply - - - - - - - - - 60 - 28 - - - - Send settings to the board and save to the non-volatile memory - - - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } - - - Save - - - - button:save - - - - - - - - - - 30 - 440 - 401 - 31 - - - - The buttons below change the autotuning settings which -will alter things for the next autotuning flight - - - - - - 250 - 380 - 171 - 31 - - - - QPushButton { -border: 1px outset #999; -border-radius: 5; -background-color: qlineargradient(spread:pad, x1:0.507, y1:0.869318, x2:0.507, y2:0.0965909, stop:0.28 rgba(236, 236, 236, 255), stop:1 rgba(252, 252, 252, 255)); -} - -QPushButton:pressed { - - border-style: inset; - background-color: qlineargradient(spread:pad, x1:0.502, y1:0.664864, x2:0.502, y2:0.034, stop:0.358209 rgba(250, 250, 250, 255), stop:0.626866 rgba(235, 235, 235, 255)); - -} - - -QPushButton:hover { - border: 1px outset #999; -border-color: rgb(83, 83, 83); -border-radius: 4; - } - - - Apply Computed Values - - - - - - 40 - 410 - 104 - 20 - - - - Step Size - - - - - - 149 - 410 - 266 - 20 - - - - Qt::Horizontal - - - - objname:RelayTuningSettings - fieldname:Amplitude - scale:0.01 - haslimits:no - - - + + + + + + Reload Board Data + + + + button:reload + buttongroup:10 + + + + + + + + + 0 + 0 + + + + Send settings to the board but do not save to the non-volatile memory + + + + + + Apply + + + + button:apply + + + + + + + + + 0 + 0 + + + + Send settings to the board and save to the non-volatile memory + + + + + + Save + + + + button:save + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/config/camerastabilization.ui b/ground/openpilotgcs/src/plugins/config/camerastabilization.ui index e71d0c5b4..b2b756ca4 100755 --- a/ground/openpilotgcs/src/plugins/config/camerastabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/camerastabilization.ui @@ -6,22 +6,34 @@ 0 0 - 789 - 615 + 786 + 566 + + + 0 + 0 + + + + + 0 + 0 + + Form - - 6 - - - 12 - + + + 0 + 0 + + 0 @@ -35,6 +47,12 @@ + + + 0 + 0 + + QFrame::NoFrame @@ -46,19 +64,37 @@ 0 0 - 742 - 560 + 741 + 559 - 6 + 12 12 + + + 0 + 0 + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + Module Control @@ -86,7 +122,7 @@ - + 0 0 @@ -94,7 +130,13 @@ 0 - 131 + 130 + + + + + 16777215 + 16777215 @@ -340,7 +382,7 @@ margin:1px; - + 0 0 @@ -348,13 +390,22 @@ margin:1px;
0 - 266 + 250 + + + + + 16777215 + 16777215 Advanced Settings (Control) + + 6 + @@ -924,6 +975,18 @@ value.
+ + + 0 + 71 + + + + + 16777215 + 16777215 + + Messages @@ -946,6 +1009,9 @@ value.
Qt::Vertical + + QSizePolicy::Expanding + 20 @@ -963,24 +1029,24 @@ value.
- - + + 4 - + Qt::Horizontal - 321 - 16 + 288 + 18 - + @@ -1029,7 +1095,7 @@ value.
- + @@ -1060,7 +1126,7 @@ Apply or Save button afterwards.
- + @@ -1093,7 +1159,7 @@ Apply or Save button afterwards.
- + @@ -1120,7 +1186,7 @@ Apply or Save button afterwards.
- + diff --git a/ground/openpilotgcs/src/plugins/config/ccattitude.ui b/ground/openpilotgcs/src/plugins/config/ccattitude.ui index cdef25670..afe6965a2 100755 --- a/ground/openpilotgcs/src/plugins/config/ccattitude.ui +++ b/ground/openpilotgcs/src/plugins/config/ccattitude.ui @@ -6,7 +6,7 @@ 0 0 - 666 + 780 566 @@ -110,14 +110,11 @@ 0 0 - 636 - 483 + 750 + 466 - - 6 - 12 @@ -126,18 +123,25 @@ Rotate virtual attitude relative to board - - + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + Roll - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + Qt::AlignCenter - + -180 @@ -147,17 +151,77 @@ - + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + -180 + + + 180 + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Yaw + + + Qt::AlignCenter + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + Pitch - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + Qt::AlignCenter - + -90 @@ -167,25 +231,31 @@ - - - - Yaw + + + + Qt::Horizontal - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + 40 + 20 + - + - - - - -180 + + + + Qt::Horizontal - - 180 + + + 40 + 20 + - + @@ -427,12 +497,6 @@ arming it in that case!
Save - - - 25 - 25 - - diff --git a/ground/openpilotgcs/src/plugins/config/ccpm.ui b/ground/openpilotgcs/src/plugins/config/ccpm.ui index ee28ad4f0..cfc6846a7 100644 --- a/ground/openpilotgcs/src/plugins/config/ccpm.ui +++ b/ground/openpilotgcs/src/plugins/config/ccpm.ui @@ -126,7 +126,7 @@ QGroupBox::title { - Outputs + Motor outputs @@ -266,7 +266,7 @@ QGroupBox::title { - Swashplate Outputs + Swashplate outputs diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.cpp index 2262316e2..4ea8dd670 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.cpp @@ -155,9 +155,10 @@ ConfigCcpmWidget::ConfigCcpmWidget(QWidget *parent) : VehicleConfig(parent) m_ccpm->ccpmServoZChannel->setCurrentIndex(0); QStringList Types; - 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º") << + 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("Coax 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); @@ -287,7 +288,6 @@ QStringList ConfigCcpmWidget::getChannelDescriptions() void ConfigCcpmWidget::UpdateType() { int TypeInt,SingleServoIndex,NumServosDefined; - QString TypeText; double AdjustmentAngle=0; SetUIComponentVisibilities(); @@ -322,13 +322,11 @@ void ConfigCcpmWidget::UpdateType() AdjustmentAngle=SingleServoIndex*90; m_ccpm->PitchCurve->setVisible(1); - //m_ccpm->customThrottleCurve2Value->setVisible(1); - //m_ccpm->label_41->setVisible(1); NumServosDefined=4; //set values for pre defined heli types - if (TypeText.compare(QString::fromUtf8("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)); m_ccpm->ccpmAngleY->setValue(0); @@ -339,12 +337,11 @@ void ConfigCcpmWidget::UpdateType() m_ccpm->ccpmServoZChannel->setCurrentIndex(0); m_ccpm->ccpmServoYChannel->setEnabled(0); m_ccpm->ccpmServoZChannel->setEnabled(0); - //m_ccpm->ccpmCorrectionAngle->setValue(0); NumServosDefined=2; - } - if (TypeText.compare(QString::fromUtf8("CCPM 3 Servo 90º"), Qt::CaseInsensitive)==0) - { + } + else 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)); m_ccpm->ccpmAngleY->setValue(fmod(AdjustmentAngle + 180,360)); @@ -352,24 +349,22 @@ void ConfigCcpmWidget::UpdateType() m_ccpm->ccpmAngleZ->setEnabled(0); m_ccpm->ccpmServoZChannel->setCurrentIndex(0); m_ccpm->ccpmServoZChannel->setEnabled(0); - //m_ccpm->ccpmCorrectionAngle->setValue(0); NumServosDefined=3; - } - if (TypeText.compare(QString::fromUtf8("CCPM 4 Servo 90º"), Qt::CaseInsensitive)==0) - { + } + else 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)); m_ccpm->ccpmAngleY->setValue(fmod(AdjustmentAngle + 180,360)); m_ccpm->ccpmAngleZ->setValue(fmod(AdjustmentAngle + 270,360)); - //m_ccpm->ccpmCorrectionAngle->setValue(0); m_ccpm->ccpmSingleServo->setEnabled(0); m_ccpm->ccpmSingleServo->setCurrentIndex(0); NumServosDefined=4; - } - if (TypeText.compare(QString::fromUtf8("CCPM 3 Servo 120º"), Qt::CaseInsensitive)==0) - { + } + else 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)); m_ccpm->ccpmAngleY->setValue(fmod(AdjustmentAngle + 240,360)); @@ -377,12 +372,11 @@ void ConfigCcpmWidget::UpdateType() m_ccpm->ccpmAngleZ->setEnabled(0); m_ccpm->ccpmServoZChannel->setCurrentIndex(0); m_ccpm->ccpmServoZChannel->setEnabled(0); - //m_ccpm->ccpmCorrectionAngle->setValue(0); NumServosDefined=3; - } - if (TypeText.compare(QString::fromUtf8("CCPM 3 Servo 140º"), Qt::CaseInsensitive)==0) - { + } + else 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)); m_ccpm->ccpmAngleY->setValue(fmod(AdjustmentAngle + 220,360)); @@ -390,12 +384,11 @@ void ConfigCcpmWidget::UpdateType() m_ccpm->ccpmAngleZ->setEnabled(0); m_ccpm->ccpmServoZChannel->setCurrentIndex(0); m_ccpm->ccpmServoZChannel->setEnabled(0); - //m_ccpm->ccpmCorrectionAngle->setValue(0); NumServosDefined=3; - } - if (TypeText.compare(QString::fromUtf8("FP 2 Servo 90º"), Qt::CaseInsensitive)==0) - { + } + else 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)); m_ccpm->ccpmAngleY->setValue(0); @@ -406,17 +399,46 @@ void ConfigCcpmWidget::UpdateType() m_ccpm->ccpmServoZChannel->setCurrentIndex(0); m_ccpm->ccpmServoYChannel->setEnabled(0); m_ccpm->ccpmServoZChannel->setEnabled(0); - //m_ccpm->ccpmCorrectionAngle->setValue(0); m_ccpm->ccpmCollectivespinBox->setEnabled(0); m_ccpm->ccpmCollectiveSlider->setEnabled(0); m_ccpm->ccpmCollectivespinBox->setValue(0); m_ccpm->ccpmCollectiveSlider->setValue(0); m_ccpm->PitchCurve->setVisible(0); - //m_ccpm->customThrottleCurve2Value->setVisible(0); - //m_ccpm->label_41->setVisible(0); NumServosDefined=2; - } + } + else if (TypeText.compare(QString::fromUtf8("Coax 2 Servo 90º"), Qt::CaseInsensitive)==0) + { + m_ccpm->ccpmAngleW->setValue(AdjustmentAngle + 0); + m_ccpm->ccpmAngleX->setValue(fmod(AdjustmentAngle + 90,360)); + m_ccpm->ccpmAngleY->setValue(0); + m_ccpm->ccpmAngleZ->setValue(0); + m_ccpm->ccpmAngleY->setEnabled(0); + m_ccpm->ccpmAngleZ->setEnabled(0); + m_ccpm->ccpmServoYChannel->setCurrentIndex(0); + m_ccpm->ccpmServoZChannel->setCurrentIndex(0); + m_ccpm->ccpmServoYChannel->setEnabled(0); + m_ccpm->ccpmServoZChannel->setEnabled(0); + + m_ccpm->ccpmCollectivespinBox->setEnabled(0); + m_ccpm->ccpmCollectiveSlider->setEnabled(0); + m_ccpm->ccpmCollectivespinBox->setValue(0); + m_ccpm->ccpmCollectiveSlider->setValue(0); + m_ccpm->PitchCurve->setVisible(0); + NumServosDefined=2; + + } + + //Set the text of the motor boxes + if (TypeText.compare(QString::fromUtf8("Coax 2 Servo 90º"), Qt::CaseInsensitive)==0) + { + m_ccpm->ccpmEngineLabel->setText("CW motor"); + m_ccpm->ccpmTailLabel->setText("CCW motor"); + } + else{ + m_ccpm->ccpmEngineLabel->setText("Engine"); + m_ccpm->ccpmTailLabel->setText("Tail rotor"); + } //set the visibility of the swashplate servo selection boxes m_ccpm->ccpmServoWLabel->setVisible(NumServosDefined>=1); @@ -439,15 +461,12 @@ void ConfigCcpmWidget::UpdateType() m_ccpm->ccpmAngleZ->setVisible(NumServosDefined>=4); - m_ccpm->ccpmAdvancedSettingsTable->resizeColumnsToContents(); - for (int i=0;i<6;i++) { - m_ccpm->ccpmAdvancedSettingsTable->setColumnWidth(i,(m_ccpm->ccpmAdvancedSettingsTable->width()- - m_ccpm->ccpmAdvancedSettingsTable->verticalHeader()->width())/6); - } + m_ccpm->ccpmAdvancedSettingsTable->resizeColumnsToContents(); + for (int i=0;i<6;i++) { + m_ccpm->ccpmAdvancedSettingsTable->setColumnWidth(i,(m_ccpm->ccpmAdvancedSettingsTable->width()- + m_ccpm->ccpmAdvancedSettingsTable->verticalHeader()->width())/6); + } - - - //update UI ccpmSwashplateUpdate(); @@ -630,25 +649,40 @@ void ConfigCcpmWidget::UpdateMixer() //go through the user data and update the mixer matrix for (i=0;i<6;i++) { - if ((MixerChannelData[i]>0)&&((ThisEnable[i])||(i<2))) + if ((MixerChannelData[i]>0) && ((ThisEnable[i])||(i<2))) { m_ccpm->ccpmAdvancedSettingsTable->item(i,0)->setText(QString("%1").arg( MixerChannelData[i] )); - //config the vector - if (i==0) - {//motor-engine + + //Generate the mixer vector + if (i==0) + {//main motor-engine m_ccpm->ccpmAdvancedSettingsTable->item(i,1)->setText(QString("%1").arg(127));//ThrottleCurve1 m_ccpm->ccpmAdvancedSettingsTable->item(i,2)->setText(QString("%1").arg(0));//ThrottleCurve2 m_ccpm->ccpmAdvancedSettingsTable->item(i,3)->setText(QString("%1").arg(0));//Roll m_ccpm->ccpmAdvancedSettingsTable->item(i,4)->setText(QString("%1").arg(0));//Pitch - m_ccpm->ccpmAdvancedSettingsTable->item(i,5)->setText(QString("%1").arg(0));//Yaw + + if (TypeText.compare(QString::fromUtf8("Coax 2 Servo 90º"), Qt::CaseInsensitive)==0) + m_ccpm->ccpmAdvancedSettingsTable->item(i,5)->setText(QString("%1").arg(-127));//Yaw + else + m_ccpm->ccpmAdvancedSettingsTable->item(i,5)->setText(QString("%1").arg(0));//Yaw + } if (i==1) - {//tailrotor - m_ccpm->ccpmAdvancedSettingsTable->item(i,1)->setText(QString("%1").arg(0));//ThrottleCurve1 + {//tailrotor --or-- counter-clockwise motor + if (TypeText.compare(QString::fromUtf8("Coax 2 Servo 90º"), Qt::CaseInsensitive)==0) + { + m_ccpm->ccpmAdvancedSettingsTable->item(i,1)->setText(QString("%1").arg(127));//ThrottleCurve1 + m_ccpm->ccpmAdvancedSettingsTable->item(i,5)->setText(QString("%1").arg(127));//Yaw + } + else{ + m_ccpm->ccpmAdvancedSettingsTable->item(i,1)->setText(QString("%1").arg(0));//ThrottleCurve1 + m_ccpm->ccpmAdvancedSettingsTable->item(i,5)->setText(QString("%1").arg(127));//Yaw + } + m_ccpm->ccpmAdvancedSettingsTable->item(i,2)->setText(QString("%1").arg(0));//ThrottleCurve2 m_ccpm->ccpmAdvancedSettingsTable->item(i,3)->setText(QString("%1").arg(0));//Roll m_ccpm->ccpmAdvancedSettingsTable->item(i,4)->setText(QString("%1").arg(0));//Pitch - m_ccpm->ccpmAdvancedSettingsTable->item(i,5)->setText(QString("%1").arg(127));//Yaw + } if (i>1) {//Swashplate @@ -915,12 +949,20 @@ void ConfigCcpmWidget::setMixer() { if (MixerChannelData[i]>0) { - //set the mixer type - *(mixerTypes[MixerChannelData[i] - 1]) = i==0 ? - MixerSettings::MIXER1TYPE_MOTOR : - MixerSettings::MIXER1TYPE_SERVO; + //Set the mixer type. If Coax, then first two are motors. Otherwise, only first is motor + if (TypeText.compare(QString::fromUtf8("Coax 2 Servo 90º"), Qt::CaseInsensitive)==0) + { + *(mixerTypes[MixerChannelData[i] - 1]) = i > 1 ? + MixerSettings::MIXER1TYPE_SERVO : + MixerSettings::MIXER1TYPE_MOTOR; + } + else{ + *(mixerTypes[MixerChannelData[i] - 1]) = i > 0 ? + MixerSettings::MIXER1TYPE_SERVO : + MixerSettings::MIXER1TYPE_MOTOR; + } - //config the vector + //Configure the vector for (j=0;j<5;j++) mixers[MixerChannelData[i] - 1][j] = m_ccpm->ccpmAdvancedSettingsTable->item(i,j+1)->text().toInt(); } @@ -1455,60 +1497,64 @@ bool ConfigCcpmWidget::throwConfigError(QString airframeType) bool error = false; - if((m_ccpm->ccpmServoWChannel->currentIndex()==0)&&(m_ccpm->ccpmServoWChannel->isEnabled())) + if((m_ccpm->ccpmServoWChannel->currentIndex()==0) && (m_ccpm->ccpmServoWChannel->isEnabled())) { - m_ccpm->ccpmServoWLabel->setText("Servo W"); + m_ccpm->ccpmServoWLabel->setText("" + m_ccpm->ccpmServoWLabel->text() + ""); error = true; } else { - m_ccpm->ccpmServoWLabel->setText("Servo W"); - } - if((m_ccpm->ccpmServoXChannel->currentIndex()==0)&&(m_ccpm->ccpmServoXChannel->isEnabled())) - { - m_ccpm->ccpmServoXLabel->setText("Servo X"); - error = true; - } - else - { - m_ccpm->ccpmServoXLabel->setText("Servo X"); - } - if((m_ccpm->ccpmServoYChannel->currentIndex()==0)&&(m_ccpm->ccpmServoYChannel->isEnabled())) - { - m_ccpm->ccpmServoYLabel->setText("Servo Y"); - error = true; - } - else - { - m_ccpm->ccpmServoYLabel->setText("Servo Y"); - } - if((m_ccpm->ccpmServoZChannel->currentIndex()==0)&&(m_ccpm->ccpmServoZChannel->isEnabled())) - { - m_ccpm->ccpmServoZLabel->setText("Servo Z"); - error = true; - } - else - { - m_ccpm->ccpmServoZLabel->setText("Servo Z"); + m_ccpm->ccpmServoWLabel->setText(QTextEdit(m_ccpm->ccpmServoWLabel->text()).toPlainText()); } - if((m_ccpm->ccpmEngineChannel->currentIndex()==0)&&(m_ccpm->ccpmEngineChannel->isEnabled())) + if((m_ccpm->ccpmServoXChannel->currentIndex()==0) && (m_ccpm->ccpmServoXChannel->isEnabled())) { - m_ccpm->ccpmEngineLabel->setText("Engine"); - } - else - { - m_ccpm->ccpmEngineLabel->setText("Engine"); - } - - if((m_ccpm->ccpmTailChannel->currentIndex()==0)&&(m_ccpm->ccpmTailChannel->isEnabled())) - { - m_ccpm->ccpmTailLabel->setText("Tail Rotor"); + m_ccpm->ccpmServoXLabel->setText("" + m_ccpm->ccpmServoXLabel->text() + ""); error = true; } else { - m_ccpm->ccpmTailLabel->setText("Tail Rotor"); + m_ccpm->ccpmServoXLabel->setText(QTextEdit(m_ccpm->ccpmServoXLabel->text()).toPlainText()); + } + + if((m_ccpm->ccpmServoYChannel->currentIndex()==0) && (m_ccpm->ccpmServoYChannel->isEnabled())) + { + m_ccpm->ccpmServoYLabel->setText("" + m_ccpm->ccpmServoYLabel->text() + ""); + error = true; + } + else + { + m_ccpm->ccpmServoYLabel->setText(QTextEdit(m_ccpm->ccpmServoYLabel->text()).toPlainText()); + } + + if((m_ccpm->ccpmServoZChannel->currentIndex()==0) && (m_ccpm->ccpmServoZChannel->isEnabled())) + { + m_ccpm->ccpmServoZLabel->setText("" + m_ccpm->ccpmServoZLabel->text()+ ""); + error = true; + } + else + { + m_ccpm->ccpmServoZLabel->setText(QTextEdit(m_ccpm->ccpmServoZLabel->text()).toPlainText()); + } + + if((m_ccpm->ccpmEngineChannel->currentIndex()==0) && (m_ccpm->ccpmEngineChannel->isEnabled())) + { + m_ccpm->ccpmEngineLabel->setText("" + m_ccpm->ccpmEngineLabel->text() + ""); + } + else + { + m_ccpm->ccpmEngineLabel->setText(QTextEdit(m_ccpm->ccpmEngineLabel->text()).toPlainText()); + } + + if((m_ccpm->ccpmTailChannel->currentIndex()==0) && (m_ccpm->ccpmTailChannel->isEnabled())) + { + m_ccpm->ccpmTailLabel->setText("" + m_ccpm->ccpmTailLabel->text() + ""); + error = true; + } + else + { + m_ccpm->ccpmTailLabel->setText(QTextEdit(m_ccpm->ccpmTailLabel->text()).toPlainText()); + } return error; diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.h index a903afa5b..2d52eed8f 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.h +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.h @@ -72,6 +72,8 @@ private: QGraphicsEllipseItem *ServosTextCircles[CCPM_MAX_SWASH_SERVOS]; QSpinBox *SwashLvlSpinBoxes[CCPM_MAX_SWASH_SERVOS]; + QString TypeText; + bool SwashLvlConfigurationInProgress; UAVObject::Metadata SwashLvlaccInitialData; int SwashLvlState; diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp index 79df8ece7..ffceaed18 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp @@ -49,7 +49,7 @@ const QString ConfigMultiRotorWidget::CHANNELBOXNAME = QString("multiMotorChanne /** Constructor */ -ConfigMultiRotorWidget::ConfigMultiRotorWidget(Ui_AircraftWidget *aircraft, QWidget *parent) : VehicleConfig(parent) +ConfigMultiRotorWidget::ConfigMultiRotorWidget(Ui_AircraftWidget *aircraft, QWidget *parent) : VehicleConfig(parent), invertMotors(1) { m_aircraft = aircraft; } @@ -87,20 +87,18 @@ void ConfigMultiRotorWidget::setupUI(QString frameType) if (frameType == "Tri" || frameType == "Tricopter Y") { setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Tricopter Y")); - quad->setElementId("tri"); //Enable all necessary motor channel boxes... enableComboBoxes(uiowner, CHANNELBOXNAME, 3, true); m_aircraft->mrRollMixLevel->setValue(100); m_aircraft->mrPitchMixLevel->setValue(100); - m_aircraft->mrYawMixLevel->setValue(50); + setYawMixLevel(50); m_aircraft->triYawChannelBox->setEnabled(true); } else if (frameType == "QuadX" || frameType == "Quad X") { setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad X")); - quad->setElementId("quad-x"); //Enable all necessary motor channel boxes... enableComboBoxes(uiowner, CHANNELBOXNAME, 4, true); @@ -108,104 +106,173 @@ void ConfigMultiRotorWidget::setupUI(QString frameType) // init mixer levels m_aircraft->mrRollMixLevel->setValue(50); m_aircraft->mrPitchMixLevel->setValue(50); - m_aircraft->mrYawMixLevel->setValue(50); + setYawMixLevel(50); } else if (frameType == "QuadP" || frameType == "Quad +") { setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad +")); - quad->setElementId("quad-plus"); //Enable all necessary motor channel boxes... enableComboBoxes(uiowner, CHANNELBOXNAME, 4, true); m_aircraft->mrRollMixLevel->setValue(100); m_aircraft->mrPitchMixLevel->setValue(100); - m_aircraft->mrYawMixLevel->setValue(50); + setYawMixLevel(50); } else if (frameType == "Hexa" || frameType == "Hexacopter") { setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter")); - quad->setElementId("quad-hexa"); //Enable all necessary motor channel boxes... enableComboBoxes(uiowner, CHANNELBOXNAME, 6, true); m_aircraft->mrRollMixLevel->setValue(50); m_aircraft->mrPitchMixLevel->setValue(33); - m_aircraft->mrYawMixLevel->setValue(33); + setYawMixLevel(33); } else if (frameType == "HexaX" || frameType == "Hexacopter X" ) { setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter X")); - quad->setElementId("quad-hexa-H"); //Enable all necessary motor channel boxes... enableComboBoxes(uiowner, CHANNELBOXNAME, 6, true); m_aircraft->mrRollMixLevel->setValue(33); m_aircraft->mrPitchMixLevel->setValue(50); - m_aircraft->mrYawMixLevel->setValue(33); + setYawMixLevel(33); } else if (frameType == "HexaCoax" || frameType == "Hexacopter Y6") { setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Hexacopter Y6")); - quad->setElementId("hexa-coax"); //Enable all necessary motor channel boxes... enableComboBoxes(uiowner, CHANNELBOXNAME, 6, true); m_aircraft->mrRollMixLevel->setValue(100); m_aircraft->mrPitchMixLevel->setValue(50); - m_aircraft->mrYawMixLevel->setValue(66); + setYawMixLevel(66); } else if (frameType == "Octo" || frameType == "Octocopter") { setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octocopter")); - quad->setElementId("quad-octo"); //Enable all necessary motor channel boxes enableComboBoxes(uiowner, CHANNELBOXNAME, 8, true); m_aircraft->mrRollMixLevel->setValue(33); m_aircraft->mrPitchMixLevel->setValue(33); - m_aircraft->mrYawMixLevel->setValue(25); + setYawMixLevel(25); } else if (frameType == "OctoV" || frameType == "Octocopter V") { setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octocopter V")); - quad->setElementId("quad-octo-v"); //Enable all necessary motor channel boxes enableComboBoxes(uiowner, CHANNELBOXNAME, 8, true); m_aircraft->mrRollMixLevel->setValue(25); m_aircraft->mrPitchMixLevel->setValue(25); - m_aircraft->mrYawMixLevel->setValue(25); + setYawMixLevel(25); } else if (frameType == "OctoCoaxP" || frameType == "Octo Coax +") { setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octo Coax +")); - quad->setElementId("octo-coax-P"); //Enable all necessary motor channel boxes enableComboBoxes(uiowner, CHANNELBOXNAME, 8, true); m_aircraft->mrRollMixLevel->setValue(100); m_aircraft->mrPitchMixLevel->setValue(100); - m_aircraft->mrYawMixLevel->setValue(50); + setYawMixLevel(50); } else if (frameType == "OctoCoaxX" || frameType == "Octo Coax X") { setComboCurrentIndex( m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Octo Coax X")); - quad->setElementId("octo-coax-X"); + //Enable all necessary motor channel boxes enableComboBoxes(uiowner, CHANNELBOXNAME, 8, true); m_aircraft->mrRollMixLevel->setValue(50); m_aircraft->mrPitchMixLevel->setValue(50); - m_aircraft->mrYawMixLevel->setValue(50); + setYawMixLevel(50); + } + + //Draw the appropriate airframe + drawAirframe(frameType); +} + +void ConfigMultiRotorWidget::drawAirframe(QString frameType){ + + invertMotors = m_aircraft->MultirotorRevMixercheckBox->isChecked() ? -1:1; + + if (frameType == "Tri" || frameType == "Tricopter Y") { + if(invertMotors > 0) + quad->setElementId("tri"); + else + quad->setElementId("tri_reverse"); + } + else if (frameType == "QuadX" || frameType == "Quad X") { + if(invertMotors > 0) + quad->setElementId("quad-x"); + else + quad->setElementId("quad-x_reverse"); + } + else if (frameType == "QuadP" || frameType == "Quad +") { + if(invertMotors > 0) + quad->setElementId("quad-plus"); + else + quad->setElementId("quad-plus_reverse"); + } + else if (frameType == "Hexa" || frameType == "Hexacopter") + { + if(invertMotors > 0) + quad->setElementId("quad-hexa"); + else + quad->setElementId("quad-hexa_reverse"); + } + else if (frameType == "HexaX" || frameType == "Hexacopter X" ) { + if(invertMotors > 0) + quad->setElementId("quad-hexa-H"); + else + quad->setElementId("quad-hexa-H_reverse"); + } + else if (frameType == "HexaCoax" || frameType == "Hexacopter Y6") + { + if(invertMotors > 0) + quad->setElementId("hexa-coax"); + else + quad->setElementId("hexa-coax_reverse"); + } + else if (frameType == "Octo" || frameType == "Octocopter") + { + if(invertMotors > 0) + quad->setElementId("quad-octo"); + else + quad->setElementId("quad-octo_reverse"); + } + else if (frameType == "OctoV" || frameType == "Octocopter V") + { + if(invertMotors > 0) + quad->setElementId("quad-octo-v"); + else + quad->setElementId("quad-octo-v_reverse"); + } + else if (frameType == "OctoCoaxP" || frameType == "Octo Coax +") + { + if(invertMotors > 0) + quad->setElementId("octo-coax-P"); + else + quad->setElementId("octo-coax-P_reverse"); + + } + else if (frameType == "OctoCoaxX" || frameType == "Octo Coax X") + { + if(invertMotors > 0) + quad->setElementId("octo-coax-X"); + else + quad->setElementId("octo-coax-X_reverse"); } } @@ -259,6 +326,21 @@ QStringList ConfigMultiRotorWidget::getChannelDescriptions() return channelDesc; } +void ConfigMultiRotorWidget::setYawMixLevel(int value) +{ + if(value<0) + { + m_aircraft->mrYawMixLevel->setValue((-1)*value); + m_aircraft->MultirotorRevMixercheckBox->setChecked(true); + } + else + { + m_aircraft->mrYawMixLevel->setValue(value); + m_aircraft->MultirotorRevMixercheckBox->setChecked(false); + } + +} + @@ -497,14 +579,14 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) if (channel > -1) { value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH); - m_aircraft->mrPitchMixLevel->setValue( value/1.27 ); + m_aircraft->mrPitchMixLevel->setValue( qRound(value/1.27) ); value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); - m_aircraft->mrYawMixLevel->setValue( 1-value/1.27 ); + setYawMixLevel( -qRound(value/1.27) ); channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1; value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); - m_aircraft->mrRollMixLevel->setValue( -value/1.27); + m_aircraft->mrRollMixLevel->setValue( -qRound(value/1.27)); } } @@ -523,13 +605,13 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) if (channel > -1) { value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH); - m_aircraft->mrPitchMixLevel->setValue( value/1.27 ); + m_aircraft->mrPitchMixLevel->setValue( qRound(value/1.27) ); value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); - m_aircraft->mrYawMixLevel->setValue( 1-value/1.27 ); + setYawMixLevel( -qRound(value/1.27) ); value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); - m_aircraft->mrRollMixLevel->setValue( value/1.27); + m_aircraft->mrRollMixLevel->setValue( qRound(value/1.27)); } @@ -553,15 +635,15 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) if (channel > -1) { value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH); - m_aircraft->mrPitchMixLevel->setValue( floor(value/1.27) ); + m_aircraft->mrPitchMixLevel->setValue( qRound(value/1.27) ); value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); - m_aircraft->mrYawMixLevel->setValue( floor(-value/1.27) ); + setYawMixLevel( -qRound(value/1.27) ); //change channels channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1; value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); - m_aircraft->mrRollMixLevel->setValue( floor(1-value/1.27) ); + m_aircraft->mrRollMixLevel->setValue( -qRound(value/1.27) ); } @@ -586,14 +668,14 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) if (channel > -1) { value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH); - m_aircraft->mrPitchMixLevel->setValue( floor(value/1.27) ); + m_aircraft->mrPitchMixLevel->setValue( qRound(value/1.27) ); value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); - m_aircraft->mrYawMixLevel->setValue( floor(-value/1.27) ); + setYawMixLevel( -qRound(value/1.27) ); channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1; value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); - m_aircraft->mrRollMixLevel->setValue( floor(1-value/1.27) ); + m_aircraft->mrRollMixLevel->setValue( -qRound(value/1.27) ); } } else if (frameType == "HexaCoax") @@ -614,14 +696,14 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) if (channel > -1) { value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH); - m_aircraft->mrPitchMixLevel->setValue( value/1.27 ); - - value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); - m_aircraft->mrYawMixLevel->setValue( value/1.27 ); + m_aircraft->mrPitchMixLevel->setValue( qRound(2*value/1.27) ); channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1; + value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); + setYawMixLevel( qRound(value/1.27) ); + value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); - m_aircraft->mrRollMixLevel->setValue( value/1.27); + m_aircraft->mrRollMixLevel->setValue( qRound(value/1.27) ); } } else if (frameType == "Octo" || frameType == "OctoV" || frameType == "OctoCoaxP") @@ -645,39 +727,39 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) { if (frameType == "Octo") { value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH); - m_aircraft->mrPitchMixLevel->setValue( floor(value/1.27) ); + m_aircraft->mrPitchMixLevel->setValue( qRound(value/1.27) ); value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); - m_aircraft->mrYawMixLevel->setValue( floor(-value/1.27) ); + setYawMixLevel( -qRound(value/1.27) ); //change channels channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1; value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); - m_aircraft->mrRollMixLevel->setValue( floor(-value/1.27) ); + m_aircraft->mrRollMixLevel->setValue( -qRound(value/1.27) ); } else if (frameType == "OctoV") { value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH); - m_aircraft->mrPitchMixLevel->setValue( floor(value/1.27) ); + m_aircraft->mrPitchMixLevel->setValue( qRound(value/1.27) ); value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); - m_aircraft->mrYawMixLevel->setValue( floor(-value/1.27) ); + setYawMixLevel( -qRound(value/1.27) ); //change channels channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1; value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); - m_aircraft->mrRollMixLevel->setValue( floor(-value/1.27) ); + m_aircraft->mrRollMixLevel->setValue( -qRound(value/1.27) ); } else if (frameType == "OctoCoaxP") { value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH); - m_aircraft->mrPitchMixLevel->setValue( floor(value/1.27) ); + m_aircraft->mrPitchMixLevel->setValue( qRound(value/1.27) ); value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); - m_aircraft->mrYawMixLevel->setValue( floor(-value/1.27) ); + setYawMixLevel( -qRound(value/1.27) ); //change channels channel = m_aircraft->multiMotorChannelBox3->currentIndex() - 1; value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); - m_aircraft->mrRollMixLevel->setValue( floor(-value/1.27) ); + m_aircraft->mrRollMixLevel->setValue( -qRound(value/1.27) ); } } @@ -702,13 +784,13 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) if (channel > -1) { value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH); - m_aircraft->mrPitchMixLevel->setValue( floor(value/1.27) ); + m_aircraft->mrPitchMixLevel->setValue( qRound(value/1.27) ); value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); - m_aircraft->mrYawMixLevel->setValue( floor(-value/1.27) ); + setYawMixLevel( -qRound(value/1.27) ); value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); - m_aircraft->mrRollMixLevel->setValue( floor(value/1.27) ); + m_aircraft->mrRollMixLevel->setValue( qRound(value/1.27) ); } } else if (frameType == "Tri") @@ -725,13 +807,15 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) if (channel > -1) { value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH); - m_aircraft->mrPitchMixLevel->setValue( floor(2*value/1.27) ); + m_aircraft->mrPitchMixLevel->setValue( qRound(2*value/1.27) ); value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); - m_aircraft->mrRollMixLevel->setValue( floor(value/1.27) ); + m_aircraft->mrRollMixLevel->setValue( qRound(value/1.27) ); } } + + drawAirframe(frameType); } @@ -959,7 +1043,8 @@ bool ConfigMultiRotorWidget::setupMultiRotorMixer(double mixerFactors[8][3]) // and enable only the relevant channels: double pFactor = (double)m_aircraft->mrPitchMixLevel->value()/100; double rFactor = (double)m_aircraft->mrRollMixLevel->value()/100; - double yFactor = (double)m_aircraft->mrYawMixLevel->value()/100; + invertMotors = m_aircraft->MultirotorRevMixercheckBox->isChecked() ? -1:1; + double yFactor =invertMotors * (double)m_aircraft->mrYawMixLevel->value()/100; for (int i=0 ; i<8; i++) { if(mmList.at(i)->isEnabled()) { diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.h index 085aab106..4ce10aae3 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.h +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.h @@ -64,9 +64,14 @@ private: void setupMotors(QList motorList); void setupQuadMotor(int channel, double roll, double pitch, double yaw); + float invertMotors; + virtual void ResetActuators(GUIConfigDataUnion* configData); static QStringList getChannelDescriptions(); static const QString CHANNELBOXNAME; + void setYawMixLevel(int); + + void drawAirframe(QString multiRotorType); private slots: virtual void setupUI(QString airframeType); 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 59654d388..d6dc18dde 100644 --- a/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp +++ b/ground/openpilotgcs/src/plugins/config/config_cc_hw_widget.cpp @@ -101,10 +101,19 @@ void ConfigCCHWWidget::refreshValues() void ConfigCCHWWidget::widgetsContentsChanged() { ConfigTaskWidget::widgetsContentsChanged(); - - if (((m_telemetry->cbTele->currentIndex() == HwSettings::CC_MAINPORT_TELEMETRY) && (m_telemetry->cbFlexi->currentIndex() == HwSettings::CC_FLEXIPORT_TELEMETRY)) || + if (((m_telemetry->cbTele->currentIndex() == HwSettings::CC_MAINPORT_DEBUGCONSOLE) && + (m_telemetry->cbFlexi->currentIndex() == HwSettings::CC_FLEXIPORT_DEBUGCONSOLE)) || + ((m_telemetry->cbFlexi->currentIndex() == HwSettings::CC_FLEXIPORT_DEBUGCONSOLE) && + (m_telemetry->cbUsbVcp->currentIndex() == HwSettings::USB_VCPPORT_DEBUGCONSOLE)) || + ((m_telemetry->cbUsbVcp->currentIndex() == HwSettings::USB_VCPPORT_DEBUGCONSOLE) && + (m_telemetry->cbTele->currentIndex() == HwSettings::CC_MAINPORT_DEBUGCONSOLE))) + { + enableControls(false); + m_telemetry->problems->setText(tr("Warning: you have configured more than one DebugConsole, this currently is not supported")); + } + else 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->cbTele->currentIndex() == HwSettings::CC_MAINPORT_DEBUGCONSOLE) && (m_telemetry->cbFlexi->currentIndex() == HwSettings::CC_FLEXIPORT_DEBUGCONSOLE)) || ((m_telemetry->cbTele->currentIndex() == HwSettings::CC_MAINPORT_COMBRIDGE) && (m_telemetry->cbFlexi->currentIndex() == HwSettings::CC_FLEXIPORT_COMBRIDGE))) { enableControls(false); diff --git a/ground/openpilotgcs/src/plugins/config/configautotunewidget.cpp b/ground/openpilotgcs/src/plugins/config/configautotunewidget.cpp index 33106be4c..63de056ad 100644 --- a/ground/openpilotgcs/src/plugins/config/configautotunewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configautotunewidget.cpp @@ -13,6 +13,7 @@ #include "relaytuningsettings.h" #include "relaytuning.h" #include "stabilizationsettings.h" +#include "hwsettings.h" ConfigAutotuneWidget::ConfigAutotuneWidget(QWidget *parent) : ConfigTaskWidget(parent) @@ -28,6 +29,9 @@ ConfigAutotuneWidget::ConfigAutotuneWidget(QWidget *parent) : connect(m_autotune->rateTuning, SIGNAL(valueChanged(int)), this, SLOT(recomputeStabilization())); connect(m_autotune->attitudeTuning, SIGNAL(valueChanged(int)), this, SLOT(recomputeStabilization())); + addUAVObject("HwSettings"); + addWidget(m_autotune->enableAutoTune); + RelayTuning *relayTuning = RelayTuning::GetInstance(getObjectManager()); Q_ASSERT(relayTuning); if(relayTuning) @@ -134,3 +138,25 @@ void ConfigAutotuneWidget::recomputeStabilization() m_autotune->pitchAttitudeKp->setText(QString().number(stabSettings.PitchPI[StabilizationSettings::PITCHPI_KP])); m_autotune->pitchAttitudeKi->setText(QString().number(stabSettings.PitchPI[StabilizationSettings::PITCHPI_KI])); } +void ConfigAutotuneWidget::refreshWidgetsValues(UAVObject *obj) +{ + HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager()); + if(obj==hwSettings) + { + bool dirtyBack=isDirty(); + HwSettings::DataFields hwSettingsData = hwSettings->getData(); + m_autotune->enableAutoTune->setChecked( + hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_AUTOTUNE] == HwSettings::OPTIONALMODULES_ENABLED); + setDirty(dirtyBack); + } + ConfigTaskWidget::refreshWidgetsValues(obj); +} +void ConfigAutotuneWidget::updateObjectsFromWidgets() +{ + HwSettings *hwSettings = HwSettings::GetInstance(getObjectManager()); + HwSettings::DataFields hwSettingsData = hwSettings->getData(); + hwSettingsData.OptionalModules[HwSettings::OPTIONALMODULES_AUTOTUNE] = + m_autotune->enableAutoTune->isChecked() ? HwSettings::OPTIONALMODULES_ENABLED : HwSettings::OPTIONALMODULES_DISABLED; + hwSettings->setData(hwSettingsData); + ConfigTaskWidget::updateObjectsFromWidgets(); +} diff --git a/ground/openpilotgcs/src/plugins/config/configautotunewidget.h b/ground/openpilotgcs/src/plugins/config/configautotunewidget.h index 7a89ed373..466335d04 100644 --- a/ground/openpilotgcs/src/plugins/config/configautotunewidget.h +++ b/ground/openpilotgcs/src/plugins/config/configautotunewidget.h @@ -51,7 +51,8 @@ private: signals: public slots: - + void refreshWidgetsValues(UAVObject *obj); + void updateObjectsFromWidgets(); private slots: void recomputeStabilization(); void saveStabilization(); diff --git a/ground/openpilotgcs/src/plugins/config/configgadget.qrc b/ground/openpilotgcs/src/plugins/config/configgadget.qrc index ffdb93e66..ff81d79fb 100644 --- a/ground/openpilotgcs/src/plugins/config/configgadget.qrc +++ b/ground/openpilotgcs/src/plugins/config/configgadget.qrc @@ -1,23 +1,34 @@ images/help2.png - images/Airframe.png - images/Servo.png images/ahrs-calib.svg - images/AHRS-v1.3.png images/paper-plane.svg images/curve-bg.svg images/multirotor-shapes.svg images/ccpm_setup.svg images/PipXtreme.png - images/Transmitter.png images/help.png images/coptercontrol.svg - images/hw_config.png - images/gyroscope.png - images/TX.svg images/TX2.svg - images/camera.png - images/txpid.png + images/output_selected.png + images/output_normal.png + images/input_selected.png + images/input_normal.png + images/hardware_normal.png + images/hardware_selected.png + images/vehicle_normal.png + images/vehicle_selected.png + images/ins_selected.png + images/ins_normal.png + images/stabilization_selected.png + images/stabilization_normal.png + images/autotune_selected.png + images/autotune_normal.png + images/txpid_selected.png + images/txpid_normal.png + images/camstab_selected.png + images/camstab_normal.png + images/pipx-selected.png + images/pipx-normal.png diff --git a/ground/openpilotgcs/src/plugins/config/configgadgetfactory.cpp b/ground/openpilotgcs/src/plugins/config/configgadgetfactory.cpp index 37447b01a..a927f2179 100644 --- a/ground/openpilotgcs/src/plugins/config/configgadgetfactory.cpp +++ b/ground/openpilotgcs/src/plugins/config/configgadgetfactory.cpp @@ -25,14 +25,18 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ #include "configgadgetfactory.h" -#include "configgadgetwidget.h" #include "configgadget.h" #include "configgadgetconfiguration.h" #include "configgadgetoptionspage.h" #include +#include +#include +#include +#include ConfigGadgetFactory::ConfigGadgetFactory(QObject *parent) : - IUAVGadgetFactory(QString("ConfigGadget"), tr("Config Gadget"), parent) + IUAVGadgetFactory(QString("ConfigGadget"), tr("Config Gadget"), parent), + gadgetWidget(0) { } @@ -42,7 +46,26 @@ ConfigGadgetFactory::~ConfigGadgetFactory() Core::IUAVGadget* ConfigGadgetFactory::createGadget(QWidget *parent) { - ConfigGadgetWidget* gadgetWidget = new ConfigGadgetWidget(parent); + gadgetWidget = new ConfigGadgetWidget(parent); + + // Add Menu entry + Core::ActionManager* am = Core::ICore::instance()->actionManager(); + Core::ActionContainer* ac = am->actionContainer(Core::Constants::M_TOOLS); + + Core::Command* cmd = am->registerAction(new QAction(this), + "ConfigPlugin.ShowInputWizard", + QList() << + Core::Constants::C_GLOBAL_ID); + cmd->setDefaultKeySequence(QKeySequence("Ctrl+R")); + cmd->action()->setText(tr("Radio Setup Wizard")); + + Core::ModeManager::instance()->addAction(cmd, 1); + + ac->appendGroup("Wizard"); + ac->addAction(cmd, "Wizard"); + + connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(startInputWizard())); + return new ConfigGadget(QString("ConfigGadget"), gadgetWidget, parent); } @@ -55,3 +78,12 @@ IOptionsPage *ConfigGadgetFactory::createOptionsPage(IUAVGadgetConfiguration *co { return new ConfigGadgetOptionsPage(qobject_cast(config)); } + +void ConfigGadgetFactory::startInputWizard() +{ + if(gadgetWidget) + { + Core::ModeManager::instance()->activateModeByWorkspaceName("Configuration"); + gadgetWidget->startInputWizard(); + } +} diff --git a/ground/openpilotgcs/src/plugins/config/configgadgetfactory.h b/ground/openpilotgcs/src/plugins/config/configgadgetfactory.h index 8d371e746..f44f2c02a 100644 --- a/ground/openpilotgcs/src/plugins/config/configgadgetfactory.h +++ b/ground/openpilotgcs/src/plugins/config/configgadgetfactory.h @@ -28,6 +28,9 @@ #define CONFIGGADGETFACTORY_H #include +#include "configgadgetwidget.h" +#include "config_global.h" + namespace Core { class IUAVGadget; @@ -36,7 +39,7 @@ class IUAVGadgetFactory; using namespace Core; -class ConfigGadgetFactory: public Core::IUAVGadgetFactory +class CONFIG_EXPORT ConfigGadgetFactory: public Core::IUAVGadgetFactory { Q_OBJECT public: @@ -47,6 +50,12 @@ public: IUAVGadget *createGadget(QWidget *parent); IUAVGadgetConfiguration *createConfiguration(QSettings* qSettings); IOptionsPage *createOptionsPage(IUAVGadgetConfiguration *config); + +public slots: + void startInputWizard(); + +private: + ConfigGadgetWidget* gadgetWidget; }; #endif // CONFIGGADGETFACTORY_H diff --git a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp index f6b64e18c..406ef469f 100644 --- a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.cpp @@ -67,33 +67,61 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent) // ********************* QWidget *qwd; + QIcon *icon = new QIcon(); + icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off); + icon->addFile(":/configgadget/images/hardware_selected.png", QSize(), QIcon::Selected, QIcon::Off); qwd = new DefaultHwSettingsWidget(this); - ftw->insertTab(ConfigGadgetWidget::hardware, qwd, QIcon(":/configgadget/images/hw_config.png"), QString("HW Settings")); + ftw->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware")); + icon = new QIcon(); + icon->addFile(":/configgadget/images/vehicle_normal.png", QSize(), QIcon::Normal, QIcon::Off); + icon->addFile(":/configgadget/images/vehicle_selected.png", QSize(), QIcon::Selected, QIcon::Off); qwd = new ConfigVehicleTypeWidget(this); - ftw->insertTab(ConfigGadgetWidget::aircraft, qwd, QIcon(":/configgadget/images/Airframe.png"), QString("Aircraft")); + ftw->insertTab(ConfigGadgetWidget::aircraft, qwd, *icon, QString("Vehicle")); + icon = new QIcon(); + icon->addFile(":/configgadget/images/input_normal.png", QSize(), QIcon::Normal, QIcon::Off); + icon->addFile(":/configgadget/images/input_selected.png", QSize(), QIcon::Selected, QIcon::Off); qwd = new ConfigInputWidget(this); - ftw->insertTab(ConfigGadgetWidget::input, qwd, QIcon(":/configgadget/images/Transmitter.png"), QString("Input")); + ftw->insertTab(ConfigGadgetWidget::input, qwd, *icon, QString("Input")); + icon = new QIcon(); + icon->addFile(":/configgadget/images/output_normal.png", QSize(), QIcon::Normal, QIcon::Off); + icon->addFile(":/configgadget/images/output_selected.png", QSize(), QIcon::Selected, QIcon::Off); qwd = new ConfigOutputWidget(this); - ftw->insertTab(ConfigGadgetWidget::output, qwd, QIcon(":/configgadget/images/Servo.png"), QString("Output")); + ftw->insertTab(ConfigGadgetWidget::output, qwd, *icon, QString("Output")); + icon = new QIcon(); + icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off); + icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off); qwd = new DefaultAttitudeWidget(this); - ftw->insertTab(ConfigGadgetWidget::sensors, qwd, QIcon(":/configgadget/images/AHRS-v1.3.png"), QString("INS")); + ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("INS")); + icon = new QIcon(); + icon->addFile(":/configgadget/images/stabilization_normal.png", QSize(), QIcon::Normal, QIcon::Off); + icon->addFile(":/configgadget/images/stabilization_selected.png", QSize(), QIcon::Selected, QIcon::Off); qwd = new ConfigStabilizationWidget(this); - ftw->insertTab(ConfigGadgetWidget::stabilization, qwd, QIcon(":/configgadget/images/gyroscope.png"), QString("Stabilization")); + ftw->insertTab(ConfigGadgetWidget::stabilization, qwd, *icon, QString("Stabilization")); + icon = new QIcon(); + icon->addFile(":/configgadget/images/autotune_normal.png", QSize(), QIcon::Normal, QIcon::Off); + icon->addFile(":/configgadget/images/autotune_selected.png", QSize(), QIcon::Selected, QIcon::Off); qwd = new ConfigAutotuneWidget(this); - ftw->insertTab(ConfigGadgetWidget::autotune, qwd, QIcon(":/configgadget/images/gyroscope.png"), QString("Autotune")); + ftw->insertTab(ConfigGadgetWidget::autotune, qwd, *icon, QString("Autotune")); + icon = new QIcon(); + icon->addFile(":/configgadget/images/camstab_normal.png", QSize(), QIcon::Normal, QIcon::Off); + icon->addFile(":/configgadget/images/camstab_selected.png", QSize(), QIcon::Selected, QIcon::Off); qwd = new ConfigCameraStabilizationWidget(this); - ftw->insertTab(ConfigGadgetWidget::camerastabilization, qwd, QIcon(":/configgadget/images/camera.png"), QString("Camera Stab")); + ftw->insertTab(ConfigGadgetWidget::camerastabilization, qwd, *icon, QString("Camera Stab")); + icon = new QIcon(); + icon->addFile(":/configgadget/images/txpid_normal.png", QSize(), QIcon::Normal, QIcon::Off); + icon->addFile(":/configgadget/images/txpid_selected.png", QSize(), QIcon::Selected, QIcon::Off); qwd = new ConfigTxPIDWidget(this); - ftw->insertTab(ConfigGadgetWidget::txpid, qwd, QIcon(":/configgadget/images/txpid.png"), QString("TxPID")); + ftw->insertTab(ConfigGadgetWidget::txpid, qwd, *icon, QString("TxPID")); + ftw->setCurrentIndex(ConfigGadgetWidget::hardware); // ********************* // Listen to autopilot connection events @@ -103,8 +131,9 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent) connect(telMngr, SIGNAL(disconnected()), this, SLOT(onAutopilotDisconnect())); // And check whether by any chance we are not already connected - if (telMngr->isConnected()) + if (telMngr->isConnected()) { onAutopilotConnect(); + } help = 0; connect(ftw,SIGNAL(currentAboutToShow(int,bool*)),this,SLOT(tabAboutToChange(int,bool*)));//,Qt::BlockingQueuedConnection); @@ -115,7 +144,7 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent) if (pipxStatusObj != NULL ) { connect(pipxStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(updatePipXStatus(UAVObject*))); } else { - qDebug() << "Error: Object is unknown (PipXStatus)."; + qDebug() << "Error: Object is unknown (PipXStatus)."; } // Create the timer that is used to timeout the connection to the PipX. @@ -126,25 +155,38 @@ ConfigGadgetWidget::ConfigGadgetWidget(QWidget *parent) : QWidget(parent) ConfigGadgetWidget::~ConfigGadgetWidget() { - // Do nothing - // TODO: properly delete all the tabs in ftw before exiting } +void ConfigGadgetWidget::startInputWizard() +{ + ftw->setCurrentIndex(ConfigGadgetWidget::input); + ConfigInputWidget* inputWidget = dynamic_cast(ftw->getWidget(ConfigGadgetWidget::input)); + Q_ASSERT(inputWidget); + inputWidget->startInputWizard(); +} + void ConfigGadgetWidget::resizeEvent(QResizeEvent *event) { - QWidget::resizeEvent(event); } void ConfigGadgetWidget::onAutopilotDisconnect() { ftw->setCurrentIndex(ConfigGadgetWidget::hardware); ftw->removeTab(ConfigGadgetWidget::sensors); + + QIcon *icon = new QIcon(); + icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off); + icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off); QWidget *qwd = new DefaultAttitudeWidget(this); - ftw->insertTab(ConfigGadgetWidget::sensors, qwd, QIcon(":/configgadget/images/AHRS-v1.3.png"), QString("INS")); + ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("INS")); ftw->removeTab(ConfigGadgetWidget::hardware); + + icon = new QIcon(); + icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off); + icon->addFile(":/configgadget/images/hardware_selected.png", QSize(), QIcon::Selected, QIcon::Off); qwd = new DefaultHwSettingsWidget(this); - ftw->insertTab(ConfigGadgetWidget::hardware, qwd, QIcon(":/configgadget/images/hw_config.png"), QString("HW Settings")); + ftw->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware")); ftw->setCurrentIndex(ConfigGadgetWidget::hardware); emit autopilotDisconnected(); @@ -164,56 +206,64 @@ void ConfigGadgetWidget::onAutopilotConnect() { // Delete the INS panel, replace with CC Panel: ftw->setCurrentIndex(ConfigGadgetWidget::hardware); ftw->removeTab(ConfigGadgetWidget::sensors); + + QIcon *icon = new QIcon(); + icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off); + icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off); QWidget *qwd = new ConfigCCAttitudeWidget(this); - ftw->insertTab(ConfigGadgetWidget::sensors, qwd, QIcon(":/configgadget/images/AHRS-v1.3.png"), QString("Attitude")); + ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("INS")); ftw->removeTab(ConfigGadgetWidget::hardware); + + icon = new QIcon(); + icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off); + icon->addFile(":/configgadget/images/hardware_selected.png", QSize(), QIcon::Selected, QIcon::Off); qwd = new ConfigCCHWWidget(this); - ftw->insertTab(ConfigGadgetWidget::hardware, qwd, QIcon(":/configgadget/images/hw_config.png"), QString("HW Settings")); + ftw->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware")); ftw->setCurrentIndex(ConfigGadgetWidget::hardware); - } else if ((board & 0xff00) == 256 ) { - // Mainboard family - Q_ASSERT(0); - /* - ftw->setCurrentIndex(ConfigGadgetWidget::hardware); - ftw->removeTab(ConfigGadgetWidget::sensors); - QWidget *qwd = new ConfigAHRSWidget(this); - ftw->insertTab(ConfigGadgetWidget::sensors, qwd, QIcon(":/configgadget/images/AHRS-v1.3.png"), QString("INS")); - ftw->removeTab(ConfigGadgetWidget::hardware); - qwd = new ConfigProHWWidget(this); - ftw->insertTab(ConfigGadgetWidget::hardware, qwd, QIcon(":/configgadget/images/hw_config.png"), QString("HW Settings")); - ftw->setCurrentIndex(ConfigGadgetWidget::hardware); - */ } else if ((board & 0xff00) == 0x0900) { // Revolution sensor calibration ftw->setCurrentIndex(ConfigGadgetWidget::hardware); ftw->removeTab(ConfigGadgetWidget::sensors); + + QIcon *icon = new QIcon(); + icon->addFile(":/configgadget/images/ins_normal.png", QSize(), QIcon::Normal, QIcon::Off); + icon->addFile(":/configgadget/images/ins_selected.png", QSize(), QIcon::Selected, QIcon::Off); QWidget *qwd = new ConfigRevoWidget(this); - ftw->insertTab(ConfigGadgetWidget::sensors, qwd, QIcon(":/configgadget/images/AHRS-v1.3.png"), QString("Revo")); + ftw->insertTab(ConfigGadgetWidget::sensors, qwd, *icon, QString("Revo")); ftw->removeTab(ConfigGadgetWidget::hardware); + + icon = new QIcon(); + icon->addFile(":/configgadget/images/hardware_normal.png", QSize(), QIcon::Normal, QIcon::Off); + icon->addFile(":/configgadget/images/hardware_selected.png", QSize(), QIcon::Normal, QIcon::On); qwd = new ConfigProHWWidget(this); - ftw->insertTab(ConfigGadgetWidget::hardware, qwd, QIcon(":/configgadget/images/hw_config.png"), QString("HW Settings")); + ftw->insertTab(ConfigGadgetWidget::hardware, qwd, *icon, QString("Hardware")); ftw->setCurrentIndex(ConfigGadgetWidget::hardware); + } else { + //Unknown board + qDebug() << "Unknown board " << board; } } emit autopilotConnected(); } -void ConfigGadgetWidget::tabAboutToChange(int i,bool * proceed) +void ConfigGadgetWidget::tabAboutToChange(int i, bool * proceed) { Q_UNUSED(i); - *proceed=true; - ConfigTaskWidget * wid=qobject_cast(ftw->currentWidget()); - if(!wid) + *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) + if(ans==QMessageBox::No) { *proceed=false; - else + } else { wid->setDirty(false); + } } } @@ -228,9 +278,14 @@ void ConfigGadgetWidget::updatePipXStatus(UAVObject *object) pipxTimeout->start(5000); if (!pipxConnected) { - qDebug()<<"ConfigGadgetWidget onPipxtremeConnect"; + qDebug() << "ConfigGadgetWidget onPipxtremeConnect"; + + QIcon *icon = new QIcon(); + icon->addFile(":/configgadget/images/pipx-normal.png", QSize(), QIcon::Normal, QIcon::Off); + icon->addFile(":/configgadget/images/pipx-selected.png", QSize(), QIcon::Selected, QIcon::Off); + QWidget *qwd = new ConfigPipXtremeWidget(this); - ftw->insertTab(ConfigGadgetWidget::pipxtreme, qwd, QIcon(":/configgadget/images/PipXtreme.png"), QString("PipXtreme")); + ftw->insertTab(ConfigGadgetWidget::pipxtreme, qwd, *icon, QString("PipXtreme")); pipxConnected = true; } } diff --git a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.h b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.h index 5c33a50e0..4f737ff36 100644 --- a/ground/openpilotgcs/src/plugins/config/configgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configgadgetwidget.h @@ -49,6 +49,7 @@ public: ConfigGadgetWidget(QWidget *parent = 0); ~ConfigGadgetWidget(); enum widgetTabs {hardware=0, aircraft, input, output, sensors, stabilization, camerastabilization, txpid, pipxtreme, autotune}; + void startInputWizard(); public slots: void onAutopilotConnect(); diff --git a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp old mode 100755 new mode 100644 index f66878779..e16d735d9 --- a/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configinputwidget.cpp @@ -1,1349 +1,1358 @@ -/** - ****************************************************************************** - * - * @file configinputwidget.cpp - * @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 - *****************************************************************************/ -/* - * 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 "configinputwidget.h" - -#include "uavtalk/telemetrymanager.h" - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include - -#define ACCESS_MIN_MOVE -3 -#define ACCESS_MAX_MOVE 3 -#define STICK_MIN_MOVE -8 -#define STICK_MAX_MOVE 8 - -ConfigInputWidget::ConfigInputWidget(QWidget *parent) : ConfigTaskWidget(parent),wizardStep(wizardNone),transmitterType(heli),loop(NULL),skipflag(false) -{ - manualCommandObj = ManualControlCommand::GetInstance(getObjectManager()); - manualSettingsObj = ManualControlSettings::GetInstance(getObjectManager()); - flightStatusObj = FlightStatus::GetInstance(getObjectManager()); - receiverActivityObj=ReceiverActivity::GetInstance(getObjectManager()); - m_config = new Ui_InputWidget(); - m_config->setupUi(this); - - addApplySaveButtons(m_config->saveRCInputToRAM,m_config->saveRCInputToSD); - - ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance(); - Core::Internal::GeneralSettings * settings=pm->getObject(); - if(!settings->useExpertMode()) - m_config->saveRCInputToRAM->setVisible(false); - - addApplySaveButtons(m_config->saveRCInputToRAM,m_config->saveRCInputToSD); - - //Generate the rows of buttons in the input channel form GUI - unsigned int index=0; - foreach (QString name, manualSettingsObj->getField("ChannelNumber")->getElementNames()) - { - Q_ASSERT(index < ManualControlSettings::CHANNELGROUPS_NUMELEM); - inputChannelForm * inpForm=new inputChannelForm(this,index==0); - m_config->channelSettings->layout()->addWidget(inpForm); //Add the row to the UI - inpForm->setName(name); - addUAVObjectToWidgetRelation("ManualControlSettings","ChannelGroups",inpForm->ui->channelGroup,index); - addUAVObjectToWidgetRelation("ManualControlSettings","ChannelNumber",inpForm->ui->channelNumber,index); - addUAVObjectToWidgetRelation("ManualControlSettings","ChannelMin",inpForm->ui->channelMin,index); - addUAVObjectToWidgetRelation("ManualControlSettings","ChannelNeutral",inpForm->ui->channelNeutral,index); - addUAVObjectToWidgetRelation("ManualControlSettings","ChannelMax",inpForm->ui->channelMax,index); - ++index; - } - - addUAVObjectToWidgetRelation("ManualControlSettings", "Deadband", m_config->deadband, 0, 0.01f); - - connect(m_config->configurationWizard,SIGNAL(clicked()),this,SLOT(goToWizard())); - connect(m_config->stackedWidget,SIGNAL(currentChanged(int)),this,SLOT(disableWizardButton(int))); - connect(m_config->runCalibration,SIGNAL(toggled(bool)),this, SLOT(simpleCalibration(bool))); - - 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())); - - m_config->stackedWidget->setCurrentIndex(0); - addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos1,0,1,true); - addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos2,1,1,true); - addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos3,2,1,true); - addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos4,3,1,true); - addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos5,4,1,true); - addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos6,5,1,true); - addUAVObjectToWidgetRelation("ManualControlSettings","FlightModeNumber",m_config->fmsPosNum); - - 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"); - - addUAVObjectToWidgetRelation("ManualControlSettings","Arming",m_config->armControl); - addUAVObjectToWidgetRelation("ManualControlSettings","ArmedTimeout",m_config->armTimeout,0,1000); - connect( ManualControlCommand::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(moveFMSlider())); - connect( ManualControlSettings::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(updatePositionSlider())); - enableControls(false); - - populateWidgets(); - refreshWidgetsValues(); - // Connect the help button - connect(m_config->inputHelp, SIGNAL(clicked()), this, SLOT(openHelp())); - - 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/TX2.svg") && m_renderer->load(QString(":/configgadget/images/TX2.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() -{ - -} - -void ConfigInputWidget::resizeEvent(QResizeEvent *event) -{ - QWidget::resizeEvent(event); - m_config->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio ); -} - -void ConfigInputWidget::openHelp() -{ - - QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/x/04Cf", QUrl::StrictMode) ); -} -void ConfigInputWidget::goToWizard() -{ - QMessageBox msgBox; - msgBox.setText(tr("Arming Settings are now set to Always Disarmed for your safety.")); - msgBox.setDetailedText(tr("You will have to reconfigure the arming settings manually when the wizard is finished.")); - msgBox.setStandardButtons(QMessageBox::Ok); - msgBox.setDefaultButton(QMessageBox::Ok); - msgBox.exec(); - wizardSetUpStep(wizardWelcome); - m_config->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio ); -} - -void ConfigInputWidget::disableWizardButton(int value) -{ - if(value!=0) - m_config->configurationWizard->setVisible(false); - else - m_config->configurationWizard->setVisible(true); -} - -void ConfigInputWidget::wzCancel() -{ - 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: - foreach(QPointer wd,extraWidgets) - { - if(!wd.isNull()) - delete wd; - } - extraWidgets.clear(); - 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" - "You can press 'back' at any time to return to the previous screeen or press 'Cancel' to quit the wizard.\n")); - m_config->stackedWidget->setCurrentIndex(1); - m_config->wzBack->setEnabled(false); - break; - case wizardChooseMode: - { - m_config->graphicsView->setVisible(true); - m_config->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio ); - setTxMovement(nothing); - m_config->wzText->setText(tr("Please choose your transmitter 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 transmitter 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.\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 controls and press next when ready (if your FlightMode switch has only two positions, leave it in either position)."))); - break; - case wizardIdentifyLimits: - { - accessoryDesiredObj0 = AccessoryDesired::GetInstance(getObjectManager(),0); - accessoryDesiredObj1 = AccessoryDesired::GetInstance(getObjectManager(),1); - accessoryDesiredObj2 = AccessoryDesired::GetInstance(getObjectManager(),2); - 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 correct all the sticks which show an inverted movement, press next when ready."))); - fastMdata(); - break; - case wizardFinish: - dimOtherControls(false); - connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); - connect(flightStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); - connect(accessoryDesiredObj0, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); - m_config->wzText->setText(QString(tr("You have completed this wizard, please check below if the picture mimics your sticks movement.\n" - "These new settings aren't saved to the board yet, after pressing next you will go to the initial screen where you can save the configuration."))); - 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())); - disconnect(flightStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); - disconnect(accessoryDesiredObj0, 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())); - disconnect(flightStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); - disconnect(accessoryDesiredObj0, 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; - UAVObject::SetFlightTelemetryUpdateMode(mdata, 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 the throttle hold mode and move the collective pitch stick."))); - else if (newChan == ManualControlSettings::CHANNELGROUPS_FLIGHTMODE) - m_config->wzText->setText(QString(tr("Please toggle the flight mode switch. For switches you may have to repeat this rapidly."))); - else if((transmitterType == heli) && (newChan == ManualControlSettings::CHANNELGROUPS_THROTTLE)) - m_config->wzText->setText(QString(tr("Please disable throttle hold mode and move the throttle stick."))); - 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") || - manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan).contains("FlightMode")) { - 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(2500, 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(); - flightStatusData=flightStatusObj->getData(); - accessoryDesiredData0=accessoryDesiredObj0->getData(); - accessoryDesiredData1=accessoryDesiredObj1->getData(); - accessoryDesiredData2=accessoryDesiredObj2->getData(); - - 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 - { - 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); - } - if(flightStatusData.FlightMode==manualSettingsData.FlightModePosition[0]) - { - m_txFlightMode->setElementId("flightModeLeft"); - m_txFlightMode->setTransform(m_txFlightModeLOrig,false); - } - else if (flightStatusData.FlightMode==manualSettingsData.FlightModePosition[1]) - { - m_txFlightMode->setElementId("flightModeCenter"); - m_txFlightMode->setTransform(m_txFlightModeCOrig,false); - } - else if (flightStatusData.FlightMode==manualSettingsData.FlightModePosition[2]) - { - m_txFlightMode->setElementId("flightModeRight"); - m_txFlightMode->setTransform(m_txFlightModeROrig,false); - } - m_txAccess0->setTransform(QTransform(m_txAccess0Orig).translate(accessoryDesiredData0.AccessoryVal*ACCESS_MAX_MOVE*10,0),false); - m_txAccess1->setTransform(QTransform(m_txAccess1Orig).translate(accessoryDesiredData1.AccessoryVal*ACCESS_MAX_MOVE*10,0),false); - m_txAccess2->setTransform(QTransform(m_txAccess2Orig).translate(accessoryDesiredData2.AccessoryVal*ACCESS_MAX_MOVE*10,0),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->getField("ChannelNumber")->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; - } - - // Bound and scale FlightMode from [-1..+1] to [0..1] range - if (valueScaled < -1.0) - valueScaled = -1.0; - else - if (valueScaled > 1.0) - valueScaled = 1.0; - - // Convert flightMode value into the switch position in the range [0..N-1] - // This uses the same optimized computation as flight code to be consistent - uint8_t pos = ((int16_t)(valueScaled * 256) + 256) * manualSettingsDataPriv.FlightModeNumber >> 9; - if (pos >= manualSettingsDataPriv.FlightModeNumber) - pos = manualSettingsDataPriv.FlightModeNumber - 1; - m_config->fmsSlider->setValue(pos); -} - -void ConfigInputWidget::updatePositionSlider() -{ - ManualControlSettings::DataFields manualSettingsDataPriv = manualSettingsObj->getData(); - - switch(manualSettingsDataPriv.FlightModeNumber) { - default: - case 6: - m_config->fmsModePos6->setEnabled(true); - // pass through - case 5: - m_config->fmsModePos5->setEnabled(true); - // pass through - case 4: - m_config->fmsModePos4->setEnabled(true); - // pass through - case 3: - m_config->fmsModePos3->setEnabled(true); - // pass through - case 2: - m_config->fmsModePos2->setEnabled(true); - // pass through - case 1: - m_config->fmsModePos1->setEnabled(true); - // pass through - case 0: - break; - } - - switch(manualSettingsDataPriv.FlightModeNumber) { - case 0: - m_config->fmsModePos1->setEnabled(false); - // pass through - case 1: - m_config->fmsModePos2->setEnabled(false); - // pass through - case 2: - m_config->fmsModePos3->setEnabled(false); - // pass through - case 3: - m_config->fmsModePos4->setEnabled(false); - // pass through - case 4: - m_config->fmsModePos5->setEnabled(false); - // pass through - case 5: - m_config->fmsModePos6->setEnabled(false); - // pass through - case 6: - default: - break; - } -} - -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 the arming settings manually when the wizard is finished.")); - 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())); - } -} +/** + ****************************************************************************** + * + * @file configinputwidget.cpp + * @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 + *****************************************************************************/ +/* + * 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 "configinputwidget.h" + +#include "uavtalk/telemetrymanager.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#define ACCESS_MIN_MOVE -3 +#define ACCESS_MAX_MOVE 3 +#define STICK_MIN_MOVE -8 +#define STICK_MAX_MOVE 8 + +ConfigInputWidget::ConfigInputWidget(QWidget *parent) : ConfigTaskWidget(parent),wizardStep(wizardNone),transmitterType(heli),loop(NULL),skipflag(false) +{ + manualCommandObj = ManualControlCommand::GetInstance(getObjectManager()); + manualSettingsObj = ManualControlSettings::GetInstance(getObjectManager()); + flightStatusObj = FlightStatus::GetInstance(getObjectManager()); + receiverActivityObj=ReceiverActivity::GetInstance(getObjectManager()); + m_config = new Ui_InputWidget(); + m_config->setupUi(this); + + addApplySaveButtons(m_config->saveRCInputToRAM,m_config->saveRCInputToSD); + + ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance(); + Core::Internal::GeneralSettings * settings=pm->getObject(); + if(!settings->useExpertMode()) + m_config->saveRCInputToRAM->setVisible(false); + + addApplySaveButtons(m_config->saveRCInputToRAM,m_config->saveRCInputToSD); + + //Generate the rows of buttons in the input channel form GUI + unsigned int index=0; + foreach (QString name, manualSettingsObj->getField("ChannelNumber")->getElementNames()) + { + Q_ASSERT(index < ManualControlSettings::CHANNELGROUPS_NUMELEM); + inputChannelForm * inpForm=new inputChannelForm(this,index==0); + m_config->channelSettings->layout()->addWidget(inpForm); //Add the row to the UI + inpForm->setName(name); + addUAVObjectToWidgetRelation("ManualControlSettings","ChannelGroups",inpForm->ui->channelGroup,index); + addUAVObjectToWidgetRelation("ManualControlSettings","ChannelNumber",inpForm->ui->channelNumber,index); + addUAVObjectToWidgetRelation("ManualControlSettings","ChannelMin",inpForm->ui->channelMin,index); + addUAVObjectToWidgetRelation("ManualControlSettings","ChannelNeutral",inpForm->ui->channelNeutral,index); + addUAVObjectToWidgetRelation("ManualControlSettings","ChannelMax",inpForm->ui->channelMax,index); + ++index; + } + + addUAVObjectToWidgetRelation("ManualControlSettings", "Deadband", m_config->deadband, 0, 0.01f); + + connect(m_config->configurationWizard,SIGNAL(clicked()),this,SLOT(goToWizard())); + connect(m_config->stackedWidget,SIGNAL(currentChanged(int)),this,SLOT(disableWizardButton(int))); + connect(m_config->runCalibration,SIGNAL(toggled(bool)),this, SLOT(simpleCalibration(bool))); + + 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())); + + m_config->stackedWidget->setCurrentIndex(0); + addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos1,0,1,true); + addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos2,1,1,true); + addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos3,2,1,true); + addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos4,3,1,true); + addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos5,4,1,true); + addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos6,5,1,true); + addUAVObjectToWidgetRelation("ManualControlSettings","FlightModeNumber",m_config->fmsPosNum); + + 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"); + + addUAVObjectToWidgetRelation("ManualControlSettings","Arming",m_config->armControl); + addUAVObjectToWidgetRelation("ManualControlSettings","ArmedTimeout",m_config->armTimeout,0,1000); + connect( ManualControlCommand::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(moveFMSlider())); + connect( ManualControlSettings::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(updatePositionSlider())); + enableControls(false); + + populateWidgets(); + refreshWidgetsValues(); + // Connect the help button + connect(m_config->inputHelp, SIGNAL(clicked()), this, SLOT(openHelp())); + + 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/TX2.svg") && m_renderer->load(QString(":/configgadget/images/TX2.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() +{ + +} + +void ConfigInputWidget::resizeEvent(QResizeEvent *event) +{ + QWidget::resizeEvent(event); + m_config->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio ); +} + +void ConfigInputWidget::openHelp() +{ + QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/x/04Cf", QUrl::StrictMode) ); +} + +void ConfigInputWidget::goToWizard() +{ + QMessageBox msgBox; + msgBox.setText(tr("Arming Settings are now set to Always Disarmed for your safety.")); + msgBox.setDetailedText(tr("You will have to reconfigure the arming settings manually " + "when the wizard is finished. After the last step of the " + "wizard you will be taken to the Arming Settings screen.")); + msgBox.setStandardButtons(QMessageBox::Ok); + msgBox.setDefaultButton(QMessageBox::Ok); + msgBox.exec(); + + // Set correct tab visible before starting wizard. + if(m_config->tabWidget->currentIndex() != 0) { + m_config->tabWidget->setCurrentIndex(0); + } + wizardSetUpStep(wizardWelcome); + m_config->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio ); +} + +void ConfigInputWidget::disableWizardButton(int value) +{ + if(value!=0) + m_config->configurationWizard->setVisible(false); + else + m_config->configurationWizard->setVisible(true); +} + +void ConfigInputWidget::wzCancel() +{ + 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); + m_config->tabWidget->setCurrentIndex(2); + 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: + foreach(QPointer wd,extraWidgets) + { + if(!wd.isNull()) + delete wd; + } + extraWidgets.clear(); + 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" + "You can press 'back' at any time to return to the previous screeen or press 'Cancel' to quit the wizard.\n")); + m_config->stackedWidget->setCurrentIndex(1); + m_config->wzBack->setEnabled(false); + break; + case wizardChooseMode: + { + m_config->graphicsView->setVisible(true); + m_config->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio ); + setTxMovement(nothing); + m_config->wzText->setText(tr("Please choose your transmitter 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 transmitter 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.\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 controls and press next when ready (if your FlightMode switch has only two positions, leave it in either position)."))); + break; + case wizardIdentifyLimits: + { + accessoryDesiredObj0 = AccessoryDesired::GetInstance(getObjectManager(),0); + accessoryDesiredObj1 = AccessoryDesired::GetInstance(getObjectManager(),1); + accessoryDesiredObj2 = AccessoryDesired::GetInstance(getObjectManager(),2); + 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 correct all the sticks which show an inverted movement, press next when ready."))); + fastMdata(); + break; + case wizardFinish: + dimOtherControls(false); + connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); + connect(flightStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); + connect(accessoryDesiredObj0, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); + m_config->wzText->setText(QString(tr("You have completed this wizard, please check below if the picture mimics your sticks movement.\n" + "These new settings aren't saved to the board yet, after pressing next you will go to the Arming Settings " + "screen where you can set your desired arming sequence and save the configuration."))); + 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())); + disconnect(flightStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); + disconnect(accessoryDesiredObj0, 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())); + disconnect(flightStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks())); + disconnect(accessoryDesiredObj0, 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; + UAVObject::SetFlightTelemetryUpdateMode(mdata, 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 the throttle hold mode and move the collective pitch stick."))); + else if (newChan == ManualControlSettings::CHANNELGROUPS_FLIGHTMODE) + m_config->wzText->setText(QString(tr("Please toggle the flight mode switch. For switches you may have to repeat this rapidly."))); + else if((transmitterType == heli) && (newChan == ManualControlSettings::CHANNELGROUPS_THROTTLE)) + m_config->wzText->setText(QString(tr("Please disable throttle hold mode and move the throttle stick."))); + 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") || + manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan).contains("FlightMode")) { + 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(2500, 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(); + flightStatusData=flightStatusObj->getData(); + accessoryDesiredData0=accessoryDesiredObj0->getData(); + accessoryDesiredData1=accessoryDesiredObj1->getData(); + accessoryDesiredData2=accessoryDesiredObj2->getData(); + + 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 + { + 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); + } + if(flightStatusData.FlightMode==manualSettingsData.FlightModePosition[0]) + { + m_txFlightMode->setElementId("flightModeLeft"); + m_txFlightMode->setTransform(m_txFlightModeLOrig,false); + } + else if (flightStatusData.FlightMode==manualSettingsData.FlightModePosition[1]) + { + m_txFlightMode->setElementId("flightModeCenter"); + m_txFlightMode->setTransform(m_txFlightModeCOrig,false); + } + else if (flightStatusData.FlightMode==manualSettingsData.FlightModePosition[2]) + { + m_txFlightMode->setElementId("flightModeRight"); + m_txFlightMode->setTransform(m_txFlightModeROrig,false); + } + m_txAccess0->setTransform(QTransform(m_txAccess0Orig).translate(accessoryDesiredData0.AccessoryVal*ACCESS_MAX_MOVE*10,0),false); + m_txAccess1->setTransform(QTransform(m_txAccess1Orig).translate(accessoryDesiredData1.AccessoryVal*ACCESS_MAX_MOVE*10,0),false); + m_txAccess2->setTransform(QTransform(m_txAccess2Orig).translate(accessoryDesiredData2.AccessoryVal*ACCESS_MAX_MOVE*10,0),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->getField("ChannelNumber")->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; + } + + // Bound and scale FlightMode from [-1..+1] to [0..1] range + if (valueScaled < -1.0) + valueScaled = -1.0; + else + if (valueScaled > 1.0) + valueScaled = 1.0; + + // Convert flightMode value into the switch position in the range [0..N-1] + // This uses the same optimized computation as flight code to be consistent + uint8_t pos = ((int16_t)(valueScaled * 256) + 256) * manualSettingsDataPriv.FlightModeNumber >> 9; + if (pos >= manualSettingsDataPriv.FlightModeNumber) + pos = manualSettingsDataPriv.FlightModeNumber - 1; + m_config->fmsSlider->setValue(pos); +} + +void ConfigInputWidget::updatePositionSlider() +{ + ManualControlSettings::DataFields manualSettingsDataPriv = manualSettingsObj->getData(); + + switch(manualSettingsDataPriv.FlightModeNumber) { + default: + case 6: + m_config->fmsModePos6->setEnabled(true); + // pass through + case 5: + m_config->fmsModePos5->setEnabled(true); + // pass through + case 4: + m_config->fmsModePos4->setEnabled(true); + // pass through + case 3: + m_config->fmsModePos3->setEnabled(true); + // pass through + case 2: + m_config->fmsModePos2->setEnabled(true); + // pass through + case 1: + m_config->fmsModePos1->setEnabled(true); + // pass through + case 0: + break; + } + + switch(manualSettingsDataPriv.FlightModeNumber) { + case 0: + m_config->fmsModePos1->setEnabled(false); + // pass through + case 1: + m_config->fmsModePos2->setEnabled(false); + // pass through + case 2: + m_config->fmsModePos3->setEnabled(false); + // pass through + case 3: + m_config->fmsModePos4->setEnabled(false); + // pass through + case 4: + m_config->fmsModePos5->setEnabled(false); + // pass through + case 5: + m_config->fmsModePos6->setEnabled(false); + // pass through + case 6: + default: + break; + } +} + +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 the arming settings manually when the wizard is finished.")); + 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 4b28ca491..ab6250e88 100644 --- a/ground/openpilotgcs/src/plugins/config/configinputwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configinputwidget.h @@ -60,7 +60,7 @@ public: 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: + void startInputWizard() { goToWizard(); } private: bool growing; @@ -144,6 +144,7 @@ private: void wizardSetUpStep(enum wizardSteps); void wizardTearDownStep(enum wizardSteps); + private slots: void wzNext(); void wzBack(); @@ -161,11 +162,10 @@ private slots: 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/configplugin.cpp b/ground/openpilotgcs/src/plugins/config/configplugin.cpp index 30418094c..fd3a30544 100644 --- a/ground/openpilotgcs/src/plugins/config/configplugin.cpp +++ b/ground/openpilotgcs/src/plugins/config/configplugin.cpp @@ -99,7 +99,7 @@ void ConfigPlugin::extensionsInitialized() void ConfigPlugin::shutdown() { - // Do nothing + // Do nothing } /** diff --git a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp index 7055851ef..99cfebdb4 100644 --- a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp @@ -215,6 +215,9 @@ ConfigVehicleTypeWidget::ConfigVehicleTypeWidget(QWidget *parent) : ConfigTaskWi connect(m_aircraft->ffTestBox2, SIGNAL(clicked(bool)), this, SLOT(enableFFTest())); connect(m_aircraft->ffTestBox3, SIGNAL(clicked(bool)), this, SLOT(enableFFTest())); + //Connect the multirotor motor reverse checkbox + connect(m_aircraft->MultirotorRevMixercheckBox, SIGNAL(clicked(bool)), this, SLOT(reverseMultirotorMotor())); + // Connect the help pushbutton connect(m_aircraft->airframeHelp, SIGNAL(clicked()), this, SLOT(openHelp())); enableControls(false); @@ -483,7 +486,7 @@ void ConfigVehicleTypeWidget::refreshWidgetsValues(UAVObject * o) UAVObjectField *field = system->getField(QString("AirframeType")); Q_ASSERT(field); // At this stage, we will need to have some hardcoded settings in this code, this - // is not ideal, but here you go. + // is not ideal, but there you go. QString frameType = field->getValue().toString(); setupAirframeUI(frameType); @@ -718,9 +721,30 @@ void ConfigVehicleTypeWidget::updateObjectsFromWidgets() // Update the table: for (int channel=0; channel<(int)(VehicleConfig::CHANNEL_NUMELEM); channel++) { QComboBox* q = (QComboBox*)m_aircraft->customMixerTable->cellWidget(0,channel); - - vconfig->setMixerType(mixer,channel, - q->currentText() == "Servo" ? VehicleConfig::MIXERTYPE_SERVO : VehicleConfig::MIXERTYPE_MOTOR); + if(q->currentText()=="Disabled") + vconfig->setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_DISABLED); + else if(q->currentText()=="Motor") + vconfig->setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_MOTOR); + else if(q->currentText()=="Servo") + vconfig->setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_SERVO); + else if(q->currentText()=="CameraRoll") + vconfig->setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_CAMERAROLL); + else if(q->currentText()=="CameraPitch") + vconfig->setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_CAMERAPITCH); + else if(q->currentText()=="CameraYaw") + vconfig->setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_CAMERAYAW); + else if(q->currentText()=="Accessory0") + vconfig->setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_ACCESSORY0); + else if(q->currentText()=="Accessory1") + vconfig->setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_ACCESSORY1); + else if(q->currentText()=="Accessory2") + vconfig->setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_ACCESSORY2); + else if(q->currentText()=="Accessory3") + vconfig->setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_ACCESSORY3); + else if(q->currentText()=="Accessory4") + vconfig->setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_ACCESSORY4); + else if(q->currentText()=="Accessory5") + vconfig->setMixerType(mixer,channel,VehicleConfig::MIXERTYPE_ACCESSORY5); vconfig->setMixerVectorValue(mixer,channel,VehicleConfig::MIXERVECTOR_THROTTLECURVE1, m_aircraft->customMixerTable->item(1,channel)->text().toDouble()); @@ -766,6 +790,12 @@ void ConfigVehicleTypeWidget::setComboCurrentIndex(QComboBox* box, int index) box->setCurrentIndex(index); } +void ConfigVehicleTypeWidget::reverseMultirotorMotor(){ + QString frameType = m_aircraft->multirotorFrameType->currentText(); + m_multirotor->drawAirframe(frameType); +} + + /** WHAT DOES THIS DO??? */ diff --git a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.h b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.h index 60ef74fbe..e4cea4cc2 100644 --- a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.h +++ b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.h @@ -95,6 +95,7 @@ private slots: void enableFFTest(); void openHelp(); + void reverseMultirotorMotor(); protected: void showEvent(QShowEvent *event); diff --git a/ground/openpilotgcs/src/plugins/config/images/autotune_normal.png b/ground/openpilotgcs/src/plugins/config/images/autotune_normal.png new file mode 100644 index 000000000..5c7ca95f1 Binary files /dev/null and b/ground/openpilotgcs/src/plugins/config/images/autotune_normal.png differ diff --git a/ground/openpilotgcs/src/plugins/config/images/autotune_selected.png b/ground/openpilotgcs/src/plugins/config/images/autotune_selected.png new file mode 100644 index 000000000..53fe7cf0c Binary files /dev/null and b/ground/openpilotgcs/src/plugins/config/images/autotune_selected.png differ diff --git a/ground/openpilotgcs/src/plugins/config/images/camstab_normal.png b/ground/openpilotgcs/src/plugins/config/images/camstab_normal.png new file mode 100644 index 000000000..07cf6c6c4 Binary files /dev/null and b/ground/openpilotgcs/src/plugins/config/images/camstab_normal.png differ diff --git a/ground/openpilotgcs/src/plugins/config/images/camstab_selected.png b/ground/openpilotgcs/src/plugins/config/images/camstab_selected.png new file mode 100644 index 000000000..30b82f0fe Binary files /dev/null and b/ground/openpilotgcs/src/plugins/config/images/camstab_selected.png differ diff --git a/ground/openpilotgcs/src/plugins/config/images/hardware_normal.png b/ground/openpilotgcs/src/plugins/config/images/hardware_normal.png new file mode 100644 index 000000000..077d9712e Binary files /dev/null and b/ground/openpilotgcs/src/plugins/config/images/hardware_normal.png differ diff --git a/ground/openpilotgcs/src/plugins/config/images/hardware_selected.png b/ground/openpilotgcs/src/plugins/config/images/hardware_selected.png new file mode 100644 index 000000000..83611be21 Binary files /dev/null and b/ground/openpilotgcs/src/plugins/config/images/hardware_selected.png differ diff --git a/ground/openpilotgcs/src/plugins/config/images/input_normal.png b/ground/openpilotgcs/src/plugins/config/images/input_normal.png new file mode 100644 index 000000000..e5315ced7 Binary files /dev/null and b/ground/openpilotgcs/src/plugins/config/images/input_normal.png differ diff --git a/ground/openpilotgcs/src/plugins/config/images/input_selected.png b/ground/openpilotgcs/src/plugins/config/images/input_selected.png new file mode 100644 index 000000000..b4c2340ee Binary files /dev/null and b/ground/openpilotgcs/src/plugins/config/images/input_selected.png differ diff --git a/ground/openpilotgcs/src/plugins/config/images/ins_normal.png b/ground/openpilotgcs/src/plugins/config/images/ins_normal.png new file mode 100644 index 000000000..335f0ff34 Binary files /dev/null and b/ground/openpilotgcs/src/plugins/config/images/ins_normal.png differ diff --git a/ground/openpilotgcs/src/plugins/config/images/ins_selected.png b/ground/openpilotgcs/src/plugins/config/images/ins_selected.png new file mode 100644 index 000000000..7e04f144f Binary files /dev/null and b/ground/openpilotgcs/src/plugins/config/images/ins_selected.png differ diff --git a/ground/openpilotgcs/src/plugins/config/images/multirotor-shapes.svg b/ground/openpilotgcs/src/plugins/config/images/multirotor-shapes.svg index de5f2bd64..92ec0177e 100644 --- a/ground/openpilotgcs/src/plugins/config/images/multirotor-shapes.svg +++ b/ground/openpilotgcs/src/plugins/config/images/multirotor-shapes.svg @@ -14,7 +14,7 @@ version="1.1" inkscape:version="0.48.2 r9819" width="4065.2493" - height="1760.019" + height="3560.019" xml:space="preserve" sodipodi:docname="multirotor-shapes.svg"> \ No newline at end of file + inkscape:connector-curvature="0" /> \ No newline at end of file diff --git a/ground/openpilotgcs/src/plugins/config/images/output_normal.png b/ground/openpilotgcs/src/plugins/config/images/output_normal.png new file mode 100644 index 000000000..f5754786c Binary files /dev/null and b/ground/openpilotgcs/src/plugins/config/images/output_normal.png differ diff --git a/ground/openpilotgcs/src/plugins/config/images/output_selected.png b/ground/openpilotgcs/src/plugins/config/images/output_selected.png new file mode 100644 index 000000000..016272b5e Binary files /dev/null and b/ground/openpilotgcs/src/plugins/config/images/output_selected.png differ diff --git a/ground/openpilotgcs/src/plugins/config/images/pipx-normal.png b/ground/openpilotgcs/src/plugins/config/images/pipx-normal.png new file mode 100644 index 000000000..74f074689 Binary files /dev/null and b/ground/openpilotgcs/src/plugins/config/images/pipx-normal.png differ diff --git a/ground/openpilotgcs/src/plugins/config/images/pipx-selected.png b/ground/openpilotgcs/src/plugins/config/images/pipx-selected.png new file mode 100644 index 000000000..ef9818a83 Binary files /dev/null and b/ground/openpilotgcs/src/plugins/config/images/pipx-selected.png differ diff --git a/ground/openpilotgcs/src/plugins/config/images/stabilization_normal.png b/ground/openpilotgcs/src/plugins/config/images/stabilization_normal.png new file mode 100644 index 000000000..7d6c750cd Binary files /dev/null and b/ground/openpilotgcs/src/plugins/config/images/stabilization_normal.png differ diff --git a/ground/openpilotgcs/src/plugins/config/images/stabilization_selected.png b/ground/openpilotgcs/src/plugins/config/images/stabilization_selected.png new file mode 100644 index 000000000..7394f23ed Binary files /dev/null and b/ground/openpilotgcs/src/plugins/config/images/stabilization_selected.png differ diff --git a/ground/openpilotgcs/src/plugins/config/images/txpid_normal.png b/ground/openpilotgcs/src/plugins/config/images/txpid_normal.png new file mode 100644 index 000000000..79d2d1d7f Binary files /dev/null and b/ground/openpilotgcs/src/plugins/config/images/txpid_normal.png differ diff --git a/ground/openpilotgcs/src/plugins/config/images/txpid_selected.png b/ground/openpilotgcs/src/plugins/config/images/txpid_selected.png new file mode 100644 index 000000000..0e4fe57d1 Binary files /dev/null and b/ground/openpilotgcs/src/plugins/config/images/txpid_selected.png differ diff --git a/ground/openpilotgcs/src/plugins/config/images/vehicle_normal.png b/ground/openpilotgcs/src/plugins/config/images/vehicle_normal.png new file mode 100644 index 000000000..ef96bb78d Binary files /dev/null and b/ground/openpilotgcs/src/plugins/config/images/vehicle_normal.png differ diff --git a/ground/openpilotgcs/src/plugins/config/images/vehicle_selected.png b/ground/openpilotgcs/src/plugins/config/images/vehicle_selected.png new file mode 100644 index 000000000..292c6026e Binary files /dev/null and b/ground/openpilotgcs/src/plugins/config/images/vehicle_selected.png differ diff --git a/ground/openpilotgcs/src/plugins/config/input.ui b/ground/openpilotgcs/src/plugins/config/input.ui index 85d63b2f5..345b6f5fb 100755 --- a/ground/openpilotgcs/src/plugins/config/input.ui +++ b/ground/openpilotgcs/src/plugins/config/input.ui @@ -6,8 +6,8 @@ 0 0 - 670 - 693 + 880 + 672 @@ -28,7 +28,7 @@ - 6 + 0 0 @@ -110,8 +110,8 @@ 0 0 - 640 - 610 + 850 + 572 @@ -119,7 +119,7 @@ 12 - 6 + -1 @@ -149,47 +149,11 @@ 12 - - - - Start Configuration Wizard - - - - - - - true - - - Run Calibration - - - - - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 20 - 12 - - - - 0 - - 0 - @@ -348,6 +312,98 @@ + + + + Calibration and Configuration Options + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Start Configuration Wizard + + + false + + + false + + + false + + + false + + + false + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + true + + + + 210 + 0 + + + + false + + + Manual Calibration + + + true + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + @@ -359,9 +415,6 @@ Flight Mode Switch Settings - - 6 - 0 @@ -442,29 +495,297 @@ 0 0 - 640 - 610 + 850 + 572 - + 12 - - 6 - + + + + + + + Configure each stabilization mode for each axis + + + + 9 + + + 12 + + + + + Qt::Horizontal + + + QSizePolicy::Minimum + + + + 5 + 20 + + + + + + + + Qt::StrongFocus + + + + + + + + 0 + 20 + + + + + 16777215 + 20 + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Yaw + + + Qt::AlignCenter + + + + + + + Qt::Horizontal + + + + 5 + 20 + + + + + + + + Stabilized1 + + + Qt::AlignCenter + + + + + + + Qt::Horizontal + + + + 5 + 20 + + + + + + + + Qt::StrongFocus + + + + + + + Stabilized2 + + + Qt::AlignCenter + + + + + + + Qt::StrongFocus + + + + + + + Qt::StrongFocus + + + + + + + + 0 + 20 + + + + + 16777215 + 20 + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Pitch + + + Qt::AlignCenter + + + + + + + + 0 + 20 + + + + + 16777215 + 20 + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Roll + + + Qt::AlignCenter + + + + + + + Qt::StrongFocus + + + + + + + + 102 + 0 + + + + Qt::StrongFocus + + + + + + + Qt::StrongFocus + + + + + + + + 102 + 0 + + + + Qt::StrongFocus + + + + + + + + 102 + 0 + + + + Qt::StrongFocus + + + + + + + Stabilized3 + + + Qt::AlignCenter + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + 0 - 195 + 230 16777215 - 195 + 230 @@ -636,7 +957,7 @@ 16777215 - 140 + 160 @@ -679,6 +1000,9 @@ Setup the flight mode channel on the RC Input tab if you have not done so alread + + 3 + @@ -858,194 +1182,17 @@ channel value for each flight mode.
Qt::Vertical + + QSizePolicy::Expanding + 20 - 100 + 20 - - - - - - - Configure each stabilization mode for each axis - - - - 0 - - - 12 - - - - - Stabilized3 - - - Qt::AlignCenter - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - Roll - - - Qt::AlignCenter - - - - - - - - 102 - 0 - - - - Qt::StrongFocus - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - Pitch - - - Qt::AlignCenter - - - - - - - Qt::StrongFocus - - - - - - - Qt::StrongFocus - - - - - - - Qt::StrongFocus - - - - - - - Stabilized1 - - - Qt::AlignCenter - - - - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - Yaw - - - Qt::AlignCenter - - - - - - - Qt::StrongFocus - - - - - - - - 102 - 0 - - - - Qt::StrongFocus - - - - - - - Qt::StrongFocus - - - - - - - Qt::StrongFocus - - - - - - - Stabilized2 - - - Qt::AlignCenter - - - - - - - - 102 - 0 - - - - Qt::StrongFocus - - - - - - @@ -1057,9 +1204,6 @@ margin:1px;
Arming Settings - - 6 - 0 @@ -1140,14 +1284,11 @@ margin:1px;
0 0 - 640 - 610 + 850 + 572 - - 6 - 12 diff --git a/ground/openpilotgcs/src/plugins/config/output.ui b/ground/openpilotgcs/src/plugins/config/output.ui index dc23ff7a4..e49f240c6 100755 --- a/ground/openpilotgcs/src/plugins/config/output.ui +++ b/ground/openpilotgcs/src/plugins/config/output.ui @@ -14,9 +14,6 @@ Form - - 6 - 12 @@ -120,12 +117,12 @@ 0 0 668 - 671 + 654 - 6 + -1 12 @@ -148,12 +145,12 @@ Output Update Speed - - 12 - 6 + + 12 + @@ -528,15 +525,9 @@ Leave at 50Hz for fixed wing.
- - 6 - QLayout::SetDefaultConstraint - - 0 - diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index 6777d0800..4ff6b33ff 100755 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -7,7 +7,7 @@ 0 0 965 - 797 + 687 @@ -505,9 +505,6 @@ Basic - - 6 - 0 @@ -603,24 +600,15 @@ 0 0 - 935 - 714 + 937 + 595 12 - - 12 - - - 5 - - - 12 - - + 12 @@ -640,7 +628,7 @@ 16777215 - 181 + 195 @@ -3496,7 +3484,7 @@ value as the Kp.
16777215 - 181 + 195 @@ -6866,9 +6854,6 @@ border-radius: 5;
Advanced - - 6 - 0 @@ -6952,17 +6937,14 @@ border-radius: 5;
0 0 - 935 - 714 + 540 + 663 true - - 6 - 12 @@ -6977,7 +6959,7 @@ border-radius: 5;
0 - 210 + 0 @@ -10299,7 +10281,7 @@ Then lower the value by 20% or so.
0 - 170 + 0 @@ -13429,7 +13411,7 @@ border-radius: 5;
0 - 195 + 0 @@ -16792,9 +16774,6 @@ border-radius: 5;
Expert - - 6 - 0 @@ -16881,14 +16860,11 @@ border-radius: 5;
0 0 - 935 - 714 + 802 + 607 - - 6 - 12 @@ -16903,7 +16879,7 @@ border-radius: 5;
0 - 150 + 0 @@ -19508,7 +19484,7 @@ border-radius: 5;
0 - 180 + 0 @@ -21916,7 +21892,7 @@ border-radius: 5;
0 - 150 + 0 diff --git a/ground/openpilotgcs/src/plugins/config/txpid.ui b/ground/openpilotgcs/src/plugins/config/txpid.ui index 9d4da0865..1c277d0fb 100755 --- a/ground/openpilotgcs/src/plugins/config/txpid.ui +++ b/ground/openpilotgcs/src/plugins/config/txpid.ui @@ -7,7 +7,7 @@ 0 0 789 - 615 + 484 @@ -113,8 +113,8 @@ 0 0 - 759 - 532 + 745 + 469 diff --git a/ground/openpilotgcs/src/plugins/coreplugin/CREDITS.html b/ground/openpilotgcs/src/plugins/coreplugin/CREDITS.html index 2f3f2bc5b..cd1c8661d 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/CREDITS.html +++ b/ground/openpilotgcs/src/plugins/coreplugin/CREDITS.html @@ -2,209 +2,76 @@

This is a credits file of people that are or have been key contributors to the OpenPilot project. Without the work of the people in this file OpenPilot would not be what it is today.

-

It is sorted alphabetically by name and formatted so that it allows for easy grepping and beautification by scripts.

+

It is sorted alphabetically by name

-The fields are:
-
-Name (N)
-Email (E),
-Description of work (D)
-Current maintainer function (M)
-
-----------
-
-N: Connor Abbott
-E: connor (at) abbott (dot) cx
-D: Win32 OpenPilot port
-M: SITL Win32
-
-N: David Ankers
-E: david (at) openpilot (dot) org
-D: Co-founder, Project Coordination
-D: Minor GCS infrastructure, updating the credit file
-M: Admin
-
-N: Pedro Assuncao
-E: pedro (dot) agda (plus) openpilot (at) gmail (dot) com
-D: Initial GCS Settings Gadget work
-
-N: Jose Barros
-E: josembarros (at) hotmail (dot) com
-D: Next-Gen OP Map Lib, Y-Modem Library, Uploader Plugin
-D: OP Bootloader, AHRS Bootloader, OPUploadTool
-M: Bootloader, OP MAP Lib
-
-N: David "Buzz" Carlson
-E: chebuzz (plus) openpilot (at) gmail (dot) com
-D: 3D ModelView GCS Plugin, sponsor of HITL merge work and XPlane addition
-M: 3D Modelview
-
-N: James Cotton
-E: peabody124 (plus) openpilot (at) gmail (dot) com
-D: Multiplatform HID implementation (firmware & GCS), GCS Joystick control
-D: Posix OpenPilot work and Mac implementation
-D: Firmware implementation of Professor Schinstock's INS/GPS
-M: Architecture co-lead
-
-N: Piotr Esden-Tempski
-E: esden (at) esden (dot) net
-D: Floss-JTAG Rev A, 4-layer initial design
-
-N: Frederic Goddeeris
-E: fredericgoddeeris (at) hotmail (dot) com
-D: I2C work and FreeRTOS work, MK integration
-D: EagleTree OSD implementation
-M: OSD Module
-
-N: Daniel Godin
-E: dgodin (at) dnsct (dot) com
-W: Sponsor: Notify Plugin for the GCS
-
-N: Bani Greyling
-E: bani (dot) greyling (plus) openpilot (at) gmail (dot) com
-D: GCS Scope plugin
-
-N: Nuno Guedes
-E: muralha (plus) openpilot (at) gmail (dot) com
-D: 3D artwork, moving surfaces and work on ModelView
-
-N: Peter Gunnarsson
-E: peter (at) pyne (dot) se
-D: GCS Core Developer
-D: Multiple GCS plugins, Gadget foundations, UAVObject viewer
-
-N: Dean Hall
-E: dwhall256 (plus) openpilot (at) gmail (dot) com
-D: Creator of http://pythononachip.org
-
-N: Joe Hlebasko
-E: joe (dot) hlebasko(plus) openpilot (at) gmail (dot) com
-D: Production Main Board & Production OP GPS
-M: Hardware Architecture Team
-
-N: Mark James
-E: mjames (plus) openpilot (at) gmail (dot) com
-D: Some of Silk Icon set used in GCS - http://www.famfamfam.com/lab/icons/silk
-
-N: Sami Korhonen
-E: samik (dot) korhonen (plus) openpilot (at) gmail (dot) com
-D: GPS Module, Spektrum RC Module, OSD work
-
-N: Thorsten Klose
-E: thorsten (dot) klose (at) dmx (dot) de
-D: Embedded STM32 infrastructure
-
-N: Hallvard Kristiansen
-E: hal (at) fleshmx (dot) com
-D: GCS Artwork, Quad layout diagrams
-
-N: Edouard Lafargue
-E: edouard (at) lafargue (dot) name
-D: GCS Dial Plugins, GCS PFD Plugin, GCS GPS plugin, GCS Config plugin
-D: Artwork including standard display dials
-M: GCS Core
-
-N: Matt Lipski
-E: mattlipski (plus) openpilot (at) gmail (dot) com
-D: Deluxe Dials Set artwork, (Artificial Horizon, Compass, Turn Indicator)
-
-N: Les Newell
-E: les (dot) newell (at) fastmail (dot) co (dot) uk
-D: Advanced mixer matrix, SPI protocol based on UAVObjects
-
-N: Ken Northup
-E: helos360 (at) bellsouth (dot) net
-D: 3D Modelling, Easystar adaption from FMS
-
-N: Guy McCaldin
-E: guymcc (at) gmail (dot) com
-D: Artwork and design including work on the Deluxe Dial Set
-
-N: Cathy Moss
-E: cmoss296 (at) blueyonder (dot) co (dot) uk
-D: Hardware design Lead: Gen 2 Mainboard, PipXtreme, Current Sensor
-D: Lead dev PipXtreme, creator OP Map Plugin
-M: Hardware Architecture Team / PipX Modem
-
-N: Angus Peart
-E: gussy (at) openpilot (dot) org
-D: Co-founder, Principal hardware architect.
-D: Hardware design of OpenPilot, AHRS, GPS and other hardware
-D: Core developer embedded code
-
-N: Eric Price
-E: corvus (dot) corax (at) cybertrench (dot) com
-D: IL2 HITL GCS Plugin, Posix OpenPilot, Advanced stabilisation module
-M: SITL Posix
-
-N: Richard Querin
-E: rfquerin (plus) openpilot (at) gmail (dot) com
-D: Graphic Design, OpenPilot Logo
-
-N: Laurent Ribon
-E: ribon (dot) l (at) club-internet (dot) fr
-D: The GLC_lib as used in the ModelView Plugin
-D: See: http://www.glc-lib.net/
-
-N: Julien Rouviere
-E: julien (dot) rouviere (plus) openpilot (at) gmail (dot) com
-D: GCS Core Developer
-D: GCS Framework and Plugins for the GCS
-
-N: Zik Saleeba
-E: zik (at) zikzak (dot) net
-D: Initial schematic based on Zik's Flying Fox schematic
-
-N: Professor Dale Schinstock
-E: dales (at) ksu (dot) edu
-D: Lead AHRS Developer
-D: Creator of the OpenPilot INS / EKF
-
-N: Oleg Semyonov
-E: os-openpilot-org (at) os-propo (dot) info
-D: Core tester & Project organisation
-M: Common part of multi-platform packaging system
-M: Windows NSIS Installer
-M: Russian Documentation Lead
-
-N: Stacey Sheldon
-E: stac (at) solidgoldbomb (dot) org
-D: Core Embedded Developer
-D: SPI protocol for AHRS, I2C rewrite and much core work
-
-N: Troy Schultz
-E: troy (dot) schultz (at) rogers (dot) com
-D: INS design review and optimisation
-M: Hardware Architecture Team
-
-N: Dr. Erhard Siegl
-E: Erhard (dot) Siegl (at) zogazoga (dot) at
-D: Configuration engine for the GCS
-
-N: Pete Stapley
-E: pete (at) stapleylabs (dot) com
-D: PPM inputs
-
-N: Rowan Taubitz
-E: rowan (at) zantek (dot) com (dot) au
-D: Hardware debugging and testing, creation of 2-layer Floss-JTAG Rev B
-D: Creation of Next-Gen FOSS-JTAG board
-
-N: Andrew Thoms
-E: electronics (at) andrewspizza (dot) net
-D: IP Telemtry plugin for the GCS
-D: Helicopter support code and mixing for CCPM
-
-N: Vassilis Varveropoulos
-E: vassilis (at) openpilot (dot) org
-D: Co-founder, Principal embedded software architect.
-D: Module architecture and UAVTalk/UAVObjects implementation.
-M: Architecture co-lead
-
-N: Alex Vrubel
-E: alex (dot) vrubel (plus) openpilot (at) gmail (dot) com
-D: Russian translation of the GCS
+Connor Abbott
+David Ankers
+Pedro Assuncao
+Fredrik Arvidsson
+Werner Backes
+Jose Barros
+Pete  Boehl
+David Carlson
+James Cotton
+Steve Doll
+Piotr Esden-Tempski
+Peter Farnworth
+Ed Faulkner
+Darren Furniss
+Frederic Goddeeris
+Daniel Godin
+Bani Greyling
+Nuno Guedes
+Peter Gunnarsson
+Dean Hall
+Joe Hlebasko
+Andy Honecker
+Ryan Hunt
+Mark James
+Sami Korhonen
+Thorsten Klose
+Hallvard Kristiansen
+Edouard Lafargue
+Mike Labranche
+Fredrik Larsson
+Pablo Lema
+David Llama
+Matt Lipski
+Les Newell
+Ken Northup
+Greg Matthews
+Guy McCaldin
+Gary Mortimer
+Cathy Moss
+Angus Peart
+Dmytro Poplavskiy
+Eric Price
+Richard Querin
+Randy Ram
+Laurent Ribon
+Julien Rouviere
+Jackson Russell
+Zik Saleeba
+Professor Dale Schinstock
+Professor Kenn Sebesta
+Oleg Semyonov
+Stacey Sheldon
+Troy Schultz
+Dr. Erhard Siegl
+Mike Smith
+Alex Sowa
+Pete Stapley
+Rowan Taubitz
+Andrew Thoms
+Jasper van Loenen
+Vassilis Varveropoulos
+Kevin Vertucio
+Alex Vrubel
+Brian Webb
+Justin Welander
+Mat Wellington
+Kendal Wells
 
diff --git a/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.cpp b/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.cpp index 30061c0c5..8d1e7ff1c 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.cpp +++ b/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.cpp @@ -101,7 +101,7 @@ void ConnectionManager::init() /** * Method called when the user clicks the "Connect" button */ -bool ConnectionManager::connectDevice() +bool ConnectionManager::connectDevice(DevListItem device) { DevListItem connection_device = findDevice(m_availableDevList->itemData(m_availableDevList->currentIndex(),Qt::ToolTipRole).toString()); if (!connection_device.connection) @@ -126,7 +126,7 @@ bool ConnectionManager::connectDevice() connect(m_connectionDevice.connection, SIGNAL(destroyed(QObject *)), this, SLOT(onConnectionDestroyed(QObject *)), Qt::QueuedConnection); // signal interested plugins that we connected to the device - emit deviceConnected(m_ioDev); + emit deviceConnected(io_dev); m_connectBtn->setText("Disconnect"); m_availableDevList->setEnabled(false); @@ -174,6 +174,7 @@ bool ConnectionManager::disconnectDevice() m_connectionDevice.connection = NULL; m_ioDev = NULL; + emit deviceDisconnected(); m_connectBtn->setText("Connect"); m_availableDevList->setEnabled(true); @@ -230,8 +231,11 @@ void ConnectionManager::onConnectClicked() { // Check if we have a ioDev already created: if (!m_ioDev) - { // connecting - connectDevice(); + { + // connecting to currently selected device + DevListItem device = findDevice(m_availableDevList->itemData(m_availableDevList->currentIndex(), Qt::ToolTipRole).toString()); + if (device.connection) + connectDevice(device); } else { // disconnecting @@ -427,6 +431,9 @@ void ConnectionManager::devChanged(IConnection *connection) updateConnectionDropdown(); + qDebug() << "# devices " << m_devList.count(); + emit availableDevicesChanged(m_devList); + //disable connection button if the liNameif (m_availableDevList->count() > 0) if (m_availableDevList->count() > 0) @@ -445,11 +452,12 @@ void ConnectionManager::updateConnectionDropdown() if(!m_ioDev && d.getConName().startsWith("USB")) { if(m_mainWindow->generalSettings()->autoConnect() || m_mainWindow->generalSettings()->autoSelect()) - m_availableDevList->setCurrentIndex(m_availableDevList->count()-1); + m_availableDevList->setCurrentIndex(m_availableDevList->count() - 1); + if(m_mainWindow->generalSettings()->autoConnect() && polling) { qDebug() << "Automatically opening device"; - connectDevice(); + connectDevice(d); qDebug()<<"ConnectionManager::devChanged autoconnected USB device"; } } diff --git a/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.h b/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.h index 7e27b3351..2f131d4a3 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.h +++ b/ground/openpilotgcs/src/plugins/coreplugin/connectionmanager.h @@ -92,7 +92,14 @@ public: void init(); QIODevice* getCurrentConnection() { return m_ioDev; } - DevListItem getCurrentDevice() { return m_connectionDevice;} + DevListItem getCurrentDevice() { return m_connectionDevice; } + DevListItem findDevice(const QString &devName); + + QLinkedList getAvailableDevices() { return m_devList; } + + bool isConnected() { return m_ioDev != 0; } + + bool connectDevice(DevListItem device); bool disconnectDevice(); void suspendPolling(); void resumePolling(); @@ -101,11 +108,12 @@ protected: void updateConnectionList(IConnection *connection); void registerDevice(IConnection *conn, IConnection::device device); void updateConnectionDropdown(); - DevListItem findDevice(const QString &devName); signals: - void deviceConnected(QIODevice *dev); + void deviceConnected(QIODevice *device); void deviceAboutToDisconnect(); + void deviceDisconnected(); + void availableDevicesChanged(const QLinkedList devices); public slots: void telemetryConnected(); diff --git a/ground/openpilotgcs/src/plugins/coreplugin/dialogs/importsettings.cpp b/ground/openpilotgcs/src/plugins/coreplugin/dialogs/importsettings.cpp index 517c534a2..c48f5a6a6 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/dialogs/importsettings.cpp +++ b/ground/openpilotgcs/src/plugins/coreplugin/dialogs/importsettings.cpp @@ -3,6 +3,7 @@ #include #include #include +#include importSettings::importSettings(QWidget *parent) : QDialog(parent), @@ -11,6 +12,7 @@ importSettings::importSettings(QWidget *parent) : ui->setupUi(this); connect(ui->cbConfigs,SIGNAL(currentIndexChanged(int)),this,SLOT(updateDetails(int))); connect(ui->btnLoad,SIGNAL(clicked()),this,SLOT(accept())); + QTimer::singleShot(500,this,SLOT(repaint())); } void importSettings::loadFiles(QString path) { diff --git a/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.cpp b/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.cpp index 663f5e545..39a656de2 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.cpp +++ b/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.cpp @@ -39,7 +39,6 @@ #include #include "ui_generalsettings.h" -#include using namespace Utils; using namespace Core::Internal; @@ -113,14 +112,8 @@ void GeneralSettings::fillLanguageBox() const QWidget *GeneralSettings::createPage(QWidget *parent) { m_page = new Ui::GeneralSettings(); - globalSettingsWidget *w = new globalSettingsWidget(parent); - connect(w,SIGNAL(showHidden()),this,SLOT(showHidden())); + QWidget *w = new QWidget(parent); m_page->setupUi(w); - m_page->labelUDP->setVisible(false); - m_page->cbUseUDPMirror->setVisible(false); - m_page->labelExpert->setVisible(false); - m_page->cbExpertMode->setVisible(false); - fillLanguageBox(); connect(m_page->checkAutoConnect,SIGNAL(stateChanged(int)),this,SLOT(slotAutoConnect(int))); m_page->checkBoxSaveOnExit->setChecked(m_saveSettingsOnExit); @@ -263,21 +256,3 @@ void GeneralSettings::slotAutoConnect(int value) else m_page->checkAutoSelect->setEnabled(true); } - -void GeneralSettings::showHidden() -{ - m_page->labelUDP->setVisible(true); - m_page->cbUseUDPMirror->setVisible(true); - m_page->labelExpert->setVisible(true); - m_page->cbExpertMode->setVisible(true); -} - -globalSettingsWidget::globalSettingsWidget(QWidget *parent):QWidget(parent){} - -void globalSettingsWidget::keyPressEvent(QKeyEvent *event) -{ - if(event->key()==Qt::Key_F7) - { - emit showHidden(); - } -} diff --git a/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.h b/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.h index 8b41d9b0f..8bd498fe8 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.h +++ b/ground/openpilotgcs/src/plugins/coreplugin/generalsettings.h @@ -69,7 +69,6 @@ private slots: void resetLanguage(); void showHelpForExternalEditor(); void slotAutoConnect(int); - void showHidden(); private: void fillLanguageBox() const; @@ -86,17 +85,6 @@ private: QList m_codecs; }; -class globalSettingsWidget:public QWidget -{ - Q_OBJECT -public: - globalSettingsWidget(QWidget * parent); -protected: - void keyPressEvent(QKeyEvent *); -signals: - void showHidden(); -}; - } // namespace Internal } // namespace Core diff --git a/ground/openpilotgcs/src/plugins/coreplugin/images/ah.png b/ground/openpilotgcs/src/plugins/coreplugin/images/ah.png index a0be19bed..646f24ad6 100644 Binary files a/ground/openpilotgcs/src/plugins/coreplugin/images/ah.png and b/ground/openpilotgcs/src/plugins/coreplugin/images/ah.png differ diff --git a/ground/openpilotgcs/src/plugins/coreplugin/images/cog.png b/ground/openpilotgcs/src/plugins/coreplugin/images/cog.png index 67de2c6cc..97b835c58 100644 Binary files a/ground/openpilotgcs/src/plugins/coreplugin/images/cog.png and b/ground/openpilotgcs/src/plugins/coreplugin/images/cog.png differ diff --git a/ground/openpilotgcs/src/plugins/coreplugin/images/config.png b/ground/openpilotgcs/src/plugins/coreplugin/images/config.png index 5c8213fef..650a00365 100644 Binary files a/ground/openpilotgcs/src/plugins/coreplugin/images/config.png and b/ground/openpilotgcs/src/plugins/coreplugin/images/config.png differ diff --git a/ground/openpilotgcs/src/plugins/coreplugin/images/joystick.png b/ground/openpilotgcs/src/plugins/coreplugin/images/joystick.png index 62168f56f..960ba9465 100644 Binary files a/ground/openpilotgcs/src/plugins/coreplugin/images/joystick.png and b/ground/openpilotgcs/src/plugins/coreplugin/images/joystick.png differ diff --git a/ground/openpilotgcs/src/plugins/coreplugin/images/scopes.png b/ground/openpilotgcs/src/plugins/coreplugin/images/scopes.png index 01e933a61..99434575f 100644 Binary files a/ground/openpilotgcs/src/plugins/coreplugin/images/scopes.png and b/ground/openpilotgcs/src/plugins/coreplugin/images/scopes.png differ diff --git a/ground/openpilotgcs/src/plugins/coreplugin/mainwindow.cpp b/ground/openpilotgcs/src/plugins/coreplugin/mainwindow.cpp index 2df94e9c9..dc74094a5 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/mainwindow.cpp +++ b/ground/openpilotgcs/src/plugins/coreplugin/mainwindow.cpp @@ -102,11 +102,11 @@ MainWindow::MainWindow() : m_additionalContexts(m_globalContext), // keep this in sync with main() in app/main.cpp m_settings(new QSettings(XmlConfig::XmlSettingsFormat, QSettings::UserScope, - QLatin1String("OpenPilot"), QLatin1String("OpenPilotGCS"), this)), + QLatin1String("OpenPilot"), QLatin1String("OpenPilotGCS_config"), this)), m_globalSettings(new QSettings(XmlConfig::XmlSettingsFormat, QSettings::SystemScope, - QLatin1String("OpenPilot"), QLatin1String("OpenPilotGCS"), this)), + QLatin1String("OpenPilot"), QLatin1String("OpenPilotGCS_config"), this)), m_settingsDatabase(new SettingsDatabase(QFileInfo(m_settings->fileName()).path(), - QLatin1String("OpenPilotGCS"), + QLatin1String("OpenPilotGCS_config"), this)), m_dontSaveSettings(false), m_actionManager(new ActionManagerPrivate(this)), diff --git a/ground/openpilotgcs/src/plugins/coreplugin/modemanager.cpp b/ground/openpilotgcs/src/plugins/coreplugin/modemanager.cpp index aa5356705..85b3c4bde 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/modemanager.cpp +++ b/ground/openpilotgcs/src/plugins/coreplugin/modemanager.cpp @@ -326,3 +326,13 @@ void ModeManager::setFocusToCurrentMode() widget->setFocus(); } } + +void ModeManager::triggerAction(const QString &actionId) +{ + foreach(Command * command, m_actions.keys()){ + if(command->action()->objectName() == actionId) { + command->action()->trigger(); + break; + } + } +} diff --git a/ground/openpilotgcs/src/plugins/coreplugin/modemanager.h b/ground/openpilotgcs/src/plugins/coreplugin/modemanager.h index ccaf50607..d8fba46bd 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/modemanager.h +++ b/ground/openpilotgcs/src/plugins/coreplugin/modemanager.h @@ -82,6 +82,7 @@ public slots: void activateMode(const QString &id); void activateModeByWorkspaceName(const QString &id); void setFocusToCurrentMode(); + void triggerAction(const QString &actionId); private slots: void objectAdded(QObject *obj); diff --git a/ground/openpilotgcs/src/plugins/coreplugin/workspacesettings.ui b/ground/openpilotgcs/src/plugins/coreplugin/workspacesettings.ui index 1c646b693..1c98fa4c2 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/workspacesettings.ui +++ b/ground/openpilotgcs/src/plugins/coreplugin/workspacesettings.ui @@ -6,8 +6,8 @@ 0 0 - 414 - 320 + 468 + 436 @@ -19,216 +19,253 @@ Form - - + + + 12 + + + 0 + + + 12 + + 0 - - - - 0 - 0 - + + + QFrame::NoFrame - - Workspaces + + QFrame::Plain - - - - - Number of workspaces: - - - - - - - Qt::Horizontal - - - - 0 - 20 - - - - - - - - Change details of workspace: - - - - - - - - - - - 0 - 0 - - - - 1 - - - 10 - - - 2 - - - - - - - - - - - 0 - 0 - + + true - - Details - - - - - - Icon: - - - - - - - - - - - - - Name: - - - - - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 20 - 10 - - - - - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> + + + + 0 + 0 + 444 + 436 + + + + + 0 + + + + + + 0 + 0 + + + + Details + + + + + + Icon: + + + + + + + + + + + + + Name: + + + + + + + Qt::Vertical + + + QSizePolicy::Fixed + + + + 20 + 10 + + + + + + + + <!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;"><span style=" font-weight:600;">Note:</span> A restart is needed for changes to number of workspaces to take effect.</p></body></html> - - - - - - - - - - - - - Workspace panel - - - - - - Placement: - - - - - - - - - 1 - - - - Top - + + + + + - - - Bottom - + + + + + + + Workspace panel + + + + + + Placement: + + - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - Allow reordering: - - - - - - - - - - - + + + + + + 1 + + + + Top + + + + + Bottom + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + Allow reordering: + + + + + + + + + + +
+ + + + + + + 0 + 0 + + + + Workspaces + + + + + + Number of workspaces: + + + + + + + Qt::Horizontal + + + + 0 + 20 + + + + + + + + Change details of workspace: + + + + + + + + + + + 0 + 0 + + + + 1 + + + 10 + + + 2 + + + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + - - - - Qt::Vertical - - - - 20 - 40 - - - - diff --git a/ground/openpilotgcs/src/plugins/dial/dialgadgetoptionspage.ui b/ground/openpilotgcs/src/plugins/dial/dialgadgetoptionspage.ui index 24711047a..14d4b54f2 100644 --- a/ground/openpilotgcs/src/plugins/dial/dialgadgetoptionspage.ui +++ b/ground/openpilotgcs/src/plugins/dial/dialgadgetoptionspage.ui @@ -6,8 +6,8 @@ 0 0 - 545 - 395 + 561 + 392 @@ -20,725 +20,756 @@ Form + + 0 + - - - - - Use OpenGL for rendering. Will lower CPU usage, depending on the capabilities of your graphics card, but might slightly alter the look & feel of the dial. - - - Use OpenGL - - - - - - - When checked, the Dial plugin will make needle moves smoother by simulating inertia. - - - Smooth updates - - - - - - - - - Qt::Horizontal + + + QFrame::NoFrame - - - - - - 10 + + QFrame::Plain - - QLayout::SetMaximumSize + + true - - 10 - - - - - - 0 - 0 - + + + + 0 + 0 + 561 + 392 + + + + + 0 - - Dial SVG: - - - - - - - - 0 - 0 - - - - - - - - - 0 - 0 - - - - Dial font: - - - - - - - Select... - - - - - - - - - Qt::Horizontal - - - - - - - - - BackgroundID - - - - - - - XML ID of the SVG source file used to display the dial background. - - - - - - - ForegroundID - - - - - - - XML ID of the SVG source file used to display the dial foreground (above everything else, needles included). - - - - - - - - - - 0 - 0 - - - - 0 - - - - Indicator 1 - - - + - - - Qt::Horizontal - - - - 40 - 20 - - - - - - + - Movement: + BackgroundID - - - - - - ID: - - - - - - - - 0 - 0 - - - - - 50 - 0 - - - - - 16777215 - 16777215 - - + - XML ID of the SVG source file used to display the first needle/indicator. + XML ID of the SVG source file used to display the dial background. + + + + + + + ForegroundID + + + + + + + XML ID of the SVG source file used to display the dial foreground (above everything else, needles included). - - - 10 - + - + + + Use OpenGL for rendering. Will lower CPU usage, depending on the capabilities of your graphics card, but might slightly alter the look & feel of the dial. + - Min: + Use OpenGL - - - - 0 - 0 - + + + When checked, the Dial plugin will make needle moves smoother by simulating inertia. - - 3 - - - -100000.000000000000000 - - - 100000.000000000000000 - - - - - - Max: - - - - - - - - 0 - 0 - - - - 3 - - - -100000.000000000000000 - - - 100000.000000000000000 - - - - - - - Factor: - - - - - - - - 0 - 0 - - - - 5 - - - -100000.000000000000000 - - - 100000.000000000000000 + Smooth updates - - - 10 - - - - - DataObject - - - - - - - - 0 - 0 - - - - - - - - ObjectField - - - - - - - - 0 - 0 - - - - - - - - + Qt::Horizontal - - - - - Indicator 2 - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Movement: - - - - - - - - - - ID: - - - - - - - - 0 - 0 - - - - - - - - - - 10 - - - - - Min: - - - - - - - - 0 - 0 - - - - 3 - - - -10000.000000000000000 - - - 100000.000000000000000 - - - - - - - Max: - - - - - - - - 0 - 0 - - - - 3 - - - -100000.000000000000000 - - - 100000.000000000000000 - - - - - - - Factor: - - - - - - - - 0 - 0 - - - - 5 - - - -100000.000000000000000 - - - 100000.000000000000000 - - - - - - - - - 10 - - - - - DataObject - - - - - - - - 0 - 0 - - - - - - - - ObjectField - - - - - - - - 0 - 0 - - - - - - - - + Qt::Horizontal - - - - - Indicator 3 - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Movement: - - - - - - - - - - ID: - - - - - - - - 0 - 0 - - - - - - - - - - 10 + + + + 0 + 0 + - - - - Min: - - - - - - - - 0 - 0 - - - - 3 - - - -10000.000000000000000 - - - 100000.000000000000000 - - - - - - - Max: - - - - - - - - 0 - 0 - - - - 3 - - - -100000.000000000000000 - - - 100000.000000000000000 - - - - - - - Factor: - - - - - - - - 0 - 0 - - - - 5 - - - -100000.000000000000000 - - - 100000.000000000000000 - - - - - - - - - 10 - - - - - DataObject - - - - - - - - 0 - 0 - - - - - - - - ObjectField - - - - - - - - 0 - 0 - - - - - - - - - - Qt::Horizontal + + 0 + + + Indicator 1 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Movement: + + + + + + + + + + ID: + + + + + + + + 0 + 0 + + + + + 50 + 0 + + + + + 16777215 + 16777215 + + + + XML ID of the SVG source file used to display the first needle/indicator. + + + + + + + + + 10 + + + + + Min: + + + + + + + + 0 + 0 + + + + 3 + + + -100000.000000000000000 + + + 100000.000000000000000 + + + + + + + Max: + + + + + + + + 0 + 0 + + + + 3 + + + -100000.000000000000000 + + + 100000.000000000000000 + + + + + + + Factor: + + + + + + + + 0 + 0 + + + + 5 + + + -100000.000000000000000 + + + 100000.000000000000000 + + + + + + + + + 10 + + + + + DataObject + + + + + + + + 0 + 0 + + + + + + + + ObjectField + + + + + + + + 0 + 0 + + + + + + + + + + Qt::Horizontal + + + + + + + + Indicator 2 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Movement: + + + + + + + + + + ID: + + + + + + + + 0 + 0 + + + + + + + + + + 10 + + + + + Min: + + + + + + + + 0 + 0 + + + + 3 + + + -10000.000000000000000 + + + 100000.000000000000000 + + + + + + + Max: + + + + + + + + 0 + 0 + + + + 3 + + + -100000.000000000000000 + + + 100000.000000000000000 + + + + + + + Factor: + + + + + + + + 0 + 0 + + + + 5 + + + -100000.000000000000000 + + + 100000.000000000000000 + + + + + + + + + 10 + + + + + DataObject + + + + + + + + 0 + 0 + + + + + + + + ObjectField + + + + + + + + 0 + 0 + + + + + + + + + + Qt::Horizontal + + + + + + + + Indicator 3 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Movement: + + + + + + + + + + ID: + + + + + + + + 0 + 0 + + + + + + + + + + 10 + + + + + Min: + + + + + + + + 0 + 0 + + + + 3 + + + -10000.000000000000000 + + + 100000.000000000000000 + + + + + + + Max: + + + + + + + + 0 + 0 + + + + 3 + + + -100000.000000000000000 + + + 100000.000000000000000 + + + + + + + Factor: + + + + + + + + 0 + 0 + + + + 5 + + + -100000.000000000000000 + + + 100000.000000000000000 + + + + + + + + + 10 + + + + + DataObject + + + + + + + + 0 + 0 + + + + + + + + ObjectField + + + + + + + + 0 + 0 + + + + + + + + + + Qt::Horizontal + + + + + + + + + 10 + + + QLayout::SetMaximumSize + + + 10 + + + + + + 0 + 0 + + + + Dial SVG: + + + + + + + + 0 + 0 + + + + + + + + + 0 + 0 + + + + Dial font: + + + + + + + Select... + + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + - - - - Qt::Vertical - - - - 20 - 40 - - - - diff --git a/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrolgadget.cpp b/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrolgadget.cpp index 485cd7b31..54447b84b 100644 --- a/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrolgadget.cpp +++ b/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrolgadget.cpp @@ -293,7 +293,6 @@ double GCSControlGadget::constrain(double value) void GCSControlGadget::buttonState(ButtonNumber number, bool pressed) { -// int state; if ((buttonSettings[number].ActionID>0)&&(buttonSettings[number].FunctionID>0)&&(pressed)) {//this button is configured ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); diff --git a/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrolgadgetoptionspage.ui b/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrolgadgetoptionspage.ui index 5191788a0..9b4ec36c1 100644 --- a/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrolgadgetoptionspage.ui +++ b/ground/openpilotgcs/src/plugins/gcscontrol/gcscontrolgadgetoptionspage.ui @@ -6,8 +6,8 @@ 0 0 - 587 - 379 + 810 + 464 @@ -19,1061 +19,1089 @@ Form - + 0 - - - - - - - - Control Mode: - - - - - + + + QFrame::NoFrame + + + QFrame::Plain + + + true + + + + + 0 + 0 + 810 + 464 + + + + + 0 + + + + - - Mode 1 - - - - - Mode 2 - - - - - Mode 3 - - - - - Mode 4 - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - External input Device: - - - - - - - false - - - Only joystick is implemented at this stage, so this control is disabled. - - - - Joystick - - - - - Audio - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Available controllers - - - - - - - true - - - - Default - - - - - - - - - - Qt::Horizontal - - - - - - - 0 - - - - Joystick Axes - - - - 0 - - - - - - - - + + + - Rev + Control Mode: - - + + + + + Mode 1 + + + + + Mode 2 + + + + + Mode 3 + + + + + Mode 4 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + - Rev + External input Device: - - - - - - - - - - - - - - - - - - - - - - - - - 24 + + + + false + + Only joystick is implemented at this stage, so this control is disabled. + + + + Joystick + + + + + Audio + + - - - - 24 + + + + Qt::Horizontal - - - - - - 24 + + + 40 + 20 + - + - - - - 24 - - - - - - - 24 - - - - - - - 24 - - - - - - - 24 - - - - - - - 24 - - - - - + + - Rev + Available controllers - - - - Rev - - - - - - - Rev - - - - - - - Rev - - - - - - - Rev - - - - - - - Rev - - - - - - - Move your joystick controls to identify channels + + + + true + + + Default + + - - - - - Joystick Buttons - - - - 2 - - - 3 - - - - - 0 - 0 - - - - Press buttons on controller to identify mappings - - - Qt::AlignCenter - - - - - - - 6 - - - 4 - - - - - - 0 - 0 - - - - 2 - - - 0.000000000000000 - - - 1.000000000000000 - - - 0.100000000000000 - - - 0.100000000000000 - - - - - - - - 0 - 0 - - - - 2 - - - 0.000000000000000 - - - 1.000000000000000 - - - 0.100000000000000 - - - 0.100000000000000 - - - - - - - - 0 - 0 - - - - 2 - - - 0.000000000000000 - - - 1.000000000000000 - - - 0.100000000000000 - - - 0.100000000000000 - - - - - - - - 0 - 0 - - - - 2 - - - 0.000000000000000 - - - 1.000000000000000 - - - 0.100000000000000 - - - 0.100000000000000 - - - - - - - - 0 - 0 - - - - 2 - - - 0.000000000000000 - - - 1.000000000000000 - - - 0.100000000000000 - - - 0.100000000000000 - - - - - - - - 0 - 0 - - - - 2 - - - 0.000000000000000 - - - 1.000000000000000 - - - 0.100000000000000 - - - 0.100000000000000 - - - - - - - - 0 - 0 - - - - 2 - - - 0.000000000000000 - - - 1.000000000000000 - - - 0.100000000000000 - - - 0.100000000000000 - - - - - - - - 0 - 0 - - - - 2 - - - 0.000000000000000 - - - 1.000000000000000 - - - 0.100000000000000 - - - 0.100000000000000 - - - - - - - - 0 - 0 - - - - button 1 - - - true - - - - - - - - 0 - 0 - - - - button 2 - - - true - - - - - - - - 0 - 0 - - - - button 8 - - - true - - - - - - - - 0 - 0 - - - - button 7 - - - true - - - - - - - - 0 - 0 - - - - button 6 - - - true - - - - - - - - 0 - 0 - - - - button 5 - - - true - - - - - - - - 0 - 0 - - - - button 4 - - - true - - - - - - - - 0 - 0 - - - - button 3 - - - true - - - - - - - - 0 - 0 - - - - - - - - - 0 - 0 - - - - - - - - - 0 - 0 - - - - - - - - - 0 - 0 - - - - - - - - - 0 - 0 - - - - - - - - - 0 - 0 - - - - - - - - - 0 - 0 - - - - - - - - - 0 - 0 - - - - - - - - - 0 - 0 - - - - - - - - - 0 - 0 - - - - - - - - - 0 - 0 - - - - - - - - - 0 - 0 - - - - - - - - - 0 - 0 - - - - - - - - - 0 - 0 - - - - - - - - - 0 - 0 - - - - - - - - - 15 - 0 - - - - - 15 - 16777215 - - - - by - - - - - - - - 0 - 0 - - - - - - - - - 15 - 0 - - - - - 15 - 16777215 - - - - by - - - - - - - - 15 - 0 - - - - - 15 - 16777215 - - - - by - - - - - - - - 15 - 0 - - - - - 15 - 16777215 - - - - by - - - - - - - - 15 - 0 - - - - - 15 - 16777215 - - - - by - - - - - - - - 15 - 0 - - - - - 15 - 16777215 - - - - by - - - - - - - - 15 - 0 - - - - - 15 - 16777215 - - - - by - - - - - - - - 15 - 0 - - - - - 15 - 16777215 - - - - by - - - - - - - - - - Audio - - - - 0 - - - - - Audio: soundcard-based PPM decoding for trainer port. Not implemented yet. - - - - - + - Qt::Vertical + Qt::Horizontal - - - 20 - 276 - + + + + + + 0 - + + + Joystick Axes + + + + 0 + + + + + + + + + + Rev + + + + + + + Rev + + + + + + + + + + + + + + + + + + + + + + + + + + + + 24 + + + + + + + 24 + + + + + + + 24 + + + + + + + 24 + + + + + + + 24 + + + + + + + 24 + + + + + + + 24 + + + + + + + 24 + + + + + + + Rev + + + + + + + Rev + + + + + + + Rev + + + + + + + Rev + + + + + + + Rev + + + + + + + Rev + + + + + + + Move your joystick controls to identify channels + + + + + + + + + + Joystick Buttons + + + + 2 + + + 3 + + + + + + 0 + 0 + + + + Press buttons on controller to identify mappings + + + Qt::AlignCenter + + + + + + + 6 + + + 4 + + + + + + 0 + 0 + + + + 2 + + + 0.000000000000000 + + + 1.000000000000000 + + + 0.100000000000000 + + + 0.100000000000000 + + + + + + + + 0 + 0 + + + + 2 + + + 0.000000000000000 + + + 1.000000000000000 + + + 0.100000000000000 + + + 0.100000000000000 + + + + + + + + 0 + 0 + + + + 2 + + + 0.000000000000000 + + + 1.000000000000000 + + + 0.100000000000000 + + + 0.100000000000000 + + + + + + + + 0 + 0 + + + + 2 + + + 0.000000000000000 + + + 1.000000000000000 + + + 0.100000000000000 + + + 0.100000000000000 + + + + + + + + 0 + 0 + + + + 2 + + + 0.000000000000000 + + + 1.000000000000000 + + + 0.100000000000000 + + + 0.100000000000000 + + + + + + + + 0 + 0 + + + + 2 + + + 0.000000000000000 + + + 1.000000000000000 + + + 0.100000000000000 + + + 0.100000000000000 + + + + + + + + 0 + 0 + + + + 2 + + + 0.000000000000000 + + + 1.000000000000000 + + + 0.100000000000000 + + + 0.100000000000000 + + + + + + + + 0 + 0 + + + + 2 + + + 0.000000000000000 + + + 1.000000000000000 + + + 0.100000000000000 + + + 0.100000000000000 + + + + + + + + 0 + 0 + + + + button 1 + + + true + + + + + + + + 0 + 0 + + + + button 2 + + + true + + + + + + + + 0 + 0 + + + + button 8 + + + true + + + + + + + + 0 + 0 + + + + button 7 + + + true + + + + + + + + 0 + 0 + + + + button 6 + + + true + + + + + + + + 0 + 0 + + + + button 5 + + + true + + + + + + + + 0 + 0 + + + + button 4 + + + true + + + + + + + + 0 + 0 + + + + button 3 + + + true + + + + + + + + 0 + 0 + + + + + + + + + 0 + 0 + + + + + + + + + 0 + 0 + + + + + + + + + 0 + 0 + + + + + + + + + 0 + 0 + + + + + + + + + 0 + 0 + + + + + + + + + 0 + 0 + + + + + + + + + 0 + 0 + + + + + + + + + 0 + 0 + + + + + + + + + 0 + 0 + + + + + + + + + 0 + 0 + + + + + + + + + 0 + 0 + + + + + + + + + 0 + 0 + + + + + + + + + 0 + 0 + + + + + + + + + 0 + 0 + + + + + + + + + 15 + 0 + + + + + 15 + 16777215 + + + + by + + + + + + + + 0 + 0 + + + + + + + + + 15 + 0 + + + + + 15 + 16777215 + + + + by + + + + + + + + 15 + 0 + + + + + 15 + 16777215 + + + + by + + + + + + + + 15 + 0 + + + + + 15 + 16777215 + + + + by + + + + + + + + 15 + 0 + + + + + 15 + 16777215 + + + + by + + + + + + + + 15 + 0 + + + + + 15 + 16777215 + + + + by + + + + + + + + 15 + 0 + + + + + 15 + 16777215 + + + + by + + + + + + + + 15 + 0 + + + + + 15 + 16777215 + + + + by + + + + + + + + + + Audio + + + + 0 + + + + + Audio: soundcard-based PPM decoding for trainer port. Not implemented yet. + + + + + + + Qt::Vertical + + + + 20 + 276 + + + + + + + + + UDP Setup + + + + + 20 + 20 + 301 + 71 + + + + UDP Port Configuration + + + + + + Host: + + + + + + + + 120 + 16777215 + + + + 127.0.0.1 + + + + + + + Port: + + + + + + + + 50 + 16777215 + + + + 2323 + + + + + + + - - - UDP Setup - - - - - 20 - 20 - 301 - 71 - - - - UDP Port Configuration - - - - - - Host: - - - - - - - - 120 - 16777215 - - - - 127.0.0.1 - - - - - - - Port: - - - - - - - - 50 - 16777215 - - - - 2323 - - - - - - - - - + + + diff --git a/ground/openpilotgcs/src/plugins/gpsdisplay/gpsdisplaygadgetoptionspage.ui b/ground/openpilotgcs/src/plugins/gpsdisplay/gpsdisplaygadgetoptionspage.ui index 26ba4270c..be60f1651 100644 --- a/ground/openpilotgcs/src/plugins/gpsdisplay/gpsdisplaygadgetoptionspage.ui +++ b/ground/openpilotgcs/src/plugins/gpsdisplay/gpsdisplaygadgetoptionspage.ui @@ -6,8 +6,8 @@ 0 0 - 587 - 359 + 477 + 416 @@ -19,212 +19,240 @@ Form - + 0 - - - - - - - - - Mode: - - - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - Qt::Horizontal - - - - - - - 0 - - - - - 0 - + + + + QFrame::NoFrame + + + QFrame::Plain + + + true + + + + + 0 + 0 + 477 + 416 + + + + + 0 + + + + - - - Serial Connection - - - - - - - - - - - - - + + + - Data Bits: + Mode: - - - - Stop Bits: + + + + + + + Qt::Horizontal - - - - - - Parity: + + + 40 + 20 + - - - - - - Timeout(ms): - - - - - - - - - - - - - - - - Port: - - - - - - - Port Speed: - - - - - - - - - - Flow Control: - - - - - - - 100000 - - + - - - - - - 0 - - - - IP Connection - - - - - - - - - Host - - - - - - - - - - Port - - - - - - - - - - - - - - 0 - - - - - Telemetry - - - - - + - Qt::Vertical + Qt::Horizontal - - - 20 - 276 - + + + + + + 0 - + + + + 0 + + + + + Serial Connection + + + + + + + + + + + + + + + Data Bits: + + + + + + + Stop Bits: + + + + + + + Parity: + + + + + + + Timeout(ms): + + + + + + + + + + + + + + + + Port: + + + + + + + Port Speed: + + + + + + + + + + Flow Control: + + + + + + + 100000 + + + + + + + + + + + 0 + + + + + IP Connection + + + + + + + + + Host + + + + + + + + + + Port + + + + + + + + + + + + + + 0 + + + + + Telemetry + + + + + + + Qt::Vertical + + + + 20 + 276 + + + + + + + - - - + + + diff --git a/ground/openpilotgcs/src/plugins/gpsdisplay/nmeaparser.cpp b/ground/openpilotgcs/src/plugins/gpsdisplay/nmeaparser.cpp index cca79a565..87ecef211 100644 --- a/ground/openpilotgcs/src/plugins/gpsdisplay/nmeaparser.cpp +++ b/ground/openpilotgcs/src/plugins/gpsdisplay/nmeaparser.cpp @@ -301,7 +301,6 @@ void NMEAParser::nmeaProcessGPGSV(char *packet) const int sentence_total = tokenslist.at(1).toInt(); // Number of sentences for full data const int sentence_index = tokenslist.at(2).toInt(); // sentence x of y -// const int sat_count = tokenslist.at(3).toInt(); // Number of satellites in view int sats = (tokenslist.size() - 4) /4; for(int sat = 0; sat < sats; sat++) { diff --git a/ground/openpilotgcs/src/plugins/hitlnew/Start Flightgear XP.bat b/ground/openpilotgcs/src/plugins/hitl/Start Flightgear XP.bat similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlnew/Start Flightgear XP.bat rename to ground/openpilotgcs/src/plugins/hitl/Start Flightgear XP.bat diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/aerosimrc.pro b/ground/openpilotgcs/src/plugins/hitl/aerosimrc/aerosimrc.pro similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/aerosimrc.pro rename to ground/openpilotgcs/src/plugins/hitl/aerosimrc/aerosimrc.pro diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/aerosimrcdatastruct.h b/ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/aerosimrcdatastruct.h similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/aerosimrcdatastruct.h rename to ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/aerosimrcdatastruct.h diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/enums.h b/ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/enums.h similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/enums.h rename to ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/enums.h diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.cpp b/ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/plugin.cpp similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.cpp rename to ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/plugin.cpp diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.h b/ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/plugin.h similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.h rename to ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/plugin.h diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.pro b/ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/plugin.pro similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/plugin.pro rename to ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/plugin.pro diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/qdebughandler.cpp b/ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/qdebughandler.cpp similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/qdebughandler.cpp rename to ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/qdebughandler.cpp diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/qdebughandler.h b/ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/qdebughandler.h similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/qdebughandler.h rename to ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/qdebughandler.h diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/resources/cc_off.tga b/ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/resources/cc_off.tga similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/resources/cc_off.tga rename to ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/resources/cc_off.tga diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/resources/cc_off_hover.tga b/ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/resources/cc_off_hover.tga similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/resources/cc_off_hover.tga rename to ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/resources/cc_off_hover.tga diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/resources/cc_on.tga b/ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/resources/cc_on.tga similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/resources/cc_on.tga rename to ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/resources/cc_on.tga diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/resources/cc_on_hover.tga b/ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/resources/cc_on_hover.tga similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/resources/cc_on_hover.tga rename to ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/resources/cc_on_hover.tga diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/resources/cc_plugin.ini b/ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/resources/cc_plugin.ini similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/resources/cc_plugin.ini rename to ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/resources/cc_plugin.ini diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/resources/plugin.txt b/ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/resources/plugin.txt similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/resources/plugin.txt rename to ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/resources/plugin.txt diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/settings.cpp b/ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/settings.cpp similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/settings.cpp rename to ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/settings.cpp diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/settings.h b/ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/settings.h similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/settings.h rename to ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/settings.h diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udpconnect.cpp b/ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/udpconnect.cpp similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udpconnect.cpp rename to ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/udpconnect.cpp diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udpconnect.h b/ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/udpconnect.h similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udpconnect.h rename to ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/udpconnect.h diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptest.pro b/ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/udptest.pro similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptest.pro rename to ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/udptest.pro diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestmain.cpp b/ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/udptestmain.cpp similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestmain.cpp rename to ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/udptestmain.cpp diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestwidget.cpp b/ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/udptestwidget.cpp similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestwidget.cpp rename to ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/udptestwidget.cpp diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestwidget.h b/ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/udptestwidget.h similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestwidget.h rename to ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/udptestwidget.h diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestwidget.ui b/ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/udptestwidget.ui similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlv2/aerosimrc/src/udptestwidget.ui rename to ground/openpilotgcs/src/plugins/hitl/aerosimrc/src/udptestwidget.ui diff --git a/ground/openpilotgcs/src/plugins/hitl/aerosimrcsimulator.cpp b/ground/openpilotgcs/src/plugins/hitl/aerosimrcsimulator.cpp new file mode 100644 index 000000000..e1cbb6b78 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitl/aerosimrcsimulator.cpp @@ -0,0 +1,273 @@ +/** + ****************************************************************************** + * + * @file aerosimrc.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup HITLPlugin HITLv2 Plugin + * @{ + * @brief The Hardware In The Loop plugin version 2 + *****************************************************************************/ +/* + * 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 "aerosimrcsimulator.h" +#include +#include +#include + +AeroSimRCSimulator::AeroSimRCSimulator(const SimulatorSettings ¶ms) + : Simulator(params) +{ + udpCounterASrecv = 0; +} + +AeroSimRCSimulator::~AeroSimRCSimulator() +{ +} + +bool AeroSimRCSimulator::setupProcess() +{ + QMutexLocker locker(&lock); + return true; +} + +void AeroSimRCSimulator::setupUdpPorts(const QString &host, int inPort, int outPort) +{ + Q_UNUSED(outPort) + if (inSocket->bind(QHostAddress(host), inPort)) + emit processOutput("Successfully bound to address " + host + ", port " + QString::number(inPort) + "\n"); + else + emit processOutput("Cannot bind to address " + host + ", port " + QString::number(inPort) + "\n"); +} + +void AeroSimRCSimulator::transmitUpdate() +{ + // read actuator output + ActuatorCommand::DataFields actCmdData; + actCmdData = actCommand->getData(); + float channels[10]; + for (int i = 0; i < 10; ++i) { + qint16 ch = actCmdData.Channel[i]; + float out = -1.0; + if (ch >= 1000 && ch <= 2000) { + ch -= 1000; + out = ((float)ch / 500.0) - 1.0; + } + channels[i] = out; + } + + // read flight status + FlightStatus::DataFields flightData; + flightData = flightStatus->getData(); + quint8 armed; + quint8 mode; + armed = flightData.Armed; + mode = flightData.FlightMode; + + QByteArray data; + // 50 - current size of values, 4(quint32) + 10*4(float) + 2(quint8) + 4(quint32) + data.resize(50); + QDataStream stream(&data, QIODevice::WriteOnly); + stream.setFloatingPointPrecision(QDataStream::SinglePrecision); + stream << quint32(0x52434D44); // magic header, "RCMD" + for (int i = 0; i < 10; ++i) + stream << channels[i]; // channels + stream << armed << mode; // flight status + stream << udpCounterASrecv; // packet counter + + if (outSocket->writeDatagram(data, QHostAddress(settings.remoteAddress), settings.outPort) == -1) { + qDebug() << "write failed: " << outSocket->errorString(); + } + +#ifdef DBG_TIMERS + static int cntTX = 0; + if (cntTX >= 100) { + qDebug() << "TX=" << 1000.0 * 100 / timeTX.restart(); + cntTX = 0; + } else { + ++cntTX; + } +#endif +} + +void AeroSimRCSimulator::processUpdate(const QByteArray &data) +{ + // check size + if (data.size() > 188) { + qDebug() << "!!! big datagram: " << data.size(); + return; + } + + QByteArray buf = data; + QDataStream stream(&buf, QIODevice::ReadOnly); + stream.setFloatingPointPrecision(QDataStream::SinglePrecision); + + // check magic header + quint32 magic; + stream >> magic; + if (magic != 0x4153494D) { // "AERO" + qDebug() << "wrong magic: " << magic << ", correct: " << quint32(0x4153494D); + return; + } + +#define AEROSIM_RCCHANNEL_NUMELEM 8 + float delT, + homeX, homeY, homeZ, + WpHX, WpHY, WpLat, WpLon, + posX, posY, posZ, // world + velX, velY, velZ, // world + angX, angY, angZ, // model + accX, accY, accZ, // model + lat, lon, agl, // world + yaw, pitch, roll, // model + volt, curr, + rx, ry, rz, fx, fy, fz, ux, uy, uz, // matrix + ch[AEROSIM_RCCHANNEL_NUMELEM]; + + stream >> delT; + stream >> homeX >> homeY >> homeZ; + stream >> WpHX >> WpHY >> WpLat >> WpLon; + stream >> posX >> posY >> posZ; + stream >> velX >> velY >> velZ; + stream >> angX >> angY >> angZ; + stream >> accX >> accY >> accZ; + stream >> lat >> lon >> agl; + stream >> yaw >> pitch >> roll; + stream >> volt >> curr; + stream >> rx >> ry >> rz >> fx >> fy >> fz >> ux >> uy >> uz; + stream >> ch[0] >> ch[1] >> ch[2] >> ch[3] >> ch[4] >> ch[5] >> ch[6] >> ch[7]; + stream >> udpCounterASrecv; + + Output2Hardware out; + memset(&out, 0, sizeof(Output2Hardware)); + + + out.delT=delT; + + /*************************************************************************************/ + for (int i=0; i< AEROSIM_RCCHANNEL_NUMELEM; i++){ + out.rc_channel[i]=ch[i]; //Elements in rc_channel are between -1 and 1 + } + + /**********************************************************************************************/ + QMatrix4x4 mat; + mat = QMatrix4x4( fy, fx, -fz, 0.0, // model matrix + ry, rx, -rz, 0.0, // (X,Y,Z) -> (+Y,+X,-Z) + -uy, -ux, uz, 0.0, + 0.0, 0.0, 0.0, 1.0); + mat.optimize(); + + QQuaternion quat; // model quat + asMatrix2Quat(mat, quat); + + /*************************************************************************************/ + // rotate gravity + QVector3D acc = QVector3D(accY, accX, -accZ); // accel (X,Y,Z) -> (+Y,+X,-Z) + QVector3D gee = QVector3D(0.0, 0.0, -GEE); + QQuaternion qWorld = quat.conjugate(); + gee = qWorld.rotatedVector(gee); + acc += gee; + + out.rollRate = angY * RAD2DEG; // gyros (X,Y,Z) -> (+Y,+X,-Z) + out.pitchRate = angX * RAD2DEG; + out.yawRate = angZ * -RAD2DEG; + + out.accX = acc.x(); + out.accY = acc.y(); + out.accZ = acc.z(); + + /*************************************************************************************/ + QVector3D rpy; // model roll, pitch, yaw + asMatrix2RPY(mat, rpy); + + out.roll = rpy.x(); + out.pitch = rpy.y(); + out.heading = rpy.z(); + + + /**********************************************************************************************/ + out.altitude = posZ; + out.heading = yaw * RAD2DEG; + out.latitude = lat * 10e6; + out.longitude = lon * 10e6; + out.groundspeed = qSqrt(velX * velX + velY * velY); + + /**********************************************************************************************/ + out.dstN = posY * 100; + out.dstE = posX * 100; + out.dstD = posZ * -100; + + out.velDown = velY * 100; + out.velEast = velX * 100; + out.velDown = velZ * 100; //WHY ISN'T THIS `-velZ`??? + + updateUAVOs(out); + + +#ifdef DBG_TIMERS + static int cntRX = 0; + if (cntRX >= 100) { + qDebug() << "RX=" << 1000.0 * 100 / timeRX.restart(); + cntRX = 0; + } else { + ++cntRX; + } +#endif +} + +// transfomations + +void AeroSimRCSimulator::asMatrix2Quat(const QMatrix4x4 &m, QQuaternion &q) +{ + qreal w, x, y, z; + + // w always >= 0 + w = qSqrt(qMax(0.0, 1.0 + m(0, 0) + m(1, 1) + m(2, 2))) / 2.0; + x = qSqrt(qMax(0.0, 1.0 + m(0, 0) - m(1, 1) - m(2, 2))) / 2.0; + y = qSqrt(qMax(0.0, 1.0 - m(0, 0) + m(1, 1) - m(2, 2))) / 2.0; + z = qSqrt(qMax(0.0, 1.0 - m(0, 0) - m(1, 1) + m(2, 2))) / 2.0; + + x = copysign(x, (m(1, 2) - m(2, 1))); + y = copysign(y, (m(2, 0) - m(0, 2))); + z = copysign(z, (m(0, 1) - m(1, 0))); + + q.setScalar(w); + q.setX(x); + q.setY(y); + q.setZ(z); +} + +void AeroSimRCSimulator::asMatrix2RPY(const QMatrix4x4 &m, QVector3D &rpy) +{ + qreal roll, pitch, yaw; + + if (qFabs(m(0, 2)) > 0.998) { + // ~86.3°, gimbal lock + roll = 0.0; + pitch = copysign(M_PI_2, -m(0, 2)); + yaw = qAtan2(-m(1, 0), m(1, 1)); + } else { + roll = qAtan2(m(1, 2), m(2, 2)); + pitch = qAsin(-m(0, 2)); + yaw = qAtan2(m(0, 1), m(0, 0)); + } + + rpy.setX(roll * RAD2DEG); + rpy.setY(pitch * RAD2DEG); + rpy.setZ(yaw * RAD2DEG); +} diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc.h b/ground/openpilotgcs/src/plugins/hitl/aerosimrcsimulator.h similarity index 98% rename from ground/openpilotgcs/src/plugins/hitlv2/aerosimrc.h rename to ground/openpilotgcs/src/plugins/hitl/aerosimrcsimulator.h index 42b7d4aa5..b265b9463 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc.h +++ b/ground/openpilotgcs/src/plugins/hitl/aerosimrcsimulator.h @@ -32,7 +32,7 @@ #include #include #include -#include "simulatorv2.h" +#include "simulator.h" class AeroSimRCSimulator: public Simulator { diff --git a/ground/openpilotgcs/src/plugins/hitlnew/fgsimulator.cpp b/ground/openpilotgcs/src/plugins/hitl/fgsimulator.cpp similarity index 94% rename from ground/openpilotgcs/src/plugins/hitlnew/fgsimulator.cpp rename to ground/openpilotgcs/src/plugins/hitl/fgsimulator.cpp index b9ca22b8d..99cbeb82e 100644 --- a/ground/openpilotgcs/src/plugins/hitlnew/fgsimulator.cpp +++ b/ground/openpilotgcs/src/plugins/hitl/fgsimulator.cpp @@ -60,6 +60,8 @@ FGSimulator::~FGSimulator() void FGSimulator::setupUdpPorts(const QString& host, int inPort, int outPort) { + Q_UNUSED(outPort); + if(inSocket->bind(QHostAddress(host), inPort)) emit processOutput("Successfully bound to address " + host + " on port " + QString::number(inPort) + "\n"); else @@ -115,9 +117,9 @@ bool FGSimulator::setupProcess() "--vc=100 " + "--log-level=alert " + "--generic=socket,out,20," + settings.hostAddress + "," + QString::number(settings.inPort) + ",udp,opfgprotocol"); - if(!settings.manual) + if(settings.manualControlEnabled) // <--[BCH] What does this do? Why does it depend on ManualControl? { - args.append(" --generic=socket,in,400," + settings.remoteHostAddress + "," + QString::number(settings.outPort) + ",udp,opfgprotocol"); + args.append(" --generic=socket,in,400," + settings.remoteAddress + "," + QString::number(settings.outPort) + ",udp,opfgprotocol"); } // Start FlightGear - only if checkbox is selected in HITL options page @@ -204,7 +206,7 @@ void FGSimulator::transmitUpdate() QByteArray data = cmd.toAscii(); - if(outSocket->writeDatagram(data, QHostAddress(settings.remoteHostAddress), settings.outPort) == -1) + if(outSocket->writeDatagram(data, QHostAddress(settings.remoteAddress), settings.outPort) == -1) { emit processOutput("Error sending UDP packet to FG: " + outSocket->errorString() + "\n"); } @@ -216,7 +218,7 @@ void FGSimulator::transmitUpdate() // V2.0 does not currently work with --generic-protocol } - if(!settings.manual) + if(settings.manualControlEnabled) { actData.Roll = ailerons; actData.Pitch = -elevator; @@ -291,8 +293,8 @@ void FGSimulator::processUpdate(const QByteArray& inp) /////// // Output formatting /////// - Output2OP out; - memset(&out, 0, sizeof(Output2OP)); + Output2Hardware out; + memset(&out, 0, sizeof(Output2Hardware)); float NED[3]; // convert from cm back to meters diff --git a/ground/openpilotgcs/src/plugins/hitlnew/fgsimulator.h b/ground/openpilotgcs/src/plugins/hitl/fgsimulator.h similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlnew/fgsimulator.h rename to ground/openpilotgcs/src/plugins/hitl/fgsimulator.h diff --git a/ground/openpilotgcs/src/plugins/hitlnew/hitlnew.pluginspec b/ground/openpilotgcs/src/plugins/hitl/hitl.pluginspec similarity index 86% rename from ground/openpilotgcs/src/plugins/hitlnew/hitlnew.pluginspec rename to ground/openpilotgcs/src/plugins/hitl/hitl.pluginspec index a52539fdc..573d8094e 100644 --- a/ground/openpilotgcs/src/plugins/hitlnew/hitlnew.pluginspec +++ b/ground/openpilotgcs/src/plugins/hitl/hitl.pluginspec @@ -1,4 +1,4 @@ - + The OpenPilot Project (C) 2010 OpenPilot Project The GNU Public License (GPL) Version 3 diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2.pro b/ground/openpilotgcs/src/plugins/hitl/hitl.pro similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlv2/hitlv2.pro rename to ground/openpilotgcs/src/plugins/hitl/hitl.pro diff --git a/ground/openpilotgcs/src/plugins/hitlnew/hitlnew_dependencies.pri b/ground/openpilotgcs/src/plugins/hitl/hitl_dependencies.pri similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlnew/hitlnew_dependencies.pri rename to ground/openpilotgcs/src/plugins/hitl/hitl_dependencies.pri diff --git a/ground/openpilotgcs/src/plugins/hitl/hitlconfiguration.cpp b/ground/openpilotgcs/src/plugins/hitl/hitlconfiguration.cpp new file mode 100644 index 000000000..3ea4d3bf2 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitl/hitlconfiguration.cpp @@ -0,0 +1,164 @@ +/** + ****************************************************************************** + * + * @file hitlconfiguration.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup HITLPlugin HITL Plugin + * @{ + * @brief The Hardware In The Loop 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 "hitlconfiguration.h" + +HITLConfiguration::HITLConfiguration(QString classId, QSettings* qSettings, QObject *parent) : + IUAVGadgetConfiguration(classId, parent) +{ + + //Default settings values + settings.simulatorId = ""; + settings.binPath = ""; + settings.dataPath = ""; + settings.manualControlEnabled = true; + settings.startSim = false; + settings.addNoise = false; + settings.hostAddress = "127.0.0.1"; + settings.remoteAddress = "127.0.0.1"; + settings.outPort = 0; + settings.inPort = 0; + settings.latitude = ""; + settings.longitude = ""; + + settings.attRawEnabled = false; + settings.attRawRate = 20; + + settings.attActualEnabled = true; + settings.attActHW = false; + settings.attActSim = true; + settings.attActCalc = false; + + settings.gpsPositionEnabled = false; + settings.gpsPosRate = 100; + + settings.groundTruthEnabled = false; + settings.groundTruthRate = 100; + + settings.inputCommand = false; + settings.gcsReceiverEnabled = false; + settings.manualControlEnabled= false; + settings.minOutputPeriod = 100; + + settings.airspeedActualEnabled= false; + settings.airspeedActualRate = 100; + + + // if a saved configuration exists load it, and overwrite defaults + if (qSettings != 0) { + + settings.simulatorId = qSettings->value("simulatorId").toString(); + settings.binPath = qSettings->value("binPath").toString(); + settings.dataPath = qSettings->value("dataPath").toString(); + + settings.hostAddress = qSettings->value("hostAddress").toString(); + settings.remoteAddress = qSettings->value("remoteAddress").toString(); + settings.outPort = qSettings->value("outPort").toInt(); + settings.inPort = qSettings->value("inPort").toInt(); + + settings.latitude = qSettings->value("latitude").toString(); + settings.longitude = qSettings->value("longitude").toString(); + settings.startSim = qSettings->value("startSim").toBool(); + settings.addNoise = qSettings->value("noiseCheckBox").toBool(); + + settings.gcsReceiverEnabled = qSettings->value("gcsReceiverEnabled").toBool(); + settings.manualControlEnabled= qSettings->value("manualControlEnabled").toBool(); + + settings.attRawEnabled = qSettings->value("attRawEnabled").toBool(); + settings.attRawRate = qSettings->value("attRawRate").toInt(); + + settings.attActualEnabled = qSettings->value("attActualEnabled").toBool(); + settings.attActHW = qSettings->value("attActHW").toBool(); + settings.attActSim = qSettings->value("attActSim").toBool(); + settings.attActCalc = qSettings->value("attActCalc").toBool(); + + settings.baroAltitudeEnabled = qSettings->value("baroAltitudeEnabled").toBool(); + settings.baroAltRate = qSettings->value("baroAltRate").toInt(); + + settings.gpsPositionEnabled = qSettings->value("gpsPositionEnabled").toBool(); + settings.gpsPosRate = qSettings->value("gpsPosRate").toInt(); + + settings.groundTruthEnabled = qSettings->value("groundTruthEnabled").toBool(); + settings.groundTruthRate = qSettings->value("groundTruthRate").toInt(); + + settings.inputCommand = qSettings->value("inputCommand").toBool(); + settings.minOutputPeriod = qSettings->value("minOutputPeriod").toInt(); + + settings.airspeedActualEnabled=qSettings->value("airspeedActualEnabled").toBool(); + settings.airspeedActualRate = qSettings->value("airspeedActualRate").toInt(); + } +} + +IUAVGadgetConfiguration *HITLConfiguration::clone() +{ + HITLConfiguration *m = new HITLConfiguration(this->classId()); + + m->settings = settings; + return m; +} + + /** + * Saves a configuration. + * + */ +void HITLConfiguration::saveConfig(QSettings* qSettings) const { + qSettings->setValue("simulatorId", settings.simulatorId); + qSettings->setValue("binPath", settings.binPath); + qSettings->setValue("dataPath", settings.dataPath); + + qSettings->setValue("hostAddress", settings.hostAddress); + qSettings->setValue("remoteAddress", settings.remoteAddress); + qSettings->setValue("outPort", settings.outPort); + qSettings->setValue("inPort", settings.inPort); + + qSettings->setValue("latitude", settings.latitude); + qSettings->setValue("longitude", settings.longitude); + qSettings->setValue("addNoise", settings.addNoise); + qSettings->setValue("startSim", settings.startSim); + + qSettings->setValue("gcsReceiverEnabled", settings.gcsReceiverEnabled); + qSettings->setValue("manualControlEnabled", settings.manualControlEnabled); + + qSettings->setValue("attRawEnabled", settings.attRawEnabled); + qSettings->setValue("attRawRate", settings.attRawRate); + qSettings->setValue("attActualEnabled", settings.attActualEnabled); + qSettings->setValue("attActHW", settings.attActHW); + qSettings->setValue("attActSim", settings.attActSim); + qSettings->setValue("attActCalc", settings.attActCalc); + qSettings->setValue("baroAltitudeEnabled", settings.baroAltitudeEnabled); + qSettings->setValue("baroAltRate", settings.baroAltRate); + qSettings->setValue("gpsPositionEnabled", settings.gpsPositionEnabled); + qSettings->setValue("gpsPosRate", settings.gpsPosRate); + qSettings->setValue("groundTruthEnabled", settings.groundTruthEnabled); + qSettings->setValue("groundTruthRate", settings.groundTruthRate); + qSettings->setValue("inputCommand", settings.inputCommand); + qSettings->setValue("minOutputPeriod", settings.minOutputPeriod); + + qSettings->setValue("airspeedActualEnabled", settings.airspeedActualEnabled); + qSettings->setValue("airspeedActualRate", settings.airspeedActualRate); +} + diff --git a/ground/openpilotgcs/src/plugins/hitlnew/hitlconfiguration.h b/ground/openpilotgcs/src/plugins/hitl/hitlconfiguration.h similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlnew/hitlconfiguration.h rename to ground/openpilotgcs/src/plugins/hitl/hitlconfiguration.h diff --git a/ground/openpilotgcs/src/plugins/hitlnew/hitlfactory.cpp b/ground/openpilotgcs/src/plugins/hitl/hitlfactory.cpp similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlnew/hitlfactory.cpp rename to ground/openpilotgcs/src/plugins/hitl/hitlfactory.cpp diff --git a/ground/openpilotgcs/src/plugins/hitlnew/hitlfactory.h b/ground/openpilotgcs/src/plugins/hitl/hitlfactory.h similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlnew/hitlfactory.h rename to ground/openpilotgcs/src/plugins/hitl/hitlfactory.h diff --git a/ground/openpilotgcs/src/plugins/hitlnew/hitlgadget.cpp b/ground/openpilotgcs/src/plugins/hitl/hitlgadget.cpp similarity index 75% rename from ground/openpilotgcs/src/plugins/hitlnew/hitlgadget.cpp rename to ground/openpilotgcs/src/plugins/hitl/hitlgadget.cpp index 4965ee3aa..a05b5ce71 100644 --- a/ground/openpilotgcs/src/plugins/hitlnew/hitlgadget.cpp +++ b/ground/openpilotgcs/src/plugins/hitl/hitlgadget.cpp @@ -44,24 +44,8 @@ HITLGadget::~HITLGadget() void HITLGadget::loadConfiguration(IUAVGadgetConfiguration* config) { HITLConfiguration *m = qobject_cast(config); - // FG -// simulator->setFGPathBin( m->fgPathBin() ); -// simulator->setFGPathData( m->fgPathData() ); -// simulator->setFGManualControl( m->fgManualControl() ); -// // IL2 + // IL2 <-- Is this still necessary? [KDS] emit changeConfiguration(); m_widget->setSettingParameters(m->Settings()); - -// m_widget->setSimulatorId(m->SimulatorId()); -// m_widget->setPathBin(m->PathBin()); -// m_widget->setPathData(m->PathData()); -// m_widget->setHostName(m->HostName()); -// m_widget->setLatitude(m->Latitude()); -// m_widget->setLongitude(m->Longitude()); -// m_widget->setOutPort(m->OutPort()); -// m_widget->setInPort(m->InPort()); -// m_widget->setManualControl(m->ManualControl()); - - } diff --git a/ground/openpilotgcs/src/plugins/hitlnew/hitlgadget.h b/ground/openpilotgcs/src/plugins/hitl/hitlgadget.h similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlnew/hitlgadget.h rename to ground/openpilotgcs/src/plugins/hitl/hitlgadget.h diff --git a/ground/openpilotgcs/src/plugins/hitl/hitlnoisegeneration.cpp b/ground/openpilotgcs/src/plugins/hitl/hitlnoisegeneration.cpp new file mode 100644 index 000000000..4efb72852 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitl/hitlnoisegeneration.cpp @@ -0,0 +1,78 @@ +/** + ****************************************************************************** + * + * @file hitlnoisegeneration.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief + * @see The GNU Public License (GPL) Version 3 + * @defgroup hitlplugin + * @{ + * + *****************************************************************************/ +/* + * 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 "hitlnoisegeneration.h" + + +HitlNoiseGeneration::HitlNoiseGeneration() +{ + memset(&noise, 0, sizeof(Noise)); +} + + +HitlNoiseGeneration::~HitlNoiseGeneration() +{ +} + +Noise HitlNoiseGeneration::getNoise(){ + return noise; +} + +Noise HitlNoiseGeneration::generateNoise(){ + + noise.accelData.x=0; + noise.accelData.y=0; + noise.accelData.z=0; + + noise.gpsPosData.Latitude=0; + noise.gpsPosData.Longitude=0; + noise.gpsPosData.Groundspeed=0; + noise.gpsPosData.Heading=0; + noise.gpsPosData.Altitude=0; + + noise.gpsVelData.North=0; + noise.gpsVelData.East=0; + noise.gpsVelData.Down=0; + + noise.baroAltData.Altitude=0; + + noise.attActualData.Roll=0; + noise.attActualData.Pitch=0; + noise.attActualData.Yaw=0; + + noise.gyroData.x=0; + noise.gyroData.y=0; + noise.gyroData.z=0; + + noise.accelData.x=0; + noise.accelData.y=0; + noise.accelData.z=0; + + noise.airspeedActual.CalibratedAirspeed=0; + + return noise; +} diff --git a/ground/openpilotgcs/src/plugins/hitl/hitlnoisegeneration.h b/ground/openpilotgcs/src/plugins/hitl/hitlnoisegeneration.h new file mode 100644 index 000000000..0a740707e --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitl/hitlnoisegeneration.h @@ -0,0 +1,66 @@ +/** + ****************************************************************************** + * + * @file hitlnoisegeneration.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @brief + * @see The GNU Public License (GPL) Version 3 + * @defgroup hitlplugin + * @{ + * + *****************************************************************************/ +/* + * 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 HITLNOISEGENERATION_H +#define HITLNOISEGENERATION_H + +//#include +//#include +#include "xplanesimulator.h" +#include "hitlnoisegeneration.h" +#include "extensionsystem/pluginmanager.h" +#include +#include + +struct Noise{ + Accels::DataFields accelData; + AttitudeActual::DataFields attActualData; + BaroAltitude::DataFields baroAltData; + AirspeedActual::DataFields airspeedActual; + GPSPosition::DataFields gpsPosData; + GPSVelocity::DataFields gpsVelData; + Gyros::DataFields gyroData; + HomeLocation::DataFields homeData; + PositionActual::DataFields positionActualData; + VelocityActual::DataFields velocityActualData; +}; + +class HitlNoiseGeneration +{ +// Q_OBJECT +public: + HitlNoiseGeneration(); + ~HitlNoiseGeneration(); + + Noise getNoise(); + Noise generateNoise(); +private slots: + +private: + Noise noise; +}; +#endif // HITLNOISEGENERATION_H diff --git a/ground/openpilotgcs/src/plugins/hitl/hitloptionspage.cpp b/ground/openpilotgcs/src/plugins/hitl/hitloptionspage.cpp new file mode 100644 index 000000000..9188e66c8 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitl/hitloptionspage.cpp @@ -0,0 +1,175 @@ +/** + ****************************************************************************** + * + * @file hitloptionspage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup HITLPlugin HITL Plugin + * @{ + * @brief The Hardware In The Loop 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 "hitloptionspage.h" +#include "hitlconfiguration.h" +#include "ui_hitloptionspage.h" +#include + +#include +#include +#include +#include + + + +HITLOptionsPage::HITLOptionsPage(HITLConfiguration *conf, QObject *parent) : + IOptionsPage(parent), + config(conf) +{ +} + +QWidget *HITLOptionsPage::createPage(QWidget *parent) +{ + Q_UNUSED(parent); + + // Create page + m_optionsPage = new Ui::HITLOptionsPage(); + QWidget* optionsPageWidget = new QWidget; + m_optionsPage->setupUi(optionsPageWidget); + int index = 0; + foreach(SimulatorCreator* creator, HITLPlugin::typeSimulators) + { + m_optionsPage->chooseFlightSimulator->insertItem(index++, creator->Description(),creator->ClassId()); + } + + //QString classId = widget->listSimulators->itemData(0).toString(); + //SimulatorCreator* creator = HITLPlugin::getSimulatorCreator(classId); + + //QWidget* embedPage = creator->createOptionsPage(); + //m_optionsPage->verticalLayout->addWidget(embedPage); + + m_optionsPage->executablePath->setExpectedKind(Utils::PathChooser::File); + m_optionsPage->executablePath->setPromptDialogTitle(tr("Choose flight simulator executable")); + m_optionsPage->dataPath->setExpectedKind(Utils::PathChooser::Directory); + m_optionsPage->dataPath->setPromptDialogTitle(tr("Choose flight simulator data directory")); + + // Restore the contents from the settings: + foreach(SimulatorCreator* creator, HITLPlugin::typeSimulators) + { + QString id = config->Settings().simulatorId; + if(creator->ClassId() == id) + m_optionsPage->chooseFlightSimulator->setCurrentIndex(HITLPlugin::typeSimulators.indexOf(creator)); + } + + m_optionsPage->executablePath->setPath(config->Settings().binPath); + m_optionsPage->dataPath->setPath(config->Settings().dataPath); + + m_optionsPage->manualControlRadioButton->setChecked(config->Settings().manualControlEnabled); + m_optionsPage->gcsReceiverRadioButton->setChecked(config->Settings().gcsReceiverEnabled); + + m_optionsPage->startSim->setChecked(config->Settings().startSim); + m_optionsPage->noiseCheckBox->setChecked(config->Settings().addNoise); + + m_optionsPage->hostAddress->setText(config->Settings().hostAddress); + m_optionsPage->remoteAddress->setText(config->Settings().remoteAddress); + m_optionsPage->outputPort->setText(QString::number(config->Settings().outPort)); + m_optionsPage->inputPort->setText(QString::number(config->Settings().inPort)); + m_optionsPage->latitude->setText(config->Settings().latitude); + m_optionsPage->longitude->setText(config->Settings().longitude); + + m_optionsPage->groundTruthCheckbox->setChecked(config->Settings().groundTruthEnabled); + m_optionsPage->gpsPositionCheckbox->setChecked(config->Settings().gpsPositionEnabled); + m_optionsPage->attActualCheckbox->setChecked(config->Settings().attActualEnabled); + m_optionsPage->attRawCheckbox->setChecked(config->Settings().attRawEnabled); + + + + m_optionsPage->attRawRateSpinbox->setValue(config->Settings().attRawRate); + m_optionsPage->gpsPosRateSpinbox->setValue(config->Settings().gpsPosRate); + m_optionsPage->groundTruthRateSpinbox->setValue(config->Settings().groundTruthRate); +// m_optionsPage->attActualRate->setValue(config->Settings().attActualRate); + + m_optionsPage->baroAltitudeCheckbox->setChecked(config->Settings().baroAltitudeEnabled); + m_optionsPage->baroAltRateSpinbox->setValue(config->Settings().baroAltRate); + + m_optionsPage->minOutputPeriodSpinbox->setValue(config->Settings().minOutputPeriod); + + m_optionsPage->attActHW->setChecked(config->Settings().attActHW); + m_optionsPage->attActCalc->setChecked(config->Settings().attActCalc); + m_optionsPage->attActSim->setChecked(config->Settings().attActSim); + + m_optionsPage->airspeedActualCheckbox->setChecked(config->Settings().airspeedActualEnabled); + m_optionsPage->airspeedRateSpinbox->setValue(config->Settings().airspeedActualRate); + + return optionsPageWidget; +} + +void HITLOptionsPage::apply() +{ + SimulatorSettings settings; + int i = m_optionsPage->chooseFlightSimulator->currentIndex(); + + settings.simulatorId = m_optionsPage->chooseFlightSimulator->itemData(i).toString(); + settings.binPath = m_optionsPage->executablePath->path(); + settings.dataPath = m_optionsPage->dataPath->path(); + settings.startSim = m_optionsPage->startSim->isChecked(); + settings.addNoise = m_optionsPage->noiseCheckBox->isChecked(); + settings.hostAddress = m_optionsPage->hostAddress->text(); + settings.remoteAddress = m_optionsPage->remoteAddress->text(); + + settings.inPort = m_optionsPage->inputPort->text().toInt(); + settings.outPort = m_optionsPage->outputPort->text().toInt(); + settings.longitude = m_optionsPage->longitude->text(); + settings.latitude = m_optionsPage->latitude->text(); + + settings.addNoise = m_optionsPage->noiseCheckBox->isChecked(); + + settings.attRawEnabled = m_optionsPage->attRawCheckbox->isChecked(); + settings.attRawRate = m_optionsPage->attRawRateSpinbox->value(); + + settings.attActualEnabled = m_optionsPage->attActualCheckbox->isChecked(); + + settings.gpsPositionEnabled = m_optionsPage->gpsPositionCheckbox->isChecked(); + settings.gpsPosRate = m_optionsPage->gpsPosRateSpinbox->value(); + + settings.groundTruthEnabled = m_optionsPage->groundTruthCheckbox->isChecked(); + settings.groundTruthRate = m_optionsPage->groundTruthRateSpinbox->value(); + + settings.baroAltitudeEnabled = m_optionsPage->baroAltitudeCheckbox->isChecked(); + settings.baroAltRate = m_optionsPage->baroAltRateSpinbox->value(); + + settings.minOutputPeriod = m_optionsPage->minOutputPeriodSpinbox->value(); + + settings.manualControlEnabled = m_optionsPage->manualControlRadioButton->isChecked(); + settings.gcsReceiverEnabled = m_optionsPage->gcsReceiverRadioButton->isChecked(); + + settings.attActHW = m_optionsPage->attActHW->isChecked(); + settings.attActSim = m_optionsPage->attActSim->isChecked(); + settings.attActCalc = m_optionsPage->attActCalc->isChecked(); + + settings.airspeedActualEnabled=m_optionsPage->airspeedActualCheckbox->isChecked(); + settings.airspeedActualRate=m_optionsPage->airspeedRateSpinbox->value(); + + //Write settings to file + config->setSimulatorSettings(settings); +} + +void HITLOptionsPage::finish() +{ + delete m_optionsPage; +} diff --git a/ground/openpilotgcs/src/plugins/hitlnew/hitloptionspage.h b/ground/openpilotgcs/src/plugins/hitl/hitloptionspage.h similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlnew/hitloptionspage.h rename to ground/openpilotgcs/src/plugins/hitl/hitloptionspage.h diff --git a/ground/openpilotgcs/src/plugins/hitl/hitloptionspage.ui b/ground/openpilotgcs/src/plugins/hitl/hitloptionspage.ui new file mode 100644 index 000000000..30eb578c5 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitl/hitloptionspage.ui @@ -0,0 +1,1108 @@ + + + HITLOptionsPage + + + + 0 + 0 + 885 + 741 + + + + + 0 + 0 + + + + + 0 + 0 + + + + Form + + + + 3 + + + 0 + + + 0 + + + 0 + + + 3 + + + + + + + Choose flight simulator: + + + + + + + + + + + + + 0 + 0 + + + + + 0 + 100 + + + + + 350 + 16777215 + + + + IP addresses + + + + + 10 + 30 + 323 + 24 + + + + + + + Local host: + + + + + + + + 0 + 0 + + + + + 125 + 16777215 + + + + For communication with sim computer via network. Should be the IP address of one of the interfaces of the GCS computer. + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Port: + + + + + + + + 0 + 0 + + + + + 55 + 16777215 + + + + IP port for receiving data from sim + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + + 10 + 60 + 322 + 24 + + + + + + + Remote host: + + + + + + + + 0 + 0 + + + + + 125 + 16777215 + + + + Only required if running simulator on remote machine. Should be the IP of the machine on which the simulator is running. + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Port: + + + + + + + + 0 + 0 + + + + + 55 + 16777215 + + + + IP port for sending data to sim + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + + + + + 0 + 180 + + + + Program parameters + + + + + 120 + 60 + 401 + 16 + + + + + 0 + 0 + + + + + + + 10 + 60 + 94 + 16 + + + + + 0 + 0 + + + + + 110 + 16777215 + + + + Data directory: + + + + + + 120 + 34 + 401 + 16 + + + + + 0 + 0 + + + + + + + 10 + 34 + 104 + 16 + + + + + 0 + 0 + + + + + 110 + 16777215 + + + + Path executable: + + + + + + 10 + 120 + 229 + 20 + + + + Check this box to start the simulator on the local computer + + + Start simulator on local machine + + + + + + 10 + 150 + 89 + 20 + + + + Add noise to sensor simulation + + + Add noise + + + + + + 10 + 80 + 491 + 16 + + + + Qt::Horizontal + + + + + + 10 + 90 + 161 + 22 + + + + Initial latitude (decimal): + + + + + + 290 + 90 + 171 + 22 + + + + Initial longitude (decimal): + + + + + + 460 + 90 + 100 + 22 + + + + + 0 + 0 + + + + + 100 + 16777215 + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + 170 + 90 + 100 + 22 + + + + + 0 + 0 + + + + + 100 + 16777215 + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + QFormLayout::AllNonFixedFieldsGrow + + + + + QFrame::StyledPanel + + + QFrame::Raised + + + + + + + + + + + + + + 16777215 + 150 + + + + Attitude data + + + + 3 + + + 3 + + + 3 + + + 3 + + + 0 + + + + + true + + + AttitudeRaw (gyro, accels) + + + true + + + true + + + false + + + + 3 + + + 3 + + + 0 + + + 0 + + + + + Refresh rate: + + + + + + + true + + + 0 - update once, or every N seconds + + + ms + + + 10 + + + 100 + + + 20 + + + + + + + + + + true + + + AttitudeActual + + + true + + + true + + + true + + + + 3 + + + 3 + + + 0 + + + 0 + + + + + + 75 + true + + + + + + + use values from simulator + + + true + + + + + + + send simulated inertial data to board + + + + + + + + + + calculate from simulated sensor data + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + + + + + + 0 + 150 + + + + Spatial data + + + + + + Ground truth position and velocity + + + true + + + true + + + true + + + + 3 + + + 3 + + + 0 + + + 0 + + + + + Refresh rate: + + + + + + + true + + + 0 - update once, or every N seconds + + + ms + + + 1 + + + 5000 + + + 100 + + + 100 + + + + + + + + + + GPS data + + + true + + + true + + + false + + + + 3 + + + 3 + + + 0 + + + 0 + + + + + true + + + Refresh rate: + + + + + + + true + + + 0 - update once, or every N seconds + + + ms + + + 1 + + + 5000 + + + 100 + + + 100 + + + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + + + + + + + 0 + 275 + + + + Other data + + + + 3 + + + 3 + + + 3 + + + 3 + + + 0 + + + + + + 0 + 0 + + + + AirspeedActual + + + true + + + true + + + + + + Refresh rate: + + + + + + + 0 - update once, or every N seconds + + + ms + + + 5000 + + + 100 + + + + + + + + + + false + + + BaroAltitude + + + true + + + true + + + false + + + + 3 + + + 6 + + + 3 + + + 0 + + + 0 + + + + + + + Range detection: + + + + + + + m + + + 1 + + + 10 + + + 5 + + + + + + + Refresh rate: + + + + + + + 0 - update once, or every N seconds + + + ms + + + 20 + + + 2000 + + + 10 + + + 250 + + + + + + + + + + + + true + + + Map transmitter commands... + + + true + + + true + + + true + + + + 3 + + + 3 + + + 0 + + + 0 + + + + + true + + + + 75 + true + + + + from hardware to simulator (via ManualCtrl) + + + true + + + + + + + from simulator to hardware (via GCSReceiver) + + + false + + + + + + + + + + 6 + + + + + Maximum GCS to hardware output rate: + + + + + + + true + + + Set the maximum rate at which GCS sends simulator data to the hardware + + + ms + + + 10 + + + 500 + + + 5 + + + 100 + + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + + + + + + + Utils::PathChooser + QWidget +
utils/pathchooser.h
+ 1 +
+
+ + chooseFlightSimulator + hostAddress + inputPort + remoteAddress + outputPort + + + +
diff --git a/ground/openpilotgcs/src/plugins/hitlnew/hitlplugin.cpp b/ground/openpilotgcs/src/plugins/hitl/hitlplugin.cpp similarity index 91% rename from ground/openpilotgcs/src/plugins/hitlnew/hitlplugin.cpp rename to ground/openpilotgcs/src/plugins/hitl/hitlplugin.cpp index dbfb27ba5..9ecca808e 100644 --- a/ground/openpilotgcs/src/plugins/hitlnew/hitlplugin.cpp +++ b/ground/openpilotgcs/src/plugins/hitl/hitlplugin.cpp @@ -29,6 +29,7 @@ #include #include #include +#include "aerosimrcsimulator.h" #include "fgsimulator.h" #include "il2simulator.h" #include "xplanesimulator.h" @@ -53,6 +54,7 @@ bool HITLPlugin::initialize(const QStringList& args, QString *errMsg) addAutoReleasedObject(mf); + addSimulator(new AeroSimRCSimulatorCreator("ASimRC", "AeroSimRC")); addSimulator(new FGSimulatorCreator("FG","FlightGear")); addSimulator(new IL2SimulatorCreator("IL2","IL2")); addSimulator(new XplaneSimulatorCreator("X-Plane","X-Plane")); diff --git a/ground/openpilotgcs/src/plugins/hitlnew/hitlplugin.h b/ground/openpilotgcs/src/plugins/hitl/hitlplugin.h similarity index 95% rename from ground/openpilotgcs/src/plugins/hitlnew/hitlplugin.h rename to ground/openpilotgcs/src/plugins/hitl/hitlplugin.h index 6caecedca..658111e79 100644 --- a/ground/openpilotgcs/src/plugins/hitlnew/hitlplugin.h +++ b/ground/openpilotgcs/src/plugins/hitl/hitlplugin.h @@ -29,7 +29,7 @@ #define HITLPLUGIN_H #include -#include +#include #include diff --git a/ground/openpilotgcs/src/plugins/hitlnew/hitlresources.qrc b/ground/openpilotgcs/src/plugins/hitl/hitlresources.qrc similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlnew/hitlresources.qrc rename to ground/openpilotgcs/src/plugins/hitl/hitlresources.qrc diff --git a/ground/openpilotgcs/src/plugins/hitlnew/hitlwidget.cpp b/ground/openpilotgcs/src/plugins/hitl/hitlwidget.cpp similarity index 74% rename from ground/openpilotgcs/src/plugins/hitlnew/hitlwidget.cpp rename to ground/openpilotgcs/src/plugins/hitl/hitlwidget.cpp index f965b5ad3..beef24f70 100644 --- a/ground/openpilotgcs/src/plugins/hitlnew/hitlwidget.cpp +++ b/ground/openpilotgcs/src/plugins/hitl/hitlwidget.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file hitlwidget.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup HITLPlugin HITL Plugin @@ -51,12 +51,13 @@ HITLWidget::HITLWidget(QWidget *parent) widget->startButton->setEnabled(true); widget->stopButton->setEnabled(false); - greenColor = "rgb(35, 221, 35)"; + greenColor = "rgb(35, 221, 35)"; //Change the green color in order to make it a bit more vibrant + strStyleEnable = QString("QFrame{background-color: %1; color: white}").arg(greenColor); + strStyleDisable = "QFrame{background-color: red; color: white}"; - strAutopilotDisconnected = " Autopilot OFF "; - strSimulatorDisconnected = " Simulator OFF "; - strAutopilotConnected = " Autopilot ON "; - strSimulatorConnected = " Simulator ON "; + strAutopilotDisconnected = " Autopilot OFF "; + strSimulatorDisconnected = " Simulator OFF "; + strAutopilotConnected = " Autopilot ON "; widget->apLabel->setText(strAutopilotDisconnected); widget->simLabel->setText(strSimulatorDisconnected); @@ -64,7 +65,6 @@ HITLWidget::HITLWidget(QWidget *parent) connect(widget->startButton, SIGNAL(clicked()), this, SLOT(startButtonClicked())); connect(widget->stopButton, SIGNAL(clicked()), this, SLOT(stopButtonClicked())); connect(widget->buttonClearLog, SIGNAL(clicked()), this, SLOT(buttonClearLogClicked())); - } HITLWidget::~HITLWidget() @@ -77,15 +77,7 @@ void HITLWidget::startButtonClicked() QThread* mainThread = QThread::currentThread(); qDebug() << "Main Thread: "<< mainThread; - // [1] -// if(Simulator::IsStarted()) -// { -// widget->textBrowser->append("HITL alreary started!"); -// return; -// } -// Simulator::setStarted(true); - - // [2] allow only one instance per simulator + //Allow only one instance per simulator if(Simulator::Instances().indexOf(settings.simulatorId) != -1) { widget->textBrowser->append(settings.simulatorId + " alreary started!"); @@ -104,25 +96,27 @@ void HITLWidget::startButtonClicked() QMetaObject::invokeMethod(simulator, "onDeleteSimulator",Qt::QueuedConnection); simulator = NULL; } - //fgBridge = new FlightGearBridge(); - //simulator = new Simulator(); - if(settings.hostAddress == "" || settings.inPort == 0) + + if(settings.hostAddress == "" || settings.inPort == 0) { widget->textBrowser->append("Before start, set UDP parameters in options page!"); return; } SimulatorCreator* creator = HITLPlugin::getSimulatorCreator(settings.simulatorId); - simulator = creator->createSimulator(settings);//hostName, outPort, inPort, manualControl, pathBin, pathData); - // move to thread + simulator = creator->createSimulator(settings); + + // move to thread <--[BCH] simulator->setName(creator->Description()); simulator->setSimulatorId(creator->ClassId()); + + connect(simulator, SIGNAL(processOutput(QString)), this, SLOT(onProcessOutput(QString))); + // Setup process widget->textBrowser->append(QString("[%1] Starting %2... ").arg(QTime::currentTime().toString("hh:mm:ss")).arg(creator->Description())); qxtLog->info("HITL: Starting " + creator->Description()); // Start bridge - //bool ret = simulator->setupProcess(); bool ret = QMetaObject::invokeMethod(simulator, "setupProcess",Qt::QueuedConnection); if(ret) { @@ -134,7 +128,6 @@ void HITLWidget::startButtonClicked() widget->stopButton->setEnabled(true); qxtLog->info("HITL: Starting bridge, initializing flight simulator and Autopilot connections"); - connect(simulator, SIGNAL(processOutput(QString)), widget->textBrowser, SLOT(append(QString))); connect(simulator, SIGNAL(autopilotConnected()), this, SLOT(onAutopilotConnect()),Qt::QueuedConnection); connect(simulator, SIGNAL(autopilotDisconnected()), this, SLOT(onAutopilotDisconnect()),Qt::QueuedConnection); connect(simulator, SIGNAL(simulatorConnected()), this, SLOT(onSimulatorConnect()),Qt::QueuedConnection); @@ -169,9 +162,9 @@ void HITLWidget::stopButtonClicked() widget->startButton->setEnabled(true); widget->stopButton->setEnabled(false); - widget->apLabel->setStyleSheet(QString::fromUtf8("QFrame{\n""background-color: transparent; color: white}")); - widget->simLabel->setStyleSheet(QString::fromUtf8("QFrame{\n""background-color: transparent; color: white}")); - widget->apLabel->setText(strAutopilotDisconnected); + widget->apLabel->setStyleSheet(QString::fromUtf8("QFrame{background-color: transparent; color: white}")); + widget->simLabel->setStyleSheet(QString::fromUtf8("QFrame{background-color: transparent; color: white}")); + widget->apLabel->setText(strAutopilotDisconnected); widget->simLabel->setText(strSimulatorDisconnected); if(simulator) { @@ -185,31 +178,35 @@ void HITLWidget::buttonClearLogClicked() widget->textBrowser->clear(); } +void HITLWidget::onProcessOutput(QString text) +{ + widget->textBrowser->append(text); +} void HITLWidget::onAutopilotConnect() { - widget->apLabel->setStyleSheet(QString::fromUtf8("QFrame{\n""background-color: %1; color: white}").arg(greenColor)); - widget->apLabel->setText(strAutopilotConnected); + widget->apLabel->setStyleSheet(strStyleEnable); + widget->apLabel->setText(strAutopilotConnected); qxtLog->info("HITL: Autopilot connected, initializing for HITL simulation"); } void HITLWidget::onAutopilotDisconnect() { - widget->apLabel->setStyleSheet(QString::fromUtf8("QFrame{\n""background-color: red; color: white}")); + widget->apLabel->setStyleSheet(strStyleDisable); widget->apLabel->setText(strAutopilotDisconnected); qxtLog->info(strAutopilotDisconnected); } void HITLWidget::onSimulatorConnect() { - widget->simLabel->setStyleSheet(QString::fromUtf8("QFrame{\n""background-color: %1; color: white}").arg(greenColor)); - widget->simLabel->setText(" " + simulator->Name() +" connected "); + widget->simLabel->setStyleSheet(strStyleEnable); + widget->simLabel->setText(" " + simulator->Name() +" connected "); qxtLog->info(QString("HITL: %1 connected").arg(simulator->Name())); } void HITLWidget::onSimulatorDisconnect() { - widget->simLabel->setStyleSheet(QString::fromUtf8("QFrame{\n""background-color: red; color: white}")); - widget->simLabel->setText(" " + simulator->Name() +" disconnected "); + widget->simLabel->setStyleSheet(strStyleDisable); + widget->simLabel->setText(" " + simulator->Name() +" disconnected "); qxtLog->info(QString("HITL: %1 disconnected").arg(simulator->Name())); } diff --git a/ground/openpilotgcs/src/plugins/hitlnew/hitlwidget.h b/ground/openpilotgcs/src/plugins/hitl/hitlwidget.h similarity index 92% rename from ground/openpilotgcs/src/plugins/hitlnew/hitlwidget.h rename to ground/openpilotgcs/src/plugins/hitl/hitlwidget.h index b5865a842..f63352f9e 100644 --- a/ground/openpilotgcs/src/plugins/hitlnew/hitlwidget.h +++ b/ground/openpilotgcs/src/plugins/hitl/hitlwidget.h @@ -50,6 +50,7 @@ private slots: void startButtonClicked(); void stopButtonClicked(); void buttonClearLogClicked(); + void onProcessOutput(QString text); void onAutopilotConnect(); void onAutopilotDisconnect(); void onSimulatorConnect(); @@ -64,8 +65,8 @@ private: QString strAutopilotDisconnected; QString strSimulatorDisconnected; QString strAutopilotConnected; - QString strSimulatorConnected; - + QString strStyleEnable; + QString strStyleDisable; }; #endif /* HITLWIDGET_H */ diff --git a/ground/openpilotgcs/src/plugins/hitlnew/hitlwidget.ui b/ground/openpilotgcs/src/plugins/hitl/hitlwidget.ui similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlnew/hitlwidget.ui rename to ground/openpilotgcs/src/plugins/hitl/hitlwidget.ui diff --git a/ground/openpilotgcs/src/plugins/hitlnew/il2simulator.cpp b/ground/openpilotgcs/src/plugins/hitl/il2simulator.cpp similarity index 90% rename from ground/openpilotgcs/src/plugins/hitlnew/il2simulator.cpp rename to ground/openpilotgcs/src/plugins/hitl/il2simulator.cpp index 8446b9d54..6bec9fbf3 100644 --- a/ground/openpilotgcs/src/plugins/hitlnew/il2simulator.cpp +++ b/ground/openpilotgcs/src/plugins/hitl/il2simulator.cpp @@ -96,10 +96,11 @@ IL2Simulator::~IL2Simulator() void IL2Simulator::setupUdpPorts(const QString& host, int inPort, int outPort) { + Q_UNUSED(outPort); + inSocket->connectToHost(host,inPort); // IL2 if(!inSocket->waitForConnected()) qxtLog->error(Name() + " cann't connect to UDP Port: " + QString::number(inPort)); - } void IL2Simulator::transmitUpdate() @@ -143,10 +144,10 @@ float IL2Simulator::PRESSURE(float alt) { } /** - * calculate CAS from IAS and altitude + * calculate TAS from IAS and altitude */ -float IL2Simulator::CAS(float IAS, float alt) { - return (IAS*sqrt(GROUNDDENSITY/DENSITY(alt))); +float IL2Simulator::TAS(float IAS, float alt) { + return (IAS*sqrt(GROUNDDENSITY/DENSITY(alt))); } /** @@ -205,8 +206,8 @@ void IL2Simulator::processUpdate(const QByteArray& inp) old.ddX=0; } - // calculate CAS from alt and IAS - current.tas = CAS(current.ias,current.Z); + // calculate TAS from alt and IAS + current.tas = TAS(current.ias,current.Z); // assume the plane actually flies straight and no wind // groundspeed is horizontal vector of TAS @@ -240,8 +241,8 @@ void IL2Simulator::processUpdate(const QByteArray& inp) /////// // Output formatting /////// - Output2OP out; - memset(&out, 0, sizeof(Output2OP)); + Output2Hardware out; + memset(&out, 0, sizeof(Output2Hardware)); // Compute rotation matrix, for later calculations float Rbe[3][3]; @@ -253,24 +254,19 @@ void IL2Simulator::processUpdate(const QByteArray& inp) Utils::CoordinateConversions().RPY2Quaternion(rpy,quat); Utils::CoordinateConversions().Quaternion2R(quat,Rbe); - //Calculate ECEF - double RNE[9]; - double ECEF[3]; - double LLA[3]; - LLA[0]=settings.latitude.toFloat(); - LLA[1]=settings.longitude.toFloat(); - LLA[2]=0; - Utils::CoordinateConversions().RneFromLLA(LLA,(double (*)[3])RNE); - Utils::CoordinateConversions().LLA2ECEF(LLA,ECEF); - // Update GPS Position objects + double HomeLLA[3]; + double LLA[3]; double NED[3]; + HomeLLA[0]=settings.latitude.toFloat(); + HomeLLA[1]=settings.longitude.toFloat(); + HomeLLA[2]=0; NED[0] = current.Y; NED[1] = current.X; NED[2] = -current.Z; - Utils::CoordinateConversions().NED2LLA_HomeECEF(ECEF,NED,LLA); - out.latitude = LLA[0] * 10e6; - out.longitude = LLA[1] * 10e6; + Utils::CoordinateConversions().NED2LLA_HomeLLA(HomeLLA,NED,LLA); + out.latitude = LLA[0] * 1e7; + out.longitude = LLA[1] * 1e7; out.groundspeed = current.groundspeed; out.calibratedAirspeed = current.ias; diff --git a/ground/openpilotgcs/src/plugins/hitlnew/il2simulator.h b/ground/openpilotgcs/src/plugins/hitl/il2simulator.h similarity index 95% rename from ground/openpilotgcs/src/plugins/hitlnew/il2simulator.h rename to ground/openpilotgcs/src/plugins/hitl/il2simulator.h index 91c8684cf..fc6b7cc5a 100644 --- a/ground/openpilotgcs/src/plugins/hitlnew/il2simulator.h +++ b/ground/openpilotgcs/src/plugins/hitl/il2simulator.h @@ -62,7 +62,7 @@ private: float DENSITY(float pressure); float PRESSURE(float alt); - float CAS(float ias,float alt); + float TAS(float ias,float alt); void processUpdate(const QByteArray& data); float angleDifference(float a,float b); diff --git a/ground/openpilotgcs/src/plugins/hitlnew/images/arrow-down.png b/ground/openpilotgcs/src/plugins/hitl/images/arrow-down.png similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlnew/images/arrow-down.png rename to ground/openpilotgcs/src/plugins/hitl/images/arrow-down.png diff --git a/ground/openpilotgcs/src/plugins/hitlnew/images/arrow-down2.png b/ground/openpilotgcs/src/plugins/hitl/images/arrow-down2.png similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlnew/images/arrow-down2.png rename to ground/openpilotgcs/src/plugins/hitl/images/arrow-down2.png diff --git a/ground/openpilotgcs/src/plugins/hitlnew/images/arrow-right.png b/ground/openpilotgcs/src/plugins/hitl/images/arrow-right.png similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlnew/images/arrow-right.png rename to ground/openpilotgcs/src/plugins/hitl/images/arrow-right.png diff --git a/ground/openpilotgcs/src/plugins/hitlnew/images/arrow-up.png b/ground/openpilotgcs/src/plugins/hitl/images/arrow-up.png similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlnew/images/arrow-up.png rename to ground/openpilotgcs/src/plugins/hitl/images/arrow-up.png diff --git a/ground/openpilotgcs/src/plugins/hitlnew/images/arrow-up2.png b/ground/openpilotgcs/src/plugins/hitl/images/arrow-up2.png similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlnew/images/arrow-up2.png rename to ground/openpilotgcs/src/plugins/hitl/images/arrow-up2.png diff --git a/ground/openpilotgcs/src/plugins/hitlnew/images/bullet_arrow_down.png b/ground/openpilotgcs/src/plugins/hitl/images/bullet_arrow_down.png similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlnew/images/bullet_arrow_down.png rename to ground/openpilotgcs/src/plugins/hitl/images/bullet_arrow_down.png diff --git a/ground/openpilotgcs/src/plugins/hitlnew/images/bullet_arrow_up.png b/ground/openpilotgcs/src/plugins/hitl/images/bullet_arrow_up.png similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlnew/images/bullet_arrow_up.png rename to ground/openpilotgcs/src/plugins/hitl/images/bullet_arrow_up.png diff --git a/ground/openpilotgcs/src/plugins/hitlnew/images/list_bullet_arrow.png b/ground/openpilotgcs/src/plugins/hitl/images/list_bullet_arrow.png similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlnew/images/list_bullet_arrow.png rename to ground/openpilotgcs/src/plugins/hitl/images/list_bullet_arrow.png diff --git a/ground/openpilotgcs/src/plugins/hitlnew/images/scrollbarvertical_down_arrow.png b/ground/openpilotgcs/src/plugins/hitl/images/scrollbarvertical_down_arrow.png similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlnew/images/scrollbarvertical_down_arrow.png rename to ground/openpilotgcs/src/plugins/hitl/images/scrollbarvertical_down_arrow.png diff --git a/ground/openpilotgcs/src/plugins/hitlnew/images/scrollbarvertical_up_arrow.png b/ground/openpilotgcs/src/plugins/hitl/images/scrollbarvertical_up_arrow.png similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlnew/images/scrollbarvertical_up_arrow.png rename to ground/openpilotgcs/src/plugins/hitl/images/scrollbarvertical_up_arrow.png diff --git a/ground/openpilotgcs/src/plugins/hitlnew/isimulator.h b/ground/openpilotgcs/src/plugins/hitl/isimulator.h similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlnew/isimulator.h rename to ground/openpilotgcs/src/plugins/hitl/isimulator.h diff --git a/ground/openpilotgcs/src/plugins/hitlnew/opfgprotocol.xml b/ground/openpilotgcs/src/plugins/hitl/opfgprotocol.xml similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlnew/opfgprotocol.xml rename to ground/openpilotgcs/src/plugins/hitl/opfgprotocol.xml diff --git a/ground/openpilotgcs/src/plugins/hitlnew/hitlnew.pro b/ground/openpilotgcs/src/plugins/hitl/plugin.pro similarity index 69% rename from ground/openpilotgcs/src/plugins/hitlnew/hitlnew.pro rename to ground/openpilotgcs/src/plugins/hitl/plugin.pro index 10658553d..066c60ec0 100644 --- a/ground/openpilotgcs/src/plugins/hitlnew/hitlnew.pro +++ b/ground/openpilotgcs/src/plugins/hitl/plugin.pro @@ -1,31 +1,37 @@ TEMPLATE = lib -TARGET = HITLNEW +TARGET = HITL QT += network + include(../../openpilotgcsplugin.pri) -include(hitlnew_dependencies.pri) +include(hitl_dependencies.pri) + HEADERS += hitlplugin.h \ hitlwidget.h \ hitloptionspage.h \ hitlfactory.h \ hitlconfiguration.h \ hitlgadget.h \ + hitlnoisegeneration.h \ simulator.h \ + aerosimrcsimulator.h \ fgsimulator.h \ il2simulator.h \ - xplanesimulator.h \ - hitlnoisegeneration.h + xplanesimulator.h SOURCES += hitlplugin.cpp \ hitlwidget.cpp \ hitloptionspage.cpp \ hitlfactory.cpp \ hitlconfiguration.cpp \ hitlgadget.cpp \ + hitlnoisegeneration.cpp \ simulator.cpp \ - il2simulator.cpp \ + aerosimrcsimulator.cpp \ fgsimulator.cpp \ - xplanesimulator.cpp \ - hitlnoisegeneration.cpp -OTHER_FILES += hitlnew.pluginspec + il2simulator.cpp \ + xplanesimulator.cpp +OTHER_FILES += hitl.pluginspec FORMS += hitloptionspage.ui \ hitlwidget.ui RESOURCES += hitlresources.qrc + + diff --git a/ground/openpilotgcs/src/plugins/hitl/simulator.cpp b/ground/openpilotgcs/src/plugins/hitl/simulator.cpp new file mode 100644 index 000000000..9eb5b6eec --- /dev/null +++ b/ground/openpilotgcs/src/plugins/hitl/simulator.cpp @@ -0,0 +1,717 @@ +/** + ****************************************************************************** + * + * @file simulator.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup HITLPlugin HITL Plugin + * @{ + * @brief The Hardware In The Loop 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 "simulator.h" +#include "qxtlogger.h" +#include "extensionsystem/pluginmanager.h" +#include "coreplugin/icore.h" +#include "coreplugin/threadmanager.h" +#include "hitlnoisegeneration.h" + +volatile bool Simulator::isStarted = false; + +const float Simulator::GEE = 9.81; +const float Simulator::FT2M = 0.3048; +const float Simulator::KT2MPS = 0.514444444; +const float Simulator::INHG2KPA = 3.386; +const float Simulator::FPS2CMPS = 30.48; +const float Simulator::DEG2RAD = (M_PI/180.0); +const float Simulator::RAD2DEG = (180.0/M_PI); + + +Simulator::Simulator(const SimulatorSettings& params) : + simProcess(NULL), + time(NULL), + inSocket(NULL), + outSocket(NULL), + settings(params), + updatePeriod(50), + simTimeout(8000), + autopilotConnectionStatus(false), + simConnectionStatus(false), + txTimer(NULL), + simTimer(NULL), + name("") +{ + // move to thread + moveToThread(Core::ICore::instance()->threadManager()->getRealTimeThread()); + connect(this, SIGNAL(myStart()), this, SLOT(onStart()),Qt::QueuedConnection); + emit myStart(); + + QTime currentTime=QTime::currentTime(); + gpsPosTime = currentTime; + groundTruthTime = currentTime; + gcsRcvrTime = currentTime; + attRawTime = currentTime; + baroAltTime = currentTime; + airspeedActualTime=currentTime; + +} + +Simulator::~Simulator() +{ + if(inSocket) + { + delete inSocket; + inSocket = NULL; + } + + if(outSocket) + { + delete outSocket; + outSocket = NULL; + } + + if(txTimer) + { + delete txTimer; + txTimer = NULL; + } + + if(simTimer) + { + delete simTimer; + simTimer = NULL; + } + // NOTE: Does not currently work, may need to send control+c to through the terminal + if (simProcess != NULL) + { + //connect(simProcess,SIGNAL(finished(int, QProcess::ExitStatus)),this,SLOT(onFinished(int, QProcess::ExitStatus))); + + simProcess->disconnect(); + if(simProcess->state() == QProcess::Running) + simProcess->kill(); + //if(simProcess->waitForFinished()) + //emit deleteSimProcess(); + delete simProcess; + simProcess = NULL; + } +} + +void Simulator::onDeleteSimulator(void) +{ + // [1] + Simulator::setStarted(false); + // [2] + Simulator::Instances().removeOne(simulatorId); + + disconnect(this); + delete this; +} + +void Simulator::onStart() +{ + QMutexLocker locker(&lock); + + QThread* mainThread = QThread::currentThread(); + + qDebug() << "Simulator Thread: "<< mainThread; + + // Get required UAVObjects + ExtensionSystem::PluginManager* pm = ExtensionSystem::PluginManager::instance(); + UAVObjectManager* objManager = pm->getObject(); + actDesired = ActuatorDesired::GetInstance(objManager); + actCommand = ActuatorCommand::GetInstance(objManager); + manCtrlCommand = ManualControlCommand::GetInstance(objManager); + gcsReceiver= GCSReceiver::GetInstance(objManager); + flightStatus = FlightStatus::GetInstance(objManager); + posHome = HomeLocation::GetInstance(objManager); + velActual = VelocityActual::GetInstance(objManager); + posActual = PositionActual::GetInstance(objManager); + baroAlt = BaroAltitude::GetInstance(objManager); + airspeedActual = AirspeedActual::GetInstance(objManager); + attActual = AttitudeActual::GetInstance(objManager); + attSettings = AttitudeSettings::GetInstance(objManager); + accels = Accels::GetInstance(objManager); + gyros = Gyros::GetInstance(objManager); + gpsPos = GPSPosition::GetInstance(objManager); + gpsVel = GPSVelocity::GetInstance(objManager); + telStats = GCSTelemetryStats::GetInstance(objManager); + + // Listen to autopilot connection events + TelemetryManager* telMngr = pm->getObject(); + connect(telMngr, SIGNAL(connected()), this, SLOT(onAutopilotConnect())); + connect(telMngr, SIGNAL(disconnected()), this, SLOT(onAutopilotDisconnect())); + //connect(telStats, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(telStatsUpdated(UAVObject*))); + + // If already connect setup autopilot + GCSTelemetryStats::DataFields stats = telStats->getData(); + if ( stats.Status == GCSTelemetryStats::STATUS_CONNECTED ) + onAutopilotConnect(); + + inSocket = new QUdpSocket(); + outSocket = new QUdpSocket(); + setupUdpPorts(settings.hostAddress,settings.inPort,settings.outPort); + + emit processOutput("\nLocal interface: " + settings.hostAddress + "\n" + \ + "Remote interface: " + settings.remoteAddress + "\n" + \ + "inputPort: " + QString::number(settings.inPort) + "\n" + \ + "outputPort: " + QString::number(settings.outPort) + "\n"); + + qxtLog->info("\nLocal interface: " + settings.hostAddress + "\n" + \ + "Remote interface: " + settings.remoteAddress + "\n" + \ + "inputPort: " + QString::number(settings.inPort) + "\n" + \ + "outputPort: " + QString::number(settings.outPort) + "\n"); + +// if(!inSocket->waitForConnected(5000)) +// emit processOutput(QString("Can't connect to %1 on %2 port!").arg(settings.hostAddress).arg(settings.inPort)); +// outSocket->connectToHost(settings.hostAddress,settings.outPort); // FG +// if(!outSocket->waitForConnected(5000)) +// emit processOutput(QString("Can't connect to %1 on %2 port!").arg(settings.hostAddress).arg(settings.outPort)); + + + connect(inSocket, SIGNAL(readyRead()), this, SLOT(receiveUpdate()),Qt::DirectConnection); + + // Setup transmit timer + txTimer = new QTimer(); + connect(txTimer, SIGNAL(timeout()), this, SLOT(transmitUpdate()),Qt::DirectConnection); + txTimer->setInterval(updatePeriod); + txTimer->start(); + // Setup simulator connection timer + simTimer = new QTimer(); + connect(simTimer, SIGNAL(timeout()), this, SLOT(onSimulatorConnectionTimeout()),Qt::DirectConnection); + simTimer->setInterval(simTimeout); + simTimer->start(); + + // setup time + time = new QTime(); + time->start(); + current.T=0; + current.i=0; + +} + +void Simulator::receiveUpdate() +{ + // Update connection timer and status + simTimer->setInterval(simTimeout); + simTimer->stop(); + simTimer->start(); + if ( !simConnectionStatus ) + { + simConnectionStatus = true; + emit simulatorConnected(); + } + + // Process data + while(inSocket->hasPendingDatagrams()) { + // Receive datagram + QByteArray datagram; + datagram.resize(inSocket->pendingDatagramSize()); + QHostAddress sender; + quint16 senderPort; + inSocket->readDatagram(datagram.data(), datagram.size(), + &sender, &senderPort); + //QString datastr(datagram); + // Process incomming data + processUpdate(datagram); + } +} + +void Simulator::setupObjects() +{ + + if (settings.gcsReceiverEnabled) { + setupInputObject(actCommand, settings.minOutputPeriod); //Input to the simulator + setupOutputObject(gcsReceiver, settings.minOutputPeriod); + } else if (settings.manualControlEnabled) { + setupInputObject(actDesired, settings.minOutputPeriod); //Input to the simulator + } + + setupOutputObject(posHome, 10000); //Hardcoded? Bleh. + + if (settings.gpsPositionEnabled){ + setupOutputObject(gpsPos, settings.gpsPosRate); + setupOutputObject(gpsVel, settings.gpsPosRate); + } + + if (settings.groundTruthEnabled){ + setupOutputObject(posActual, settings.groundTruthRate); + setupOutputObject(velActual, settings.groundTruthRate); + } + + if (settings.attRawEnabled) { + setupOutputObject(accels, settings.attRawRate); + setupOutputObject(gyros, settings.attRawRate); + } + + if (settings.attActualEnabled && settings.attActHW) { + setupOutputObject(accels, settings.attRawRate); + setupOutputObject(gyros, settings.attRawRate); + } + + if (settings.attActualEnabled && !settings.attActHW) + setupOutputObject(attActual, 20); //Hardcoded? Bleh. + else + setupWatchedObject(attActual, 100); //Hardcoded? Bleh. + + if(settings.airspeedActualEnabled) + setupOutputObject(airspeedActual, settings.airspeedActualRate); + + if(settings.baroAltitudeEnabled) + setupOutputObject(baroAlt, settings.baroAltRate); + +} + + +void Simulator::setupInputObject(UAVObject* obj, quint32 updatePeriod) +{ + UAVObject::Metadata mdata; + mdata = obj->getDefaultMetadata(); + + UAVObject::SetGcsAccess(mdata, UAVObject::ACCESS_READONLY); + UAVObject::SetGcsTelemetryAcked(mdata, false); + UAVObject::SetGcsTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_MANUAL); + mdata.gcsTelemetryUpdatePeriod = 0; + + UAVObject::SetFlightAccess(mdata, UAVObject::ACCESS_READWRITE); + UAVObject::SetFlightTelemetryAcked(mdata, false); + + UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC); + mdata.flightTelemetryUpdatePeriod = updatePeriod; + + obj->setMetadata(mdata); +} + + +void Simulator::setupWatchedObject(UAVObject *obj, quint32 updatePeriod) +{ + UAVObject::Metadata mdata; + mdata = obj->getDefaultMetadata(); + + UAVObject::SetGcsAccess(mdata, UAVObject::ACCESS_READONLY); + UAVObject::SetGcsTelemetryAcked(mdata, false); + UAVObject::SetGcsTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_MANUAL); + mdata.gcsTelemetryUpdatePeriod = 0; + + UAVObject::SetFlightAccess(mdata, UAVObject::ACCESS_READWRITE); + UAVObject::SetFlightTelemetryAcked(mdata, false); + UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC); + mdata.flightTelemetryUpdatePeriod = updatePeriod; + + obj->setMetadata(mdata); +} + + +void Simulator::setupOutputObject(UAVObject* obj, quint32 updatePeriod) +{ + UAVObject::Metadata mdata; + mdata = obj->getDefaultMetadata(); + + UAVObject::SetGcsAccess(mdata, UAVObject::ACCESS_READWRITE); + UAVObject::SetGcsTelemetryAcked(mdata, false); + UAVObject::SetGcsTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC); + mdata.gcsTelemetryUpdatePeriod = updatePeriod; + + UAVObject::SetFlightAccess(mdata, UAVObject::ACCESS_READONLY); + UAVObject::SetFlightTelemetryUpdateMode(mdata,UAVObject::UPDATEMODE_MANUAL); + + obj->setMetadata(mdata); +} + +void Simulator::onAutopilotConnect() +{ + autopilotConnectionStatus = true; + setupObjects(); + emit autopilotConnected(); +} + +void Simulator::onAutopilotDisconnect() +{ + autopilotConnectionStatus = false; + emit autopilotDisconnected(); +} + +void Simulator::onSimulatorConnectionTimeout() +{ + if ( simConnectionStatus ) + { + simConnectionStatus = false; + emit simulatorDisconnected(); + } +} + + +void Simulator::telStatsUpdated(UAVObject* obj) +{ + Q_UNUSED(obj); + + GCSTelemetryStats::DataFields stats = telStats->getData(); + if ( !autopilotConnectionStatus && stats.Status == GCSTelemetryStats::STATUS_CONNECTED ) + { + onAutopilotConnect(); + } + else if ( autopilotConnectionStatus && stats.Status != GCSTelemetryStats::STATUS_CONNECTED ) + { + onAutopilotDisconnect(); + } +} + + +void Simulator::resetInitialHomePosition(){ + once=false; +} + + +void Simulator::updateUAVOs(Output2Hardware out){ + + QTime currentTime = QTime::currentTime(); + + Noise noise; + HitlNoiseGeneration noiseSource; + + if(settings.addNoise){ + noise = noiseSource.generateNoise(); + } + else{ + memset(&noise, 0, sizeof(Noise)); + } + + HomeLocation::DataFields homeData = posHome->getData(); + if(!once) + { + // Upon startup, we reset the HomeLocation object to + // the plane's location: + memset(&homeData, 0, sizeof(HomeLocation::DataFields)); + // Update homelocation + homeData.Latitude = out.latitude; //Already in *10^7 integer format + homeData.Longitude = out.longitude; //Already in *10^7 integer format + homeData.Altitude = out.altitude; + double LLA[3]; + LLA[0]=out.latitude; + LLA[1]=out.longitude; + LLA[2]=out.altitude; + double ECEF[3]; + double RNE[9]; + Utils::CoordinateConversions().RneFromLLA(LLA,(double (*)[3])RNE); + Utils::CoordinateConversions().LLA2ECEF(LLA,ECEF); + homeData.Be[0]=0; + homeData.Be[1]=0; + homeData.Be[2]=0; + posHome->setData(homeData); + posHome->updated(); + + // Compute initial distance + initN = out.dstN; + initE = out.dstE; + initD = out.dstD; + + once=true; + } + + + // Update attActual object + AttitudeActual::DataFields attActualData; + attActualData = attActual->getData(); + + if (settings.attActHW) { + // do nothing + /*****************************************/ + } else if (settings.attActSim) { + // take all data from simulator + attActualData.Roll = out.roll + noise.attActualData.Roll; //roll; + attActualData.Pitch = out.pitch + noise.attActualData.Pitch; // pitch + attActualData.Yaw = out.heading + noise.attActualData.Yaw; // Yaw + float rpy[3]; + float quat[4]; + rpy[0] = attActualData.Roll; + rpy[1] = attActualData.Pitch; + rpy[2] = attActualData.Yaw; + Utils::CoordinateConversions().RPY2Quaternion(rpy,quat); + attActualData.q1 = quat[0]; + attActualData.q2 = quat[1]; + attActualData.q3 = quat[2]; + attActualData.q4 = quat[3]; + + //Set UAVO + attActual->setData(attActualData); + /*****************************************/ + } else if (settings.attActCalc) { + // calculate RPY with code from Attitude module + static float q[4] = {1, 0, 0, 0}; + static float gyro_correct_int2 = 0; + + float dT = out.delT; + + AttitudeSettings::DataFields attSettData = attSettings->getData(); + float accelKp = attSettData.AccelKp * 0.1666666666666667; + float accelKi = attSettData.AccelKp * 0.1666666666666667; + float yawBiasRate = attSettData.YawBiasRate; + + // calibrate sensors on arming + if (flightStatus->getData().Armed == FlightStatus::ARMED_ARMING) { + accelKp = 2.0; + accelKi = 0.9; + } + + float gyro[3] = {out.rollRate, out.pitchRate, out.yawRate}; + float attRawAcc[3] = {out.accX, out.accY, out.accZ}; + + // code from Attitude module begin /////////////////////////////// + float *accels = attRawAcc; + 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 + { + accel_err[0] = accels[1]*grot[2] - grot[1]*accels[2]; + accel_err[1] = grot[0]*accels[2] - accels[0]*grot[2]; + accel_err[2] = accels[0]*grot[1] - grot[0]*accels[1]; + } + + // 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_int2 += -gyro[2] * yawBiasRate; + + // 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 + gyro_correct_int2; + + // Work out time derivative from INSAlgo writeup + // Also accounts for the fact that gyros are in deg/s + float qdot[4]; + qdot[0] = (-q[1] * gyro[0] - q[2] * gyro[1] - q[3] * gyro[2]) * dT * M_PI / 180 / 2; + 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] += qdot[0]; + q[1] += qdot[1]; + q[2] += qdot[2]; + q[3] += qdot[3]; + + if(q[0] < 0) { + q[0] = -q[0]; + q[1] = -q[1]; + q[2] = -q[2]; + 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] /= qmag; + q[1] /= qmag; + q[2] /= qmag; + q[3] /= qmag; + + // If quaternion has become inappropriately short or is nan reinit. + // THIS SHOULD NEVER ACTUALLY HAPPEN + if((fabs(qmag) < 1e-3) || (qmag != qmag)) { + q[0] = 1; + q[1] = 0; + q[2] = 0; + q[3] = 0; + } + + float rpy2[3]; + // Quaternion2RPY + { + float q0s, q1s, q2s, q3s; + q0s = q[0] * q[0]; + q1s = q[1] * q[1]; + q2s = q[2] * q[2]; + q3s = q[3] * q[3]; + + float R13, R11, R12, R23, R33; + R13 = 2 * (q[1] * q[3] - q[0] * q[2]); + R11 = q0s + q1s - q2s - q3s; + R12 = 2 * (q[1] * q[2] + q[0] * q[3]); + R23 = 2 * (q[2] * q[3] + q[0] * q[1]); + R33 = q0s - q1s - q2s + q3s; + + rpy2[1] = RAD2DEG * asinf(-R13); // pitch always between -pi/2 to pi/2 + rpy2[2] = RAD2DEG * atan2f(R12, R11); + rpy2[0] = RAD2DEG * atan2f(R23, R33); + } + + attActualData.Roll = rpy2[0]; + attActualData.Pitch = rpy2[1]; + attActualData.Yaw = rpy2[2]; + attActualData.q1 = q[0]; + attActualData.q2 = q[1]; + attActualData.q3 = q[2]; + attActualData.q4 = q[3]; + + //Set UAVO + attActual->setData(attActualData); + /*****************************************/ + } + + if (settings.gcsReceiverEnabled) { + if (gcsRcvrTime.msecsTo(currentTime) >= settings.minOutputPeriod) { + GCSReceiver::DataFields gcsRcvrData; + memset(&gcsRcvrData, 0, sizeof(GCSReceiver::DataFields)); + + for (quint16 i = 0; i < GCSReceiver::CHANNEL_NUMELEM; i++){ + gcsRcvrData.Channel[i] = 1500 + (out.rc_channel[i]*500); //Elements in rc_channel are between -1 and 1 + } + + gcsReceiver->setData(gcsRcvrData); + + gcsRcvrTime=gcsRcvrTime.addMSecs(settings.minOutputPeriod); + + } + } + + + if (settings.gpsPositionEnabled) { + if (gpsPosTime.msecsTo(currentTime) >= settings.gpsPosRate) { + qDebug()<< " GPS time:" << gpsPosTime << ", currentTime: " << currentTime << ", difference: " << gpsPosTime.msecsTo(currentTime); + // Update GPS Position objects + GPSPosition::DataFields gpsPosData; + memset(&gpsPosData, 0, sizeof(GPSPosition::DataFields)); + gpsPosData.Altitude = out.altitude + noise.gpsPosData.Altitude; + gpsPosData.Heading = out.heading + noise.gpsPosData.Heading; + gpsPosData.Groundspeed = out.groundspeed + noise.gpsPosData.Groundspeed; + gpsPosData.Latitude = out.latitude + noise.gpsPosData.Latitude; //Already in *10^7 integer format + gpsPosData.Longitude = out.longitude + noise.gpsPosData.Longitude; //Already in *10^7 integer format + gpsPosData.GeoidSeparation = 0.0; + gpsPosData.PDOP = 3.0; + gpsPosData.VDOP = gpsPosData.PDOP*1.5; + gpsPosData.Satellites = 10; + gpsPosData.Status = GPSPosition::STATUS_FIX3D; + + gpsPos->setData(gpsPosData); + + // Update GPS Velocity.{North,East,Down} + GPSVelocity::DataFields gpsVelData; + memset(&gpsVelData, 0, sizeof(GPSVelocity::DataFields)); + gpsVelData.North = out.velNorth + noise.gpsVelData.North; + gpsVelData.East = out.velEast + noise.gpsVelData.East; + gpsVelData.Down = out.velDown + noise.gpsVelData.Down; + + gpsVel->setData(gpsVelData); + + gpsPosTime=gpsPosTime.addMSecs(settings.gpsPosRate); + } + } + + // Update VelocityActual.{North,East,Down} + if (settings.groundTruthEnabled) { + if (groundTruthTime.msecsTo(currentTime) >= settings.groundTruthRate) { + VelocityActual::DataFields velocityActualData; + memset(&velocityActualData, 0, sizeof(VelocityActual::DataFields)); + velocityActualData.North = out.velNorth + noise.velocityActualData.North; + velocityActualData.East = out.velEast + noise.velocityActualData.East; + velocityActualData.Down = out.velDown + noise.velocityActualData.Down; + velActual->setData(velocityActualData); + + // Update PositionActual.{Nort,East,Down} + PositionActual::DataFields positionActualData; + memset(&positionActualData, 0, sizeof(PositionActual::DataFields)); + positionActualData.North = (out.dstN-initN) + noise.positionActualData.North; + positionActualData.East = (out.dstE-initE) + noise.positionActualData.East; + positionActualData.Down = (out.dstD/*-initD*/) + noise.positionActualData.Down; + posActual->setData(positionActualData); + + groundTruthTime=groundTruthTime.addMSecs(settings.groundTruthRate); + } + } + +// if (settings.sonarAltitude) { +// static QTime sonarAltTime = currentTime; +// if (sonarAltTime.msecsTo(currentTime) >= settings.sonarAltRate) { +// SonarAltitude::DataFields sonarAltData; +// sonarAltData = sonarAlt->getData(); + +// float sAlt = settings.sonarMaxAlt; +// // 0.35 rad ~= 20 degree +// if ((agl < (sAlt * 2.0)) && (roll < 0.35) && (pitch < 0.35)) { +// float x = agl * qTan(roll); +// float y = agl * qTan(pitch); +// float h = qSqrt(x*x + y*y + agl*agl); +// sAlt = qMin(h, sAlt); +// } + +// sonarAltData.Altitude = sAlt; +// sonarAlt->setData(sonarAltData); +// sonarAltTime = currentTime; +// } +// } + + // Update BaroAltitude object + if (settings.baroAltitudeEnabled){ + if (baroAltTime.msecsTo(currentTime) >= settings.baroAltRate) { + BaroAltitude::DataFields baroAltData; + memset(&baroAltData, 0, sizeof(BaroAltitude::DataFields)); + baroAltData.Altitude = out.altitude + noise.baroAltData.Altitude; + baroAltData.Temperature = out.temperature + noise.baroAltData.Temperature; + baroAltData.Pressure = out.pressure + noise.baroAltData.Pressure; + baroAlt->setData(baroAltData); + + baroAltTime=baroAltTime.addMSecs(settings.baroAltRate); + } + } + + // Update AirspeedActual object + if (settings.airspeedActualEnabled){ + if (airspeedActualTime.msecsTo(currentTime) >= settings.airspeedActualRate) { + AirspeedActual::DataFields airspeedActualData; + memset(&airspeedActualData, 0, sizeof(AirspeedActual::DataFields)); + airspeedActualData.CalibratedAirspeed = out.calibratedAirspeed + noise.airspeedActual.CalibratedAirspeed; + airspeedActual->setData(airspeedActualData); + + airspeedActualTime=airspeedActualTime.addMSecs(settings.airspeedActualRate); + } + } + + // Update raw attitude sensors + if (settings.attRawEnabled) { + if (attRawTime.msecsTo(currentTime) >= settings.attRawRate) { + //Update gyroscope sensor data + Gyros::DataFields gyroData; + memset(&gyroData, 0, sizeof(Gyros::DataFields)); + gyroData.x = out.rollRate + noise.gyroData.x; + gyroData.y = out.pitchRate + noise.gyroData.y; + gyroData.z = out.yawRate + noise.gyroData.z; + gyros->setData(gyroData); + + //Update accelerometer sensor data + Accels::DataFields accelData; + memset(&accelData, 0, sizeof(Accels::DataFields)); + accelData.x = out.accX + noise.accelData.x; + accelData.y = out.accY + noise.accelData.y; + accelData.z = out.accZ + noise.accelData.z; + accels->setData(accelData); + + attRawTime=attRawTime.addMSecs(settings.attRawRate); + } + } +} diff --git a/ground/openpilotgcs/src/plugins/hitlnew/simulator.h b/ground/openpilotgcs/src/plugins/hitl/simulator.h similarity index 75% rename from ground/openpilotgcs/src/plugins/hitlnew/simulator.h rename to ground/openpilotgcs/src/plugins/hitl/simulator.h index a872fc117..41de0937d 100644 --- a/ground/openpilotgcs/src/plugins/hitlnew/simulator.h +++ b/ground/openpilotgcs/src/plugins/hitl/simulator.h @@ -32,23 +32,30 @@ #include #include #include +#include + #include "qscopedpointer.h" #include "uavtalk/telemetrymanager.h" #include "uavobjectmanager.h" + +#include "accels.h" +#include "actuatorcommand.h" #include "actuatordesired.h" -#include "manualcontrolcommand.h" -#include "positionactual.h" -#include "velocityactual.h" -#include "baroaltitude.h" -#include "baroairspeed.h" #include "attitudeactual.h" +#include "attitudesettings.h" +#include "airspeedactual.h" +#include "baroaltitude.h" +#include "flightstatus.h" +#include "gcsreceiver.h" +#include "gcstelemetrystats.h" #include "gpsposition.h" #include "gpsvelocity.h" -#include "homelocation.h" -#include "accels.h" #include "gyros.h" -#include "gcstelemetrystats.h" -#include "flightstatus.h" +#include "homelocation.h" +#include "manualcontrolcommand.h" +#include "positionactual.h" +#include "sonaraltitude.h" +#include "velocityactual.h" #include "utils/coordinateconversions.h" @@ -101,26 +108,53 @@ typedef struct _CONNECTION QString binPath; QString dataPath; QString hostAddress; - QString remoteHostAddress; + QString remoteAddress; int outPort; int inPort; - bool manual; bool startSim; bool addNoise; QString latitude; QString longitude; + +// bool homeLocation; + + bool attRawEnabled; + quint8 attRawRate; + + bool attActualEnabled; + bool attActHW; + bool attActSim; + bool attActCalc; + + bool baroAltitudeEnabled; + quint16 baroAltRate; + + bool groundTruthEnabled; + quint16 groundTruthRate; + + bool gpsPositionEnabled; + quint16 gpsPosRate; + + bool inputCommand; + bool gcsReceiverEnabled; + bool manualControlEnabled; + quint16 minOutputPeriod; + + bool airspeedActualEnabled; + quint16 airspeedActualRate; + } SimulatorSettings; -struct Output2OP{ +struct Output2Hardware{ float latitude; float longitude; float altitude; float heading; float groundspeed; //[m/s] float calibratedAirspeed; //[m/s] - float pitch; float roll; + float pitch; float pressure; float temperature; float velNorth; //[m/s] @@ -132,11 +166,31 @@ struct Output2OP{ float accX; //[m/s^2] float accY; //[m/s^2] float accZ; //[m/s^2] - float rollRate; - float pitchRate; - float yawRate; + float rollRate; //[deg/s] + float pitchRate; //[deg/s] + float yawRate; //[deg/s] + float delT; + + float rc_channel[GCSReceiver::CHANNEL_NUMELEM]; //Elements in rc_channel are between -1 and 1 + + + float rollDesired; + float pitchDesired; + float yawDesired; + float throttleDesired; }; +//struct Output2Simulator{ +// float roll; +// float pitch; +// float yaw; +// float throttle; + +// float ailerons; +// float rudder; +// float elevator; +// float motor; +//}; class Simulator : public QObject { @@ -165,7 +219,7 @@ public: virtual void setupUdpPorts(const QString& host, int inPort, int outPort) { Q_UNUSED(host) Q_UNUSED(inPort) Q_UNUSED(outPort)} void resetInitialHomePosition(); - void updateUAVOs(Output2OP out); + void updateUAVOs(Output2Hardware out); signals: void autopilotConnected(); @@ -197,18 +251,21 @@ protected: static const float INHG2KPA; static const float FPS2CMPS; static const float DEG2RAD; + static const float RAD2DEG; QProcess* simProcess; QTime* time; QUdpSocket* inSocket;//(new QUdpSocket()); QUdpSocket* outSocket; + ActuatorCommand* actCommand; ActuatorDesired* actDesired; ManualControlCommand* manCtrlCommand; FlightStatus* flightStatus; BaroAltitude* baroAlt; - BaroAirspeed* baroAirspeed; + AirspeedActual* airspeedActual; AttitudeActual* attActual; + AttitudeSettings* attSettings; VelocityActual* velActual; GPSPosition* gpsPos; GPSVelocity* gpsVel; @@ -217,6 +274,7 @@ protected: Accels* accels; Gyros* gyros; GCSTelemetryStats* telStats; + GCSReceiver* gcsReceiver; SimulatorSettings settings; @@ -236,13 +294,22 @@ private: volatile bool simConnectionStatus; QTimer* txTimer; QTimer* simTimer; + + QTime attRawTime; + QTime gpsPosTime; + QTime groundTruthTime; + QTime baroAltTime; + QTime gcsRcvrTime; + QTime airspeedActualTime; + QString name; QString simulatorId; volatile static bool isStarted; static QStringList instances; //QList > requiredUAVObjects; - void setupOutputObject(UAVObject* obj, int updatePeriod); - void setupInputObject(UAVObject* obj, int updatePeriod); + void setupOutputObject(UAVObject* obj, quint32 updatePeriod); + void setupInputObject(UAVObject* obj, quint32 updatePeriod); + void setupWatchedObject(UAVObject *obj, quint32 updatePeriod); void setupObjects(); }; diff --git a/ground/openpilotgcs/src/plugins/hitlnew/xplanesimulator.cpp b/ground/openpilotgcs/src/plugins/hitl/xplanesimulator.cpp similarity index 65% rename from ground/openpilotgcs/src/plugins/hitlnew/xplanesimulator.cpp rename to ground/openpilotgcs/src/plugins/hitl/xplanesimulator.cpp index e2b9b9630..448e6f45a 100644 --- a/ground/openpilotgcs/src/plugins/hitlnew/xplanesimulator.cpp +++ b/ground/openpilotgcs/src/plugins/hitl/xplanesimulator.cpp @@ -78,6 +78,8 @@ XplaneSimulator::~XplaneSimulator() void XplaneSimulator::setupUdpPorts(const QString& host, int inPort, int outPort) { + Q_UNUSED(outPort); + inSocket->bind(QHostAddress(host), inPort); //outSocket->bind(QHostAddress(host), outPort); resetInitialHomePosition(); @@ -97,29 +99,30 @@ bool XplaneSimulator::setupProcess() */ void XplaneSimulator::transmitUpdate() { - //Read ActuatorDesired from autopilot - ActuatorDesired::DataFields actData = actDesired->getData(); - float ailerons = actData.Roll; - float elevator = actData.Pitch; - float rudder = actData.Yaw; - float throttle = actData.Throttle > 0? actData.Throttle : 0; - float none = -999; - //quint32 none = *((quint32*)&tmp); // get float as 4 bytes - - quint32 code; - QByteArray buf; - QDataStream stream(&buf,QIODevice::ReadWrite); - - // !!! LAN byte order - Big Endian + if (settings.manualControlEnabled) { + //Read ActuatorDesired from autopilot + ActuatorDesired::DataFields actData = actDesired->getData(); + float ailerons = actData.Roll; + float elevator = actData.Pitch; + float rudder = actData.Yaw; + float throttle = actData.Throttle > 0? actData.Throttle : 0; + float none = -999; + //quint32 none = *((quint32*)&tmp); // get float as 4 bytes + + quint32 code; + QByteArray buf; + QDataStream stream(&buf,QIODevice::ReadWrite); + + // !!! LAN byte order - Big Endian #if Q_BYTE_ORDER == Q_LITTLE_ENDIAN - stream.setByteOrder(QDataStream::LittleEndian); + stream.setByteOrder(QDataStream::LittleEndian); #endif - - // 11th data settings (flight con: ail/elv/rud) - buf.clear(); - code = 11; - //quint8 header[] = "DATA"; - /* + + // 11th data settings (flight con: ail/elv/rud) + buf.clear(); + code = 11; + //quint8 header[] = "DATA"; + /* stream << *((quint32*)header) << (quint8)0x30 << code << @@ -132,57 +135,58 @@ void XplaneSimulator::transmitUpdate() none << none; */ - buf.append("DATA0"); - buf.append(reinterpret_cast(&code), sizeof(code)); - buf.append(reinterpret_cast(&elevator), sizeof(elevator)); - buf.append(reinterpret_cast(&ailerons), sizeof(ailerons)); - buf.append(reinterpret_cast(&rudder), sizeof(rudder)); - buf.append(reinterpret_cast(&none), sizeof(none)); - buf.append(reinterpret_cast(&rudder), sizeof(rudder)); - buf.append(reinterpret_cast(&none), sizeof(none)); - buf.append(reinterpret_cast(&none), sizeof(none)); - buf.append(reinterpret_cast(&none), sizeof(none)); -// TraceBuf(buf.data(),41); - - if(outSocket->writeDatagram(buf, QHostAddress(settings.remoteHostAddress), settings.outPort) == -1) - { - emit processOutput("Error sending UDP packet to XPlane: " + outSocket->errorString() + "\n"); - } - //outSocket->write(buf); - - // 25th data settings (throttle command) - buf.clear(); - code = 25; - //stream << *((quint32*)header) << (quint8)0x30 << code << *((quint32*)&throttle) << none << none - // << none << none << none << none << none; - buf.append("DATA0"); - buf.append(reinterpret_cast(&code), sizeof(code)); - buf.append(reinterpret_cast(&throttle), sizeof(throttle)); - buf.append(reinterpret_cast(&throttle), sizeof(throttle)); - buf.append(reinterpret_cast(&throttle), sizeof(throttle)); - buf.append(reinterpret_cast(&throttle), sizeof(throttle)); - buf.append(reinterpret_cast(&none), sizeof(none)); - buf.append(reinterpret_cast(&none), sizeof(none)); - buf.append(reinterpret_cast(&none), sizeof(none)); - buf.append(reinterpret_cast(&none), sizeof(none)); - - if(outSocket->writeDatagram(buf, QHostAddress(settings.remoteHostAddress), settings.outPort) == -1) - { - emit processOutput("Error sending UDP packet to XPlane: " + outSocket->errorString() + "\n"); - } - - //outSocket->write(buf); - - - - /** !!! this settings was given from ardupilot X-Plane.pl, I comment them + buf.append("DATA0"); + buf.append(reinterpret_cast(&code), sizeof(code)); + buf.append(reinterpret_cast(&elevator), sizeof(elevator)); + buf.append(reinterpret_cast(&ailerons), sizeof(ailerons)); + buf.append(reinterpret_cast(&rudder), sizeof(rudder)); + buf.append(reinterpret_cast(&none), sizeof(none)); + buf.append(reinterpret_cast(&rudder), sizeof(rudder)); + buf.append(reinterpret_cast(&none), sizeof(none)); + buf.append(reinterpret_cast(&none), sizeof(none)); + buf.append(reinterpret_cast(&none), sizeof(none)); +// TraceBuf(buf.data(),41); + + if(outSocket->writeDatagram(buf, QHostAddress(settings.remoteAddress), settings.outPort) == -1) + { + emit processOutput("Error sending UDP packet to XPlane: " + outSocket->errorString() + "\n"); + } + //outSocket->write(buf); + + // 25th data settings (throttle command) + buf.clear(); + code = 25; + //stream << *((quint32*)header) << (quint8)0x30 << code << *((quint32*)&throttle) << none << none + // << none << none << none << none << none; + buf.append("DATA0"); + buf.append(reinterpret_cast(&code), sizeof(code)); + buf.append(reinterpret_cast(&throttle), sizeof(throttle)); + buf.append(reinterpret_cast(&throttle), sizeof(throttle)); + buf.append(reinterpret_cast(&throttle), sizeof(throttle)); + buf.append(reinterpret_cast(&throttle), sizeof(throttle)); + buf.append(reinterpret_cast(&none), sizeof(none)); + buf.append(reinterpret_cast(&none), sizeof(none)); + buf.append(reinterpret_cast(&none), sizeof(none)); + buf.append(reinterpret_cast(&none), sizeof(none)); + + if(outSocket->writeDatagram(buf, QHostAddress(settings.remoteAddress), settings.outPort) == -1) + { + emit processOutput("Error sending UDP packet to XPlane: " + outSocket->errorString() + "\n"); + } + + //outSocket->write(buf); + + + + /** !!! this settings was given from ardupilot X-Plane.pl, I comment them but if it needed comment should be removed !!! - + // 8th data settings (joystick 1 ail/elv/rud) stream << "DATA0" << quint32(11) << elevator << ailerons << rudder << float(-999) << float(-999) << float(-999) << float(-999) << float(-999); outSocket->write(buf); */ + } } @@ -190,7 +194,7 @@ void XplaneSimulator::transmitUpdate() * process data string from X-Plane simulator */ void XplaneSimulator::processUpdate(const QByteArray& dataBuf) -{ +{ float altitude = 0; float latitude = 0; float longitude = 0; @@ -210,9 +214,9 @@ void XplaneSimulator::processUpdate(const QByteArray& dataBuf) float accX = 0; float accY = 0; float accZ = 0; - float rollRate=0; - float pitchRate=0; - float yawRate=0; + float rollRate_rad=0; + float pitchRate_rad=0; + float yawRate_rad=0; // QString str; QByteArray& buf = const_cast(dataBuf); @@ -254,7 +258,7 @@ void XplaneSimulator::processUpdate(const QByteArray& dataBuf) pressure = *((float*)(buf.data()+4*1)); break; */ - + case XplaneSimulator::AtmosphereWeather: pressure = *((float*)(buf.data()+4*1)) * INHG2KPA; temperature = *((float*)(buf.data()+4*2)); @@ -269,11 +273,11 @@ void XplaneSimulator::processUpdate(const QByteArray& dataBuf) velZ = *((float*)(buf.data()+4*5)); break; - case XplaneSimulator::AngularVelocities: - pitchRate = *((float*)(buf.data()+4*1)); - rollRate = *((float*)(buf.data()+4*2)); - yawRate = *((float*)(buf.data()+4*3)); - break; + case XplaneSimulator::AngularVelocities: //In [rad/s] + pitchRate_rad = *((float*)(buf.data()+4*1)); + rollRate_rad = *((float*)(buf.data()+4*2)); + yawRate_rad = *((float*)(buf.data()+4*3)); + break; case XplaneSimulator::Gload: accX = *((float*)(buf.data()+4*6)) * GEE; @@ -292,8 +296,8 @@ void XplaneSimulator::processUpdate(const QByteArray& dataBuf) /////// // Output formatting /////// - Output2OP out; - memset(&out, 0, sizeof(Output2OP)); + Output2Hardware out; + memset(&out, 0, sizeof(Output2Hardware)); // Update GPS Position objects out.latitude = latitude * 1e7; @@ -323,9 +327,9 @@ void XplaneSimulator::processUpdate(const QByteArray& dataBuf) out.velDown = -velZ; //Update gyroscope sensor data - out.rollRate = rollRate; - out.pitchRate = pitchRate; - out.yawRate = yawRate; + out.rollRate = rollRate_rad; + out.pitchRate = pitchRate_rad; + out.yawRate = yawRate_rad; //Update accelerometer sensor data out.accX = accX; @@ -344,23 +348,24 @@ void XplaneSimulator::processUpdate(const QByteArray& dataBuf) void TraceBuf(const char* buf,int len) { - QString str; - bool reminder=true; - for(int i=0; i < len; i++) - { - if(!(i%16)) - { - if(i>0) - { + QString str; + bool reminder=true; + for(int i=0; i < len; i++) + { + if(!(i%16)) + { + if(i>0) + { qDebug() << str; - str.clear(); - reminder=false; - } - reminder=true; - } - str+=QString(" 0x%1").arg((quint8)buf[i],2,16,QLatin1Char('0')); - } + str.clear(); + reminder=false; + } + reminder=true; + } + str+=QString(" 0x%1").arg((quint8)buf[i],2,16,QLatin1Char('0')); + } - if(reminder) + if(reminder){ qDebug() << str; + } } diff --git a/ground/openpilotgcs/src/plugins/hitlnew/xplanesimulator.h b/ground/openpilotgcs/src/plugins/hitl/xplanesimulator.h similarity index 100% rename from ground/openpilotgcs/src/plugins/hitlnew/xplanesimulator.h rename to ground/openpilotgcs/src/plugins/hitl/xplanesimulator.h diff --git a/ground/openpilotgcs/src/plugins/hitlnew/hitlconfiguration.cpp b/ground/openpilotgcs/src/plugins/hitlnew/hitlconfiguration.cpp deleted file mode 100644 index dbb589283..000000000 --- a/ground/openpilotgcs/src/plugins/hitlnew/hitlconfiguration.cpp +++ /dev/null @@ -1,89 +0,0 @@ -/** - ****************************************************************************** - * - * @file hitlconfiguration.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup HITLPlugin HITL Plugin - * @{ - * @brief The Hardware In The Loop 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 "hitlconfiguration.h" - -HITLConfiguration::HITLConfiguration(QString classId, QSettings* qSettings, QObject *parent) : - IUAVGadgetConfiguration(classId, parent) -{ - settings.simulatorId = ""; - settings.binPath = ""; - settings.dataPath = ""; - settings.manual = false; - settings.startSim = false; - settings.addNoise = false; - settings.hostAddress = "127.0.0.1"; - settings.remoteHostAddress = "127.0.0.1"; - settings.outPort = 0; - settings.inPort = 0; - settings.latitude = ""; - settings.longitude = ""; - - //if a saved configuration exists load it - if(qSettings != 0) { - settings.simulatorId = qSettings->value("simulatorId").toString(); - settings.binPath = qSettings->value("binPath").toString(); - settings.dataPath = qSettings->value("dataPath").toString(); - settings.manual = qSettings->value("manual").toBool(); - settings.addNoise = qSettings->value("noiseCheckBox").toBool(); - settings.startSim = qSettings->value("startSim").toBool(); - settings.hostAddress = qSettings->value("hostAddress").toString(); - settings.remoteHostAddress = qSettings->value("remoteHostAddress").toString(); - settings.outPort = qSettings->value("outPort").toInt(); - settings.inPort = qSettings->value("inPort").toInt(); - settings.latitude = qSettings->value("latitude").toString(); - settings.longitude = qSettings->value("longitude").toString(); - } -} - -IUAVGadgetConfiguration *HITLConfiguration::clone() -{ - HITLConfiguration *m = new HITLConfiguration(this->classId()); - - m->settings = settings; - return m; -} - -/** - * Saves a configuration. - * - */ -void HITLConfiguration::saveConfig(QSettings* qSettings) const { - qSettings->setValue("simulatorId", settings.simulatorId); - qSettings->setValue("binPath", settings.binPath); - qSettings->setValue("dataPath", settings.dataPath); - qSettings->setValue("manual", settings.manual); - qSettings->setValue("addNoise", settings.addNoise); - qSettings->setValue("startSim", settings.startSim); - qSettings->setValue("hostAddress", settings.hostAddress); - qSettings->setValue("remoteHostAddress", settings.remoteHostAddress); - qSettings->setValue("outPort", settings.outPort); - qSettings->setValue("inPort", settings.inPort); - qSettings->setValue("latitude", settings.latitude); - qSettings->setValue("longitude", settings.longitude); -} - diff --git a/ground/openpilotgcs/src/plugins/hitlnew/hitloptionspage.cpp b/ground/openpilotgcs/src/plugins/hitlnew/hitloptionspage.cpp deleted file mode 100644 index 70aefa2d3..000000000 --- a/ground/openpilotgcs/src/plugins/hitlnew/hitloptionspage.cpp +++ /dev/null @@ -1,118 +0,0 @@ -/** - ****************************************************************************** - * - * @file hitloptionspage.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup HITLPlugin HITL Plugin - * @{ - * @brief The Hardware In The Loop 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 "hitloptionspage.h" -#include "hitlconfiguration.h" -#include "ui_hitloptionspage.h" -#include - -#include -#include -#include -#include - - - -HITLOptionsPage::HITLOptionsPage(HITLConfiguration *conf, QObject *parent) : - IOptionsPage(parent), - config(conf) -{ -} - -QWidget *HITLOptionsPage::createPage(QWidget *parent) -{ - // Create page - m_optionsPage = new Ui::HITLOptionsPage(); - QWidget* optionsPageWidget = new QWidget; - m_optionsPage->setupUi(optionsPageWidget); - int index = 0; - foreach(SimulatorCreator* creator, HITLPlugin::typeSimulators) - { - m_optionsPage->chooseFlightSimulator->insertItem(index++, creator->Description(),creator->ClassId()); - } - - //QString classId = widget->listSimulators->itemData(0).toString(); - //SimulatorCreator* creator = HITLPlugin::getSimulatorCreator(classId); - - //QWidget* embedPage = creator->createOptionsPage(); - //m_optionsPage->verticalLayout->addWidget(embedPage); - - m_optionsPage->executablePath->setExpectedKind(Utils::PathChooser::File); - m_optionsPage->executablePath->setPromptDialogTitle(tr("Choose flight simulator executable")); - m_optionsPage->dataPath->setExpectedKind(Utils::PathChooser::Directory); - m_optionsPage->dataPath->setPromptDialogTitle(tr("Choose flight simulator data directory")); - - // Restore the contents from the settings: - foreach(SimulatorCreator* creator, HITLPlugin::typeSimulators) - { - QString id = config->Settings().simulatorId; - if(creator->ClassId() == id) - m_optionsPage->chooseFlightSimulator->setCurrentIndex(HITLPlugin::typeSimulators.indexOf(creator)); - } - - m_optionsPage->executablePath->setPath(config->Settings().binPath); - m_optionsPage->dataPath->setPath(config->Settings().dataPath); - m_optionsPage->manualControl->setChecked(config->Settings().manual); - m_optionsPage->startSim->setChecked(config->Settings().startSim); - m_optionsPage->noiseCheckBox->setChecked(config->Settings().addNoise); - - m_optionsPage->hostAddress->setText(config->Settings().hostAddress); - m_optionsPage->remoteHostAddress->setText(config->Settings().remoteHostAddress); - m_optionsPage->outputPort->setText(QString::number(config->Settings().outPort)); - m_optionsPage->inputPort->setText(QString::number(config->Settings().inPort)); - m_optionsPage->latitude->setText(config->Settings().latitude); - m_optionsPage->longitude->setText(config->Settings().longitude); - - return optionsPageWidget; -} - -void HITLOptionsPage::apply() -{ - SimulatorSettings settings; - int i = m_optionsPage->chooseFlightSimulator->currentIndex(); - - settings.simulatorId = m_optionsPage->chooseFlightSimulator->itemData(i).toString(); - settings.binPath = m_optionsPage->executablePath->path(); - settings.dataPath = m_optionsPage->dataPath->path(); - settings.manual = m_optionsPage->manualControl->isChecked(); - settings.startSim = m_optionsPage->startSim->isChecked(); - settings.addNoise = m_optionsPage->noiseCheckBox->isChecked(); - settings.hostAddress = m_optionsPage->hostAddress->text(); - settings.remoteHostAddress = m_optionsPage->remoteHostAddress->text(); - - settings.inPort = m_optionsPage->inputPort->text().toInt(); - settings.outPort = m_optionsPage->outputPort->text().toInt(); - settings.longitude = m_optionsPage->longitude->text(); - settings.latitude = m_optionsPage->latitude->text(); - - config->setSimulatorSettings(settings); -} - -void HITLOptionsPage::finish() -{ - delete m_optionsPage; -} diff --git a/ground/openpilotgcs/src/plugins/hitlnew/hitloptionspage.ui b/ground/openpilotgcs/src/plugins/hitlnew/hitloptionspage.ui deleted file mode 100644 index 0fa07190e..000000000 --- a/ground/openpilotgcs/src/plugins/hitlnew/hitloptionspage.ui +++ /dev/null @@ -1,281 +0,0 @@ - - - HITLOptionsPage - - - - 0 - 0 - 599 - 367 - - - - - 0 - 0 - - - - Form - - - - 0 - - - - - Choose flight simulator: - - - - - - - - - - Qt::Horizontal - - - - - - - Qt::Vertical - - - - 20 - 182 - - - - - - - - - 0 - 0 - - - - Local interface address (IP): - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Latitude in degrees: - - - - - - - Longitude in degrees: - - - - - - - - 0 - 0 - - - - Data directory: - - - - - - - - 0 - 0 - - - - For receiving data from sim - - - - - - - - 1 - 0 - - - - - - - - - 0 - 0 - - - - Output Port: - - - - - - - - - - - 0 - 0 - - - - - - - - - 0 - 0 - - - - For sending data to sim - - - - - - - - 0 - 0 - - - - Manual aircraft control (can be used when hardware is not available) - - - Manual aircraft control (can be used when hardware is not available) - - - - - - - - 0 - 0 - - - - Path executable: - - - - - - - - 0 - 0 - - - - - - - - Input Port: - - - - - - - true - - - - 0 - 0 - - - - Check this box to start the simulator on the local computer - - - Start simulator on local machine - - - - - - - Remote interface address (IP): - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - Only required if running simulator on remote machine. Should be the IP of the machine on which the simulator is running. - - - - - - - - 0 - 0 - - - - For communication with sim computer via network. Should be the IP address of one of the interfaces of the GCS computer. - - - - - - - Add noise - - - - - - - - Utils::PathChooser - QWidget -
utils/pathchooser.h
- 1 -
-
- - -
diff --git a/ground/openpilotgcs/src/plugins/hitlnew/simulator.cpp b/ground/openpilotgcs/src/plugins/hitlnew/simulator.cpp deleted file mode 100644 index 6b2f3c547..000000000 --- a/ground/openpilotgcs/src/plugins/hitlnew/simulator.cpp +++ /dev/null @@ -1,435 +0,0 @@ -/** - ****************************************************************************** - * - * @file simulator.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup HITLPlugin HITL Plugin - * @{ - * @brief The Hardware In The Loop 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 "simulator.h" -#include "qxtlogger.h" -#include "extensionsystem/pluginmanager.h" -#include "coreplugin/icore.h" -#include "coreplugin/threadmanager.h" -#include "hitlnoisegeneration.h" -#include - -volatile bool Simulator::isStarted = false; - -const float Simulator::GEE = 9.81; -const float Simulator::FT2M = 0.3048; -const float Simulator::KT2MPS = 0.514444444; -const float Simulator::INHG2KPA = 3.386; -const float Simulator::FPS2CMPS = 30.48; -const float Simulator::DEG2RAD = (M_PI/180.0); - - -Simulator::Simulator(const SimulatorSettings& params) : - simProcess(NULL), - time(NULL), - inSocket(NULL), - outSocket(NULL), - settings(params), - updatePeriod(50), - simTimeout(8000), - autopilotConnectionStatus(false), - simConnectionStatus(false), - txTimer(NULL), - simTimer(NULL), - name(""), - once(false) -{ - // move to thread - moveToThread(Core::ICore::instance()->threadManager()->getRealTimeThread()); - connect(this, SIGNAL(myStart()), this, SLOT(onStart()),Qt::QueuedConnection); - emit myStart(); -} - -Simulator::~Simulator() -{ - if(inSocket) - { - delete inSocket; - inSocket = NULL; - } - - if(outSocket) - { - delete outSocket; - outSocket = NULL; - } - - if(txTimer) - { - delete txTimer; - txTimer = NULL; - } - - if(simTimer) - { - delete simTimer; - simTimer = NULL; - } - // NOTE: Does not currently work, may need to send control+c to through the terminal - if (simProcess != NULL) - { - //connect(simProcess,SIGNAL(finished(int, QProcess::ExitStatus)),this,SLOT(onFinished(int, QProcess::ExitStatus))); - - simProcess->disconnect(); - if(simProcess->state() == QProcess::Running) - simProcess->kill(); - //if(simProcess->waitForFinished()) - //emit deleteSimProcess(); - delete simProcess; - simProcess = NULL; - } -} - -void Simulator::onDeleteSimulator(void) -{ - // [1] - Simulator::setStarted(false); - // [2] - Simulator::Instances().removeOne(simulatorId); - - disconnect(this); - delete this; -} - -void Simulator::onStart() -{ - QMutexLocker locker(&lock); - - QThread* mainThread = QThread::currentThread(); - qDebug() << "Simulator Thread: "<< mainThread; - - // Get required UAVObjects - ExtensionSystem::PluginManager* pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager* objManager = pm->getObject(); - actDesired = ActuatorDesired::GetInstance(objManager); - manCtrlCommand = ManualControlCommand::GetInstance(objManager); - flightStatus = FlightStatus::GetInstance(objManager); - posHome = HomeLocation::GetInstance(objManager); - velActual = VelocityActual::GetInstance(objManager); - posActual = PositionActual::GetInstance(objManager); - baroAlt = BaroAltitude::GetInstance(objManager); - baroAirspeed = BaroAirspeed::GetInstance(objManager); - attActual = AttitudeActual::GetInstance(objManager); - accels = Accels::GetInstance(objManager); - gyros = Gyros::GetInstance(objManager); - gpsPos = GPSPosition::GetInstance(objManager); - gpsVel = GPSVelocity::GetInstance(objManager); - telStats = GCSTelemetryStats::GetInstance(objManager); - - // Listen to autopilot connection events - TelemetryManager* telMngr = pm->getObject(); - connect(telMngr, SIGNAL(connected()), this, SLOT(onAutopilotConnect())); - connect(telMngr, SIGNAL(disconnected()), this, SLOT(onAutopilotDisconnect())); - //connect(telStats, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(telStatsUpdated(UAVObject*))); - - // If already connect setup autopilot - GCSTelemetryStats::DataFields stats = telStats->getData(); - if ( stats.Status == GCSTelemetryStats::STATUS_CONNECTED ) - onAutopilotConnect(); - - inSocket = new QUdpSocket(); - outSocket = new QUdpSocket(); - setupUdpPorts(settings.hostAddress,settings.inPort,settings.outPort); - - emit processOutput("\nLocal interface: " + settings.hostAddress + "\n" + \ - "Remote interface: " + settings.remoteHostAddress + "\n" + \ - "inputPort: " + QString::number(settings.inPort) + "\n" + \ - "outputPort: " + QString::number(settings.outPort) + "\n"); - - qxtLog->info("\nLocal interface: " + settings.hostAddress + "\n" + \ - "Remote interface: " + settings.remoteHostAddress + "\n" + \ - "inputPort: " + QString::number(settings.inPort) + "\n" + \ - "outputPort: " + QString::number(settings.outPort) + "\n"); - -// if(!inSocket->waitForConnected(5000)) -// emit processOutput(QString("Can't connect to %1 on %2 port!").arg(settings.hostAddress).arg(settings.inPort)); -// outSocket->connectToHost(settings.hostAddress,settings.outPort); // FG -// if(!outSocket->waitForConnected(5000)) -// emit processOutput(QString("Can't connect to %1 on %2 port!").arg(settings.hostAddress).arg(settings.outPort)); - - - connect(inSocket, SIGNAL(readyRead()), this, SLOT(receiveUpdate()),Qt::DirectConnection); - - // Setup transmit timer - txTimer = new QTimer(); - connect(txTimer, SIGNAL(timeout()), this, SLOT(transmitUpdate()),Qt::DirectConnection); - txTimer->setInterval(updatePeriod); - txTimer->start(); - // Setup simulator connection timer - simTimer = new QTimer(); - connect(simTimer, SIGNAL(timeout()), this, SLOT(onSimulatorConnectionTimeout()),Qt::DirectConnection); - simTimer->setInterval(simTimeout); - simTimer->start(); - - // setup time - time = new QTime(); - time->start(); - current.T=0; - current.i=0; - -} - -void Simulator::receiveUpdate() -{ - // Update connection timer and status - simTimer->setInterval(simTimeout); - simTimer->stop(); - simTimer->start(); - if ( !simConnectionStatus ) - { - simConnectionStatus = true; - emit simulatorConnected(); - } - - // Process data - while(inSocket->hasPendingDatagrams()) { - // Receive datagram - QByteArray datagram; - datagram.resize(inSocket->pendingDatagramSize()); - QHostAddress sender; - quint16 senderPort; - inSocket->readDatagram(datagram.data(), datagram.size(), - &sender, &senderPort); - //QString datastr(datagram); - // Process incomming data - processUpdate(datagram); - } -} - -void Simulator::setupObjects() -{ - - - setupInputObject(actDesired, 100); //100ms update period - setupOutputObject(baroAlt, 100); //250ms update period - setupOutputObject(baroAirspeed, 100); //250ms update period - setupOutputObject(attActual, 10); //etc... - setupOutputObject(gpsPos, 100); - setupOutputObject(gpsVel, 100); - setupOutputObject(posActual, 250); - setupOutputObject(velActual, 250); -// setupOutputObject(posHome, 1000); //WE DON'T WANT TO UPDATE HOME - setupOutputObject(accels, 10); - setupOutputObject(gyros, 10); -} - -void Simulator::setupInputObject(UAVObject* obj, int updatePeriod) -{ - UAVObject::Metadata mdata; - mdata = obj->getDefaultMetadata(); - UAVObject::SetFlightAccess(mdata, UAVObject::ACCESS_READWRITE); - UAVObject::SetGcsAccess(mdata, UAVObject::ACCESS_READWRITE); - UAVObject::SetFlightTelemetryAcked(mdata, false); - UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC); - mdata.flightTelemetryUpdatePeriod = updatePeriod; - UAVObject::SetGcsTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_MANUAL); - obj->setMetadata(mdata); -} - -void Simulator::setupOutputObject(UAVObject* obj, int updatePeriod) -{ - UAVObject::Metadata mdata; - mdata = obj->getDefaultMetadata(); - UAVObject::SetFlightAccess(mdata, UAVObject::ACCESS_READONLY); - UAVObject::SetGcsAccess(mdata, UAVObject::ACCESS_READWRITE); - UAVObject::SetFlightTelemetryUpdateMode(mdata,UAVObject::UPDATEMODE_MANUAL); - UAVObject::SetGcsTelemetryAcked(mdata, false); - UAVObject::SetGcsTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC); - mdata.gcsTelemetryUpdatePeriod = updatePeriod; - obj->setMetadata(mdata); -} - -void Simulator::onAutopilotConnect() -{ - autopilotConnectionStatus = true; - setupObjects(); - emit autopilotConnected(); -} - -void Simulator::onAutopilotDisconnect() -{ - autopilotConnectionStatus = false; - emit autopilotDisconnected(); -} - -void Simulator::onSimulatorConnectionTimeout() -{ - if ( simConnectionStatus ) - { - simConnectionStatus = false; - emit simulatorDisconnected(); - } -} - - -void Simulator::telStatsUpdated(UAVObject* obj) -{ - GCSTelemetryStats::DataFields stats = telStats->getData(); - if ( !autopilotConnectionStatus && stats.Status == GCSTelemetryStats::STATUS_CONNECTED ) - { - onAutopilotConnect(); - } - else if ( autopilotConnectionStatus && stats.Status != GCSTelemetryStats::STATUS_CONNECTED ) - { - onAutopilotDisconnect(); - } -} - -void Simulator::resetInitialHomePosition(){ - once=false; -} - -void Simulator::updateUAVOs(Output2OP out){ - - Noise noise; - HitlNoiseGeneration noiseSource; - if(settings.addNoise){ - noise = noiseSource.generateNoise(); - } - else{ - memset(&noise, 0, sizeof(Noise)); - } - - HomeLocation::DataFields homeData = posHome->getData(); - if(!once) - { - // Upon startup, we reset the HomeLocation object to - // the plane's location: - memset(&homeData, 0, sizeof(HomeLocation::DataFields)); - // Update homelocation - homeData.Latitude = out.latitude; //Already in *10^7 integer format - homeData.Longitude = out.longitude; //Already in *10^7 integer format - homeData.Altitude = out.altitude; - double LLA[3]; - LLA[0]=out.latitude; - LLA[1]=out.longitude; - LLA[2]=out.altitude; - double ECEF[3]; - double RNE[9]; - Utils::CoordinateConversions().RneFromLLA(LLA,(double (*)[3])RNE); - Utils::CoordinateConversions().LLA2ECEF(LLA,ECEF); - homeData.Be[0]=0; - homeData.Be[1]=0; - homeData.Be[2]=0; - posHome->setData(homeData); - posHome->updated(); - - // Compute initial distance - initN = out.dstN; - initE = out.dstE; - initD = out.dstD; - - once=true; - } - - // Update attActual object - AttitudeActual::DataFields attActualData; - memset(&attActualData, 0, sizeof(AttitudeActual::DataFields)); - attActualData.Roll = out.roll + noise.attActualData.Roll; //roll; - attActualData.Pitch = out.pitch + noise.attActualData.Pitch; // pitch - attActualData.Yaw = out.heading + noise.attActualData.Yaw; // Yaw - float rpy[3]; - float quat[4]; - rpy[0] = attActualData.Roll; - rpy[1] = attActualData.Pitch; - rpy[2] = attActualData.Yaw; - Utils::CoordinateConversions().RPY2Quaternion(rpy,quat); - attActualData.q1 = quat[0]; - attActualData.q2 = quat[1]; - attActualData.q3 = quat[2]; - attActualData.q4 = quat[3]; - attActual->setData(attActualData); - - // Update GPS Position objects - GPSPosition::DataFields gpsPosData; - memset(&gpsPosData, 0, sizeof(GPSPosition::DataFields)); - gpsPosData.Altitude = out.altitude + noise.gpsPosData.Altitude; - gpsPosData.Heading = out.heading + noise.gpsPosData.Heading; - gpsPosData.Groundspeed = out.groundspeed + noise.gpsPosData.Groundspeed; - gpsPosData.Latitude = out.latitude + noise.gpsPosData.Latitude; //Already in *10^7 integer format - gpsPosData.Longitude = out.longitude + noise.gpsPosData.Longitude; //Already in *10^7 integer format - gpsPosData.Satellites = 10; - gpsPosData.Status = GPSPosition::STATUS_FIX3D; - gpsPos->setData(gpsPosData); - - // Update GPS Velocity.{North,East,Down} - GPSVelocity::DataFields gpsVelData; - memset(&gpsVelData, 0, sizeof(GPSVelocity::DataFields)); - gpsVelData.North = out.velNorth + noise.gpsVelData.North; - gpsVelData.East = out.velEast + noise.gpsVelData.East; - gpsVelData.Down = out.velDown + noise.gpsVelData.Down; - gpsVel->setData(gpsVelData); - - - // Update VelocityActual.{North,East,Down} - VelocityActual::DataFields velocityActualData; - memset(&velocityActualData, 0, sizeof(VelocityActual::DataFields)); - velocityActualData.North = out.velNorth + noise.velocityActualData.North; - velocityActualData.East = out.velEast + noise.velocityActualData.East; - velocityActualData.Down = out.velDown + noise.velocityActualData.Down; - velActual->setData(velocityActualData); - - // Update PositionActual.{Nort,East,Down} - PositionActual::DataFields positionActualData; - memset(&positionActualData, 0, sizeof(PositionActual::DataFields)); - positionActualData.North = (out.dstN-initN) + noise.positionActualData.North; - positionActualData.East = (out.dstE-initE) + noise.positionActualData.East; - positionActualData.Down = (out.dstD/*-initD*/) + noise.positionActualData.Down; - posActual->setData(positionActualData); - - - // Update BaroAltitude object - BaroAltitude::DataFields baroAltData; - memset(&baroAltData, 0, sizeof(BaroAltitude::DataFields)); - baroAltData.Altitude = out.altitude + noise.baroAltData.Altitude; - baroAltData.Temperature = out.temperature + noise.baroAltData.Temperature; - baroAltData.Pressure = out.pressure + noise.baroAltData.Pressure; - baroAlt->setData(baroAltData); - - // Update BaroAirspeed object - BaroAirspeed::DataFields baroAirspeedData; - memset(&baroAirspeedData, 0, sizeof(BaroAirspeed::DataFields)); - baroAirspeedData.CalibratedAirspeed = out.calibratedAirspeed + noise.baroAirspeed.CalibratedAirspeed; - baroAirspeed->setData(baroAirspeedData); - - //Update gyroscope sensor data - Gyros::DataFields gyroData; - memset(&gyroData, 0, sizeof(Gyros::DataFields)); - gyroData.x = out.rollRate + noise.gyroData.x; - gyroData.y = out.pitchRate + noise.gyroData.y; - gyroData.z = out.yawRate + noise.gyroData.z; - gyros->setData(gyroData); - - //Update accelerometer sensor data - Accels::DataFields accelData; - memset(&accelData, 0, sizeof(Accels::DataFields)); - accelData.x = out.accX + noise.accelData.x; - accelData.y = out.accY + noise.accelData.y; - accelData.z = out.accZ + noise.accelData.z; - accels->setData(accelData); -} diff --git a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc.cpp b/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc.cpp deleted file mode 100644 index f8306e30d..000000000 --- a/ground/openpilotgcs/src/plugins/hitlv2/aerosimrc.cpp +++ /dev/null @@ -1,495 +0,0 @@ -/** - ****************************************************************************** - * - * @file aerosimrc.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup HITLPlugin HITLv2 Plugin - * @{ - * @brief The Hardware In The Loop plugin version 2 - *****************************************************************************/ -/* - * 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 "aerosimrc.h" -#include -#include -#include - -AeroSimRCSimulator::AeroSimRCSimulator(const SimulatorSettings ¶ms) - : Simulator(params) -{ - udpCounterASrecv = 0; -} - -AeroSimRCSimulator::~AeroSimRCSimulator() -{ -} - -bool AeroSimRCSimulator::setupProcess() -{ - QMutexLocker locker(&lock); - return true; -} - -void AeroSimRCSimulator::setupUdpPorts(const QString &host, int inPort, int outPort) -{ - Q_UNUSED(outPort) - if (inSocket->bind(QHostAddress(host), inPort)) - emit processOutput("Successfully bound to address " + host + ", port " + QString::number(inPort) + "\n"); - else - emit processOutput("Cannot bind to address " + host + ", port " + QString::number(inPort) + "\n"); -} - -void AeroSimRCSimulator::transmitUpdate() -{ - // read actuator output - ActuatorCommand::DataFields actCmdData; - actCmdData = actCommand->getData(); - float channels[10]; - for (int i = 0; i < 10; ++i) { - qint16 ch = actCmdData.Channel[i]; - float out = -1.0; - if (ch >= 1000 && ch <= 2000) { - ch -= 1000; - out = ((float)ch / 500.0) - 1.0; - } - channels[i] = out; - } - - // read flight status - FlightStatus::DataFields flightData; - flightData = flightStatus->getData(); - quint8 armed; - quint8 mode; - armed = flightData.Armed; - mode = flightData.FlightMode; - - QByteArray data; - // 50 - current size of values, 4(quint32) + 10*4(float) + 2(quint8) + 4(quint32) - data.resize(50); - QDataStream stream(&data, QIODevice::WriteOnly); - stream.setFloatingPointPrecision(QDataStream::SinglePrecision); - stream << quint32(0x52434D44); // magic header, "RCMD" - for (int i = 0; i < 10; ++i) - stream << channels[i]; // channels - stream << armed << mode; // flight status - stream << udpCounterASrecv; // packet counter - - if (outSocket->writeDatagram(data, QHostAddress(settings.remoteAddress), settings.outPort) == -1) { - qDebug() << "write failed: " << outSocket->errorString(); - } - -#ifdef DBG_TIMERS - static int cntTX = 0; - if (cntTX >= 100) { - qDebug() << "TX=" << 1000.0 * 100 / timeTX.restart(); - cntTX = 0; - } else { - ++cntTX; - } -#endif -} - -void AeroSimRCSimulator::processUpdate(const QByteArray &data) -{ - // check size - if (data.size() > 188) { - qDebug() << "!!! big datagram: " << data.size(); - return; - } - - QByteArray buf = data; - QDataStream stream(&buf, QIODevice::ReadOnly); - stream.setFloatingPointPrecision(QDataStream::SinglePrecision); - - // check magic header - quint32 magic; - stream >> magic; - if (magic != 0x4153494D) { // "AERO" - qDebug() << "wrong magic: " << magic << ", correct: " << quint32(0x4153494D); - return; - } - - float timeStep, - homeX, homeY, homeZ, - WpHX, WpHY, WpLat, WpLon, - posX, posY, posZ, // world - velX, velY, velZ, // world - angX, angY, angZ, // model - accX, accY, accZ, // model - lat, lon, agl, // world - yaw, pitch, roll, // model - volt, curr, - rx, ry, rz, fx, fy, fz, ux, uy, uz, // matrix - ch[8]; - - stream >> timeStep; - stream >> homeX >> homeY >> homeZ; - stream >> WpHX >> WpHY >> WpLat >> WpLon; - stream >> posX >> posY >> posZ; - stream >> velX >> velY >> velZ; - stream >> angX >> angY >> angZ; - stream >> accX >> accY >> accZ; - stream >> lat >> lon >> agl; - stream >> yaw >> pitch >> roll; - stream >> volt >> curr; - stream >> rx >> ry >> rz >> fx >> fy >> fz >> ux >> uy >> uz; - stream >> ch[0] >> ch[1] >> ch[2] >> ch[3] >> ch[4] >> ch[5] >> ch[6] >> ch[7]; - stream >> udpCounterASrecv; - - /**********************************************************************************************/ - QTime currentTime = QTime::currentTime(); - /**********************************************************************************************/ - static bool firstRun = true; - if (settings.homeLocation) { - if (firstRun) { - HomeLocation::DataFields homeData; - homeData = posHome->getData(); - - homeData.Latitude = WpLat * 10e6; - homeData.Longitude = WpLon * 10e6; - homeData.Altitude = homeZ; - homeData.Set = HomeLocation::SET_TRUE; - - posHome->setData(homeData); - - firstRun = false; - } - if (settings.homeLocRate > 0) { - static QTime homeLocTime = currentTime; - if (homeLocTime.secsTo(currentTime) >= settings.homeLocRate) { - firstRun = true; - homeLocTime = currentTime; - } - } - } - /**********************************************************************************************/ - if (settings.attRaw || settings.attActual) { - QMatrix4x4 mat; - mat = QMatrix4x4( fy, fx, -fz, 0.0, // model matrix - ry, rx, -rz, 0.0, // (X,Y,Z) -> (+Y,+X,-Z) - -uy, -ux, uz, 0.0, - 0.0, 0.0, 0.0, 1.0); - mat.optimize(); - - QQuaternion quat; // model quat - asMatrix2Quat(mat, quat); - - // rotate gravity - QVector3D acc = QVector3D(accY, accX, -accZ); // accel (X,Y,Z) -> (+Y,+X,-Z) - QVector3D gee = QVector3D(0.0, 0.0, -GEE); - QQuaternion qWorld = quat.conjugate(); - gee = qWorld.rotatedVector(gee); - acc += gee; - - /*************************************************************************************/ - if (settings.attRaw) { - Accels::DataFields accelsData; - accelsData = accels->getData(); - Gyros::DataFields gyrosData; - gyrosData = gyros->getData(); - - gyrosData.x = angY * RAD2DEG; // gyros (X,Y,Z) -> (+Y,+X,-Z) - gyrosData.y = angX * RAD2DEG; - gyrosData.z = angZ * -RAD2DEG; - accelsData.x = acc.x(); - accelsData.y = acc.y(); - accelsData.z = acc.z(); - - accels->setData(accelsData); - gyros->setData(gyrosData); - } - /*************************************************************************************/ - if (settings.attActHW) { - // do nothing - /*****************************************/ - } else if (settings.attActSim) { - // take all data from simulator - AttitudeActual::DataFields attActData; - attActData = attActual->getData(); - - QVector3D rpy; // model roll, pitch, yaw - asMatrix2RPY(mat, rpy); - - attActData.Roll = rpy.x(); - attActData.Pitch = rpy.y(); - attActData.Yaw = rpy.z(); - attActData.q1 = quat.scalar(); - attActData.q2 = quat.x(); - attActData.q3 = quat.y(); - attActData.q4 = quat.z(); - - attActual->setData(attActData); - /*****************************************/ - } else if (settings.attActCalc) { - // calculate RPY with code from Attitude module - AttitudeActual::DataFields attActData; - attActData = attActual->getData(); - - static float q[4] = {1, 0, 0, 0}; - static float gyro_correct_int2 = 0; - - float dT = timeStep; - - AttitudeSettings::DataFields attSettData = attSettings->getData(); - float accelKp = attSettData.AccelKp * 0.1666666666666667; - float accelKi = attSettData.AccelKp * 0.1666666666666667; - float yawBiasRate = attSettData.YawBiasRate; - - // calibrate sensors on arming - if (flightStatus->getData().Armed == FlightStatus::ARMED_ARMING) { - accelKp = 2.0; - accelKi = 0.9; - } - - float gyro[3] = {angY * RAD2DEG, angX * RAD2DEG, angZ * -RAD2DEG}; - float attRawAcc[3] = {acc.x(), acc.y(), acc.z()}; - - // code from Attitude module begin /////////////////////////////// - float *accels = attRawAcc; - 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 - { - accel_err[0] = accels[1]*grot[2] - grot[1]*accels[2]; - accel_err[1] = grot[0]*accels[2] - accels[0]*grot[2]; - accel_err[2] = accels[0]*grot[1] - grot[0]*accels[1]; - } - - // 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_int2 += -gyro[2] * yawBiasRate; - - // 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 + gyro_correct_int2; - - // Work out time derivative from INSAlgo writeup - // Also accounts for the fact that gyros are in deg/s - float qdot[4]; - qdot[0] = (-q[1] * gyro[0] - q[2] * gyro[1] - q[3] * gyro[2]) * dT * M_PI / 180 / 2; - 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] += qdot[0]; - q[1] += qdot[1]; - q[2] += qdot[2]; - q[3] += qdot[3]; - - if(q[0] < 0) { - q[0] = -q[0]; - q[1] = -q[1]; - q[2] = -q[2]; - 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] /= qmag; - q[1] /= qmag; - q[2] /= qmag; - q[3] /= qmag; - - // If quaternion has become inappropriately short or is nan reinit. - // THIS SHOULD NEVER ACTUALLY HAPPEN - if((fabs(qmag) < 1e-3) || (qmag != qmag)) { - q[0] = 1; - q[1] = 0; - q[2] = 0; - q[3] = 0; - } - - float rpy2[3]; - // Quaternion2RPY - { - float q0s, q1s, q2s, q3s; - q0s = q[0] * q[0]; - q1s = q[1] * q[1]; - q2s = q[2] * q[2]; - q3s = q[3] * q[3]; - - float R13, R11, R12, R23, R33; - R13 = 2 * (q[1] * q[3] - q[0] * q[2]); - R11 = q0s + q1s - q2s - q3s; - R12 = 2 * (q[1] * q[2] + q[0] * q[3]); - R23 = 2 * (q[2] * q[3] + q[0] * q[1]); - R33 = q0s - q1s - q2s + q3s; - - rpy2[1] = RAD2DEG * asinf(-R13); // pitch always between -pi/2 to pi/2 - rpy2[2] = RAD2DEG * atan2f(R12, R11); - rpy2[0] = RAD2DEG * atan2f(R23, R33); - } - - attActData.Roll = rpy2[0]; - attActData.Pitch = rpy2[1]; - attActData.Yaw = rpy2[2]; - attActData.q1 = q[0]; - attActData.q2 = q[1]; - attActData.q3 = q[2]; - attActData.q4 = q[3]; - attActual->setData(attActData); - /*****************************************/ - } - } - /**********************************************************************************************/ - if (settings.gcsReciever) { - static QTime gcsRcvrTime = currentTime; - if (!settings.manualOutput || gcsRcvrTime.msecsTo(currentTime) >= settings.outputRate) { - GCSReceiver::DataFields gcsRcvrData; - gcsRcvrData = gcsReceiver->getData(); - - for (int i = 0; i < 8; ++i) - gcsRcvrData.Channel[i] = 1500 + (ch[i] * 500); - - gcsReceiver->setData(gcsRcvrData); - if (settings.manualOutput) - gcsRcvrTime = currentTime; - } - } else if (settings.manualControl) { - // not implemented yet - } - /**********************************************************************************************/ - if (settings.gpsPosition) { - static QTime gpsPosTime = currentTime; - if (gpsPosTime.msecsTo(currentTime) >= settings.gpsPosRate) { - GPSPosition::DataFields gpsPosData; - gpsPosData = gpsPosition->getData(); - - gpsPosData.Altitude = posZ; - gpsPosData.Heading = yaw * RAD2DEG; - gpsPosData.Latitude = lat * 10e6; - gpsPosData.Longitude = lon * 10e6; - gpsPosData.Groundspeed = qSqrt(velX * velX + velY * velY); - gpsPosData.GeoidSeparation = 0.0; - gpsPosData.Satellites = 8; - gpsPosData.PDOP = 3.0; - gpsPosData.Status = GPSPosition::STATUS_FIX3D; - - gpsPosition->setData(gpsPosData); - gpsPosTime = currentTime; - } - } - /**********************************************************************************************/ - if (settings.sonarAltitude) { - static QTime sonarAltTime = currentTime; - if (sonarAltTime.msecsTo(currentTime) >= settings.sonarAltRate) { - SonarAltitude::DataFields sonarAltData; - sonarAltData = sonarAlt->getData(); - - float sAlt = settings.sonarMaxAlt; - // 0.35 rad ~= 20 degree - if ((agl < (sAlt * 2.0)) && (roll < 0.35) && (pitch < 0.35)) { - float x = agl * qTan(roll); - float y = agl * qTan(pitch); - float h = qSqrt(x*x + y*y + agl*agl); - sAlt = qMin(h, sAlt); - } - - sonarAltData.Altitude = sAlt; - sonarAlt->setData(sonarAltData); - sonarAltTime = currentTime; - } - } - /**********************************************************************************************/ -/* - BaroAltitude::DataFields altActData; - altActData = altActual->getData(); - altActData.Altitude = posZ; - altActual->setData(altActData); - - PositionActual::DataFields posActData; - posActData = posActual->getData(); - posActData.North = posY * 100; - posActData.East = posX * 100; - posActData.Down = posZ * -100; - posActual->setData(posActData); - - VelocityActual::DataFields velActData; - velActData = velActual->getData(); - velActData.North = velY * 100; - velActData.East = velX * 100; - velActData.Down = velZ * 100; - velActual->setData(velActData); -*/ - -#ifdef DBG_TIMERS - static int cntRX = 0; - if (cntRX >= 100) { - qDebug() << "RX=" << 1000.0 * 100 / timeRX.restart(); - cntRX = 0; - } else { - ++cntRX; - } -#endif -} - -// transfomations - -void AeroSimRCSimulator::asMatrix2Quat(const QMatrix4x4 &m, QQuaternion &q) -{ - qreal w, x, y, z; - - // w always >= 0 - w = qSqrt(qMax(0.0, 1.0 + m(0, 0) + m(1, 1) + m(2, 2))) / 2.0; - x = qSqrt(qMax(0.0, 1.0 + m(0, 0) - m(1, 1) - m(2, 2))) / 2.0; - y = qSqrt(qMax(0.0, 1.0 - m(0, 0) + m(1, 1) - m(2, 2))) / 2.0; - z = qSqrt(qMax(0.0, 1.0 - m(0, 0) - m(1, 1) + m(2, 2))) / 2.0; - - x = copysign(x, (m(1, 2) - m(2, 1))); - y = copysign(y, (m(2, 0) - m(0, 2))); - z = copysign(z, (m(0, 1) - m(1, 0))); - - q.setScalar(w); - q.setX(x); - q.setY(y); - q.setZ(z); -} - -void AeroSimRCSimulator::asMatrix2RPY(const QMatrix4x4 &m, QVector3D &rpy) -{ - qreal roll, pitch, yaw; - - if (qFabs(m(0, 2)) > 0.998) { - // ~86.3°, gimbal lock - roll = 0.0; - pitch = copysign(M_PI_2, -m(0, 2)); - yaw = qAtan2(-m(1, 0), m(1, 1)); - } else { - roll = qAtan2(m(1, 2), m(2, 2)); - pitch = qAsin(-m(0, 2)); - yaw = qAtan2(m(0, 1), m(0, 0)); - } - - rpy.setX(roll * RAD2DEG); - rpy.setY(pitch * RAD2DEG); - rpy.setZ(yaw * RAD2DEG); -} diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2.pluginspec b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2.pluginspec deleted file mode 100644 index 26fede385..000000000 --- a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2.pluginspec +++ /dev/null @@ -1,12 +0,0 @@ - - The OpenPilot Project - (C) 2011 OpenPilot Project - The GNU Public License (GPL) Version 3 - Hardware In The Loop Simulation (v2) - http://www.openpilot.org - - - - - - diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2_dependencies.pri b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2_dependencies.pri deleted file mode 100644 index 50268face..000000000 --- a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2_dependencies.pri +++ /dev/null @@ -1,4 +0,0 @@ -include(../../plugins/uavobjects/uavobjects.pri) -include(../../plugins/uavtalk/uavtalk.pri) -#include(../../plugins/coreplugin/coreplugin.pri) -#include(../../libs/utils/utils.pri) diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2configuration.cpp b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2configuration.cpp deleted file mode 100644 index 5977e5220..000000000 --- a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2configuration.cpp +++ /dev/null @@ -1,178 +0,0 @@ -/** - ****************************************************************************** - * - * @file hitlv2configuration.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup HITLPlugin HITLv2 Plugin - * @{ - * @brief The Hardware In The Loop plugin version 2 - *****************************************************************************/ -/* - * 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 "hitlv2configuration.h" - -HITLConfiguration::HITLConfiguration(QString classId, - QSettings* qSettings, - QObject *parent) - : IUAVGadgetConfiguration(classId, parent) -{ -// qDebug() << "HITLV2Configuration"; - // default values - QString simulatorId = "ASimRC"; - QString hostAddress = "127.0.0.1"; - int inPort = 40100; - QString remoteAddress = "127.0.0.1"; - int outPort = 40200; - QString binPath = ""; - QString dataPath = ""; - - bool homeLocation = true; - quint16 homeLocRate = 0; - - bool attRaw = true; - quint8 attRawRate = 20; - - bool attActual = true; - bool attActHW = false; - bool attActSim = true; - bool attActCalc = false; - - bool sonarAltitude = false; - float sonarMaxAlt = 5.0; - quint16 sonarAltRate = 50; - - bool gpsPosition = true; - quint16 gpsPosRate = 200; - - bool inputCommand = true; - bool gcsReciever = true; - bool manualControl = false; - - bool manualOutput = false; - quint8 outputRate = 20; - - // if a saved configuration exists load it - if (qSettings != 0) { - settings.simulatorId = qSettings->value("simulatorId", simulatorId).toString(); - settings.hostAddress = qSettings->value("hostAddress", hostAddress).toString(); - settings.inPort = qSettings->value("inPort", inPort).toInt(); - settings.remoteAddress = qSettings->value("remoteAddress", remoteAddress).toString(); - settings.outPort = qSettings->value("outPort", outPort).toInt(); - settings.binPath = qSettings->value("binPath", binPath).toString(); - settings.dataPath = qSettings->value("dataPath", dataPath).toString(); - - settings.homeLocation = qSettings->value("homeLocation", homeLocation).toBool(); - settings.homeLocRate = qSettings->value("homeLocRate", homeLocRate).toInt(); - - settings.attRaw = qSettings->value("attRaw", attRaw).toBool(); - settings.attRawRate = qSettings->value("attRawRate", attRawRate).toInt(); - - settings.attActual = qSettings->value("attActual", attActual).toBool(); - settings.attActHW = qSettings->value("attActHW", attActHW).toBool(); - settings.attActSim = qSettings->value("attActSim", attActSim).toBool(); - settings.attActCalc = qSettings->value("attActCalc", attActCalc).toBool(); - - settings.sonarAltitude = qSettings->value("sonarAltitude", sonarAltitude).toBool(); - settings.sonarMaxAlt = qSettings->value("sonarMaxAlt", sonarMaxAlt).toFloat(); - settings.sonarAltRate = qSettings->value("sonarAltRate", sonarAltRate).toInt(); - - settings.gpsPosition = qSettings->value("gpsPosition", gpsPosition).toBool(); - settings.gpsPosRate = qSettings->value("gpsPosRate", gpsPosRate).toInt(); - - settings.inputCommand = qSettings->value("inputCommand", inputCommand).toBool(); - settings.gcsReciever = qSettings->value("gcsReciever", gcsReciever).toBool(); - settings.manualControl = qSettings->value("manualControl", manualControl).toBool(); - settings.manualOutput = qSettings->value("manualOutput", manualOutput).toBool(); - settings.outputRate = qSettings->value("outputRate", outputRate).toInt(); - } else { - settings.simulatorId = simulatorId; - settings.hostAddress = hostAddress; - settings.inPort = inPort; - settings.remoteAddress = remoteAddress; - settings.outPort = outPort; - settings.binPath = binPath; - settings.dataPath = dataPath; - - settings.homeLocation = homeLocation; - settings.homeLocRate = homeLocRate; - - settings.attRaw = attRaw; - settings.attRawRate = attRawRate; - - settings.attActual = attActual; - settings.attActHW = attActHW; - settings.attActSim = attActSim; - settings.attActCalc = attActCalc; - - settings.sonarAltitude = sonarAltitude; - settings.sonarMaxAlt = sonarMaxAlt; - settings.sonarAltRate = sonarAltRate; - - settings.gpsPosition = gpsPosition; - settings.gpsPosRate = gpsPosRate; - - settings.inputCommand = inputCommand; - settings.gcsReciever = gcsReciever; - settings.manualControl = manualControl; - settings.manualOutput = manualOutput; - settings.outputRate = outputRate; - } -} - -IUAVGadgetConfiguration *HITLConfiguration::clone() -{ - HITLConfiguration *m = new HITLConfiguration(this->classId()); - m->settings = settings; - return m; -} - -void HITLConfiguration::saveConfig(QSettings* qSettings) const -{ - qSettings->setValue("simulatorId", settings.simulatorId); - qSettings->setValue("hostAddress", settings.hostAddress); - qSettings->setValue("inPort", settings.inPort); - qSettings->setValue("remoteAddress", settings.remoteAddress); - qSettings->setValue("outPort", settings.outPort); - qSettings->setValue("binPath", settings.binPath); - qSettings->setValue("dataPath", settings.dataPath); - - qSettings->setValue("homeLocation", settings.homeLocation); - qSettings->setValue("homeLocRate", settings.homeLocRate); - - qSettings->setValue("attRaw", settings.attRaw); - qSettings->setValue("attRawRate", settings.attRawRate); - - qSettings->setValue("attActual", settings.attActual); - qSettings->setValue("attActHW", settings.attActHW); - qSettings->setValue("attActSim", settings.attActSim); - qSettings->setValue("attActCalc", settings.attActCalc); - - qSettings->setValue("sonarAltitude", settings.sonarAltitude); - qSettings->setValue("sonarMaxAlt", settings.sonarMaxAlt); - qSettings->setValue("sonarAltRate", settings.sonarAltRate); - - qSettings->setValue("gpsPosition", settings.gpsPosition); - qSettings->setValue("gpsPosRate", settings.gpsPosRate); - - qSettings->setValue("inputCommand", settings.inputCommand); - qSettings->setValue("gcsReciever", settings.gcsReciever); - qSettings->setValue("manualControl", settings.manualControl); - qSettings->setValue("manualOutput", settings.manualOutput); - qSettings->setValue("outputRate", settings.outputRate); -} diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2factory.cpp b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2factory.cpp deleted file mode 100644 index c9e52ebb4..000000000 --- a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2factory.cpp +++ /dev/null @@ -1,59 +0,0 @@ -/** - ****************************************************************************** - * - * @file hitlv2factory.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup HITLPlugin HITLv2 Plugin - * @{ - * @brief The Hardware In The Loop plugin version 2 - *****************************************************************************/ -/* - * 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 "hitlv2factory.h" -#include "hitlv2widget.h" -#include "hitlv2gadget.h" -#include "hitlv2configuration.h" -#include "hitlv2optionspage.h" -#include - -HITLFactory::HITLFactory(QObject *parent) - : IUAVGadgetFactory(QString("HITLv2"), tr("HITL Simulation (v2)"), parent) -{ -} - -HITLFactory::~HITLFactory() -{ -} - -Core::IUAVGadget* HITLFactory::createGadget(QWidget *parent) -{ - HITLWidget* gadgetWidget = new HITLWidget(parent); - return new HITLGadget(QString("HITLv2"), gadgetWidget, parent); -} - -IUAVGadgetConfiguration *HITLFactory::createConfiguration(QSettings* qSettings) -{ - return new HITLConfiguration(QString("HITLv2"), qSettings); -} - -IOptionsPage *HITLFactory::createOptionsPage(IUAVGadgetConfiguration *config) -{ - return new HITLOptionsPage(qobject_cast(config)); -} - diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2optionspage.cpp b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2optionspage.cpp deleted file mode 100644 index 280ccf030..000000000 --- a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2optionspage.cpp +++ /dev/null @@ -1,146 +0,0 @@ -/** - ****************************************************************************** - * - * @file hitlv2optionspage.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup HITLPlugin HITLv2 Plugin - * @{ - * @brief The Hardware In The Loop plugin version 2 - *****************************************************************************/ -/* - * 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 "hitlv2optionspage.h" -#include "hitlv2configuration.h" -#include "ui_hitlv2optionspage.h" -#include "hitlv2plugin.h" - -#include -#include -#include -#include "simulatorv2.h" - -HITLOptionsPage::HITLOptionsPage(HITLConfiguration *conf, QObject *parent) : - IOptionsPage(parent), - config(conf) -{ -} - -QWidget *HITLOptionsPage::createPage(QWidget *parent) -{ -// qDebug() << "HITLOptionsPage::createPage"; - // Create page - m_optionsPage = new Ui::HITLOptionsPage(); - QWidget* optionsPageWidget = new QWidget; - m_optionsPage->setupUi(optionsPageWidget); - int index = 0; - foreach (SimulatorCreator* creator, HITLPlugin::typeSimulators) - m_optionsPage->chooseFlightSimulator->insertItem(index++, creator->Description(), creator->ClassId()); - - m_optionsPage->executablePath->setExpectedKind(Utils::PathChooser::File); - m_optionsPage->executablePath->setPromptDialogTitle(tr("Choose flight simulator executable")); - m_optionsPage->dataPath->setExpectedKind(Utils::PathChooser::Directory); - m_optionsPage->dataPath->setPromptDialogTitle(tr("Choose flight simulator data directory")); - - // Restore the contents from the settings: - foreach (SimulatorCreator* creator, HITLPlugin::typeSimulators) { - QString id = config->Settings().simulatorId; - if (creator->ClassId() == id) - m_optionsPage->chooseFlightSimulator->setCurrentIndex(HITLPlugin::typeSimulators.indexOf(creator)); - } - - m_optionsPage->hostAddress->setText(config->Settings().hostAddress); - m_optionsPage->inputPort->setText(QString::number(config->Settings().inPort)); - m_optionsPage->remoteAddress->setText(config->Settings().remoteAddress); - m_optionsPage->outputPort->setText(QString::number(config->Settings().outPort)); - m_optionsPage->executablePath->setPath(config->Settings().binPath); - m_optionsPage->dataPath->setPath(config->Settings().dataPath); - - m_optionsPage->homeLocation->setChecked(config->Settings().homeLocation); - m_optionsPage->homeLocRate->setValue(config->Settings().homeLocRate); - - m_optionsPage->attRaw->setChecked(config->Settings().attRaw); - m_optionsPage->attRawRate->setValue(config->Settings().attRawRate); - - m_optionsPage->attActual->setChecked(config->Settings().attActual); - m_optionsPage->attActHW->setChecked(config->Settings().attActHW); - m_optionsPage->attActSim->setChecked(config->Settings().attActSim); - m_optionsPage->attActCalc->setChecked(config->Settings().attActCalc); - - m_optionsPage->sonarAltitude->setChecked(config->Settings().sonarAltitude); - m_optionsPage->sonarMaxAlt->setValue(config->Settings().sonarMaxAlt); - m_optionsPage->sonarAltRate->setValue(config->Settings().sonarAltRate); - - m_optionsPage->gpsPosition->setChecked(config->Settings().gpsPosition); - m_optionsPage->gpsPosRate->setValue(config->Settings().gpsPosRate); - - m_optionsPage->inputCommand->setChecked(config->Settings().inputCommand); - m_optionsPage->gcsReciever->setChecked(config->Settings().gcsReciever); - m_optionsPage->manualControl->setChecked(config->Settings().manualControl); - - m_optionsPage->manualOutput->setChecked(config->Settings().manualOutput); - m_optionsPage->outputRate->setValue(config->Settings().outputRate); - - return optionsPageWidget; -} - -void HITLOptionsPage::apply() -{ - SimulatorSettings settings; - int i = m_optionsPage->chooseFlightSimulator->currentIndex(); - - settings.simulatorId = m_optionsPage->chooseFlightSimulator->itemData(i).toString(); - settings.hostAddress = m_optionsPage->hostAddress->text(); - settings.inPort = m_optionsPage->inputPort->text().toInt(); - settings.remoteAddress = m_optionsPage->remoteAddress->text(); - settings.outPort = m_optionsPage->outputPort->text().toInt(); - settings.binPath = m_optionsPage->executablePath->path(); - settings.dataPath = m_optionsPage->dataPath->path(); - - settings.homeLocation = m_optionsPage->homeLocation->isChecked(); - settings.homeLocRate = m_optionsPage->homeLocRate->value(); - - settings.attRaw = m_optionsPage->attRaw->isChecked(); - settings.attRawRate = m_optionsPage->attRawRate->value(); - - settings.attActual = m_optionsPage->attActual->isChecked(); - settings.attActHW = m_optionsPage->attActHW->isChecked(); - settings.attActSim = m_optionsPage->attActSim->isChecked(); - settings.attActCalc = m_optionsPage->attActCalc->isChecked(); - - settings.sonarAltitude = m_optionsPage->sonarAltitude->isChecked(); - settings.sonarMaxAlt = m_optionsPage->sonarMaxAlt->value(); - settings.sonarAltRate = m_optionsPage->sonarAltRate->value(); - - settings.gpsPosition = m_optionsPage->gpsPosition->isChecked(); - settings.gpsPosRate = m_optionsPage->gpsPosRate->value(); - - settings.inputCommand = m_optionsPage->inputCommand->isChecked(); - settings.gcsReciever = m_optionsPage->gcsReciever->isChecked(); - settings.manualControl = m_optionsPage->manualControl->isChecked(); - - settings.manualOutput = m_optionsPage->manualOutput->isChecked(); - settings.outputRate = m_optionsPage->outputRate->value(); - - config->setSimulatorSettings(settings); -} - -void HITLOptionsPage::finish() -{ - delete m_optionsPage; -} diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2optionspage.ui b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2optionspage.ui deleted file mode 100644 index 00a2f60aa..000000000 --- a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2optionspage.ui +++ /dev/null @@ -1,639 +0,0 @@ - - - HITLOptionsPage - - - - 0 - 0 - 403 - 400 - - - - Form - - - - 3 - - - 0 - - - 0 - - - 0 - - - 3 - - - - - - - Choose flight simulator: - - - - - - - - - - - - - - Local interface (IP): - - - - - - - For communication with sim computer via network. Should be the IP address of one of the interfaces of the GCS computer. - - - - - - - Remote interface (IP): - - - - - - - Only required if running simulator on remote machine. Should be the IP of the machine on which the simulator is running. - - - - - - - Input Port: - - - - - - - For receiving data from sim - - - - - - - Output Port: - - - - - - - For sending data to sim - - - - - - - - - QFormLayout::AllNonFixedFieldsGrow - - - - - - 0 - 0 - - - - Path executable: - - - - - - - - - - - 0 - 0 - - - - Data directory: - - - - - - - - - - - - - - Attitude data - - - - 3 - - - 3 - - - 3 - - - 3 - - - 0 - - - - - AttitudeRaw (gyro, accels) - - - true - - - true - - - false - - - - 3 - - - 3 - - - 0 - - - 0 - - - - - Refresh rate - - - - - - - ms - - - 10 - - - 100 - - - 20 - - - - - - - - - - AttitudeActual - - - true - - - true - - - false - - - - 3 - - - 3 - - - 0 - - - 0 - - - - - send raw data to board - - - - - - - - 75 - true - - - - - - - use values from simulator - - - true - - - - - - - - - - calculate from AttitudeRaw - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - - - - - Other data - - - - 3 - - - 3 - - - 3 - - - 3 - - - 0 - - - - - HomeLocation - - - true - - - true - - - false - - - - 3 - - - 3 - - - 0 - - - 0 - - - - - Refresh rate - - - - - - - 0 - update once, or every N seconds - - - sec - - - 10 - - - - - - - - - - GPSPosition - - - true - - - true - - - false - - - - 3 - - - 3 - - - 0 - - - 0 - - - - - Refresh rate - - - - - - - ms - - - 100 - - - 2000 - - - 500 - - - - - - - - - - SonarAltitude - - - true - - - true - - - false - - - - 3 - - - 6 - - - 3 - - - 0 - - - 0 - - - - - - - Range detectioon - - - - - - - m - - - 1 - - - 10 - - - 5 - - - - - - - Refresh rate - - - - - - - ms - - - 20 - - - 2000 - - - 10 - - - 50 - - - - - - - - - - - - Map command from simulator - - - true - - - true - - - false - - - - 3 - - - 3 - - - 0 - - - 0 - - - - - - 75 - true - - - - to GCSReciver - - - true - - - - - - - false - - - to ManualCtrll (not implemented) - - - - - - - - - - 6 - - - - - Maximum output rate - - - - - - - ms - - - 10 - - - 100 - - - 5 - - - 15 - - - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - - - - - Utils::PathChooser - QWidget -
utils/pathchooser.h
- 1 -
-
- - chooseFlightSimulator - hostAddress - inputPort - remoteAddress - outputPort - - - -
diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2plugin.h b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2plugin.h deleted file mode 100644 index 3e83915b3..000000000 --- a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2plugin.h +++ /dev/null @@ -1,67 +0,0 @@ -/** - ****************************************************************************** - * - * @file hitlv2plugin.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup HITLPlugin HITLv2 Plugin - * @{ - * @brief The Hardware In The Loop plugin version 2 - *****************************************************************************/ -/* - * 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 HITLV2PLUGIN_H -#define HITLV2PLUGIN_H - -#include -#include - -#include - -class HITLFactory; - -class HITLPlugin : public ExtensionSystem::IPlugin -{ -public: - HITLPlugin(); - ~HITLPlugin(); - - void extensionsInitialized(); - bool initialize(const QStringList & arguments, QString * errorString); - void shutdown(); - - static void addSimulator(SimulatorCreator* creator) - { - HITLPlugin::typeSimulators.append(creator); - } - - static SimulatorCreator* getSimulatorCreator(const QString classId) - { - foreach(SimulatorCreator* creator, HITLPlugin::typeSimulators) { - if(classId == creator->ClassId()) - return creator; - } - return 0; - } - - static QList typeSimulators; - -private: - HITLFactory *mf; -}; -#endif /* HITLV2PLUGIN_H */ diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2widget.cpp b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2widget.cpp deleted file mode 100644 index 8933d7748..000000000 --- a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2widget.cpp +++ /dev/null @@ -1,188 +0,0 @@ -/** - ****************************************************************************** - * - * @file hitlv2widget.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup HITLPlugin HITLv2 Plugin - * @{ - * @brief The Hardware In The Loop plugin version 2 - *****************************************************************************/ -/* - * 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 "hitlv2widget.h" -#include "ui_hitlv2widget.h" -#include -#include -#include -#include -#include - -#include "hitlv2plugin.h" -#include "simulatorv2.h" -#include "uavobjectmanager.h" -#include -#include - -QStringList Simulator::instances; - -HITLWidget::HITLWidget(QWidget *parent) - : QWidget(parent), - simulator(0) -{ - widget = new Ui_HITLWidget(); - widget->setupUi(this); - widget->startButton->setEnabled(true); - widget->stopButton->setEnabled(false); - - strAutopilotDisconnected = " AP OFF "; - strSimulatorDisconnected = " Sim OFF "; - strAutopilotConnected = " AP ON "; -// strSimulatorConnected = " Sim ON "; - strStyleEnable = "QFrame{background-color: green; color: white}"; - strStyleDisable = "QFrame{background-color: red; color: grey}"; - - widget->apLabel->setText(strAutopilotDisconnected); - widget->simLabel->setText(strSimulatorDisconnected); - - connect(widget->startButton, SIGNAL(clicked()), this, SLOT(startButtonClicked())); - connect(widget->stopButton, SIGNAL(clicked()), this, SLOT(stopButtonClicked())); - connect(widget->buttonClearLog, SIGNAL(clicked()), this, SLOT(buttonClearLogClicked())); -} - -HITLWidget::~HITLWidget() -{ - delete widget; -} - -void HITLWidget::startButtonClicked() -{ - // allow only one instance per simulator - if (Simulator::Instances().indexOf(settings.simulatorId) != -1) { - widget->textBrowser->append(settings.simulatorId + " alreary started!"); - return; - } - - if (!HITLPlugin::typeSimulators.size()) { - widget->textBrowser->append("There is no registered simulators, add through HITLPlugin::addSimulator"); - return; - } - - // Stop running process if one is active - if (simulator) { - QMetaObject::invokeMethod(simulator, "onDeleteSimulator", Qt::QueuedConnection); - simulator = NULL; - } - - if (settings.hostAddress == "" || settings.inPort == 0) { - widget->textBrowser->append("Before start, set UDP parameters in options page!"); - return; - } - - SimulatorCreator* creator = HITLPlugin::getSimulatorCreator(settings.simulatorId); - simulator = creator->createSimulator(settings); - simulator->setName(creator->Description()); - simulator->setSimulatorId(creator->ClassId()); - - connect(simulator, SIGNAL(processOutput(QString)), this, SLOT(onProcessOutput(QString))); - - // Setup process - onProcessOutput(QString("[%1] Starting %2... ") - .arg(QTime::currentTime().toString("hh:mm:ss")) - .arg(creator->Description())); - - // Start bridge - bool ret = QMetaObject::invokeMethod(simulator, "setupProcess", Qt::QueuedConnection); - if (ret) { - Simulator::setInstance(settings.simulatorId); - - connect(this, SIGNAL(deleteSimulator()), simulator, SLOT(onDeleteSimulator()), Qt::QueuedConnection); - - widget->startButton->setEnabled(false); - widget->stopButton->setEnabled(true); - - connect(simulator, SIGNAL(autopilotConnected()), this, SLOT(onAutopilotConnect()), Qt::QueuedConnection); - connect(simulator, SIGNAL(autopilotDisconnected()), this, SLOT(onAutopilotDisconnect()), Qt::QueuedConnection); - connect(simulator, SIGNAL(simulatorConnected()), this, SLOT(onSimulatorConnect()), Qt::QueuedConnection); - connect(simulator, SIGNAL(simulatorDisconnected()), this, SLOT(onSimulatorDisconnect()), Qt::QueuedConnection); - - // Initialize connection status - if (simulator->isAutopilotConnected()) - onAutopilotConnect(); - else - onAutopilotDisconnect(); - - if (simulator->isSimulatorConnected()) - onSimulatorConnect(); - else - onSimulatorDisconnect(); - } -} - -void HITLWidget::stopButtonClicked() -{ - if (simulator) - widget->textBrowser->append(QString("[%1] Terminate %2 ") - .arg(QTime::currentTime().toString("hh:mm:ss")) - .arg(simulator->Name())); - - widget->startButton->setEnabled(true); - widget->stopButton->setEnabled(false); - widget->apLabel->setStyleSheet(QString::fromUtf8("QFrame{background-color: transparent; color: white}")); - widget->simLabel->setStyleSheet(QString::fromUtf8("QFrame{background-color: transparent; color: white}")); - widget->apLabel->setText(strAutopilotDisconnected); - widget->simLabel->setText(strSimulatorDisconnected); - if (simulator) { - QMetaObject::invokeMethod(simulator, "onDeleteSimulator", Qt::QueuedConnection); - simulator = NULL; - } -} - -void HITLWidget::buttonClearLogClicked() -{ - widget->textBrowser->clear(); -} - -void HITLWidget::onProcessOutput(QString text) -{ - widget->textBrowser->append(text); -} - -void HITLWidget::onAutopilotConnect() -{ - widget->apLabel->setStyleSheet(strStyleEnable); - widget->apLabel->setText(strAutopilotConnected); -} - -void HITLWidget::onAutopilotDisconnect() -{ - widget->apLabel->setStyleSheet(strStyleDisable); - widget->apLabel->setText(strAutopilotDisconnected); -} - -void HITLWidget::onSimulatorConnect() -{ - widget->simLabel->setStyleSheet(strStyleEnable); - widget->simLabel->setText(" " + simulator->Name() + " ON "); -} - -void HITLWidget::onSimulatorDisconnect() -{ - widget->simLabel->setStyleSheet(strStyleDisable); - widget->simLabel->setText(" " + simulator->Name() + " OFF "); -} diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2widget.h b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2widget.h deleted file mode 100644 index 6cf1c66c7..000000000 --- a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2widget.h +++ /dev/null @@ -1,72 +0,0 @@ -/** - ****************************************************************************** - * - * @file hitlv2widget.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup HITLPlugin HITLv2 Plugin - * @{ - * @brief The Hardware In The Loop plugin version 2 - *****************************************************************************/ -/* - * 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 HITLV2WIDGET_H -#define HITLV2WIDGET_H - -#include -#include -#include "simulatorv2.h" - -class Ui_HITLWidget; - -class HITLWidget : public QWidget -{ - Q_OBJECT - -public: - HITLWidget(QWidget *parent = 0); - ~HITLWidget(); - - void setSettingParameters(const SimulatorSettings& params) { settings = params; } - -signals: - void deleteSimulator(); - -private slots: - void startButtonClicked(); - void stopButtonClicked(); - void buttonClearLogClicked(); - void onProcessOutput(QString text); - void onAutopilotConnect(); - void onAutopilotDisconnect(); - void onSimulatorConnect(); - void onSimulatorDisconnect(); - -private: - Ui_HITLWidget* widget; - Simulator* simulator; - SimulatorSettings settings; - - QString strAutopilotDisconnected; - QString strSimulatorDisconnected; - QString strAutopilotConnected; -// QString strSimulatorConnected; - QString strStyleEnable; - QString strStyleDisable; -}; -#endif /* HITLV2WIDGET_H */ diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2widget.ui b/ground/openpilotgcs/src/plugins/hitlv2/hitlv2widget.ui deleted file mode 100644 index 48d2c2db2..000000000 --- a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2widget.ui +++ /dev/null @@ -1,314 +0,0 @@ - - - HITLWidget - - - - 0 - 0 - 477 - 300 - - - - - 0 - 0 - - - - Form - - - - -QScrollBar:vertical { - border: 1px solid grey; - background: grey; - margin: 22px 0 22px 0; - } - -QScrollBar:vertical:disabled { - border: 1px solid grey; - - background-color: grey; - margin: 22px 0 22px 0; - } - - QScrollBar::handle:vertical { -background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(120, 120, 255, 255), stop:1 rgba(80, 80, 160, 255)); - min-height: 20px; - } - -QScrollBar::handle:vertical:disabled{ -background-color: grey; - min-height: 20px; - } - - - QScrollBar::handle:vertical:pressed { - - background-color: rgb(85, 85, 255); -background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(170, 170, 255, 255), stop:1 rgba(80, 80, 160, 255)); - - min-height: 20px; - } - - QScrollBar::add-line:vertical { - border: 1px solid black; -background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(48, 48, 48, 255), stop:1 rgba(120, 120, 120, 255)); - height: 20px; - subcontrol-position: bottom; - subcontrol-origin: margin; - } - - QScrollBar::add-line:vertical:disabled { -background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(100, 100, 100, 255)); - border: 1px solid grey; - - } - - QScrollBar::sub-line:vertical:disabled { -background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(100, 100, 100, 255)); - border: 1px solid grey; - - } - - QScrollBar::add-line:vertical:pressed { -background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(255, 255, 255, 200), stop:1 rgba(180, 180, 180, 200)); - } - - QScrollBar::sub-line:vertical:pressed { -background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(255, 255, 255, 200), stop:1 rgba(180, 180, 180, 200)); - } - - QScrollBar::sub-line:vertical { - border: 1px solid black; -background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(48, 48, 48, 255), stop:1 rgba(120, 120, 120, 255)); - height: 20px; - subcontrol-position: top; - subcontrol-origin: margin; - } - QScrollBar::down-arrow:vertical { - - image: url(:/hitlnew/images/arrow-down2.png); - } - - QScrollBar::up-arrow:vertical { - image: url(:/hitlnew/images/arrow-up2.png); - } - - QScrollBar::add-page:vertical, QScrollBar::sub-page:vertical { - background: none; - } - - -QPushButton { -background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(110, 110, 110, 255), stop:1 rgba(71, 71, 71, 255)); - - color: rgb(255, 255, 255); -border: 1px solid black; -width: 66px; -height: 20px; -} - -QPushButton:disabled { -background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(120, 120, 120, 255)); - color: rgb(194, 194, 194); -border: 1px solid gray; -width: 66px; -height: 20px; -} - -QPushButton:hover { -background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(255, 255, 255, 200), stop:1 rgba(180, 180, 180, 200)); -color: rgb(255, 255, 255); -border: 0px; -} -QPushButton:pressed { -background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(48, 48, 48, 255), stop:1 rgba(120, 120, 120, 255)); -color: rgb(255, 255, 255); -border: 0px; -} - -QPushButton:checked { -background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(48, 48, 48, 255), stop:1 rgba(120, 120, 120, 255)); -color: rgb(255, 255, 255); -border: 0px; -} - - - - 0 - - - - - - 0 - 0 - - - - - 0 - 0 - - - - - 16777215 - 16777215 - - - - - -QFrame{ -background-color: qlineargradient(spread:pad, x1:0.5, y1:0, x2:0.5, y2:1, stop:0 rgba(110, 110, 110, 255), stop:1 rgba(71, 71, 71, 255)); -color: rgba(0, 0, 0, 128); -} - - - - QFrame::StyledPanel - - - QFrame::Raised - - - - QLayout::SetMaximumSize - - - - - QLayout::SetDefaultConstraint - - - - - Request update - - - - - - Start - - - - - - - false - - - Send update - - - Stop - - - - - - - - 0 - 22 - - - - - 50 - false - - - - Qt::LeftToRight - - - false - - - color: rgb(255, 255, 255); - - - AP OFF - - - Qt::AlignCenter - - - - - - - - 0 - 22 - - - - color: rgb(255, 255, 255); - - - Sim OFF - - - Qt::AlignCenter - - - - - - - Clear Log - - - - - - - - - - 0 - 0 - - - - - 0 - 0 - - - - false - - - QTextEdit { - background-color: white; - color: rgb(0, 0, 0); -} - - - QFrame::NoFrame - - - QFrame::Plain - - - Qt::ScrollBarAlwaysOn - - - - - - - - - - - diff --git a/ground/openpilotgcs/src/plugins/hitlv2/plugin.pro b/ground/openpilotgcs/src/plugins/hitlv2/plugin.pro deleted file mode 100644 index 2d375e426..000000000 --- a/ground/openpilotgcs/src/plugins/hitlv2/plugin.pro +++ /dev/null @@ -1,32 +0,0 @@ -TEMPLATE = lib -TARGET = HITLv2 -QT += network - -include(../../openpilotgcsplugin.pri) -include(hitlv2_dependencies.pri) - -HEADERS += \ - aerosimrc.h \ - hitlv2configuration.h \ - hitlv2factory.h \ - hitlv2gadget.h \ - hitlv2optionspage.h \ - hitlv2plugin.h \ - hitlv2widget.h \ - simulatorv2.h - -SOURCES += \ - aerosimrc.cpp \ - hitlv2configuration.cpp \ - hitlv2factory.cpp \ - hitlv2gadget.cpp \ - hitlv2optionspage.cpp \ - hitlv2plugin.cpp \ - hitlv2widget.cpp \ - simulatorv2.cpp - -FORMS += \ - hitlv2optionspage.ui \ - hitlv2widget.ui - -OTHER_FILES += hitlv2.pluginspec diff --git a/ground/openpilotgcs/src/plugins/hitlv2/simulatorv2.cpp b/ground/openpilotgcs/src/plugins/hitlv2/simulatorv2.cpp deleted file mode 100644 index bc5e0b0b1..000000000 --- a/ground/openpilotgcs/src/plugins/hitlv2/simulatorv2.cpp +++ /dev/null @@ -1,341 +0,0 @@ -/** - ****************************************************************************** - * - * @file simulatorv2.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup HITLPlugin HITLv2 Plugin - * @{ - * @brief The Hardware In The Loop plugin version 2 - *****************************************************************************/ -/* - * 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 "simulatorv2.h" -#include -#include -#include - -volatile bool Simulator::isStarted = false; - -const float Simulator::GEE = 9.81; -const float Simulator::FT2M = 0.3048; -const float Simulator::KT2MPS = 0.514444444; -const float Simulator::INHG2KPA = 3.386; -const float Simulator::FPS2CMPS = 30.48; -const float Simulator::DEG2RAD = (M_PI/180.0); -const float Simulator::RAD2DEG = (180.0/M_PI); - - -Simulator::Simulator(const SimulatorSettings& params) : - inSocket(NULL), - outSocket(NULL), - settings(params), - updatePeriod(50), - simTimeout(2000), - autopilotConnectionStatus(false), - simConnectionStatus(false), - txTimer(NULL), - simTimer(NULL), - name("") -{ - // move to thread - moveToThread(Core::ICore::instance()->threadManager()->getRealTimeThread()); - connect(this, SIGNAL(myStart()), this, SLOT(onStart()), Qt::QueuedConnection); - emit myStart(); -} - -Simulator::~Simulator() -{ -// qDebug() << "Simulator::~Simulator"; - if (inSocket) { - delete inSocket; - inSocket = NULL; - } - if (outSocket) { - delete outSocket; - outSocket = NULL; - } - if (txTimer) { - delete txTimer; - txTimer = NULL; - } - if (simTimer) { - delete simTimer; - simTimer = NULL; - } -} - -void Simulator::onDeleteSimulator(void) -{ -// qDebug() << "Simulator::onDeleteSimulator"; - resetAllObjects(); - - Simulator::setStarted(false); - Simulator::Instances().removeOne(simulatorId); - - disconnect(this); - delete this; -} - -void Simulator::onStart() -{ -// qDebug() << "Simulator::onStart"; - QMutexLocker locker(&lock); - - // Get required UAVObjects - ExtensionSystem::PluginManager* pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager* objManager = pm->getObject(); - -// actDesired = ActuatorDesired::GetInstance(objManager); -// manCtrlCommand = ManualControlCommand::GetInstance(objManager); -// velActual = VelocityActual::GetInstance(objManager); -// posActual = PositionActual::GetInstance(objManager); -// altActual = BaroAltitude::GetInstance(objManager); -// camDesired = CameraDesired::GetInstance(objManager); -// acsDesired = AccessoryDesired::GetInstance(objManager); - posHome = HomeLocation::GetInstance(objManager); - accels = Accels::GetInstance(objManager); - gyros = Gyros::GetInstance(objManager); - attActual = AttitudeActual::GetInstance(objManager); - gpsPosition = GPSPosition::GetInstance(objManager); - flightStatus = FlightStatus::GetInstance(objManager); - gcsReceiver = GCSReceiver::GetInstance(objManager); - actCommand = ActuatorCommand::GetInstance(objManager); - attSettings = AttitudeSettings::GetInstance(objManager); - sonarAlt = SonarAltitude::GetInstance(objManager); - - telStats = GCSTelemetryStats::GetInstance(objManager); - - // Listen to autopilot connection events - TelemetryManager* telMngr = pm->getObject(); - connect(telMngr, SIGNAL(connected()), this, SLOT(onAutopilotConnect())); - connect(telMngr, SIGNAL(disconnected()), this, SLOT(onAutopilotDisconnect())); - - // If already connect setup autopilot - GCSTelemetryStats::DataFields stats = telStats->getData(); - if (stats.Status == GCSTelemetryStats::STATUS_CONNECTED) - onAutopilotConnect(); - - emit processOutput("Local interface: " + settings.hostAddress + ":" + \ - QString::number(settings.inPort) + "\n" + \ - "Remote interface: " + settings.remoteAddress + ":" + \ - QString::number(settings.outPort) + "\n"); - - inSocket = new QUdpSocket(); - outSocket = new QUdpSocket(); - setupUdpPorts(settings.hostAddress, settings.inPort, settings.outPort); - - connect(inSocket, SIGNAL(readyRead()), this, SLOT(receiveUpdate())/*, Qt::DirectConnection*/); - - // Setup transmit timer - if (settings.manualOutput) { - txTimer = new QTimer(); - connect(txTimer, SIGNAL(timeout()), this, SLOT(transmitUpdate())/*, Qt::DirectConnection*/); - txTimer->setInterval(settings.outputRate); - txTimer->start(); - } - - // Setup simulator connection timer - simTimer = new QTimer(); - connect(simTimer, SIGNAL(timeout()), this, SLOT(onSimulatorConnectionTimeout())/*, Qt::DirectConnection*/); - simTimer->setInterval(simTimeout); - simTimer->start(); - -#ifdef DBG_TIMERS - timeRX = QTime(); - timeRX.start(); - timeTX = QTime(); - timeTX.start(); -#endif - - setupObjects(); -} - -void Simulator::receiveUpdate() -{ - // Update connection timer and status - simTimer->start(); - if (!simConnectionStatus) { - simConnectionStatus = true; - emit simulatorConnected(); - } - - // Process data - while (inSocket->hasPendingDatagrams()) { - // Receive datagram - QByteArray datagram; - datagram.resize(inSocket->pendingDatagramSize()); - QHostAddress sender; - quint16 senderPort; - inSocket->readDatagram(datagram.data(), datagram.size(), &sender, &senderPort); - // Process incomming data - processUpdate(datagram); - } - if (!settings.manualOutput) - transmitUpdate(); -} - -void Simulator::setupObjects() -{ - if (settings.gcsReciever) { - setupInputObject(actCommand, settings.outputRate); - setupOutputObject(gcsReceiver); - } else if (settings.manualControl) { -// setupInputObject(actDesired); -// setupInputObject(camDesired); -// setupInputObject(acsDesired); -// setupOutputObject(manCtrlCommand); - qDebug() << "ManualControlCommand not implemented yet"; - } - - if (settings.homeLocation) - setupOutputObject(posHome); - - if (settings.sonarAltitude) - setupOutputObject(sonarAlt); - - if (settings.gpsPosition) - setupOutputObject(gpsPosition); - - if (settings.attRaw || settings.attActual) { - setupOutputObject(accels); - setupOutputObject(gyros); - } - - if (settings.attActual && !settings.attActHW) - setupOutputObject(attActual); - else - setupWatchedObject(attActual); -} - -void Simulator::resetAllObjects() -{ - setupDefaultObject(posHome); - setupDefaultObject(accels); - setupDefaultObject(gyros); - setupDefaultObject(attActual); - setupDefaultObject(gpsPosition); - setupDefaultObject(gcsReceiver); - setupDefaultObject(actCommand); - setupDefaultObject(sonarAlt); -// setupDefaultObject(manCtrlCommand); -// setupDefaultObject(actDesired); -// setupDefaultObject(camDesired); -// setupDefaultObject(acsDesired); -// setupDefaultObject(altActual); -// setupDefaultObject(posActual); -// setupDefaultObject(velActual); -} - -void Simulator::setupInputObject(UAVObject* obj, quint32 updateRate) -{ - UAVObject::Metadata mdata; - mdata = obj->getDefaultMetadata(); - - UAVObject::SetGcsAccess(mdata, UAVObject::ACCESS_READONLY); - UAVObject::SetGcsTelemetryAcked(mdata, false); - UAVObject::SetGcsTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_MANUAL); - mdata.gcsTelemetryUpdatePeriod = 0; - - UAVObject::SetFlightAccess(mdata, UAVObject::ACCESS_READWRITE); - UAVObject::SetFlightTelemetryAcked(mdata, false); - - if (settings.manualOutput) { - UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC); - mdata.flightTelemetryUpdatePeriod = updateRate; - } else { - UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_ONCHANGE); - mdata.flightTelemetryUpdatePeriod = 0; - } - - obj->setMetadata(mdata); -} - -void Simulator::setupWatchedObject(UAVObject *obj) -{ - UAVObject::Metadata mdata; - mdata = obj->getDefaultMetadata(); - - UAVObject::SetGcsAccess(mdata, UAVObject::ACCESS_READONLY); - UAVObject::SetGcsTelemetryAcked(mdata, false); - UAVObject::SetGcsTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_MANUAL); - mdata.gcsTelemetryUpdatePeriod = 0; - - UAVObject::SetFlightAccess(mdata, UAVObject::ACCESS_READWRITE); - UAVObject::SetFlightTelemetryAcked(mdata, false); - UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC); - mdata.flightTelemetryUpdatePeriod = 100; - - obj->setMetadata(mdata); -} - -void Simulator::setupOutputObject(UAVObject* obj) -{ - UAVObject::Metadata mdata; - mdata = obj->getDefaultMetadata(); - - UAVObject::SetGcsAccess(mdata, UAVObject::ACCESS_READWRITE); - UAVObject::SetGcsTelemetryAcked(mdata, false); - UAVObject::SetGcsTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_ONCHANGE); - mdata.gcsTelemetryUpdatePeriod = 0; - - UAVObject::SetFlightAccess(mdata, UAVObject::ACCESS_READONLY); - UAVObject::SetFlightTelemetryAcked(mdata, false); - UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_MANUAL); - mdata.flightTelemetryUpdatePeriod = 0; - - obj->setMetadata(mdata); -} - -void Simulator::setupDefaultObject(UAVObject *obj) -{ - UAVObject::Metadata mdata; - mdata = obj->getDefaultMetadata(); - - obj->setMetadata(mdata); -} - -void Simulator::onAutopilotConnect() -{ - autopilotConnectionStatus = true; - emit autopilotConnected(); -} - -void Simulator::onAutopilotDisconnect() -{ - autopilotConnectionStatus = false; - emit autopilotDisconnected(); -} - -void Simulator::onSimulatorConnectionTimeout() -{ - if (simConnectionStatus) { - simConnectionStatus = false; - emit simulatorDisconnected(); - } -} - -void Simulator::telStatsUpdated(UAVObject* obj) -{ - GCSTelemetryStats::DataFields stats = telStats->getData(); - if (!autopilotConnectionStatus && stats.Status == GCSTelemetryStats::STATUS_CONNECTED) - onAutopilotConnect(); - else if (autopilotConnectionStatus && stats.Status != GCSTelemetryStats::STATUS_CONNECTED) - onAutopilotDisconnect(); -} - diff --git a/ground/openpilotgcs/src/plugins/hitlv2/simulatorv2.h b/ground/openpilotgcs/src/plugins/hitlv2/simulatorv2.h deleted file mode 100644 index 445358a22..000000000 --- a/ground/openpilotgcs/src/plugins/hitlv2/simulatorv2.h +++ /dev/null @@ -1,222 +0,0 @@ -/** - ****************************************************************************** - * - * @file simulatorv2.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup HITLPlugin HITLv2 Plugin - * @{ - * @brief The Hardware In The Loop plugin version 2 - *****************************************************************************/ -/* - * 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 ISIMULATORV2_H -#define ISIMULATORV2_H - -#include -#include -#include -#include -#include -#include -#include "uavtalk/telemetrymanager.h" -#include "uavobjectmanager.h" -#include "homelocation.h" -#include "accels.h" -#include "gyros.h" -#include "attitudeactual.h" -#include "gpsposition.h" -#include "flightstatus.h" -#include "gcsreceiver.h" -#include "actuatorcommand.h" -#include "gcstelemetrystats.h" -#include "attitudesettings.h" -#include "sonaraltitude.h" - -//#define DBG_TIMERS -#undef DBG_TIMERS - -/** - * just imagine this was a class without methods and all public properties - */ - -typedef struct _CONNECTION -{ - QString simulatorId; - QString hostAddress; - int inPort; - QString remoteAddress; - int outPort; - QString binPath; - QString dataPath; - - bool homeLocation; - quint16 homeLocRate; - - bool attRaw; - quint8 attRawRate; - - bool attActual; - bool attActHW; - bool attActSim; - bool attActCalc; - - bool sonarAltitude; - float sonarMaxAlt; - quint16 sonarAltRate; - - bool gpsPosition; - quint16 gpsPosRate; - - bool inputCommand; - bool gcsReciever; - bool manualControl; - bool manualOutput; - quint8 outputRate; - -} SimulatorSettings; - -class Simulator : public QObject -{ - Q_OBJECT - -public: - Simulator(const SimulatorSettings& params); - virtual ~Simulator(); - - bool isAutopilotConnected() const { return autopilotConnectionStatus; } - bool isSimulatorConnected() const { return simConnectionStatus; } - - QString Name() const { return name; } - void setName(QString str) { name = str; } - - QString SimulatorId() const { return simulatorId; } - void setSimulatorId(QString str) { simulatorId = str; } - - static bool IsStarted() { return isStarted; } - static void setStarted(bool val) { isStarted = val; } - - static QStringList& Instances() { return Simulator::instances; } - static void setInstance(const QString& str) { Simulator::instances.append(str); } - - virtual void stopProcess() {} - virtual void setupUdpPorts(const QString& host, int inPort, int outPort) { Q_UNUSED(host) Q_UNUSED(inPort) Q_UNUSED(outPort)} - -signals: - void processOutput(QString str); - void autopilotConnected(); - void autopilotDisconnected(); - void simulatorConnected(); - void simulatorDisconnected(); - void myStart(); - -public slots: - Q_INVOKABLE virtual bool setupProcess() { return true; } - -private slots: - void onStart(); - void receiveUpdate(); - void onAutopilotConnect(); - void onAutopilotDisconnect(); - void onSimulatorConnectionTimeout(); - void telStatsUpdated(UAVObject* obj); - Q_INVOKABLE void onDeleteSimulator(void); - - virtual void transmitUpdate() = 0; - virtual void processUpdate(const QByteArray& data) = 0; - -protected: - static const float GEE; - static const float FT2M; - static const float KT2MPS; - static const float INHG2KPA; - static const float FPS2CMPS; - static const float DEG2RAD; - static const float RAD2DEG; - -#ifdef DBG_TIMERS - QTime timeRX; - QTime timeTX; -#endif - - QUdpSocket* inSocket; - QUdpSocket* outSocket; - -// ActuatorDesired* actDesired; -// ManualControlCommand* manCtrlCommand; -// VelocityActual* velActual; -// PositionActual* posActual; -// BaroAltitude* altActual; -// CameraDesired *camDesired; -// AccessoryDesired *acsDesired; - Accels *accels; - Gyros *gyros; - AttitudeActual *attActual; - HomeLocation *posHome; - FlightStatus *flightStatus; - GPSPosition *gpsPosition; - GCSReceiver *gcsReceiver; - ActuatorCommand *actCommand; - AttitudeSettings *attSettings; - SonarAltitude *sonarAlt; - - GCSTelemetryStats* telStats; - SimulatorSettings settings; - - QMutex lock; - -private: - int updatePeriod; - int simTimeout; - volatile bool autopilotConnectionStatus; - volatile bool simConnectionStatus; - QTimer* txTimer; - QTimer* simTimer; - QString name; - QString simulatorId; - volatile static bool isStarted; - static QStringList instances; - - void setupObjects(); - void resetAllObjects(); - void setupInputObject(UAVObject* obj, quint32 updateRate); - void setupOutputObject(UAVObject* obj); - void setupWatchedObject(UAVObject *obj); - void setupDefaultObject(UAVObject *obj); -}; - -class SimulatorCreator -{ -public: - SimulatorCreator(QString id, QString descr) : - classId(id), - description(descr) - {} - virtual ~SimulatorCreator() {} - - QString ClassId() const { return classId; } - QString Description() const { return description; } - - virtual Simulator* createSimulator(const SimulatorSettings& params) = 0; - -private: - QString classId; - QString description; -}; - -#endif // ISIMULATORV2_H diff --git a/ground/openpilotgcs/src/plugins/ipconnection/ipconnectionoptionspage.ui b/ground/openpilotgcs/src/plugins/ipconnection/ipconnectionoptionspage.ui index e02a15577..26df94b66 100644 --- a/ground/openpilotgcs/src/plugins/ipconnection/ipconnectionoptionspage.ui +++ b/ground/openpilotgcs/src/plugins/ipconnection/ipconnectionoptionspage.ui @@ -6,71 +6,130 @@ 0 0 - 388 - 300 + 429 + 291
Form - - + + + 12 + + 0 - - + + 12 + + + 0 + + + + + QFrame::NoFrame + + + QFrame::Plain + + + true + + + + + 0 + 0 + 390 + 154 + + + + + 0 + + + + + IP Network Telemetry + + + + + + Host Name/Number + + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + TCP connection + + + + + + + UDP connection + + + + + + + Port + + + + + + + 1 + + + 999999 + + + + + + + + + + + + - Qt::Horizontal + Qt::Vertical - 40 - 20 + 20 + 40 - - - - TCP connection - - - - - - - UDP connection - - - - - - - 1 - - - 999999 - - - - - - - Port - - - - - - - - - - Host Name/Number - - - diff --git a/ground/openpilotgcs/src/plugins/lineardial/lineardialgadgetoptionspage.ui b/ground/openpilotgcs/src/plugins/lineardial/lineardialgadgetoptionspage.ui index 9bf5c93e0..06c14c183 100644 --- a/ground/openpilotgcs/src/plugins/lineardial/lineardialgadgetoptionspage.ui +++ b/ground/openpilotgcs/src/plugins/lineardial/lineardialgadgetoptionspage.ui @@ -6,8 +6,8 @@ 0 0 - 540 - 347 + 604 + 455 @@ -20,478 +20,509 @@ Form + + 0 + - - - - - Use OpenGL - - - true - - - - - - - - - Qt::Horizontal + + + QFrame::NoFrame + + QFrame::Plain + + + true + + + + + 0 + 0 + 604 + 455 + + + + + 0 + + + + + + + + 0 + 0 + + + + Whole range: + + + + + + + Min: + + + + + + + + 0 + 0 + + + + 3 + + + -99999.000000000000000 + + + 99999.990000000005239 + + + + + + + Max: + + + + + + + + 0 + 0 + + + + 3 + + + -99999.000000000000000 + + + 99999.990000000005239 + + + + + + + + + + + + 0 + 0 + + + + Red: + + + + + + + Min: + + + + + + + + 0 + 0 + + + + 3 + + + -99999.000000000000000 + + + 99999.990000000005239 + + + + + + + Max: + + + + + + + + 0 + 0 + + + + 3 + + + -99999.000000000000000 + + + 99999.990000000005239 + + + + + + + + + + + + 0 + 0 + + + + Yellow: + + + + + + + Min: + + + + + + + + 0 + 0 + + + + 3 + + + -99999.000000000000000 + + + 99999.990000000005239 + + + + + + + Max: + + + + + + + + 0 + 0 + + + + 3 + + + -99999.000000000000000 + + + 99999.990000000005239 + + + + + + + + + 0 + + + + + + 0 + 0 + + + + Dial font: + + + + + + + Select... + + + + + + + Decimal places: + + + + + + + 99 + + + + + + + Factor: + + + + + + + 6 + + + -10000.000000000000000 + + + 100000.000000000000000 + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + Qt::Horizontal + + + + + + + + + + 0 + 0 + + + + Input: + + + + + + + ObjectName + + + + + + + + 0 + 0 + + + + + + + + ObjectField + + + + + + + + 0 + 0 + + + + + + + + + + + + + 0 + 0 + + + + Green: + + + + + + + Min: + + + + + + + + 0 + 0 + + + + 3 + + + -99999.000000000000000 + + + 99999.990000000005239 + + + + + + + Max: + + + + + + + + 0 + 0 + + + + 3 + + + -99999.000000000000000 + + + 99999.990000000005239 + + + + + + + + + + + Use OpenGL + + + true + + + + + + + + + Qt::Horizontal + + + + + + + 10 + + + QLayout::SetMaximumSize + + + 10 + + + + + Dial SVG: + + + + + + + + 0 + 0 + + + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + - - - - 10 - - - QLayout::SetMaximumSize - - - 10 - - - - - Dial SVG: - - - - - - - - 0 - 0 - - - - - - - - - - - - - 0 - 0 - - - - Whole range: - - - - - - - Min: - - - - - - - - 0 - 0 - - - - 3 - - - -99999.000000000000000 - - - 99999.990000000005239 - - - - - - - Max: - - - - - - - - 0 - 0 - - - - 3 - - - -99999.000000000000000 - - - 99999.990000000005239 - - - - - - - - - Qt::Horizontal - - - - - - - - - - 0 - 0 - - - - Green: - - - - - - - Min: - - - - - - - - 0 - 0 - - - - 3 - - - -99999.000000000000000 - - - 99999.990000000005239 - - - - - - - Max: - - - - - - - - 0 - 0 - - - - 3 - - - -99999.000000000000000 - - - 99999.990000000005239 - - - - - - - - - - - - 0 - 0 - - - - Yellow: - - - - - - - Min: - - - - - - - - 0 - 0 - - - - 3 - - - -99999.000000000000000 - - - 99999.990000000005239 - - - - - - - Max: - - - - - - - - 0 - 0 - - - - 3 - - - -99999.000000000000000 - - - 99999.990000000005239 - - - - - - - - - - - - 0 - 0 - - - - Red: - - - - - - - Min: - - - - - - - - 0 - 0 - - - - 3 - - - -99999.000000000000000 - - - 99999.990000000005239 - - - - - - - Max: - - - - - - - - 0 - 0 - - - - 3 - - - -99999.000000000000000 - - - 99999.990000000005239 - - - - - - - - - - - - 0 - 0 - - - - Input: - - - - - - - ObjectName - - - - - - - - 0 - 0 - - - - - - - - ObjectField - - - - - - - - 0 - 0 - - - - - - - - - - 0 - - - - - - 0 - 0 - - - - Dial font: - - - - - - - Select... - - - - - - - Decimal places: - - - - - - - 99 - - - - - - - Factor: - - - - - - - 6 - - - -10000.000000000000000 - - - 100000.000000000000000 - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - diff --git a/ground/openpilotgcs/src/plugins/notify/notifypluginoptionspage.ui b/ground/openpilotgcs/src/plugins/notify/notifypluginoptionspage.ui index 94560ff1a..39e0c4c5b 100644 --- a/ground/openpilotgcs/src/plugins/notify/notifypluginoptionspage.ui +++ b/ground/openpilotgcs/src/plugins/notify/notifypluginoptionspage.ui @@ -6,8 +6,8 @@ 0 0 - 570 - 453 + 608 + 483 @@ -19,361 +19,413 @@ Form - - - QLayout::SetMinimumSize + + + 12 + + + 0 + + + 12 + + + 0 - - - QLayout::SetFixedSize + + + QFrame::NoFrame - - - - - 0 - 0 - + + QFrame::Plain + + + true + + + + + 0 + 0 + 584 + 483 + + + + + 0 - - Sound Collection + + 12 - - - - - true + + 0 + + + 0 + + + + + + + + Sound Notifications + + + + 12 - - - 75 - 23 - - - - - 550 - 16777215 - - - - - - - - - 0 - 0 - - - - Language - - - - - - - - 147 - 0 - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> + + + + QAbstractItemView::ContiguousSelection + + + QAbstractItemView::SelectRows + + + 22 + + + 22 + + + + + + + 0 + + + + + Enable Sounds + + + + + + + Qt::Horizontal + + + + 138 + 20 + + + + + + + + Play + + + + :/notify/images/play.png:/notify/images/play.png + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Add + + + + :/notify/images/add.png:/notify/images/add.png + + + + + + + Modify + + + + :/notify/images/modify.png:/notify/images/modify.png + + + + + + + Delete + + + + :/utils/images/removesubmitfield.png:/utils/images/removesubmitfield.png + + + + + + + + + + + + + + + + + DataObject + + + + + + + + 0 + 0 + + + + + + + + ObjectField + + + + + + + + 0 + 0 + + + + + + + + + + QLayout::SetFixedSize + + + + + + 0 + 0 + + + + Sound Collection + + + + + + true + + + + 75 + 23 + + + + + 550 + 16777215 + + + + + + + + + 0 + 0 + + + + Language + + + + + + + + 147 + 0 + + + + <!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:'MS Shell Dlg 2'; font-size:8.25pt; 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:8pt;">Select the sound collection</span></p></body></html> - - - - - - - - - - - - - - - - - DataObject - - - - - - - - 0 - 0 - - - - - - - - ObjectField - - - - - - - - 0 - 0 - - - - - - - - - - Qt::Horizontal - - - - - - - - - - - - - 0 - 0 - - - - Sound1: - - - - - - - - 0 - 0 - - - - - 110 - 0 - - - - - 16777215 - 16777215 - - - - - - - - - 0 - 0 - - - - Sound2: - - - - - - - - 0 - 0 - - - - - 110 - 0 - - - - - 16777215 - 16777215 - - - - - - - - - 0 - 0 - - - - Sound3: - - - - - - - - 0 - 0 - - - - - 110 - 0 - - - - - 16777215 - 16777215 - - - - - - - - - - - - - Sound Notifications - - - - - - QAbstractItemView::ContiguousSelection - - - QAbstractItemView::SelectRows - - - 22 - - - 22 - - - - - - - - - Enable Sounds - - - - - - - Qt::Horizontal - - - - 138 - 20 - - - - - - - - Play - - - - :/notify/images/play.png:/notify/images/play.png - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Add - - - - :/notify/images/add.png:/notify/images/add.png - - - - - - - Modify - - - - :/notify/images/modify.png:/notify/images/modify.png - - - - - - - Delete - - - - :/utils/images/removesubmitfield.png:/utils/images/removesubmitfield.png - - - - - - + + + + + + + + + + + + Qt::Horizontal + + + + + + + + + + + + + 0 + 0 + + + + Sound1: + + + + + + + + 0 + 0 + + + + + 110 + 0 + + + + + 16777215 + 16777215 + + + + + + + + + 0 + 0 + + + + Sound2: + + + + + + + + 0 + 0 + + + + + 110 + 0 + + + + + 16777215 + 16777215 + + + + + + + + + 0 + 0 + + + + Sound3: + + + + + + + + 0 + 0 + + + + + 110 + 0 + + + + + 16777215 + 16777215 + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetoptionspage.ui b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetoptionspage.ui index 913678fae..fde5fd44b 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetoptionspage.ui +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetoptionspage.ui @@ -6,12 +6,12 @@ 0 0 - 445 - 300 + 564 + 391 - + 0 0 @@ -19,450 +19,487 @@ 445 - 300 + 5 Form - + - 5 + 0 - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Map type - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 0 - - - - OpenHandCursor - - - 15 - - - true - - - - - - - Default zoom - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 0 - - - - - 50 - 16777215 - - - - true - - - 2 - - - 18 - - - - - - - Default latitude - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 120 - 0 - - - - true - - - 8 - - - -90.000000000000000 - - - 90.000000000000000 - - - - - - - Default longitude - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 120 - 0 - - - - true - - - 8 - - - -180.000000000000000 - - - 180.000000000000000 - - - - - - - true - - - - 0 - 0 - - - - - 161 - 0 - - - - true - - - Qt::RightToLeft - - - Show Tile Grid Lines - - - - - - - true - - - - 0 - 0 - - - - - 0 - 0 - - - - Qt::RightToLeft - - - Use OpenGL - - - - - - - - - - Default Max Update Rate - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - - Qt::Vertical + + + + QFrame::NoFrame - - - 20 - 40 - + + QFrame::Plain - - - - - - Qt::Horizontal + + true + + + + 0 + 0 + 564 + 391 + + + + + 0 + 0 + + + + + 12 + + + + + + + + 0 + 0 + + + + UAV Symbol + + + + + + + + 0 + 0 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + Qt::Horizontal + + + + + + + + + + 0 + 0 + + + + Cache location + + + + + + + + 0 + 0 + + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + OpenHandCursor + + + Restore default server and cache settings + + + Default + + + false + + + false + + + false + + + + + + + + + + + Access mode + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 160 + 0 + + + + OpenHandCursor + + + true + + + + + + + true + + + + 0 + 0 + + + + + 0 + 0 + + + + Qt::RightToLeft + + + Use Memory Cache + + + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Map type + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + OpenHandCursor + + + 15 + + + true + + + + + + + Default zoom + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 50 + 16777215 + + + + true + + + 2 + + + 18 + + + + + + + Default latitude + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 120 + 0 + + + + true + + + 8 + + + -90.000000000000000 + + + 90.000000000000000 + + + + + + + Default longitude + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 120 + 0 + + + + true + + + 8 + + + -180.000000000000000 + + + 180.000000000000000 + + + + + + + true + + + + 0 + 0 + + + + + 161 + 0 + + + + true + + + Qt::RightToLeft + + + Show Tile Grid Lines + + + + + + + true + + + + 0 + 0 + + + + + 0 + 0 + + + + Qt::RightToLeft + + + Use OpenGL + + + + + + + + + + Default Max Update Rate + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + + Server and Cache + + + Qt::AlignCenter + + + + + + + Qt::Vertical + + + QSizePolicy::Preferred + + + + 20 + 40 + + + + + + + + + + verticalSpacer + line + label_7 + - - - - Server and Cache - - - Qt::AlignCenter - - - - - - - Qt::Horizontal - - - - - - - - - Access mode - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 160 - 0 - - - - OpenHandCursor - - - true - - - - - - - true - - - - 0 - 0 - - - - - 0 - 0 - - - - Qt::RightToLeft - - - Use Memory Cache - - - - - - - - - - - - 0 - 0 - - - - Cache location - - - - - - - - 0 - 0 - - - - - - - - - 0 - 0 - - - - - 0 - 0 - - - - OpenHandCursor - - - Restore default server and cache settings - - - Default - - - false - - - false - - - false - - - - - - - - - - - - 0 - 0 - - - - UAV Symbol - - - - - - - - 0 - 0 - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp index 19a2a0426..c4e084a89 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.cpp @@ -866,8 +866,10 @@ void OPMapGadgetWidget::onTelemetryConnect() setHome(internals::PointLatLng(LLA[0], LLA[1]),LLA[2]); if (m_map) - m_map->SetCurrentPosition(m_home_position.coord); // set the map position - + { + if(m_map->UAV->GetMapFollowType()!=UAVMapFollowType::None) + m_map->SetCurrentPosition(m_home_position.coord); // set the map position + } // *********************** } @@ -2167,6 +2169,7 @@ void OPMapGadgetWidget::on_tbFind_clicked() { pal.setColor( m_widget->leFind->backgroundRole(), Qt::green); m_widget->leFind->setPalette(pal); + m_map->SetZoom(12); } else { @@ -2188,3 +2191,8 @@ void OPMapGadgetWidget::onOverlayOpacityActGroup_triggered(QAction *action) m_map->setOverlayOpacity(action->data().toReal()/100); emit overlayOpacityChanged(action->data().toReal()/100); } + +void OPMapGadgetWidget::on_leFind_returnPressed() +{ + on_tbFind_clicked(); +} diff --git a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h index c58eade5e..fbac0b958 100644 --- a/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/opmap/opmapgadgetwidget.h @@ -212,6 +212,8 @@ private slots: void on_tbFind_clicked(); void onHomeDoubleClick(HomeItem*); void onOverlayOpacityActGroup_triggered(QAction *action); + void on_leFind_returnPressed(); + private: int m_min_zoom; int m_max_zoom; diff --git a/ground/openpilotgcs/src/plugins/pfd/pfdgadgetoptionspage.ui b/ground/openpilotgcs/src/plugins/pfd/pfdgadgetoptionspage.ui index f9a2808b3..86e92c283 100644 --- a/ground/openpilotgcs/src/plugins/pfd/pfdgadgetoptionspage.ui +++ b/ground/openpilotgcs/src/plugins/pfd/pfdgadgetoptionspage.ui @@ -6,8 +6,8 @@ 0 0 - 529 - 271 + 430 + 306 @@ -20,97 +20,128 @@ Form + + 0 + - - - 10 + + + QFrame::NoFrame - - QLayout::SetMaximumSize + + QFrame::Plain - - 10 + + true - - - - PFD SVG: + + + + 0 + 0 + 430 + 306 + + + + + 0 - - - - - - - 0 - 0 - - - - - - - - - - Qt::Horizontal - + + + + 10 + + + QLayout::SetMaximumSize + + + 10 + + + + + PFD SVG: + + + + + + + + 0 + 0 + + + + + + + + + + + + true + + + Use OpenGL for rendering + + + true + + + + + + + High Quality text (OpenGL) + + + + + + + + + + + Smooth updates + + + true + + + + + + + + + Qt::Horizontal + + + + + + + Qt::Vertical + + + QSizePolicy::MinimumExpanding + + + + 20 + 40 + + + + + + - - - - - - true - - - Use OpenGL for rendering - - - true - - - - - - - High Quality text (OpenGL) - - - - - - - - - - - Smooth updates - - - true - - - - - - - - - Qt::Vertical - - - QSizePolicy::MinimumExpanding - - - - 20 - 40 - - - - diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadget.h b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadget.h index 073e1f326..be6625ab0 100644 --- a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadget.h +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadget.h @@ -1,45 +1,45 @@ -/* - * 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 PFDQMLGADGET_H_ -#define PFDQMLQMLGADGET_H_ - -#include -#include "pfdqmlgadgetwidget.h" - -class IUAVGadget; -class QWidget; -class QString; -class PfdQmlGadgetWidget; - -using namespace Core; - -class PfdQmlGadget : public Core::IUAVGadget -{ - Q_OBJECT -public: - PfdQmlGadget(QString classId, PfdQmlGadgetWidget *widget, QWidget *parent = 0); - ~PfdQmlGadget(); - - QWidget *widget() { return m_widget; } - void loadConfiguration(IUAVGadgetConfiguration* config); - -private: - PfdQmlGadgetWidget *m_widget; -}; - - -#endif // PFDQMLQMLGADGET_H_ +/* + * 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 PFDQMLGADGET_H_ +#define PFDQMLQMLGADGET_H_ + +#include +#include "pfdqmlgadgetwidget.h" + +class IUAVGadget; +class QWidget; +class QString; +class PfdQmlGadgetWidget; + +using namespace Core; + +class PfdQmlGadget : public Core::IUAVGadget +{ + Q_OBJECT +public: + PfdQmlGadget(QString classId, PfdQmlGadgetWidget *widget, QWidget *parent = 0); + ~PfdQmlGadget(); + + QWidget *widget() { return m_widget; } + void loadConfiguration(IUAVGadgetConfiguration* config); + +private: + PfdQmlGadgetWidget *m_widget; +}; + + +#endif // PFDQMLQMLGADGET_H_ diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.ui b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.ui index 92e87fbb3..20d617e9b 100644 --- a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.ui +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetoptionspage.ui @@ -20,6 +20,9 @@ Form + + 0 + @@ -36,11 +39,14 @@ 0 0 - 439 - 418 + 457 + 436 + + 0 + diff --git a/ground/openpilotgcs/src/plugins/plugins.pro b/ground/openpilotgcs/src/plugins/plugins.pro index de7a462e1..5d3aa31a2 100644 --- a/ground/openpilotgcs/src/plugins/plugins.pro +++ b/ground/openpilotgcs/src/plugins/plugins.pro @@ -10,7 +10,6 @@ SUBDIRS = plugin_coreplugin #plugin_donothing.subdir = donothing #plugin_donothing.depends = plugin_coreplugin - # Core plugin plugin_coreplugin.subdir = coreplugin @@ -55,12 +54,14 @@ plugin_opmap.subdir = opmap plugin_opmap.depends = plugin_coreplugin plugin_opmap.depends += plugin_uavobjects plugin_opmap.depends += plugin_uavobjectutil +plugin_opmap.depends += plugin_uavtalk SUBDIRS += plugin_opmap # Scope UAVGadget plugin_scope.subdir = scope plugin_scope.depends = plugin_coreplugin plugin_scope.depends += plugin_uavobjects +plugin_scope.depends += plugin_uavtalk SUBDIRS += plugin_scope # UAVObject Browser gadget @@ -75,57 +76,60 @@ plugin_modelview.depends = plugin_coreplugin plugin_modelview.depends += plugin_uavobjects SUBDIRS += plugin_modelview - #Qt 4.8.0 / phonon may crash on Mac, fixed in Qt 4.8.1, QTBUG-23128 macx:contains(QT_VERSION, ^4\\.8\\.0): CONFIG += disable_notify_plugin +# Notify gadget !disable_notify_plugin { -#Notify gadget -plugin_notify.subdir = notify -plugin_notify.depends = plugin_coreplugin -plugin_notify.depends += plugin_uavobjects -SUBDIRS += plugin_notify + plugin_notify.subdir = notify + plugin_notify.depends = plugin_coreplugin + plugin_notify.depends += plugin_uavobjects + plugin_notify.depends += plugin_uavtalk + SUBDIRS += plugin_notify } -#Uploader gadget +# Uploader gadget plugin_uploader.subdir = uploader plugin_uploader.depends = plugin_coreplugin plugin_uploader.depends += plugin_uavobjects +plugin_uploader.depends += plugin_uavtalk plugin_uploader.depends += plugin_rawhid plugin_uploader.depends += plugin_uavobjectutil SUBDIRS += plugin_uploader -#Dial gadget +# Dial gadget plugin_dial.subdir = dial plugin_dial.depends = plugin_coreplugin plugin_dial.depends += plugin_uavobjects SUBDIRS += plugin_dial -#Linear Dial gadget +# Linear Dial gadget plugin_lineardial.subdir = lineardial plugin_lineardial.depends = plugin_coreplugin plugin_lineardial.depends += plugin_uavobjects SUBDIRS += plugin_lineardial -#System Health gadget +# System Health gadget plugin_systemhealth.subdir = systemhealth plugin_systemhealth.depends = plugin_coreplugin plugin_systemhealth.depends += plugin_uavobjects plugin_systemhealth.depends += plugin_uavtalk SUBDIRS += plugin_systemhealth -#Config gadget +# Config gadget plugin_config.subdir = config plugin_config.depends = plugin_coreplugin +plugin_config.depends += plugin_uavtalk plugin_config.depends += plugin_uavobjects +plugin_config.depends += plugin_uavobjectutil plugin_config.depends += plugin_uavobjectwidgetutils plugin_config.depends += plugin_uavsettingsimportexport SUBDIRS += plugin_config -#GPS Display gadget +# GPS Display gadget plugin_gpsdisplay.subdir = gpsdisplay plugin_gpsdisplay.depends = plugin_coreplugin -plugin_gpsdisplay.depends += plugin_uavtalk +plugin_gpsdisplay.depends += plugin_uavobjects SUBDIRS += plugin_gpsdisplay # Primary Flight Display (PFD) gadget @@ -158,24 +162,17 @@ plugin_pfdqml.depends = plugin_coreplugin plugin_pfdqml.depends += plugin_uavobjects SUBDIRS += plugin_pfdqml -#IP connection plugin +# IP connection plugin plugin_ipconnection.subdir = ipconnection plugin_ipconnection.depends = plugin_coreplugin SUBDIRS += plugin_ipconnection -#HITLNEW Simulation gadget -plugin_hitlnew.subdir = hitlnew -plugin_hitlnew.depends = plugin_coreplugin -plugin_hitlnew.depends += plugin_uavobjects -plugin_hitlnew.depends += plugin_uavtalk -SUBDIRS += plugin_hitlnew - -#HITLNEW Simulation gadget v2 -plugin_hitl_v2.subdir = hitlv2 -plugin_hitl_v2.depends = plugin_coreplugin -plugin_hitl_v2.depends += plugin_uavobjects -plugin_hitl_v2.depends += plugin_uavtalk -SUBDIRS += plugin_hitl_v2 +#HITL Simulation gadget +plugin_hitl.subdir = hitl +plugin_hitl.depends = plugin_coreplugin +plugin_hitl.depends += plugin_uavobjects +plugin_hitl.depends += plugin_uavtalk +SUBDIRS += plugin_hitl # Export and Import GCS Configuration plugin_importexport.subdir = importexport @@ -190,20 +187,19 @@ plugin_logging.depends += plugin_uavtalk plugin_logging.depends += plugin_scope SUBDIRS += plugin_logging -#GCS Control of UAV gadget +# GCS Control of UAV gadget plugin_gcscontrol.subdir = gcscontrol plugin_gcscontrol.depends = plugin_coreplugin plugin_gcscontrol.depends += plugin_uavobjects -plugin_gcscontrol.depends += plugin_uavtalk SUBDIRS += plugin_gcscontrol # Antenna tracker #plugin_antennatrack.subdir = antennatrack #plugin_antennatrack.depends = plugin_coreplugin -#plugin_antennatrack.depends += plugin_uavtalk +#plugin_antennatrack.depends += plugin_uavobjects #SUBDIRS += plugin_antennatrack -#Scope OpenGL Gadget +# Scope OpenGL Gadget #plugin_scopeogl.subdir = scopeogl #plugin_scopeogl.depends = plugin_coreplugin #plugin_scopeogl.depends += plugin_uavobjects @@ -234,6 +230,7 @@ SUBDIRS += plugin_magicwaypoint plugin_uavsettingsimportexport.subdir = uavsettingsimportexport plugin_uavsettingsimportexport.depends = plugin_coreplugin plugin_uavsettingsimportexport.depends += plugin_uavobjects +plugin_uavsettingsimportexport.depends += plugin_uavobjectutil SUBDIRS += plugin_uavsettingsimportexport # UAV Object Widget Utility plugin @@ -242,8 +239,17 @@ plugin_uavobjectwidgetutils.depends = plugin_coreplugin plugin_uavobjectwidgetutils.depends += plugin_uavobjects plugin_uavobjectwidgetutils.depends += plugin_uavobjectutil plugin_uavobjectwidgetutils.depends += plugin_uavsettingsimportexport +plugin_uavobjectwidgetutils.depends += plugin_uavtalk SUBDIRS += plugin_uavobjectwidgetutils +# Setup Wizard plugin +plugin_setupwizard.subdir = setupwizard +plugin_setupwizard.depends = plugin_coreplugin +plugin_setupwizard.depends += plugin_uavobjectutil +plugin_setupwizard.depends += plugin_config +plugin_setupwizard.depends += plugin_uploader +SUBDIRS += plugin_setupwizard + # Junsi Powerlog plugin #plugin_powerlog.subdir = powerlog #plugin_powerlog.depends = plugin_coreplugin diff --git a/ground/openpilotgcs/src/plugins/qmlview/qmlviewgadgetoptionspage.ui b/ground/openpilotgcs/src/plugins/qmlview/qmlviewgadgetoptionspage.ui index aa9667b50..d23bcad19 100644 --- a/ground/openpilotgcs/src/plugins/qmlview/qmlviewgadgetoptionspage.ui +++ b/ground/openpilotgcs/src/plugins/qmlview/qmlviewgadgetoptionspage.ui @@ -6,8 +6,8 @@ 0 0 - 529 - 271 + 423 + 318 @@ -19,77 +19,108 @@ Form - + + + 0 + - - - 10 + + + QFrame::NoFrame - - QLayout::SetMaximumSize + + QFrame::Plain - - 10 + + true - - - - QML file: + + + + 0 + 0 + 423 + 318 + + + + + 0 - - - - - - - 0 - 0 - - - - - - - - - - Qt::Horizontal - + + + + Qt::Horizontal + + + + + + + + + true + + + Use OpenGL for rendering + + + true + + + + + + + + + 10 + + + QLayout::SetMaximumSize + + + 10 + + + + + QML file: + + + + + + + + 0 + 0 + + + + + + + + + + Qt::Vertical + + + QSizePolicy::MinimumExpanding + + + + 20 + 40 + + + + + + - - - - - - true - - - Use OpenGL for rendering - - - true - - - - - - - - - Qt::Vertical - - - QSizePolicy::MinimumExpanding - - - - 20 - 40 - - - - diff --git a/ground/openpilotgcs/src/plugins/scope/plotdata.cpp b/ground/openpilotgcs/src/plugins/scope/plotdata.cpp index 57b17c193..c916b9cc5 100644 --- a/ground/openpilotgcs/src/plugins/scope/plotdata.cpp +++ b/ground/openpilotgcs/src/plugins/scope/plotdata.cpp @@ -165,7 +165,7 @@ bool ChronoPlotData::append(UAVObject* obj) //Perform scope math, if necessary if (mathFunction == "Boxcar average" || mathFunction == "Standard deviation"){ - //Put the new value at the front + //Put the new value at the back yDataHistory->append( currentValue ); // calculate average value diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.ui b/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.ui index c120544aa..e5da31784 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.ui +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetoptionspage.ui @@ -6,429 +6,460 @@ 0 0 - 548 - 457 + 753 + 576 Form - + + + 0 + - - - - - true - - - - - - - - 255 - 0 - 0 - - - - - - - - - 255 - 0 - 0 - - - - - - - - - 120 - 120 - 120 - - - - - - - - 1 - - - - - - - - - - - - QLayout::SetDefaultConstraint + + + QFrame::NoFrame - - - - QFormLayout::AllNonFixedFieldsGrow - - - - - - Bitstream Charter - 75 - true - - - - X-Axis - - - - - - - Plot Type: - - - - - - - Qt::StrongFocus - - - - - - - Data Size: - - - - - - - Qt::StrongFocus - - - seconds - - - 5000 - - - 30 - - - 300 - - - - - - - Update Interval: - - - - - - - Qt::StrongFocus - - - ms - - - 10 - - - 30000 - - - 500 - - - 1000 - - - - - - - - Bitstream Charter - 75 - true - - - - Y-axis - - - - - - - UAVObject: - - - - - - - Qt::StrongFocus - - - - - - - UAVField: - - - - - - - Qt::StrongFocus - - - - - - - Color: - - - - - - - Qt::StrongFocus - - - Choose - - - - - - - Y-axis scale factor: - - - - - - - Qt::StrongFocus - - - false - - - - - - - Math window size - - - - - - - false - - - - 16777215 - 16777215 - - - - Qt::StrongFocus - - - samples - - - 1 - - - 1001 - - - 10 - - - 1 - - - - - - - Math function: - - - - - - - Qt::StrongFocus - - - - - - - - - QLayout::SetFixedSize + + QFrame::Plain + + + true + + + + + 0 + 0 + 753 + 576 + + + + + 0 - - - Qt::Vertical + + + QLayout::SetDefaultConstraint - - - 20 - 100 - - - - - - - - Add a new curve to the scope, or update it if the UAVObject and UAVField is the same. - - - Add + + + + QFormLayout::AllNonFixedFieldsGrow + + + + + + Bitstream Charter + 75 + true + + + + X-Axis + + + + + + + Plot Type: + + + + + + + Qt::StrongFocus + + + + + + + Data Size: + + + + + + + Qt::StrongFocus + + + seconds + + + 5000 + + + 30 + + + 300 + + + + + + + Update Interval: + + + + + + + Qt::StrongFocus + + + ms + + + 10 + + + 30000 + + + 500 + + + 1000 + + + + + + + + Bitstream Charter + 75 + true + + + + Y-axis + + + + + + + UAVObject: + + + + + + + Qt::StrongFocus + + + + + + + UAVField: + + + + + + + Qt::StrongFocus + + + + + + + Color: + + + + + + + Qt::StrongFocus + + + Choose + + + + + + + Y-axis scale factor: + + + + + + + Qt::StrongFocus + + + false + + + + + + + Math window size + + + + + + + false + + + + 16777215 + 16777215 + + + + Qt::StrongFocus + + + samples + + + 1 + + + 1001 + + + 10 + + + 1 + + + + + + + Math function: + + + + + + + Qt::StrongFocus + + + + + + + + + QLayout::SetFixedSize + + + + + Qt::Vertical + + + + 20 + 100 + + + + + + + + Add a new curve to the scope, or update it if the UAVObject and UAVField is the same. + + + Add Update - - - - - - - Remove the curve from the scope. - - - Remove + + + + + + + Remove the curve from the scope. + + + Remove - - + + + + + + + Qt::Vertical + + + QSizePolicy::Fixed + + + + 20 + 15 + + + + + + + + + + + + Qt::Vertical + + + + 0 + 200 + + + + + + + + QAbstractItemView::SelectItems + + + 100 + + + + + + - + Qt::Vertical - - QSizePolicy::Fixed - 20 - 15 - - - - - - - - - - - - Qt::Vertical - - - - 0 - 200 + 40 - - - QAbstractItemView::SelectItems - - - 100 - - - - - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - - - Log data to csv file (not interpolated) - - + + + + + + + Log data to csv file (not interpolated) + + + + + + + New file on connect + + + + + + + + + Logging path + + + + + + + + 0 + 0 + + + + + - - - New file on connect - - + + + + + true + + + + + + + + 255 + 0 + 0 + + + + + + + + + 255 + 0 + 0 + + + + + + + + + 120 + 120 + 120 + + + + + + + + 1 + + + + + + + - - - - - Logging path - - - - - - - - 0 - 0 - - - - - + + diff --git a/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.cpp b/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.cpp index 21b5b21c4..65fc167ac 100644 --- a/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/scope/scopegadgetwidget.cpp @@ -677,13 +677,13 @@ int ScopeGadgetWidget::csvLoggingAddData() } else { - ss << QString().sprintf("%3.6g",plotData2->yData->last()); + ss << QString().sprintf("%3.10g",plotData2->yData->last()); m_csvLoggingDataValid=1; } } else { - ss << QString().sprintf("%3.6g",plotData2->yDataHistory->last()); + ss << QString().sprintf("%3.10g",plotData2->yData->last()); m_csvLoggingDataValid=1; } } diff --git a/ground/openpilotgcs/src/plugins/serialconnection/serialpluginoptions.ui b/ground/openpilotgcs/src/plugins/serialconnection/serialpluginoptions.ui index 1aedd7e2c..912099bac 100644 --- a/ground/openpilotgcs/src/plugins/serialconnection/serialpluginoptions.ui +++ b/ground/openpilotgcs/src/plugins/serialconnection/serialpluginoptions.ui @@ -13,26 +13,57 @@ Form - + - - - Serial telemetry speed: + + + Serial Connection + + + + + + 0 + 0 + + + + Serial telemetry speed: + + + + + + + + + + Qt::Horizontal + + + + 76 + 20 + + + + + - - - - + - Qt::Horizontal + Qt::Vertical + + + QSizePolicy::Expanding - 40 - 20 + 20 + 40 diff --git a/ground/openpilotgcs/src/plugins/setupwizard/SetupWizard.pluginspec b/ground/openpilotgcs/src/plugins/setupwizard/SetupWizard.pluginspec new file mode 100644 index 000000000..693a224bb --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/SetupWizard.pluginspec @@ -0,0 +1,13 @@ + + The OpenPilot Project + (C) 2012 OpenPilot Project + The GNU Public License (GPL) Version 3 + A plugin that provides a setup wizard for easy initial setup of airframes. + http://www.openpilot.org + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp new file mode 100644 index 000000000..1b94c1cae --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp @@ -0,0 +1,193 @@ +/** + ****************************************************************************** + * + * @file connectiondiagram.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup ConnectionDiagram + * @{ + * @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 + */ + +#include +#include +#include +#include "connectiondiagram.h" +#include "ui_connectiondiagram.h" + +ConnectionDiagram::ConnectionDiagram(QWidget *parent, VehicleConfigurationSource* configSource) : + QDialog(parent), ui(new Ui::ConnectionDiagram), m_configSource(configSource), m_background(0) +{ + ui->setupUi(this); + setWindowTitle(tr("Connection Diagram")); + setupGraphicsScene(); +} + +ConnectionDiagram::~ConnectionDiagram() +{ + delete ui; +} + +void ConnectionDiagram::resizeEvent(QResizeEvent *event) +{ + QWidget::resizeEvent(event); + ui->connectionDiagram->fitInView(m_background, Qt::KeepAspectRatio); +} + +void ConnectionDiagram::showEvent(QShowEvent * event) +{ + QWidget::showEvent(event); + ui->connectionDiagram->fitInView(m_background, Qt::KeepAspectRatio); +} + +void ConnectionDiagram::setupGraphicsScene() +{ + m_renderer = new QSvgRenderer(); + if (QFile::exists(QString(":/setupwizard/resources/connection-diagrams.svg")) && + m_renderer->load(QString(":/setupwizard/resources/connection-diagrams.svg")) && + m_renderer->isValid()) + { + m_scene = new QGraphicsScene(this); + ui->connectionDiagram->setScene(m_scene); + //ui->connectionDiagram->setViewportUpdateMode(QGraphicsView::FullViewportUpdate); + + m_background = new QGraphicsSvgItem(); + m_background->setSharedRenderer(m_renderer); + m_background->setElementId("background"); + m_background->setOpacity(0); + //m_background->setFlags(QGraphicsItem::ItemClipsToShape); + m_background->setZValue(-1); + m_scene->addItem(m_background); + + QList elementsToShow; + + switch(m_configSource->getControllerType()) + { + case VehicleConfigurationSource::CONTROLLER_CC: + case VehicleConfigurationSource::CONTROLLER_CC3D: + case VehicleConfigurationSource::CONTROLLER_REVO: + case VehicleConfigurationSource::CONTROLLER_PIPX: + default: + elementsToShow << "controller"; + break; + } + + switch (m_configSource->getVehicleType()) + { + case VehicleConfigurationSource::VEHICLE_MULTI: + switch (m_configSource->getVehicleSubType()) + { + case VehicleConfigurationSource::MULTI_ROTOR_TRI_Y: + elementsToShow << "tri"; + break; + case VehicleConfigurationSource::MULTI_ROTOR_QUAD_X: + elementsToShow << "quad-x"; + break; + case VehicleConfigurationSource::MULTI_ROTOR_QUAD_PLUS: + elementsToShow << "quad-p"; + break; + case VehicleConfigurationSource::MULTI_ROTOR_HEXA: + elementsToShow << "hexa"; + break; + case VehicleConfigurationSource::MULTI_ROTOR_HEXA_COAX_Y: + elementsToShow << "hexa-y"; + break; + case VehicleConfigurationSource::MULTI_ROTOR_HEXA_H: + elementsToShow << "hexa-h"; + break; + default: + break; + } + break; + case VehicleConfigurationSource::VEHICLE_FIXEDWING: + case VehicleConfigurationSource::VEHICLE_HELI: + case VehicleConfigurationSource::VEHICLE_SURFACE: + default: + break; + } + + switch (m_configSource->getInputType()) + { + case VehicleConfigurationSource::INPUT_PWM: + elementsToShow << "pwm" ; + break; + case VehicleConfigurationSource::INPUT_PPM: + elementsToShow << "ppm"; + break; + case VehicleConfigurationSource::INPUT_SBUS: + elementsToShow << "sbus"; + break; + case VehicleConfigurationSource::INPUT_DSMX10: + case VehicleConfigurationSource::INPUT_DSMX11: + case VehicleConfigurationSource::INPUT_DSM2: + elementsToShow << "satellite"; + break; + default: + break; + } + + setupGraphicsSceneItems(elementsToShow); + + ui->connectionDiagram->setSceneRect(m_background->boundingRect()); + ui->connectionDiagram->fitInView(m_background, Qt::KeepAspectRatio); + + qDebug() << "Scene complete"; + } +} + +void ConnectionDiagram::setupGraphicsSceneItems(QList elementsToShow) +{ + qreal z = 0; + QRectF backgBounds = m_renderer->boundsOnElement("background"); + + foreach(QString elementId, elementsToShow) { + if(m_renderer->elementExists(elementId)) { + QGraphicsSvgItem* element = new QGraphicsSvgItem(); + element->setSharedRenderer(m_renderer); + element->setElementId(elementId); + element->setZValue(z++); + element->setOpacity(1.0); + + QMatrix matrix = m_renderer->matrixForElement(elementId); + QRectF orig = matrix.mapRect(m_renderer->boundsOnElement(elementId)); + element->setPos(orig.x(),orig.y()); + + //QRectF orig = m_renderer->boundsOnElement(elementId); + //element->setPos(orig.x() - backgBounds.x(), orig.y() - backgBounds.y()); + + m_scene->addItem(element); + qDebug() << "Adding " << elementId << " to scene at " << element->pos(); + } + else { + qDebug() << "Element with id: " << elementId << " not found."; + } + } +} + +void ConnectionDiagram::on_saveButton_clicked() +{ + QImage image(2200, 1100, QImage::Format_ARGB32); + image.fill(0); + QPainter painter(&image); + m_scene->render(&painter); + QString fileName = QFileDialog::getSaveFileName(this, tr("Save File"), "", tr("Images (*.png *.xpm *.jpg)")); + if(!fileName.isEmpty()) { + image.save(fileName); + } +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.h b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.h new file mode 100644 index 000000000..e03ed6b0e --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.h @@ -0,0 +1,70 @@ +/** + ****************************************************************************** + * + * @file connectiondiagram.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup ConnectionDiagram + * @{ + * @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 CONNECTIONDIAGRAM_H +#define CONNECTIONDIAGRAM_H + +#include +#include +#include + +#include +#include "vehicleconfigurationsource.h" + + +namespace Ui { +class ConnectionDiagram; +} + +class ConnectionDiagram : public QDialog +{ + Q_OBJECT + +public: + explicit ConnectionDiagram(QWidget *parent, VehicleConfigurationSource *configSource); + ~ConnectionDiagram(); + +private: + Ui::ConnectionDiagram *ui; + VehicleConfigurationSource *m_configSource; + + QSvgRenderer *m_renderer; + QGraphicsSvgItem* m_background; + QGraphicsScene *m_scene; + + void setupGraphicsScene(); + void setupGraphicsSceneItems(QList elementsToShow); +protected: + void resizeEvent(QResizeEvent *event); + void showEvent(QShowEvent *event); + +private slots: + + void on_saveButton_clicked(); +}; + +#endif // CONNECTIONDIAGRAM_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.ui b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.ui new file mode 100644 index 000000000..7e86a99a2 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.ui @@ -0,0 +1,112 @@ + + + ConnectionDiagram + + + + 0 + 0 + 800 + 440 + + + + Dialog + + + true + + + true + + + + + + QFrame::WinPanel + + + Qt::ScrollBarAlwaysOff + + + Qt::ScrollBarAlwaysOff + + + + + 255 + 255 + 255 + + + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 0 + 0 + + + + Save + + + + + + + + 0 + 0 + + + + Close + + + true + + + + + + + + + + + closeButton + clicked() + ConnectionDiagram + close() + + + 752 + 418 + + + 399 + 219 + + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/levellingutil.cpp b/ground/openpilotgcs/src/plugins/setupwizard/levellingutil.cpp new file mode 100644 index 000000000..23d422adf --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/levellingutil.cpp @@ -0,0 +1,217 @@ +/** + ****************************************************************************** + * + * @file levellingutil.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup LevellingUtil + * @{ + * @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 + */ + +#include "levellingutil.h" +#include "extensionsystem/pluginmanager.h" +#include "uavobjectmanager.h" +#include "attitudesettings.h" +#include "accels.h" +#include "gyros.h" + + +LevellingUtil::LevellingUtil(long measurementCount, long measurementRate) : QObject(), + m_isMeasuring(false), m_accelMeasurementCount(measurementCount), m_gyroMeasurementCount(measurementCount), + m_accelMeasurementRate(measurementRate), m_gyroMeasurementRate(measurementRate) +{ +} + +LevellingUtil::LevellingUtil(long accelMeasurementCount, long accelMeasurementRate, + long gyroMeasurementCount, long gyroMeasurementRate) : QObject(), + m_isMeasuring(false), m_accelMeasurementCount(accelMeasurementCount), m_gyroMeasurementCount(gyroMeasurementCount), + m_accelMeasurementRate(accelMeasurementRate), m_gyroMeasurementRate(gyroMeasurementRate) +{ +} + +void LevellingUtil::start() +{ + if(!m_isMeasuring) { + startMeasurement(); + + // Set up timeout timer + connect(&m_timeoutTimer, SIGNAL(timeout()), this, SLOT(timeout())); + //Set timeout to max time of measurement + 10 secs + m_timeoutTimer.start(std::max(m_accelMeasurementCount * m_accelMeasurementRate, m_gyroMeasurementCount * m_gyroMeasurementRate) + 10000); + } +} + +void LevellingUtil::abort() +{ + if(m_isMeasuring) { + stopMeasurement(); + } +} + +void LevellingUtil::gyroMeasurementsUpdated(UAVObject *obj) +{ + QMutexLocker locker(&m_measurementMutex); + + if(m_receivedGyroUpdates < m_gyroMeasurementCount) { + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + UAVObjectManager * uavObjectManager = pm->getObject(); + Q_ASSERT(uavObjectManager); + + Gyros * gyros = Gyros::GetInstance(uavObjectManager); + Gyros::DataFields gyrosData = gyros->getData(); + + m_gyroX += gyrosData.x; + m_gyroY += gyrosData.y; + m_gyroZ += gyrosData.z; + + m_receivedGyroUpdates++; + emit progress(m_receivedGyroUpdates + m_receivedAccelUpdates, m_gyroMeasurementCount + m_accelMeasurementCount); + } + else if (m_receivedAccelUpdates >= m_accelMeasurementCount && + m_receivedGyroUpdates >= m_gyroMeasurementCount && m_isMeasuring) { + stopMeasurement(); + emit done(calculateLevellingData()); + } +} + +void LevellingUtil::accelMeasurementsUpdated(UAVObject *obj) +{ + QMutexLocker locker(&m_measurementMutex); + + if(m_receivedAccelUpdates < m_accelMeasurementCount) { + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + UAVObjectManager * uavObjectManager = pm->getObject(); + Q_ASSERT(uavObjectManager); + + Accels * accels = Accels::GetInstance(uavObjectManager); + Accels::DataFields accelsData = accels->getData(); + + m_accelerometerX += accelsData.x; + m_accelerometerY += accelsData.y; + m_accelerometerZ += accelsData.z; + + m_receivedAccelUpdates++; + emit progress(m_receivedGyroUpdates + m_receivedAccelUpdates, m_gyroMeasurementCount + m_accelMeasurementCount); + } + else if (m_receivedAccelUpdates >= m_accelMeasurementCount && + m_receivedGyroUpdates >= m_gyroMeasurementCount && m_isMeasuring) { + stopMeasurement(); + emit done(calculateLevellingData()); + } +} + +void LevellingUtil::timeout() +{ + QMutexLocker locker(&m_measurementMutex); + + stopMeasurement(); + emit timeout(tr("Calibration timed out before receiving required updates.")); +} + +void LevellingUtil::startMeasurement() +{ + QMutexLocker locker(&m_measurementMutex); + + m_isMeasuring = true; + + // Reset variables + m_receivedAccelUpdates = 0; + m_accelerometerX = 0; + m_accelerometerY = 0; + m_accelerometerZ = 0; + + m_receivedGyroUpdates = 0; + m_gyroX = 0; + m_gyroY = 0; + m_gyroZ = 0; + + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + UAVObjectManager * uavObjectManager = pm->getObject(); + Q_ASSERT(uavObjectManager); + + // Disable gyro bias correction to see raw data + AttitudeSettings::DataFields attitudeSettingsData = AttitudeSettings::GetInstance(uavObjectManager)->getData(); + attitudeSettingsData.BiasCorrectGyro = AttitudeSettings::BIASCORRECTGYRO_FALSE; + AttitudeSettings::GetInstance(uavObjectManager)->setData(attitudeSettingsData); + + // Set up to receive updates for accels + UAVDataObject *uavObject = Accels::GetInstance(uavObjectManager); + connect(uavObject, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(accelMeasurementsUpdated(UAVObject*))); + + // Set update period for accels + m_previousAccelMetaData = uavObject->getMetadata(); + UAVObject::Metadata newMetaData = m_previousAccelMetaData; + UAVObject::SetFlightTelemetryUpdateMode(newMetaData, UAVObject::UPDATEMODE_PERIODIC); + newMetaData.flightTelemetryUpdatePeriod = m_accelMeasurementRate; + uavObject->setMetadata(newMetaData); + + // Set up to receive updates from gyros + uavObject = Gyros::GetInstance(uavObjectManager); + connect(uavObject, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(gyroMeasurementsUpdated(UAVObject*))); + + // Set update period for gyros + m_previousGyroMetaData = uavObject->getMetadata(); + newMetaData = m_previousGyroMetaData; + UAVObject::SetFlightTelemetryUpdateMode(newMetaData, UAVObject::UPDATEMODE_PERIODIC); + newMetaData.flightTelemetryUpdatePeriod = m_gyroMeasurementRate; + uavObject->setMetadata(newMetaData); +} + +void LevellingUtil::stopMeasurement() +{ + m_isMeasuring = false; + + //Stop timeout timer + m_timeoutTimer.stop(); + disconnect(&m_timeoutTimer, SIGNAL(timeout()), this, SLOT(timeout())); + + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + UAVObjectManager * uavObjectManager = pm->getObject(); + Q_ASSERT(uavObjectManager); + + // Stop listening for updates from accels + UAVDataObject *uavObject = Accels::GetInstance(uavObjectManager); + disconnect(uavObject, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(accelMeasurementsUpdated(UAVObject*))); + uavObject->setMetadata(m_previousAccelMetaData); + + // Stop listening for updates from gyros + uavObject = Gyros::GetInstance(uavObjectManager); + disconnect(uavObject, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(gyroMeasurementsUpdated(UAVObject*))); + uavObject->setMetadata(m_previousGyroMetaData); + + // Enable gyro bias correction again + AttitudeSettings::DataFields attitudeSettingsData = AttitudeSettings::GetInstance(uavObjectManager)->getData(); + attitudeSettingsData.BiasCorrectGyro = AttitudeSettings::BIASCORRECTGYRO_TRUE; + AttitudeSettings::GetInstance(uavObjectManager)->setData(attitudeSettingsData); +} + +accelGyroBias LevellingUtil::calculateLevellingData() +{ + accelGyroBias bias; + bias.m_accelerometerXBias = m_accelerometerX / (double)m_receivedAccelUpdates / ACCELERATION_SCALE; + bias.m_accelerometerYBias = m_accelerometerY / (double)m_receivedAccelUpdates / ACCELERATION_SCALE; + bias.m_accelerometerZBias = (m_accelerometerZ / (double)m_receivedAccelUpdates + G) / ACCELERATION_SCALE; + + bias.m_gyroXBias = m_gyroX / (double)m_receivedGyroUpdates * 100.0; + bias.m_gyroYBias = m_gyroY / (double)m_receivedGyroUpdates * 100.0; + bias.m_gyroZBias = m_gyroZ / (double)m_receivedGyroUpdates * 100.0; + return bias; +} + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/levellingutil.h b/ground/openpilotgcs/src/plugins/setupwizard/levellingutil.h new file mode 100644 index 000000000..c5cbe8709 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/levellingutil.h @@ -0,0 +1,92 @@ +/** + ****************************************************************************** + * + * @file levellingutil.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup LevellingUtil + * @{ + * @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 LEVELLINGUTIL_H +#define LEVELLINGUTIL_H + +#include +#include +#include + +#include "uavobject.h" +#include "vehicleconfigurationsource.h" + +class LevellingUtil : public QObject +{ + Q_OBJECT +public: + explicit LevellingUtil(long measurementCount, long measurementRate); + explicit LevellingUtil(long accelMeasurementCount, long accelMeasurementRate, + long gyroMeasurementCount, long gyroMeasurementRate); + +signals: + void progress(long current, long total); + void done(accelGyroBias measuredBias); + void timeout(QString message); + +public slots: + void start(); + void abort(); + +private slots: + void gyroMeasurementsUpdated(UAVObject * obj); + void accelMeasurementsUpdated(UAVObject * obj); + void timeout(); + +private: + static const float G = 9.81f; + static const float ACCELERATION_SCALE = 0.004f * 9.81f; + + QMutex m_measurementMutex; + QTimer m_timeoutTimer; + + bool m_isMeasuring; + long m_receivedAccelUpdates; + long m_receivedGyroUpdates; + + long m_accelMeasurementCount; + long m_gyroMeasurementCount; + long m_accelMeasurementRate; + long m_gyroMeasurementRate; + + UAVObject::Metadata m_previousGyroMetaData; + UAVObject::Metadata m_previousAccelMetaData; + + double m_accelerometerX; + double m_accelerometerY; + double m_accelerometerZ; + double m_gyroX; + double m_gyroY; + double m_gyroZ; + + void stop(); + void startMeasurement(); + void stopMeasurement(); + accelGyroBias calculateLevellingData(); +}; + +#endif // LEVELLINGUTIL_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/outputcalibrationutil.cpp b/ground/openpilotgcs/src/plugins/setupwizard/outputcalibrationutil.cpp new file mode 100644 index 000000000..30144ec42 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/outputcalibrationutil.cpp @@ -0,0 +1,115 @@ +/** + ****************************************************************************** + * + * @file outputcalibrationutil.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup OutputCalibrationUtil + * @{ + * @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 + */ + +#include "outputcalibrationutil.h" +#include "actuatorcommand.h" +#include "extensionsystem/pluginmanager.h" +#include "vehicleconfigurationhelper.h" +#include "manualcontrolsettings.h" + +OutputCalibrationUtil::OutputCalibrationUtil(QObject *parent) : + QObject(parent), m_outputChannel(-1), m_safeValue(1000) +{ + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + m_uavObjectManager = pm->getObject(); + Q_ASSERT(m_uavObjectManager); +} + +OutputCalibrationUtil::~OutputCalibrationUtil() +{ + stopChannelOutput(); +} + +void OutputCalibrationUtil::startChannelOutput(quint16 channel, quint16 safeValue) +{ + if(m_outputChannel < 0 && channel >= 0 && channel < ActuatorCommand::CHANNEL_NUMELEM) + { + //Start output... + m_outputChannel = channel; + m_safeValue = safeValue; + + qDebug() << "Starting output for channel " << m_outputChannel << "..."; + + ActuatorCommand *actuatorCommand = ActuatorCommand::GetInstance(m_uavObjectManager); + Q_ASSERT(actuatorCommand); + UAVObject::Metadata metaData = actuatorCommand->getMetadata(); + m_savedActuatorCommandMetadata = metaData; + + //Store current data for later restore + m_savedActuatorCommandData = actuatorCommand->getData(); + + //Enable actuator control from GCS... + //Store current metadata for later restore + UAVObject::SetFlightAccess(metaData, UAVObject::ACCESS_READONLY); + UAVObject::SetFlightTelemetryUpdateMode(metaData, UAVObject::UPDATEMODE_ONCHANGE); + UAVObject::SetGcsTelemetryAcked(metaData, false); + UAVObject::SetGcsTelemetryUpdateMode(metaData, UAVObject::UPDATEMODE_ONCHANGE); + metaData.gcsTelemetryUpdatePeriod = 100; + + //Apply changes + actuatorCommand->setMetadata(metaData); + actuatorCommand->updated(); + + qDebug() << "Output for channel " << m_outputChannel << " started."; + } +} + +void OutputCalibrationUtil::stopChannelOutput() +{ + if(m_outputChannel >= 0) + { + qDebug() << "Stopping output for channel " << m_outputChannel << "..."; + //Stop output... + setChannelOutputValue(m_safeValue); + qDebug() << "Settings output for channel " << m_outputChannel << " to " << m_safeValue; + + // Restore metadata to what it was before + ActuatorCommand *actuatorCommand = ActuatorCommand::GetInstance(m_uavObjectManager); + Q_ASSERT(actuatorCommand); + //actuatorCommand->setData(m_savedActuatorCommandData); + actuatorCommand->setMetadata(m_savedActuatorCommandMetadata); + actuatorCommand->updated(); + + qDebug() << "Output for channel " << m_outputChannel << " stopped."; + + m_outputChannel = -1; + } +} + +void OutputCalibrationUtil::setChannelOutputValue(quint16 value) +{ + if(m_outputChannel >= 0) + { + //Set output value + qDebug() << "Setting output value for channel " << m_outputChannel << " to " << value << "."; + ActuatorCommand *actuatorCommand = ActuatorCommand::GetInstance(m_uavObjectManager); + Q_ASSERT(actuatorCommand); + ActuatorCommand::DataFields data = actuatorCommand->getData(); + data.Channel[m_outputChannel] = value; + actuatorCommand->setData(data); + } +} diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2configuration.h b/ground/openpilotgcs/src/plugins/setupwizard/outputcalibrationutil.h similarity index 52% rename from ground/openpilotgcs/src/plugins/hitlv2/hitlv2configuration.h rename to ground/openpilotgcs/src/plugins/setupwizard/outputcalibrationutil.h index 3e6a96df6..dc9fc7fc8 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2configuration.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/outputcalibrationutil.h @@ -1,13 +1,13 @@ /** ****************************************************************************** * - * @file hitlv2configuration.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. - * @addtogroup GCSPlugins GCS Plugins + * @file outputcalibrationutil.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup * @{ - * @addtogroup HITLPlugin HITLv2 Plugin + * @addtogroup OutputCalibrationUtil * @{ - * @brief The Hardware In The Loop plugin version 2 + * @brief *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify @@ -25,37 +25,38 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#ifndef HITLV2CONFIGURATION_H -#define HITLV2CONFIGURATION_H +#ifndef OUTPUTCALIBRATIONUTIL_H +#define OUTPUTCALIBRATIONUTIL_H -#include -#include -#include -#include +#include +#include +#include "uavobject.h" +#include "uavobjectmanager.h" +#include "vehicleconfigurationsource.h" +#include "actuatorcommand.h" -using namespace Core; -class HITLConfiguration : public IUAVGadgetConfiguration +class OutputCalibrationUtil : public QObject { - Q_OBJECT - - Q_PROPERTY(SimulatorSettings settings READ Settings WRITE setSimulatorSettings) - public: - explicit HITLConfiguration(QString classId, QSettings* qSettings = 0, QObject *parent = 0); - - void saveConfig(QSettings* settings) const; - IUAVGadgetConfiguration *clone(); - - SimulatorSettings Settings() const { return settings; } - + explicit OutputCalibrationUtil(QObject *parent = 0); + ~OutputCalibrationUtil(); + +signals: + public slots: - void setSimulatorSettings (const SimulatorSettings& params ) { settings = params; } + void startChannelOutput(quint16 channel, quint16 safeValue); + void stopChannelOutput(); + void setChannelOutputValue(quint16 value); private: - SimulatorSettings settings; + qint16 m_outputChannel; + quint16 m_safeValue; + UAVObject::Metadata m_savedActuatorCommandMetadata; + ActuatorCommand::DataFields m_savedActuatorCommandData; + UAVObjectManager *m_uavObjectManager; }; -#endif // HITLV2CONFIGURATION_H +#endif // OUTPUTCALIBRATIONUTIL_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/abstractwizardpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/abstractwizardpage.cpp new file mode 100644 index 000000000..2e5ed82da --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/abstractwizardpage.cpp @@ -0,0 +1,35 @@ +/** + ****************************************************************************** + * + * @file abstractwizardpage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup AbstractWizardPage + * @{ + * @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 + */ + +#include "abstractwizardpage.h" + +AbstractWizardPage::AbstractWizardPage(SetupWizard* wizard, QWidget *parent) : + QWizardPage(parent) +{ + m_wizard = wizard; + //setFixedSize(600, 400); +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/abstractwizardpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/abstractwizardpage.h new file mode 100644 index 000000000..072d619e7 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/abstractwizardpage.h @@ -0,0 +1,48 @@ +/** + ****************************************************************************** + * + * @file abstractwizardpage.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup AbstractWizardPage + * @{ + * @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 ABSTRACTWIZARDPAGE_H +#define ABSTRACTWIZARDPAGE_H + +#include +#include "setupwizard.h" + +class AbstractWizardPage : public QWizardPage +{ + Q_OBJECT +protected: + explicit AbstractWizardPage(SetupWizard *wizard, QWidget *parent = 0); + +private: + SetupWizard *m_wizard; + +public: + SetupWizard* getWizard() { return m_wizard; } + +}; + +#endif // ABSTRACTWIZARDPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/autoupdatepage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/autoupdatepage.cpp new file mode 100644 index 000000000..571ae774c --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/autoupdatepage.cpp @@ -0,0 +1,69 @@ +#include "autoupdatepage.h" +#include "ui_autoupdatepage.h" +#include "setupwizard.h" +#include +#include +#include +#include "uploader/uploadergadgetfactory.h" + +AutoUpdatePage::AutoUpdatePage(SetupWizard *wizard, QWidget *parent) : + AbstractWizardPage(wizard, parent), + ui(new Ui::AutoUpdatePage),m_wiz(wizard) +{ + ui->setupUi(this); + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + Q_ASSERT(pm); + UploaderGadgetFactory *uploader = pm->getObject(); + Q_ASSERT(uploader); + connect(ui->startUpdate,SIGNAL(clicked()),uploader,SIGNAL(autoUpdate())); + connect(uploader,SIGNAL(autoUpdateSignal(uploader::AutoUpdateStep,QVariant)),this,SLOT(updateStatus(uploader::AutoUpdateStep,QVariant))); +} + +AutoUpdatePage::~AutoUpdatePage() +{ + delete ui; +} + +void AutoUpdatePage::updateStatus(uploader::AutoUpdateStep status, QVariant value) +{ + switch(status) + { + case uploader::WAITING_DISCONNECT: + m_wiz->setWindowFlags(m_wiz->windowFlags() & ~Qt::WindowStaysOnTopHint); + ui->statusLabel->setText("Waiting for all OP boards to be disconnected"); + break; + case uploader::WAITING_CONNECT: + m_wiz->setWindowFlags(m_wiz->windowFlags() | Qt::WindowStaysOnTopHint); + m_wiz->setWindowIcon(qApp->windowIcon()); + m_wiz->show(); + ui->statusLabel->setText("Please connect the board to the USB port (don't use external supply)"); + ui->levellinProgressBar->setValue(value.toInt()); + break; + case uploader::JUMP_TO_BL: + ui->levellinProgressBar->setValue(0); + ui->statusLabel->setText("Board going into bootloader mode"); + break; + case uploader::LOADING_FW: + ui->statusLabel->setText("Loading firmware"); + break; + case uploader::UPLOADING_FW: + ui->statusLabel->setText("Uploading firmware"); + ui->levellinProgressBar->setValue(value.toInt()); + break; + case uploader::UPLOADING_DESC: + ui->statusLabel->setText("Uploading description"); + break; + case uploader::BOOTING: + ui->statusLabel->setText("Booting the board"); + break; + case uploader::SUCCESS: + ui->statusLabel->setText("Board Updated, please press the 'next' button below"); + break; + case uploader::FAILURE: + m_wiz->setWindowFlags(m_wiz->windowFlags() | Qt::WindowStaysOnTopHint); + m_wiz->setWindowIcon(qApp->windowIcon()); + m_wiz->show(); + ui->statusLabel->setText("Something went wrong, you will have to manualy upgrade the board using the uploader plugin"); + break; + } +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/autoupdatepage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/autoupdatepage.h new file mode 100644 index 000000000..8d77085e2 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/autoupdatepage.h @@ -0,0 +1,58 @@ +/** + ****************************************************************************** + * + * @file autoupdatepage.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup AutoUpdatePage + * @{ + * @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 AUTOUPDATEPAGE_H +#define AUTOUPDATEPAGE_H + +#include +#include +#include "setupwizard.h" +#include "uavtalk/telemetrymanager.h" +#include "abstractwizardpage.h" +#include "uploader/enums.h" + +namespace Ui { +class AutoUpdatePage; +} + +class AutoUpdatePage : public AbstractWizardPage +{ + Q_OBJECT + +public: + explicit AutoUpdatePage(SetupWizard *wizard, QWidget *parent = 0); + ~AutoUpdatePage(); + +private slots: + void updateStatus(uploader::AutoUpdateStep ,QVariant); + +private: + Ui::AutoUpdatePage *ui; + SetupWizard * m_wiz; +}; + +#endif // AUTOUPDATEPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/autoupdatepage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/autoupdatepage.ui new file mode 100644 index 000000000..762980787 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/autoupdatepage.ui @@ -0,0 +1,129 @@ + + + AutoUpdatePage + + + + 0 + 0 + 600 + 400 + + + + WizardPage + + + + + + <!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:'MS Shell Dlg 2'; 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;"><span style=" font-size:12pt; font-weight:600;">Firmware Update Wizard</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:12pt; font-weight:600;"><br /></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">It is necessary that your firmware and ground control software are the same version.</p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><br /></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">To update your firmware to the correct version now:</p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"> - Unplug all batteries and USB from OpenPilot</p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"> - Ensure your board is powered down &amp; no LED's are active.</p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><br /></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">When you are ready you can start the upgrade below by pushing the button and follow the onscreen prompts, it is critical that nothing disturbs the board while the firmware is being written.</p></body></html> + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + Calculate gyro and accelerometer bias + + + QToolButton { border: none } + + + Calculate + + + + :/setupwizard/resources/bttn-upgrade-up.png + :/setupwizard/resources/bttn-upgrade-down.png:/setupwizard/resources/bttn-upgrade-up.png + + + + 200 + 70 + + + + + + + + + + + + Ready... + + + + + + + QProgressBar { + border: 2px solid grey; + border-radius: 5px; + text-align: center; + } +QProgressBar::chunk { + background-color: #3D6699; + width: 10px; + margin: 0.5px; + } + + + 0 + + + + + + + + + + + + + + + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.cpp new file mode 100644 index 000000000..deed9d6eb --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.cpp @@ -0,0 +1,212 @@ +/** + ****************************************************************************** + * + * @file controllerpage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup ControllerPage + * @{ + * @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 + */ + +#include "controllerpage.h" +#include "ui_controllerpage.h" +#include "setupwizard.h" + +#include +#include + +ControllerPage::ControllerPage(SetupWizard *wizard, QWidget *parent) : + AbstractWizardPage(wizard, parent), + ui(new Ui::ControllerPage) +{ + ui->setupUi(this); + + m_connectionManager = getWizard()->getConnectionManager(); + Q_ASSERT(m_connectionManager); + connect(m_connectionManager, SIGNAL(availableDevicesChanged(QLinkedList)), this, SLOT(devicesChanged(QLinkedList))); + + ExtensionSystem::PluginManager *pluginManager = ExtensionSystem::PluginManager::instance(); + Q_ASSERT(pluginManager); + m_telemtryManager = pluginManager->getObject(); + Q_ASSERT(m_telemtryManager); + connect(m_telemtryManager, SIGNAL(connected()), this, SLOT(connectionStatusChanged())); + connect(m_telemtryManager, SIGNAL(disconnected()), this, SLOT(connectionStatusChanged())); + + connect(ui->connectButton, SIGNAL(clicked()), this, SLOT(connectDisconnect())); + + setupBoardTypes(); + setupDeviceList(); +} + +ControllerPage::~ControllerPage() +{ + delete ui; +} + +void ControllerPage::initializePage() +{ + if(anyControllerConnected()) { + SetupWizard::CONTROLLER_TYPE type = getControllerType(); + setControllerType(type); + } + else { + setControllerType(SetupWizard::CONTROLLER_UNKNOWN); + } + emit completeChanged(); +} + +bool ControllerPage::isComplete() const +{ + return m_telemtryManager->isConnected() && ui->boardTypeCombo->currentIndex() > 0 && + m_connectionManager->getCurrentDevice().getConName().startsWith("USB:", Qt::CaseInsensitive); +} + +bool ControllerPage::validatePage() +{ + getWizard()->setControllerType((SetupWizard::CONTROLLER_TYPE)ui->boardTypeCombo->itemData(ui->boardTypeCombo->currentIndex()).toInt()); + return true; +} + +bool ControllerPage::anyControllerConnected() +{ + return m_telemtryManager->isConnected(); +} + +SetupWizard::CONTROLLER_TYPE ControllerPage::getControllerType() +{ + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + UAVObjectUtilManager* utilMngr = pm->getObject(); + int id = utilMngr->getBoardModel(); + + switch (id) { + case 0x0301: + return SetupWizard::CONTROLLER_PIPX; + case 0x0401: + return SetupWizard::CONTROLLER_CC; + case 0x0402: + return SetupWizard::CONTROLLER_CC3D; + case 0x0901: + return SetupWizard::CONTROLLER_REVO; + default: + return SetupWizard::CONTROLLER_UNKNOWN; + } +} + +void ControllerPage::setupDeviceList() +{ + devicesChanged(m_connectionManager->getAvailableDevices()); + connectionStatusChanged(); +} + +void ControllerPage::setupBoardTypes() +{ + QVariant v(0); + ui->boardTypeCombo->addItem(tr(""), SetupWizard::CONTROLLER_UNKNOWN); + ui->boardTypeCombo->addItem(tr("OpenPilot CopterControl"), SetupWizard::CONTROLLER_CC); + ui->boardTypeCombo->addItem(tr("OpenPilot CopterControl 3D"), SetupWizard::CONTROLLER_CC3D); + ui->boardTypeCombo->addItem(tr("OpenPilot Revolution"), SetupWizard::CONTROLLER_REVO); + //ui->boardTypeCombo->model()->setData(ui->boardTypeCombo->model()->index(ui->boardTypeCombo->count() - 1, 0), v, Qt::UserRole - 1); + ui->boardTypeCombo->addItem(tr("OpenPilot PipX Radio Modem"), SetupWizard::CONTROLLER_PIPX); + //ui->boardTypeCombo->model()->setData(ui->boardTypeCombo->model()->index(ui->boardTypeCombo->count() - 1, 0), v, Qt::UserRole - 1); +} + +void ControllerPage::setControllerType(SetupWizard::CONTROLLER_TYPE type) +{ + for(int i = 0; i < ui->boardTypeCombo->count(); ++i) { + if(ui->boardTypeCombo->itemData(i) == type) { + ui->boardTypeCombo->setCurrentIndex(i); + break; + } + } +} + +void ControllerPage::devicesChanged(QLinkedList devices) +{ + // Get the selected item before the update if any + QString currSelectedDeviceName = ui->deviceCombo->currentIndex() != -1 ? + ui->deviceCombo->itemData(ui->deviceCombo->currentIndex(), Qt::ToolTipRole).toString() : ""; + + // Clear the box + ui->deviceCombo->clear(); + + int indexOfSelectedItem = -1; + int i = 0; + + // Loop and fill the combo with items from connectionmanager + foreach (Core::DevListItem deviceItem, devices) + { + ui->deviceCombo->addItem(deviceItem.getConName()); + QString deviceName = (const QString)deviceItem.getConName(); + ui->deviceCombo->setItemData(ui->deviceCombo->count() - 1, deviceName, Qt::ToolTipRole); + if(!deviceName.startsWith("USB:", Qt::CaseInsensitive)) { + ui->deviceCombo->setItemData(ui->deviceCombo->count() - 1, QVariant(0), Qt::UserRole - 1); + } + if(currSelectedDeviceName != "" && currSelectedDeviceName == deviceName) { + indexOfSelectedItem = i; + } + i++; + } + + // Re select the item that was selected before if any + if(indexOfSelectedItem != -1) { + ui->deviceCombo->setCurrentIndex(indexOfSelectedItem); + } + //connectionStatusChanged(); +} + +void ControllerPage::connectionStatusChanged() +{ + if(m_connectionManager->isConnected()) { + ui->deviceCombo->setEnabled(false); + ui->connectButton->setText(tr("Disconnect")); + ui->boardTypeCombo->setEnabled(false); + QString connectedDeviceName = m_connectionManager->getCurrentDevice().getConName(); + for(int i = 0; i < ui->deviceCombo->count(); ++i) { + if(connectedDeviceName == ui->deviceCombo->itemData(i, Qt::ToolTipRole).toString()) { + ui->deviceCombo->setCurrentIndex(i); + break; + } + } + + SetupWizard::CONTROLLER_TYPE type = getControllerType(); + setControllerType(type); + qDebug() << "Connection status changed: Connected, controller type: " << getControllerType(); + } + else { + ui->deviceCombo->setEnabled(true); + ui->connectButton->setText(tr("Connect")); + ui->boardTypeCombo->setEnabled(false); + ui->boardTypeCombo->model()->setData(ui->boardTypeCombo->model()->index(0, 0), QVariant(0), Qt::UserRole - 1); + setControllerType(SetupWizard::CONTROLLER_UNKNOWN); + qDebug() << "Connection status changed: Disconnected"; + } + emit completeChanged(); +} + +void ControllerPage::connectDisconnect() +{ + if(m_connectionManager->isConnected()) { + m_connectionManager->disconnectDevice(); + } + else { + m_connectionManager->connectDevice(m_connectionManager->findDevice(ui->deviceCombo->itemData(ui->deviceCombo->currentIndex(), Qt::ToolTipRole).toString())); + } + emit completeChanged(); +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.h new file mode 100644 index 000000000..9370f4cd4 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.h @@ -0,0 +1,68 @@ +/** + ****************************************************************************** + * + * @file controllerpage.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup ControllerPage + * @{ + * @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 CONTROLLERPAGE_H +#define CONTROLLERPAGE_H + +#include +#include +#include "setupwizard.h" +#include "uavtalk/telemetrymanager.h" +#include "abstractwizardpage.h" + +namespace Ui { +class ControllerPage; +} + +class ControllerPage : public AbstractWizardPage +{ + Q_OBJECT + +public: + explicit ControllerPage(SetupWizard *wizard, QWidget *parent = 0); + ~ControllerPage(); + void initializePage(); + bool isComplete() const; + bool validatePage(); + +private: + Ui::ControllerPage *ui; + bool anyControllerConnected(); + SetupWizard::CONTROLLER_TYPE getControllerType(); + void setupDeviceList(); + void setupBoardTypes(); + void setControllerType(SetupWizard::CONTROLLER_TYPE type); + Core::ConnectionManager *m_connectionManager; + TelemetryManager *m_telemtryManager; + +private slots: + void devicesChanged(QLinkedList devices); + void connectionStatusChanged(); + void connectDisconnect(); +}; + +#endif // CONTROLLERPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.ui new file mode 100644 index 000000000..124f54c86 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.ui @@ -0,0 +1,180 @@ + + + ControllerPage + + + + 0 + 0 + 600 + 400 + + + + + 0 + 0 + + + + + 400 + 400 + + + + WizardPage + + + + + + <!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:'MS Shell Dlg 2'; 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;"><span style=" font-size:12pt; font-weight:600;">OpenPilot board identification</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><br /></p> +<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:10pt;">To continue, the wizard needs to determine the configuration required for the type of OpenPilot controller you have. When connected, the wizard will attempt to automatically detect the type of board.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;"><br /></p> +<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:10pt;">If the board is already connected and successfully detected, the board type will already be displayed. You can </span><span style=" font-size:10pt; font-weight:600;">Disconnect</span><span style=" font-size:10pt;"> and select another device if you need to detect another board.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;"><br /></p> +<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:10pt;">If your board is not connected, please connect the board to a USB port on your computer and select the device from the list below. Then press </span><span style=" font-size:10pt; font-weight:600;">Connect</span><span style=" font-size:10pt;">.</span></p></body></html> + + + Qt::AutoText + + + true + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + + + + 150 + 0 + + + + + 10 + 50 + false + + + + Connection device: + + + + + + + + 0 + 0 + + + + + + + + + + + + + 150 + 0 + + + + + 10 + 50 + false + + + + Detected board type: + + + + + + + false + + + + 0 + 0 + + + + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 120 + 16777215 + + + + Connect + + + + + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.cpp new file mode 100644 index 000000000..34228c401 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.cpp @@ -0,0 +1,65 @@ +/** + ****************************************************************************** + * + * @file endpage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup Setup Wizard Plugin + * @{ + * @brief A Wizard to make the initial setup easy for everyone. + *****************************************************************************/ +/* + * 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 "endpage.h" +#include "ui_endpage.h" +#include +#include +#include +#include + +EndPage::EndPage(SetupWizard *wizard, QWidget *parent) : + AbstractWizardPage(wizard, parent), + ui(new Ui::EndPage) +{ + ui->setupUi(this); + setFinalPage(true); + connect(ui->inputWizardButton, SIGNAL(clicked()), this, SLOT(openInputWizard())); +} + +EndPage::~EndPage() +{ + delete ui; +} + +void EndPage::openInputWizard() +{ + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + ConfigGadgetFactory* configGadgetFactory = pm->getObject(); + + if(configGadgetFactory) { + //Core::ModeManager::instance()->activateModeByWorkspaceName("Configuration"); + getWizard()->close(); + configGadgetFactory->startInputWizard(); + } + else { + QMessageBox msgBox; + msgBox.setText(tr("Unable to open Input Wizard since the Config Plugin is not\nloaded in the current workspace.")); + msgBox.setStandardButtons(QMessageBox::Ok); + msgBox.setDefaultButton(QMessageBox::Ok); + msgBox.exec(); + } +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.h new file mode 100644 index 000000000..dfbad7942 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.h @@ -0,0 +1,52 @@ +/** + ****************************************************************************** + * + * @file endpage.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @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 ENDPAGE_H +#define ENDPAGE_H + +#include "abstractwizardpage.h" + +namespace Ui { +class EndPage; +} + +class EndPage : public AbstractWizardPage +{ + Q_OBJECT + +public: + explicit EndPage(SetupWizard *wizard, QWidget *parent = 0); + ~EndPage(); + +private slots: + void openInputWizard(); + +private: + Ui::EndPage *ui; +}; + +#endif // ENDPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.ui new file mode 100644 index 000000000..944381d96 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.ui @@ -0,0 +1,82 @@ + + + EndPage + + + + 0 + 0 + 600 + 400 + + + + + 600 + 400 + + + + WizardPage + + + + + + <!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:'MS Shell Dlg 2'; 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;"><span style=" font-size:12pt; font-weight:600;">Congratulations!</span></p> +<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:12pt; font-weight:600;">Setup wizard is completed.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:12pt; font-weight:600;"><br /></p> +<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:10pt;">This part of the setup procedure is now complete and you are one step away from completing the setup of your OpenPilot controller.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;"><br /></p> +<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:10pt;">To complete the setup please click the Radio Setup Wizard button below to close this wizard and go directly to the Radio Setup Wizard.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;"><br /></p></body></html> + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + + + + + + + + QToolButton { border: none } + + + Go to Input Wizard... + + + + :/setupwizard/resources/bttn-txwizard-off.png + :/setupwizard/resources/bttn-txwizard-on.png + :/setupwizard/resources/bttn-txwizard-off.png + :/setupwizard/resources/bttn-txwizard-off.png:/setupwizard/resources/bttn-txwizard-off.png + + + + 200 + 100 + + + + true + + + + + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp new file mode 100644 index 000000000..7295cc8a3 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp @@ -0,0 +1,42 @@ +/** + ****************************************************************************** + * + * @file fixedwingpage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup FixedWingPage + * @{ + * @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 + */ + +#include "fixedwingpage.h" +#include "ui_fixedwingpage.h" + +FixedWingPage::FixedWingPage(SetupWizard *wizard, QWidget *parent) : + AbstractWizardPage(wizard, parent), + ui(new Ui::FixedWingPage) +{ + ui->setupUi(this); + setFinalPage(true); +} + +FixedWingPage::~FixedWingPage() +{ + delete ui; +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h new file mode 100644 index 000000000..697721a9e --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h @@ -0,0 +1,49 @@ +/** + ****************************************************************************** + * + * @file fixedwingpage.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup FixedWingPage + * @{ + * @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 FIXEDWINGPAGE_H +#define FIXEDWINGPAGE_H + +#include "abstractwizardpage.h" + +namespace Ui { +class FixedWingPage; +} + +class FixedWingPage : public AbstractWizardPage +{ + Q_OBJECT + +public: + explicit FixedWingPage(SetupWizard *wizard, QWidget *parent = 0); + ~FixedWingPage(); + +private: + Ui::FixedWingPage *ui; +}; + +#endif // FIXEDWINGPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui new file mode 100644 index 000000000..8b478be7d --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui @@ -0,0 +1,39 @@ + + + FixedWingPage + + + + 0 + 0 + 600 + 400 + + + + WizardPage + + + + + + <!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:'MS Shell Dlg 2'; font-size:8.25pt; 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:12pt; font-weight:600;">The Fixed Wing section of the OpenPilot Setup Wizard is not yet implemented</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"></p></body></html> + + + Qt::AlignCenter + + + true + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.cpp new file mode 100644 index 000000000..93bfc3503 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.cpp @@ -0,0 +1,42 @@ +/** + ****************************************************************************** + * + * @file helipage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup HeliPage + * @{ + * @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 + */ + +#include "helipage.h" +#include "ui_helipage.h" + +HeliPage::HeliPage(SetupWizard *wizard, QWidget *parent) : + AbstractWizardPage(wizard, parent), + ui(new Ui::HeliPage) +{ + ui->setupUi(this); + setFinalPage(true); +} + +HeliPage::~HeliPage() +{ + delete ui; +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.h new file mode 100644 index 000000000..2b2b5b894 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.h @@ -0,0 +1,49 @@ +/** + ****************************************************************************** + * + * @file helipage.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup HeliPage + * @{ + * @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 HELIPAGE_H +#define HELIPAGE_H + +#include "abstractwizardpage.h" + +namespace Ui { +class HeliPage; +} + +class HeliPage : public AbstractWizardPage +{ + Q_OBJECT + +public: + explicit HeliPage(SetupWizard *wizard, QWidget *parent = 0); + ~HeliPage(); + +private: + Ui::HeliPage *ui; +}; + +#endif // HELIPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.ui new file mode 100644 index 000000000..8e14881d9 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.ui @@ -0,0 +1,43 @@ + + + HeliPage + + + + 0 + 0 + 600 + 400 + + + + WizardPage + + + + + 50 + 160 + 500 + 41 + + + + <!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:'MS Shell Dlg 2'; font-size:8.25pt; 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:12pt; font-weight:600;">The Helicopter section of the OpenPilot Setup Wizard is not yet implemented</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"></p></body></html> + + + Qt::AlignHCenter|Qt::AlignTop + + + true + + + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/inputpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/inputpage.cpp new file mode 100644 index 000000000..607df838a --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/inputpage.cpp @@ -0,0 +1,91 @@ +/** + ****************************************************************************** + * + * @file inputpage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup InputPage + * @{ + * @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 + */ + +#include "inputpage.h" +#include "ui_inputpage.h" +#include "setupwizard.h" +#include "extensionsystem/pluginmanager.h" +#include "uavobjectmanager.h" +#include "hwsettings.h" + +InputPage::InputPage(SetupWizard *wizard, QWidget *parent) : + AbstractWizardPage(wizard, parent), + + ui(new Ui::InputPage) +{ + ui->setupUi(this); +} + +InputPage::~InputPage() +{ + delete ui; +} + +bool InputPage::validatePage() +{ + if(ui->pwmButton->isChecked()) { + getWizard()->setInputType(SetupWizard::INPUT_PWM); + } + else if(ui->ppmButton->isChecked()) { + getWizard()->setInputType(SetupWizard::INPUT_PPM); + } + else if(ui->sbusButton->isChecked()) { + getWizard()->setInputType(SetupWizard::INPUT_SBUS); + } + else if(ui->spectrumButton->isChecked()) { + getWizard()->setInputType(SetupWizard::INPUT_DSM2); + } + else { + getWizard()->setInputType(SetupWizard::INPUT_PWM); + } + getWizard()->setRestartNeeded(getWizard()->isRestartNeeded() || restartNeeded(getWizard()->getInputType())); + + return true; +} + +bool InputPage::restartNeeded(VehicleConfigurationSource::INPUT_TYPE selectedType) +{ + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + UAVObjectManager *uavoManager = pm->getObject(); + Q_ASSERT(uavoManager); + HwSettings* hwSettings = HwSettings::GetInstance(uavoManager); + HwSettings::DataFields data = hwSettings->getData(); + switch(selectedType) + { + case VehicleConfigurationSource::INPUT_PWM: + return data.CC_RcvrPort != HwSettings::CC_RCVRPORT_PWM; + case VehicleConfigurationSource::INPUT_PPM: + return data.CC_RcvrPort != HwSettings::CC_RCVRPORT_PPM; + case VehicleConfigurationSource::INPUT_SBUS: + return data.CC_MainPort != HwSettings::CC_MAINPORT_SBUS; + case VehicleConfigurationSource::INPUT_DSM2: + // TODO: Handle all of the DSM types ?? Which is most common? + return data.CC_MainPort != HwSettings::CC_MAINPORT_DSM2; + default: + return true; + } +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/inputpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/inputpage.h new file mode 100644 index 000000000..dde50b6e6 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/inputpage.h @@ -0,0 +1,51 @@ +/** + ****************************************************************************** + * + * @file inputpage.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup InputPage + * @{ + * @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 INPUTPAGE_H +#define INPUTPAGE_H + +#include "abstractwizardpage.h" + +namespace Ui { +class InputPage; +} + +class InputPage : public AbstractWizardPage +{ + Q_OBJECT + +public: + explicit InputPage(SetupWizard *wizard, QWidget *parent = 0); + ~InputPage(); + bool validatePage(); + +private: + bool restartNeeded(VehicleConfigurationSource::INPUT_TYPE selectedType); + Ui::InputPage *ui; +}; + +#endif // INPUTPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/inputpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/inputpage.ui new file mode 100644 index 000000000..cf17df324 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/inputpage.ui @@ -0,0 +1,231 @@ + + + InputPage + + + + 0 + 0 + 600 + 400 + + + + WizardPage + + + + + + QFrame::NoFrame + + + <!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:'MS Shell Dlg 2'; 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;"><span style=" font-size:12pt; font-weight:600;">OpenPilot basic input signal configuration</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:12pt; font-weight:600;"><br /></p> +<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:10pt;">The OpenPilot controller supports many different types of input signals. Please select the type of input that matches your receiver configuration. If you are unsure, just leave the default option selected and continue the wizard.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;"><br /></p> +<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:10pt;">Some input options require the OpenPilot controller to be rebooted before the changes can take place. If an option that requires a reboot is selected, you will be instructed to do so on the next page of this wizard.</span></p></body></html> + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + + 10 + + + + PWM - One cable per channel + + + QToolButton { border: none } + + + PWM + + + + :/setupwizard/resources/bttn-pwm-up.png + :/setupwizard/resources/bttn-pwm-down.png:/setupwizard/resources/bttn-pwm-up.png + + + + 100 + 100 + + + + true + + + true + + + true + + + Qt::ToolButtonTextUnderIcon + + + true + + + + + + + + 10 + + + + PPM - One cable for all channels + + + QToolButton { border: none } + + + PPM + + + + :/setupwizard/resources/bttn-ppm-up.png + :/setupwizard/resources/bttn-ppm-down.png:/setupwizard/resources/bttn-ppm-up.png + + + + 100 + 100 + + + + true + + + true + + + Qt::ToolButtonTextUnderIcon + + + true + + + + + + + + 10 + + + + Futaba S-BUS + + + QToolButton { border: none } + + + Futaba + + + + :/setupwizard/resources/bttn-sbus-up.png + :/setupwizard/resources/bttn-sbus-down.png:/setupwizard/resources/bttn-sbus-up.png + + + + 100 + 100 + + + + true + + + true + + + Qt::ToolButtonTextUnderIcon + + + true + + + + + + + + 10 + + + + Spektrum Satellite + + + QToolButton { border: none } + + + Spektrum + + + + :/setupwizard/resources/bttn-sat-up.png + :/setupwizard/resources/bttn-sat-down.png:/setupwizard/resources/bttn-sat-up.png + + + + 100 + 100 + + + + true + + + true + + + Qt::ToolButtonTextUnderIcon + + + true + + + + + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/levellingpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/levellingpage.cpp new file mode 100644 index 000000000..28dac7c33 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/levellingpage.cpp @@ -0,0 +1,136 @@ +/** + ****************************************************************************** + * + * @file levellingpage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup LevellingPage + * @{ + * @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 + */ + +#include +#include +#include "levellingpage.h" +#include "ui_levellingpage.h" +#include "setupwizard.h" + +LevellingPage::LevellingPage(SetupWizard *wizard, QWidget *parent) : + AbstractWizardPage(wizard, parent), + ui(new Ui::LevellingPage), m_levellingUtil(0) +{ + ui->setupUi(this); + connect(ui->levelButton, SIGNAL(clicked()), this, SLOT(performLevelling())); +} + +LevellingPage::~LevellingPage() +{ + if(m_levellingUtil) { + delete m_levellingUtil; + } + delete ui; +} + +bool LevellingPage::validatePage() +{ + return true; +} + +bool LevellingPage::isComplete() const +{ + //const_cast(this)->getWizard()->isLevellingPerformed() && + return ui->levelButton->isEnabled(); +} + +void LevellingPage::enableButtons(bool enable) +{ + ui->levelButton->setEnabled(enable); + getWizard()->button(QWizard::NextButton)->setEnabled(enable); + getWizard()->button(QWizard::CancelButton)->setEnabled(enable); + getWizard()->button(QWizard::BackButton)->setEnabled(enable); + QApplication::processEvents(); +} + +void LevellingPage::performLevelling() +{ + if(!getWizard()->getConnectionManager()->isConnected()) { + QMessageBox msgBox; + msgBox.setText(tr("An OpenPilot controller must be connected to your computer to perform bias " + "calculations.\nPlease connect your OpenPilot controller to your computer and try again.")); + msgBox.setStandardButtons(QMessageBox::Ok); + msgBox.setDefaultButton(QMessageBox::Ok); + msgBox.exec(); + return; + } + + enableButtons(false); + ui->progressLabel->setText(QString(tr("Retrieving data..."))); + + + if(!m_levellingUtil) + { + m_levellingUtil = new LevellingUtil(BIAS_CYCLES, BIAS_RATE); + } + + connect(m_levellingUtil, SIGNAL(progress(long,long)), this, SLOT(levellingProgress(long,long))); + connect(m_levellingUtil, SIGNAL(done(accelGyroBias)), this, SLOT(levellingDone(accelGyroBias))); + connect(m_levellingUtil, SIGNAL(timeout(QString)), this, SLOT(levellingTimeout(QString))); + + m_levellingUtil->start(); +} + +void LevellingPage::levellingProgress(long current, long total) +{ + if(ui->levellinProgressBar->maximum() != (int)total) { + ui->levellinProgressBar->setMaximum((int)total); + } + if(ui->levellinProgressBar->value() != (int)current) { + ui->levellinProgressBar->setValue((int)current); + } +} + +void LevellingPage::levellingDone(accelGyroBias bias) +{ + stopLevelling(); + getWizard()->setLevellingBias(bias); + emit completeChanged(); +} + +void LevellingPage::levellingTimeout(QString message) +{ + stopLevelling(); + + QMessageBox msgBox; + msgBox.setText(message); + msgBox.setStandardButtons(QMessageBox::Ok); + msgBox.setDefaultButton(QMessageBox::Ok); + msgBox.exec(); +} + +void LevellingPage::stopLevelling() +{ + if(m_levellingUtil) + { + disconnect(m_levellingUtil, SIGNAL(progress(long,long)), this, SLOT(levellingProgress(long,long))); + disconnect(m_levellingUtil, SIGNAL(done(accelGyroBias)), this, SLOT(levellingDone(accelGyroBias))); + disconnect(m_levellingUtil, SIGNAL(timeout(QString)), this, SLOT(levellingTimeout(QString))); + ui->progressLabel->setText(QString(tr("Done!"))); + enableButtons(true); + } +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/levellingpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/levellingpage.h new file mode 100644 index 000000000..06b18ed75 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/levellingpage.h @@ -0,0 +1,65 @@ +/** + ****************************************************************************** + * + * @file levellingpage.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup LevellingPage + * @{ + * @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 LEVELLINGPAGE_H +#define LEVELLINGPAGE_H + +#include "abstractwizardpage.h" +#include "levellingutil.h" + +namespace Ui { +class LevellingPage; +} + +class LevellingPage : public AbstractWizardPage +{ + Q_OBJECT + +public: + explicit LevellingPage(SetupWizard *wizard, QWidget *parent = 0); + ~LevellingPage(); + bool validatePage(); + bool isComplete() const; + +private slots: + void performLevelling(); + void levellingProgress(long current, long total); + void levellingDone(accelGyroBias bias); + void levellingTimeout(QString message); + +private: + static const int BIAS_CYCLES = 200; + static const int BIAS_RATE = 30; + + Ui::LevellingPage *ui; + LevellingUtil *m_levellingUtil; + + void stopLevelling(); + void enableButtons(bool enable); +}; + +#endif // LEVELLINGPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/levellingpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/levellingpage.ui new file mode 100644 index 000000000..c257619ed --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/levellingpage.ui @@ -0,0 +1,118 @@ + + + LevellingPage + + + + 0 + 0 + 600 + 400 + + + + WizardPage + + + + + + <!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:'Lucida Grande'; font-size:13pt; 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-family:'MS Shell Dlg 2'; font-size:12pt; font-weight:600;">OpenPilot controller leveling calibration procedure</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'MS Shell Dlg 2'; font-size:12pt; font-weight:600;"></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'MS Shell Dlg 2'; font-size:10pt;">The wizard needs to get information from the controller to determine in which position the vehicle is normally considered to be level. To be able to successfully perform these measurements, you need to place the vehicle on a surface that is as flat and level as possible. Examples of such surfaces could be a table top or the floor. Be careful to ensure that the vehicle really is level, since this step will affect the accelerometer and gyro bias in the controller software.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'MS Shell Dlg 2'; font-size:10pt;"></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'MS Shell Dlg 2'; font-size:10pt;">To perform the leveling, please push the Calculate button and wait for the process to finish. </span></p></body></html> + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + Calculate gyro and accelerometer bias + + + QToolButton { border: none } + + + Calculate + + + + :/setupwizard/resources/bttn-calculate-up.png + :/setupwizard/resources/bttn-calculate-down.png:/setupwizard/resources/bttn-calculate-up.png + + + + 200 + 70 + + + + + + + + + + + + + + + + + + + QProgressBar { + border: 2px solid grey; + border-radius: 5px; + text-align: center; + } +QProgressBar::chunk { + background-color: #3D6699; + width: 10px; + margin: 0.5px; + } + + + 0 + + + + + + + + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp new file mode 100644 index 000000000..79ea7131c --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp @@ -0,0 +1,182 @@ +/** + ****************************************************************************** + * + * @file multipage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup MultiPage + * @{ + * @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 + */ + +#include "multipage.h" +#include "ui_multipage.h" +#include "setupwizard.h" + +MultiPage::MultiPage(SetupWizard *wizard, QWidget *parent) : + AbstractWizardPage(wizard, parent), + ui(new Ui::MultiPage) +{ + ui->setupUi(this); + + QSvgRenderer *renderer = new QSvgRenderer(); + renderer->load(QString(":/configgadget/images/multirotor-shapes.svg")); + m_multiPic = new QGraphicsSvgItem(); + m_multiPic->setSharedRenderer(renderer); + QGraphicsScene *scene = new QGraphicsScene(this); + scene->addItem(m_multiPic); + ui->typeGraphicsView->setScene(scene); + + setupMultiTypesCombo(); + + // Default to Quad X since it is the most common setup + ui->typeCombo->setCurrentIndex(1); + connect(ui->typeCombo, SIGNAL(currentIndexChanged(int)), this, SLOT(updateImageAndDescription())); + ui->typeGraphicsView->setSceneRect(m_multiPic->boundingRect()); + ui->typeGraphicsView->fitInView(m_multiPic, Qt::KeepAspectRatio); +} + +MultiPage::~MultiPage() +{ + delete ui; +} + +void MultiPage::initializePage() +{ + updateAvailableTypes(); + updateImageAndDescription(); +} + +bool MultiPage::validatePage() +{ + SetupWizard::VEHICLE_SUB_TYPE type = (SetupWizard::VEHICLE_SUB_TYPE) ui->typeCombo->itemData(ui->typeCombo->currentIndex()).toInt(); + getWizard()->setVehicleSubType(type); + return true; +} + +void MultiPage::resizeEvent(QResizeEvent *event) +{ + Q_UNUSED(event); + if(m_multiPic) { + ui->typeGraphicsView->setSceneRect(m_multiPic->boundingRect()); + ui->typeGraphicsView->fitInView(m_multiPic, Qt::KeepAspectRatio); + } +} + +void MultiPage::setupMultiTypesCombo() +{ + ui->typeCombo->addItem(tr("Tricopter"), SetupWizard::MULTI_ROTOR_TRI_Y); + m_descriptions << tr("The Tricopter uses three motors and one servo. The servo is used to give yaw authority to the rear motor. " + "The front motors are rotating in opposite directions. The Tricopter is known for its sweeping yaw movement and " + "it is very well suited for FPV since the front rotors are spread wide apart."); + + ui->typeCombo->addItem(tr("Quadcopter X"), SetupWizard::MULTI_ROTOR_QUAD_X); + m_descriptions << tr("The X Quadcopter uses four motors and is the most common multi rotor configuration. Two of the motors rotate clockwise " + "and two counter clockwise. The motors positioned diagonal to each other rotate in the same direction. " + "This setup is perfect for sport flying and is also commonly used for FPV platforms."); + + ui->typeCombo->addItem(tr("Quadcopter +"), SetupWizard::MULTI_ROTOR_QUAD_PLUS); + m_descriptions << tr("The Plus(+) Quadcopter uses four motors and is similar to the X Quadcopter but the forward direction is offset by 45 degrees. " + "The motors front and rear rotate in clockwise and the motors right and left rotate counter-clockwise. " + "This setup was one of the first to be used and is still used for sport flying. This configuration is not that well suited " + "for FPV since the fore rotor tend to be in the way of the camera."); + + ui->typeCombo->addItem(tr("Hexacopter"), SetupWizard::MULTI_ROTOR_HEXA); + m_descriptions << tr("Hexacopter"); + + ui->typeCombo->addItem(tr("Hexacopter Coax (Y6)"), SetupWizard::MULTI_ROTOR_HEXA_COAX_Y); + m_descriptions << tr("Hexacopter Coax (Y6)"); + + ui->typeCombo->addItem(tr("Hexacopter X"), SetupWizard::MULTI_ROTOR_HEXA_H); + m_descriptions << tr("Hexacopter H"); + + // Fredrik Arvidsson(m_thread) 2012-08-26 Disable Octos until further notice + /* + ui->typeCombo->addItem(tr("Octocopter"), SetupWizard::MULTI_ROTOR_OCTO); + m_descriptions << tr("Octocopter"); + + ui->typeCombo->addItem(tr("Octocopter Coax X"), SetupWizard::MULTI_ROTOR_OCTO_COAX_X); + m_descriptions << tr("Octocopter Coax X"); + + ui->typeCombo->addItem(tr("Octocopter Coax +"), SetupWizard::MULTI_ROTOR_OCTO_COAX_PLUS); + m_descriptions << tr("Octocopter Coax +"); + + ui->typeCombo->addItem(tr("Octocopter V"), SetupWizard::MULTI_ROTOR_OCTO_V); + m_descriptions << tr("Octocopter V"); + */ +} + +void MultiPage::updateAvailableTypes() +{ + /* + QVariant enable = (getWizard()->getInputType() == SetupWizard::INPUT_PWM) ? QVariant(0) : QVariant(1 | 32); + ui->typeCombo->model()->setData(ui->typeCombo->model()->index(6, 0), enable, Qt::UserRole - 1); + ui->typeCombo->model()->setData(ui->typeCombo->model()->index(7, 0), enable, Qt::UserRole - 1); + ui->typeCombo->model()->setData(ui->typeCombo->model()->index(8, 0), enable, Qt::UserRole - 1); + ui->typeCombo->model()->setData(ui->typeCombo->model()->index(9, 0), enable, Qt::UserRole - 1); + */ +} + +void MultiPage::updateImageAndDescription() +{ + SetupWizard::VEHICLE_SUB_TYPE type = (SetupWizard::VEHICLE_SUB_TYPE) ui->typeCombo->itemData(ui->typeCombo->currentIndex()).toInt(); + QString elementId = ""; + QString description = m_descriptions.at(ui->typeCombo->currentIndex()); + switch(type) + { + case SetupWizard::MULTI_ROTOR_TRI_Y: + elementId = "tri"; + break; + case SetupWizard::MULTI_ROTOR_QUAD_X: + elementId = "quad-x"; + break; + case SetupWizard::MULTI_ROTOR_QUAD_PLUS: + elementId = "quad-plus"; + break; + case SetupWizard::MULTI_ROTOR_HEXA: + elementId = "quad-hexa"; + break; + case SetupWizard::MULTI_ROTOR_HEXA_COAX_Y: + elementId = "hexa-coax"; + break; + case SetupWizard::MULTI_ROTOR_HEXA_H: + elementId = "quad-hexa-H"; + break; + case SetupWizard::MULTI_ROTOR_OCTO: + elementId = "quad-octo"; + break; + case SetupWizard::MULTI_ROTOR_OCTO_COAX_X: + elementId = "octo-coax-X"; + break; + case SetupWizard::MULTI_ROTOR_OCTO_COAX_PLUS: + elementId = "octo-coax-P"; + break; + case SetupWizard::MULTI_ROTOR_OCTO_V: + elementId = "quad-octo-v"; + break; + default: + elementId = ""; + break; + } + m_multiPic->setElementId(elementId); + ui->typeGraphicsView->setSceneRect(m_multiPic->boundingRect()); + ui->typeGraphicsView->fitInView(m_multiPic, Qt::KeepAspectRatio); + + ui->typeDescription->setText(description); +} diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2optionspage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.h similarity index 57% rename from ground/openpilotgcs/src/plugins/hitlv2/hitlv2optionspage.h rename to ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.h index dbfe028bc..5614ea6cb 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2optionspage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.h @@ -1,13 +1,13 @@ /** ****************************************************************************** * - * @file hitlv2optionspage.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. - * @addtogroup GCSPlugins GCS Plugins + * @file multipage.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup * @{ - * @addtogroup HITLPlugin HITLv2 Plugin + * @addtogroup MultiPage * @{ - * @brief The Hardware In The Loop plugin version 2 + * @brief *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify @@ -25,37 +25,42 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#ifndef HITLV2OPTIONSPAGE_H -#define HITLV2OPTIONSPAGE_H +#ifndef MULTIPAGE_H +#define MULTIPAGE_H -#include +#include +#include +#include -namespace Core { -class IUAVGadgetConfiguration; -} - -class HITLConfiguration; - -using namespace Core; +#include "abstractwizardpage.h" namespace Ui { -class HITLOptionsPage; +class MultiPage; } -class HITLOptionsPage : public IOptionsPage +class MultiPage : public AbstractWizardPage { Q_OBJECT + public: - explicit HITLOptionsPage(HITLConfiguration *conf, QObject *parent = 0); + explicit MultiPage(SetupWizard *wizard, QWidget *parent = 0); + ~MultiPage(); - QWidget *createPage(QWidget *parent); - void apply(); - void finish(); - bool isDecorated() const { return true; } + void initializePage(); + bool validatePage(); +protected: + void resizeEvent(QResizeEvent *event); + private: - HITLConfiguration* config; - Ui::HITLOptionsPage* m_optionsPage; + Ui::MultiPage *ui; + void setupMultiTypesCombo(); + QGraphicsSvgItem *m_multiPic; + void updateAvailableTypes(); + QList m_descriptions; + +private slots: + void updateImageAndDescription(); }; -#endif // HITLV2OPTIONSPAGE_H +#endif // MULTIPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.ui new file mode 100644 index 000000000..b4da7c0a7 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.ui @@ -0,0 +1,164 @@ + + + MultiPage + + + + 0 + 0 + 600 + 400 + + + + WizardPage + + + + + + <!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:'MS Shell Dlg 2'; 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;"><span style=" font-size:12pt; font-weight:600;">OpenPilot multirotor configuration</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:12pt; font-weight:600;"><br /></p> +<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:10pt;">This part of the wizard will set up the OpenPilot controller for use with a flying platform utilizing multiple rotors. The wizard supports the most common types of multirotors. Other variants of multirotors can be configured by using custom configuration options in the Configuration plugin in the GCS.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;"><br /></p> +<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:10pt;">Please select the type of multirotor you want to create a configuration for below:</span></p></body></html> + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + + + + + + 4 + + + + + + + 4 + + + + + + 125 + 36 + + + + + 10 + 50 + false + + + + Multirotor type: + + + + + + + + 125 + 20 + + + + + + + + + + + 0 + 0 + + + + Qt::ScrollBarAlwaysOn + + + Qt::ScrollBarAlwaysOff + + + Qt::TextSelectableByKeyboard|Qt::TextSelectableByMouse + + + + + + + + + + 0 + 0 + + + + + 200 + 200 + + + + true + + + QFrame::NoFrame + + + 0 + + + 0 + + + Qt::ScrollBarAlwaysOff + + + Qt::ScrollBarAlwaysOff + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + false + + + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/notyetimplementedpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/notyetimplementedpage.cpp new file mode 100644 index 000000000..57a43fda8 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/notyetimplementedpage.cpp @@ -0,0 +1,42 @@ +/** + ****************************************************************************** + * + * @file notyetimplementedpage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup NotYetImplementedPage + * @{ + * @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 + */ + +#include "notyetimplementedpage.h" +#include "ui_notyetimplementedpage.h" + +NotYetImplementedPage::NotYetImplementedPage(SetupWizard *wizard, QWidget *parent) : + AbstractWizardPage(wizard, parent), + ui(new Ui::NotYetImplementedPage) +{ + ui->setupUi(this); + setFinalPage(true); +} + +NotYetImplementedPage::~NotYetImplementedPage() +{ + delete ui; +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/notyetimplementedpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/notyetimplementedpage.h new file mode 100644 index 000000000..4f323d9fc --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/notyetimplementedpage.h @@ -0,0 +1,49 @@ +/** + ****************************************************************************** + * + * @file notyetimplementedpage.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup NotYetImplementedPage + * @{ + * @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 NOTYETIMPLEMENTEDPAGE_H +#define NOTYETIMPLEMENTEDPAGE_H + +#include "abstractwizardpage.h" + +namespace Ui { +class NotYetImplementedPage; +} + +class NotYetImplementedPage : public AbstractWizardPage +{ + Q_OBJECT + +public: + explicit NotYetImplementedPage(SetupWizard *wizard, QWidget *parent = 0); + ~NotYetImplementedPage(); + +private: + Ui::NotYetImplementedPage *ui; +}; + +#endif // NOTYETIMPLEMENTEDPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/notyetimplementedpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/notyetimplementedpage.ui new file mode 100644 index 000000000..e1a066a4f --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/notyetimplementedpage.ui @@ -0,0 +1,43 @@ + + + NotYetImplementedPage + + + + 0 + 0 + 600 + 400 + + + + WizardPage + + + + + 20 + 170 + 551 + 51 + + + + <!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:'MS Shell Dlg 2'; font-size:8.25pt; 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:12pt; font-weight:600;">This section of the OpenPilot Setup Wizard is not yet implemented</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"></p></body></html> + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp new file mode 100644 index 000000000..642d2a3ba --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp @@ -0,0 +1,402 @@ +/** + ****************************************************************************** + * + * @file outputcalibrationpage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup OutputCalibrationPage + * @{ + * @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 + */ + +#include "outputcalibrationpage.h" +#include "ui_outputcalibrationpage.h" +#include "systemalarms.h" +#include "uavobjectmanager.h" + +OutputCalibrationPage::OutputCalibrationPage(SetupWizard *wizard, QWidget *parent) : + AbstractWizardPage(wizard, parent), ui(new Ui::OutputCalibrationPage), m_vehicleBoundsItem(0), + m_currentWizardIndex(-1), m_calibrationUtil(0) +{ + ui->setupUi(this); + + m_vehicleRenderer = new QSvgRenderer(); + if (QFile::exists(QString(":/setupwizard/resources/multirotor-shapes.svg")) && + m_vehicleRenderer->load(QString(":/setupwizard/resources/multirotor-shapes.svg")) && + m_vehicleRenderer->isValid()) + { + m_vehicleScene = new QGraphicsScene(this); + ui->vehicleView->setScene(m_vehicleScene); + } +} + +OutputCalibrationPage::~OutputCalibrationPage() +{ + if(m_calibrationUtil) { + delete m_calibrationUtil; + m_calibrationUtil = 0; + } + delete ui; +} + +void OutputCalibrationPage::setupVehicle() +{ + m_actuatorSettings = getWizard()->getActuatorSettings(); + m_wizardIndexes.clear(); + m_vehicleElementIds.clear(); + m_vehicleHighlightElementIndexes.clear(); + m_channelIndex.clear(); + m_currentWizardIndex = 0; + m_vehicleScene->clear(); + switch(getWizard()->getVehicleSubType()) + { + case SetupWizard::MULTI_ROTOR_TRI_Y: + m_wizardIndexes << 0 << 1 << 1 << 1 << 2 << 3 << 4; + m_vehicleElementIds << "tri" << "tri-frame" << "tri-m1" << "tri-m2" << "tri-m3" << "tri-s1"; + m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4 << 4 << 4; + m_channelIndex << 0 << 0 << 1 << 2 << 3 << 3 << 3; + m_actuatorSettings[3].channelMin = 1500; + m_actuatorSettings[3].channelNeutral = 1500; + m_actuatorSettings[3].channelMax = 1500; + getWizard()->setActuatorSettings(m_actuatorSettings); + break; + case SetupWizard::MULTI_ROTOR_QUAD_X: + m_wizardIndexes << 0 << 1 << 1 << 1 << 1; + m_vehicleElementIds << "quad-x" << "quad-x-frame" << "quad-x-m1" << "quad-x-m2" << "quad-x-m3" << "quad-x-m4"; + m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4; + m_channelIndex << 0 << 0 << 1 << 2 << 3; + break; + case SetupWizard::MULTI_ROTOR_QUAD_PLUS: + m_wizardIndexes << 0 << 1 << 1 << 1 << 1; + m_vehicleElementIds << "quad-p" << "quad-p-frame" << "quad-p-m1" << "quad-p-m2" << "quad-p-m3" << "quad-p-m4"; + m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4; + m_channelIndex << 0 << 0 << 1 << 2 << 3; + break; + case SetupWizard::MULTI_ROTOR_HEXA: + m_wizardIndexes << 0 << 1 << 1 << 1 << 1 << 1 << 1; + m_vehicleElementIds << "hexa" << "hexa-frame" << "hexa-m1" << "hexa-m2" << "hexa-m3" << "hexa-m4" << "hexa-m5" << "hexa-m6"; + m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4 << 5 << 6; + m_channelIndex << 0 << 0 << 1 << 2 << 3 << 4 << 5; + break; + case SetupWizard::MULTI_ROTOR_HEXA_COAX_Y: + m_wizardIndexes << 0 << 1 << 1 << 1 << 1 << 1 << 1; + m_vehicleElementIds << "hexa-y6" << "hexa-y6-frame" << "hexa-y6-m2" << "hexa-y6-m1" << "hexa-y6-m4" << "hexa-y6-m3" << "hexa-y6-m6" << "hexa-y6-m5"; + m_vehicleHighlightElementIndexes << 0 << 2 << 1 << 4 << 3 << 6 << 5; + m_channelIndex << 0 << 0 << 1 << 2 << 3 << 4 << 5; + break; + case SetupWizard::MULTI_ROTOR_HEXA_H: + m_wizardIndexes << 0 << 1 << 1 << 1 << 1 << 1 << 1; + m_vehicleElementIds << "hexa-h" << "hexa-h-frame" << "hexa-h-m1" << "hexa-h-m2" << "hexa-h-m3" << "hexa-h-m4" << "hexa-h-m5" << "hexa-h-m6"; + m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4 << 5 << 6; + m_channelIndex << 0 << 0 << 1 << 2 << 3 << 4 << 5; + break; + default: + break; + } + + VehicleConfigurationHelper helper(getWizard()); + helper.setupVehicle(false); + + if(m_calibrationUtil) { + delete m_calibrationUtil; + m_calibrationUtil = 0; + } + m_calibrationUtil = new OutputCalibrationUtil(); + + setupVehicleItems(); +} + +void OutputCalibrationPage::setupVehicleItems() +{ + m_vehicleItems.clear(); + m_vehicleBoundsItem = new QGraphicsSvgItem(); + m_vehicleBoundsItem->setSharedRenderer(m_vehicleRenderer); + m_vehicleBoundsItem->setElementId(m_vehicleElementIds[0]); + m_vehicleBoundsItem->setZValue(-1); + m_vehicleBoundsItem->setOpacity(0); + m_vehicleScene->addItem(m_vehicleBoundsItem); + + QRectF parentBounds = m_vehicleRenderer->boundsOnElement(m_vehicleElementIds[0]); + + for(int i = 1; i < m_vehicleElementIds.size(); i++) + { + QGraphicsSvgItem *item = new QGraphicsSvgItem(); + item->setSharedRenderer(m_vehicleRenderer); + item->setElementId(m_vehicleElementIds[i]); + item->setZValue(i); + item->setOpacity(1.0); + + QRectF itemBounds = m_vehicleRenderer->boundsOnElement(m_vehicleElementIds[i]); + item->setPos(itemBounds.x() - parentBounds.x(), itemBounds.y() - parentBounds.y()); + + m_vehicleScene->addItem(item); + m_vehicleItems << item; + } +} + +void OutputCalibrationPage::startWizard() +{ + ui->calibrationStack->setCurrentIndex(m_wizardIndexes[0]); + setupVehicleHighlightedPart(); +} + +void OutputCalibrationPage::setupVehicleHighlightedPart() +{ + qreal dimOpaque = m_currentWizardIndex == 0 ? 1.0 : 0.3; + qreal highlightOpaque = 1.0; + int highlightedIndex = m_vehicleHighlightElementIndexes[m_currentWizardIndex]; + for(int i = 0; i < m_vehicleItems.size(); i++) { + QGraphicsSvgItem* item = m_vehicleItems[i]; + item->setOpacity((highlightedIndex == i) ? highlightOpaque : dimOpaque); + } +} + +void OutputCalibrationPage::setWizardPage() +{ + qDebug() << "Wizard index: " << m_currentWizardIndex; + m_calibrationUtil->stopChannelOutput(); + + QApplication::processEvents(); + + int currentPageIndex = m_wizardIndexes[m_currentWizardIndex]; + qDebug() << "Current page: " << currentPageIndex; + ui->calibrationStack->setCurrentIndex(currentPageIndex); + + int currentChannel = getCurrentChannel(); + qDebug() << "Current channel: " << currentChannel; + if(currentChannel >= 0) { + if(currentPageIndex == 1) { + ui->motorNeutralSlider->setValue(m_actuatorSettings[currentChannel].channelNeutral); + } + else if(currentPageIndex == 2) { + ui->servoCenterSlider->setValue(m_actuatorSettings[currentChannel].channelNeutral); + } + else if(currentPageIndex == 3) { + ui->servoMinAngleSlider->setMaximum(m_actuatorSettings[currentChannel].channelNeutral); + ui->servoMinAngleSlider->setValue(m_actuatorSettings[currentChannel].channelMin); + } + else if(currentPageIndex == 4) { + ui->servoMaxAngleSlider->setMinimum(m_actuatorSettings[currentChannel].channelNeutral); + ui->servoMaxAngleSlider->setValue(m_actuatorSettings[currentChannel].channelMax); + } + } + setupVehicleHighlightedPart(); +} + +void OutputCalibrationPage::initializePage() +{ + if(m_vehicleScene) { + setupVehicle(); + startWizard(); + } +} + +bool OutputCalibrationPage::validatePage() +{ + if(isFinished()) { + getWizard()->setActuatorSettings(m_actuatorSettings); + return true; + } else { + m_currentWizardIndex++; + setWizardPage(); + return false; + } +} + +void OutputCalibrationPage::showEvent(QShowEvent *event) +{ + Q_UNUSED(event); + if(m_vehicleBoundsItem) { + ui->vehicleView->setSceneRect(m_vehicleBoundsItem->boundingRect()); + ui->vehicleView->fitInView(m_vehicleBoundsItem, Qt::KeepAspectRatio); + } +} + +void OutputCalibrationPage::resizeEvent(QResizeEvent *event) +{ + Q_UNUSED(event); + if(m_vehicleBoundsItem) { + ui->vehicleView->setSceneRect(m_vehicleBoundsItem->boundingRect()); + ui->vehicleView->fitInView(m_vehicleBoundsItem, Qt::KeepAspectRatio); + } +} + +void OutputCalibrationPage::customBackClicked() +{ + if(m_currentWizardIndex > 0) + { + m_currentWizardIndex--; + setWizardPage(); + } + else + { + getWizard()->back(); + } +} + +quint16 OutputCalibrationPage::getCurrentChannel() +{ + return m_channelIndex[m_currentWizardIndex]; +} + +void OutputCalibrationPage::enableButtons(bool enable) +{ + getWizard()->button(QWizard::NextButton)->setEnabled(enable); + getWizard()->button(QWizard::CustomButton1)->setEnabled(enable); + getWizard()->button(QWizard::CancelButton)->setEnabled(enable); + getWizard()->button(QWizard::BackButton)->setEnabled(enable); + QApplication::processEvents(); +} + +void OutputCalibrationPage::on_motorNeutralButton_toggled(bool checked) +{ + ui->motorNeutralButton->setText(checked ? tr("Stop") : tr("Start")); + quint16 channel = getCurrentChannel(); + onStartButtonToggle(ui->motorNeutralButton, channel, m_actuatorSettings[channel].channelNeutral, 1000, ui->motorNeutralSlider); +} + +void OutputCalibrationPage::onStartButtonToggle(QAbstractButton *button, quint16 channel, quint16 value, quint16 safeValue, QSlider *slider) { + if(button->isChecked()) { + if(checkAlarms()) { + enableButtons(false); + m_calibrationUtil->startChannelOutput(channel, safeValue); + slider->setValue(value); + m_calibrationUtil->setChannelOutputValue(value); + } + else { + button->setChecked(false); + } + } + else { + m_calibrationUtil->stopChannelOutput(); + enableButtons(true); + } + debugLogChannelValues(); +} + +bool OutputCalibrationPage::checkAlarms() +{ + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + UAVObjectManager *uavObjectManager = pm->getObject(); + Q_ASSERT(uavObjectManager); + SystemAlarms * systemAlarms = SystemAlarms::GetInstance(uavObjectManager); + Q_ASSERT(systemAlarms); + SystemAlarms::DataFields data = systemAlarms->getData(); + + if(data.Alarm[SystemAlarms::ALARM_ACTUATOR] != SystemAlarms::ALARM_OK) { + QMessageBox mbox(this); + mbox.setText(QString(tr("The actuator module is in an error state.\n\n" + "Please make sure the correct firmware version is used then " + "restart the wizard and try again. If the problem persists please " + "consult the openpilot.org support forum."))); + mbox.setStandardButtons(QMessageBox::Ok); + mbox.setIcon(QMessageBox::Critical); + + getWizard()->setWindowFlags(getWizard()->windowFlags() & ~Qt::WindowStaysOnTopHint); + + mbox.exec(); + + getWizard()->setWindowFlags(getWizard()->windowFlags() | Qt::WindowStaysOnTopHint); + getWizard()->setWindowIcon(qApp->windowIcon()); + getWizard()->show(); + return false; + } + return true; +} + +void OutputCalibrationPage::debugLogChannelValues() +{ + quint16 channel = getCurrentChannel(); + qDebug() << "ChannelMin : " << m_actuatorSettings[channel].channelMin; + qDebug() << "ChannelNeutral: " << m_actuatorSettings[channel].channelNeutral; + qDebug() << "ChannelMax : " << m_actuatorSettings[channel].channelMax; +} + +void OutputCalibrationPage::on_motorNeutralSlider_valueChanged(int value) +{ + if(ui->motorNeutralButton->isChecked()) { + quint16 value = ui->motorNeutralSlider->value(); + m_calibrationUtil->setChannelOutputValue(value); + m_actuatorSettings[getCurrentChannel()].channelNeutral = value; + debugLogChannelValues(); + } +} + +void OutputCalibrationPage::on_servoCenterButton_toggled(bool checked) +{ + ui->servoCenterButton->setText(checked ? tr("Stop") : tr("Start")); + quint16 channel = getCurrentChannel(); + quint16 safeValue = m_actuatorSettings[channel].channelNeutral; + onStartButtonToggle(ui->servoCenterButton, channel, safeValue, safeValue, ui->servoCenterSlider); +} + +void OutputCalibrationPage::on_servoCenterSlider_valueChanged(int position) +{ + if(ui->servoCenterButton->isChecked()) { + quint16 value = ui->servoCenterSlider->value(); + m_calibrationUtil->setChannelOutputValue(value); + quint16 channel = getCurrentChannel(); + m_actuatorSettings[channel].channelNeutral = value; + + //Adjust min and max + if(value < m_actuatorSettings[channel].channelMin) { + m_actuatorSettings[channel].channelMin = value; + } + if(value > m_actuatorSettings[channel].channelMax) { + m_actuatorSettings[channel].channelMax = value; + } + debugLogChannelValues(); + } +} + +void OutputCalibrationPage::on_servoMinAngleButton_toggled(bool checked) +{ + ui->servoMinAngleButton->setText(checked ? tr("Stop") : tr("Start")); + quint16 channel = getCurrentChannel(); + quint16 safeValue = m_actuatorSettings[channel].channelNeutral; + onStartButtonToggle(ui->servoMinAngleButton, channel, m_actuatorSettings[channel].channelMin, safeValue, ui->servoMinAngleSlider); +} + +void OutputCalibrationPage::on_servoMinAngleSlider_valueChanged(int position) +{ + if(ui->servoMinAngleButton->isChecked()) { + quint16 value = ui->servoMinAngleSlider->value(); + m_calibrationUtil->setChannelOutputValue(value); + m_actuatorSettings[getCurrentChannel()].channelMin = value; + debugLogChannelValues(); + } +} + +void OutputCalibrationPage::on_servoMaxAngleButton_toggled(bool checked) +{ + ui->servoMaxAngleButton->setText(checked ? tr("Stop") : tr("Start")); + quint16 channel = getCurrentChannel(); + quint16 safeValue = m_actuatorSettings[channel].channelNeutral; + onStartButtonToggle(ui->servoMaxAngleButton, channel, m_actuatorSettings[channel].channelMax, safeValue, ui->servoMaxAngleSlider); +} + +void OutputCalibrationPage::on_servoMaxAngleSlider_valueChanged(int position) +{ + if(ui->servoMaxAngleButton->isChecked()) { + quint16 value = ui->servoMaxAngleSlider->value(); + m_calibrationUtil->setChannelOutputValue(value); + m_actuatorSettings[getCurrentChannel()].channelMax = value; + debugLogChannelValues(); + } +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.h new file mode 100644 index 000000000..1a3302e53 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.h @@ -0,0 +1,104 @@ +/** + ****************************************************************************** + * + * @file outputcalibrationpage.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup OutputCalibrationPage + * @{ + * @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 OUTPUTCALIBRATIONPAGE_H +#define OUTPUTCALIBRATIONPAGE_H + +#include +#include "abstractwizardpage.h" +#include "setupwizard.h" +#include "outputcalibrationutil.h" +#include "vehicleconfigurationhelper.h" + +namespace Ui { +class OutputCalibrationPage; +} + +class OutputCalibrationPage : public AbstractWizardPage +{ + Q_OBJECT + +public: + explicit OutputCalibrationPage(SetupWizard *wizard, QWidget *parent = 0); + ~OutputCalibrationPage(); + void initializePage(); + bool validatePage(); + + bool isFinished() { return m_currentWizardIndex >= m_wizardIndexes.size() - 1; } + +protected: + void showEvent(QShowEvent *event); + void resizeEvent(QResizeEvent *event); + +public slots: + void customBackClicked(); + +private slots: + void on_motorNeutralButton_toggled(bool checked); + void on_motorNeutralSlider_valueChanged(int value); + + void on_servoCenterButton_toggled(bool checked); + void on_servoCenterSlider_valueChanged(int position); + + void on_servoMinAngleButton_toggled(bool checked); + void on_servoMinAngleSlider_valueChanged(int position); + + void on_servoMaxAngleButton_toggled(bool checked); + void on_servoMaxAngleSlider_valueChanged(int position); + +private: + void setupVehicle(); + void startWizard(); + void setupVehicleItems(); + void setupVehicleHighlightedPart(); + void setWizardPage(); + void enableButtons(bool enable); + void onStartButtonToggle(QAbstractButton *button, quint16 channel, quint16 value, quint16 safeValue, QSlider *slider); + bool checkAlarms(); + void debugLogChannelValues(); + quint16 getCurrentChannel(); + + Ui::OutputCalibrationPage *ui; + QSvgRenderer *m_vehicleRenderer; + QGraphicsScene *m_vehicleScene; + QGraphicsSvgItem *m_vehicleBoundsItem; + + qint16 m_currentWizardIndex; + + QList m_vehicleElementIds; + QList m_vehicleItems; + QList m_vehicleHighlightElementIndexes; + QList m_channelIndex; + QList m_wizardIndexes; + + QList m_actuatorSettings; + + OutputCalibrationUtil *m_calibrationUtil; + +}; + +#endif // OUTPUTCALIBRATIONPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.ui new file mode 100644 index 000000000..6699ad531 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.ui @@ -0,0 +1,425 @@ + + + OutputCalibrationPage + + + + 0 + 0 + 600 + 400 + + + + WizardPage + + + + + + + 12 + 75 + true + + + + Output calibration + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + + + + 1 + + + + + + + <!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:'MS Shell Dlg 2'; font-size:8pt; font-weight:400; font-style:normal;"> +<p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:10pt;">It is now time to calibrate the output levels for the signals controlling your vehicle. </span></p> +<p align="center" style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:10pt; font-weight:600; color:#ff0000;">VERY IMPORTANT!</span><span style=" font-family:'Lucida Grande'; font-size:10pt;"><br /></span><span style=" font-family:'Lucida Grande'; font-size:10pt; font-weight:600; color:#ff0000;">REMOVE ALL PROPELLERS FROM THE VEHICLE BEFORE PROCEEDING!</span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:10pt;">Connect all components according to the illustration on the summary page, and provide power using an external power supply such as a battery before continuing.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Lucida Grande'; font-size:10pt;"><br /></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:10pt;">Depending on what vehicle you have selected, both the motors controlled by ESCs and/or servos controlled directly by the OpenPilot controller may have to be calibrated. The following steps will guide you safely through this process. </span></p></body></html> + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + + + + + + + + + + <html><head/><body><p>In this step we will set the neutral rate for the motor highlighted in the illustration to the right. <br/>Plase pay attention to the details and in particular the motors position and its rotation direction.</p><p>To find the neutral rate for this engine, press the Start button below and slide the slider to the right until the engine just starts to spin stably. <br/><br/>When done press button again to stop.</p></body></html> + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + + + + + + false + + + 1000 + + + 1300 + + + 10 + + + 20 + + + Qt::Horizontal + + + false + + + QSlider::TicksBelow + + + 20 + + + + + + + Start + + + true + + + false + + + + + + + + + + + <html><head/><body><p>This step calibrates the center position of the servo. To set the center position for this servo, press the Start button below and slide the slider to center the servo. </p><p>When done press button again to stop.</p></body></html> + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + + + + + + false + + + 1000 + + + 2000 + + + 10 + + + 20 + + + 1500 + + + true + + + Qt::Horizontal + + + false + + + false + + + QSlider::TicksBelow + + + 40 + + + + + + + Start + + + true + + + false + + + + + + + + + + + <html><head/><body><p>To save the servo and other hardware from damage we have to set the max and min angles for the servo. </p><p>To set the minimum angle for the servo, press the Start button below and select the top slider and slide it to the left until min angle is reached.</p><p>When done press button again to stop.</p></body></html> + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + + + + + + false + + + 1000 + + + 1500 + + + 10 + + + 20 + + + 1500 + + + true + + + Qt::Horizontal + + + false + + + false + + + QSlider::TicksBelow + + + 40 + + + + + + + Start + + + true + + + false + + + + + + + + + + + <html><head/><body><p>To set the maximum angle for the servo, press the Start button below and select the top slider and slide it to the right until max angle is reached.</p><p>When done press button again to stop.</p></body></html> + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + + + + + + false + + + 1500 + + + 2000 + + + 10 + + + 20 + + + 1500 + + + true + + + Qt::Horizontal + + + false + + + false + + + QSlider::TicksBelow + + + 40 + + + + + + + Start + + + true + + + false + + + + + + + + + + + + 0 + 0 + + + + + 200 + 200 + + + + QFrame::NoFrame + + + + + + + + + motorNeutralButton + toggled(bool) + motorNeutralSlider + setEnabled(bool) + + + 147 + 291 + + + 150 + 249 + + + + + servoMinAngleButton + toggled(bool) + servoMinAngleSlider + setEnabled(bool) + + + 147 + 291 + + + 150 + 249 + + + + + servoMaxAngleButton + toggled(bool) + servoMaxAngleSlider + setEnabled(bool) + + + 147 + 291 + + + 150 + 249 + + + + + servoCenterButton + toggled(bool) + servoCenterSlider + setEnabled(bool) + + + 147 + 291 + + + 150 + 249 + + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpage.cpp new file mode 100644 index 000000000..d9903af57 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpage.cpp @@ -0,0 +1,55 @@ +/** + ****************************************************************************** + * + * @file outputpage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup OutputPage + * @{ + * @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 + */ + +#include "outputpage.h" +#include "ui_outputpage.h" +#include "setupwizard.h" + +OutputPage::OutputPage(SetupWizard *wizard, QWidget *parent) : + AbstractWizardPage(wizard, parent), + + ui(new Ui::OutputPage) +{ + ui->setupUi(this); +} + +OutputPage::~OutputPage() +{ + delete ui; +} + +bool OutputPage::validatePage() +{ + if(ui->rapidESCButton->isChecked()) { + getWizard()->setESCType(SetupWizard::ESC_RAPID); + } + else { + getWizard()->setESCType(SetupWizard::ESC_LEGACY); + } + + return true; +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpage.h new file mode 100644 index 000000000..3a7130238 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpage.h @@ -0,0 +1,50 @@ +/** + ****************************************************************************** + * + * @file outputpage.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup OutputPage + * @{ + * @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 OUTPUTPAGE_H +#define OUTPUTPAGE_H + +#include "abstractwizardpage.h" + +namespace Ui { +class OutputPage; +} + +class OutputPage : public AbstractWizardPage +{ + Q_OBJECT + +public: + explicit OutputPage(SetupWizard *wizard, QWidget *parent = 0); + ~OutputPage(); + bool validatePage(); + +private: + Ui::OutputPage *ui; +}; + +#endif // OUTPUTPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpage.ui new file mode 100644 index 000000000..9265d3845 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpage.ui @@ -0,0 +1,154 @@ + + + OutputPage + + + + 0 + 0 + 600 + 400 + + + + WizardPage + + + + + + <!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:'Lucida Grande'; font-size:13pt; 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-family:'MS Shell Dlg 2'; font-size:12pt; font-weight:600;">OpenPilot basic output signal configuration</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'MS Shell Dlg 2'; font-size:12pt; font-weight:600;"></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'MS Shell Dlg 2'; font-size:10pt;">To set an optimal configuration of the output signals powering your motors, the wizard needs to know what type of Electronic Speed Controllers (ESCs) you will use and what their capabilities are.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'MS Shell Dlg 2'; font-size:10pt;"></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'MS Shell Dlg 2'; font-size:10pt;">Please select one of the options below. If you are unsure about the capabilities of your ESCs, just leave the default option selected and continue the wizard.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'MS Shell Dlg 2'; font-size:10pt;"></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'MS Shell Dlg 2'; font-size:10pt;">To read more regarding ESC refresh rates, please see </span><a href="http://wiki.openpilot.org/x/HIEu"><span style=" text-decoration: underline; color:#0000ff;">this article</span></a><span style=" font-family:'MS Shell Dlg 2'; font-size:10pt;"> in the OpenPilot Wiki</span></p></body></html> + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + + true + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + + 10 + + + + Standard ESC 50Hz + + + QToolButton { border: none } + + + Standard ESC + + + + :/setupwizard/resources/bttn-ESC-up.png + :/setupwizard/resources/bttn-ESC-down.png:/setupwizard/resources/bttn-ESC-up.png + + + + 200 + 100 + + + + true + + + false + + + true + + + Qt::ToolButtonTextUnderIcon + + + true + + + + + + + + 10 + + + + Turbo PWM ESC 400Hz + + + QToolButton { border: none } + + + Turbo PWM + + + + :/setupwizard/resources/bttn-turbo-up.png + :/setupwizard/resources/bttn-turbo-down.png:/setupwizard/resources/bttn-turbo-up.png + + + + 200 + 100 + + + + true + + + true + + + true + + + Qt::ToolButtonTextUnderIcon + + + true + + + + + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2plugin.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/rebootpage.cpp similarity index 51% rename from ground/openpilotgcs/src/plugins/hitlv2/hitlv2plugin.cpp rename to ground/openpilotgcs/src/plugins/setupwizard/pages/rebootpage.cpp index c63ba5c86..43153380b 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2plugin.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/rebootpage.cpp @@ -1,13 +1,13 @@ /** ****************************************************************************** * - * @file hitlv2plugin.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. - * @addtogroup GCSPlugins GCS Plugins + * @file rebootpage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup * @{ - * @addtogroup HITLPlugin HITLv2 Plugin + * @addtogroup RebootPage * @{ - * @brief The Hardware In The Loop plugin version 2 + * @brief *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify @@ -25,47 +25,43 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#include "hitlv2plugin.h" -#include "hitlv2factory.h" -#include -#include -#include +#include "rebootpage.h" +#include "ui_rebootpage.h" -#include "aerosimrc.h" - -QList HITLPlugin::typeSimulators; - -HITLPlugin::HITLPlugin() +RebootPage::RebootPage(SetupWizard *wizard, QWidget *parent) : + AbstractWizardPage(wizard, parent), + ui(new Ui::RebootPage), m_toggl(false) { - // Do nothing + ui->setupUi(this); + ui->yellowLabel->setVisible(false); + ui->redLabel->setVisible(true); } -HITLPlugin::~HITLPlugin() +RebootPage::~RebootPage() { - // Do nothing + disconnect(&m_timer, SIGNAL(timeout()), this, SLOT(toggleLabel())); + m_timer.stop(); + delete ui; } -bool HITLPlugin::initialize(const QStringList& args, QString *errMsg) +void RebootPage::initializePage() { - Q_UNUSED(args); - Q_UNUSED(errMsg); - mf = new HITLFactory(this); - - addAutoReleasedObject(mf); - - addSimulator(new AeroSimRCSimulatorCreator("ASimRC", "AeroSimRC")); + if(!m_timer.isActive()) { + connect(&m_timer, SIGNAL(timeout()), this, SLOT(toggleLabel())); + m_timer.setInterval(500); + m_timer.setSingleShot(false); + m_timer.start(); + } +} +bool RebootPage::validatePage() +{ return true; } -void HITLPlugin::extensionsInitialized() +void RebootPage::toggleLabel() { - // Do nothing + m_toggl = !m_toggl; + ui->yellowLabel->setVisible(m_toggl); + ui->redLabel->setVisible(!m_toggl); } - -void HITLPlugin::shutdown() -{ - // Do nothing -} -Q_EXPORT_PLUGIN(HITLPlugin) - diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/rebootpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/rebootpage.h new file mode 100644 index 000000000..c3d32fca2 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/rebootpage.h @@ -0,0 +1,57 @@ +/** + ****************************************************************************** + * + * @file rebootpage.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup RebootPage + * @{ + * @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 REBOOTPAGE_H +#define REBOOTPAGE_H + +#include "abstractwizardpage.h" + +namespace Ui { +class RebootPage; +} + +class RebootPage : public AbstractWizardPage +{ + Q_OBJECT + +public: + explicit RebootPage(SetupWizard *wizard, QWidget *parent = 0); + ~RebootPage(); + + void initializePage(); + bool validatePage(); + +private: + Ui::RebootPage *ui; + QTimer m_timer; + bool m_toggl; + +private slots: + void toggleLabel(); +}; + +#endif // REBOOTPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/rebootpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/rebootpage.ui new file mode 100644 index 000000000..5a833dd3e --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/rebootpage.ui @@ -0,0 +1,76 @@ + + + RebootPage + + + + 0 + 0 + 600 + 400 + + + + WizardPage + + + + + + <!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:'MS Shell Dlg 2'; font-size:8pt; font-weight:400; font-style:normal;"> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:18pt; color:#ff0000;">PLEASE REBOOT YOUR CONTROLLER</span></p></body></html> + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + 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:'MS Shell Dlg 2'; font-size:8pt; font-weight:400; font-style:normal;"> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:18pt; color:#ffd500;">PLEASE REBOOT YOUR CONTROLLER</span></p></body></html> + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + 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:'MS Shell Dlg 2'; font-size:8pt; font-weight:400; font-style:normal;"> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt; color:#000000;">The configuration created by the wizard contains settings that require a reboot of your controller. Please power cycle the controller before continuing. To power cycle the controller remove all batteries and the USB cable for at least 30 seconds.</span></p> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt; color:#000000;">After 30 seconds, plug in the board again and wait for it to connect, this can take a few seconds. Then press next.</span></p></body></html> + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + + + + yellowLabel + redLabel + label_3 + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/savepage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/savepage.cpp new file mode 100644 index 000000000..f3e03e0fb --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/savepage.cpp @@ -0,0 +1,103 @@ +/** + ****************************************************************************** + * + * @file savepage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup SavePage + * @{ + * @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 + */ + +#include +#include "savepage.h" +#include "ui_savepage.h" +#include "setupwizard.h" +#include "vehicleconfigurationhelper.h" + +SavePage::SavePage(SetupWizard *wizard, QWidget *parent) : + AbstractWizardPage(wizard, parent), + ui(new Ui::SavePage), m_successfulWrite(false) +{ + ui->setupUi(this); + connect(ui->saveButton, SIGNAL(clicked()), this, SLOT(writeToController())); +} + +SavePage::~SavePage() +{ + delete ui; +} + +bool SavePage::validatePage() +{ + return true; +} + +bool SavePage::isComplete() const +{ + return m_successfulWrite; +} + +void SavePage::writeToController() +{ + if(!getWizard()->getConnectionManager()->isConnected()) { + QMessageBox msgBox; + msgBox.setText(tr("An OpenPilot controller must be connected to your computer to save the " + "configuration.\nPlease connect your OpenPilot controller to your computer and try again.")); + msgBox.setStandardButtons(QMessageBox::Ok); + msgBox.setDefaultButton(QMessageBox::Ok); + msgBox.exec(); + return; + } + + enableButtons(false); + VehicleConfigurationHelper helper(getWizard()); + connect(&helper, SIGNAL(saveProgress(int, int, QString)),this, SLOT(saveProgress(int, int, QString))); + + m_successfulWrite = helper.setupVehicle(); + + disconnect(&helper, SIGNAL(saveProgress(int, int, QString)),this, SLOT(saveProgress(int, int, QString))); + ui->saveProgressLabel->setText(QString("%2").arg(m_successfulWrite ? "green" : "red", ui->saveProgressLabel->text())); + enableButtons(true); + + emit completeChanged(); +} + +void SavePage::enableButtons(bool enable) +{ + ui->saveButton->setEnabled(enable); + getWizard()->button(QWizard::NextButton)->setEnabled(enable); + getWizard()->button(QWizard::CancelButton)->setEnabled(enable); + getWizard()->button(QWizard::BackButton)->setEnabled(enable); + QApplication::processEvents(); +} + +void SavePage::saveProgress(int total, int current, QString description) +{ + qDebug() << "Progress " << current << "(" << total << ")"; + if(ui->saveProgressBar->maximum() != total) { + ui->saveProgressBar->setMaximum(total); + } + if(ui->saveProgressBar->value() != current) { + ui->saveProgressBar->setValue(current); + } + if(ui->saveProgressLabel->text() != description) { + ui->saveProgressLabel->setText(description); + } +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/savepage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/savepage.h new file mode 100644 index 000000000..d8382df93 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/savepage.h @@ -0,0 +1,57 @@ +/** + ****************************************************************************** + * + * @file savepage.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup SavePage + * @{ + * @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 SAVEPAGE_H +#define SAVEPAGE_H + +#include "abstractwizardpage.h" + +namespace Ui { +class SavePage; +} + +class SavePage : public AbstractWizardPage +{ + Q_OBJECT + +public: + explicit SavePage(SetupWizard *wizard, QWidget *parent = 0); + ~SavePage(); + bool validatePage(); + bool isComplete() const; + +private: + Ui::SavePage *ui; + bool m_successfulWrite; + void enableButtons(bool enable); + +private slots: + void writeToController(); + void saveProgress(int total, int current, QString description); +}; + +#endif // SAVEPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/savepage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/savepage.ui new file mode 100644 index 000000000..a17a254db --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/savepage.ui @@ -0,0 +1,127 @@ + + + SavePage + + + + 0 + 0 + 600 + 400 + + + + WizardPage + + + + + + <!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:'MS Shell Dlg 2'; 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;"><span style=" font-size:12pt; font-weight:600;">OpenPilot configuration ready to save</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:12pt; font-weight:600;"><br /></p> +<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:10pt;">The wizard is now ready to save the configuration directly to your OpenPilot controller. </span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;"><br /></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;"><br /></p> +<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:10pt;">If any of the selections made in this wizard require a reboot of the controller, then power cycling the OpenPilot controller board will have to be performed after you save in this step.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;"><br /></p> +<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:10pt;">Press the Save button to save the configuration.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;"><br /></p> +<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:10pt;"><br /></span></p></body></html> + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + Write configuration to controller + + + QToolButton { border: none } + + + Save + + + + :/setupwizard/resources/bttn-save-up.png + :/setupwizard/resources/bttn-save-down.png:/setupwizard/resources/bttn-save-up.png + + + + 200 + 70 + + + + Qt::ToolButtonIconOnly + + + + + + + + + + 10 + + + + Ready... + + + + + + + QProgressBar { + border: 2px solid grey; + border-radius: 5px; + text-align: center; + } +QProgressBar::chunk { + background-color: #3D6699; + width: 10px; + margin: 0.5px; + } + + + 0 + + + + + + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2gadget.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.cpp similarity index 57% rename from ground/openpilotgcs/src/plugins/hitlv2/hitlv2gadget.cpp rename to ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.cpp index b114cbde5..bc0ee36f1 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2gadget.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.cpp @@ -1,13 +1,13 @@ /** ****************************************************************************** * - * @file hitlv2gadget.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. + * @file startpage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ - * @addtogroup HITLPlugin HITLv2 Plugin + * @addtogroup Setup Wizard Plugin * @{ - * @brief The Hardware In The Loop plugin version 2 + * @brief A Wizard to make the initial setup easy for everyone. *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify @@ -24,27 +24,18 @@ * with this program; if not, write to the Free Software Foundation, Inc., * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ +#include "startpage.h" +#include "ui_startpage.h" -#include "hitlv2gadget.h" -#include "hitlv2widget.h" -#include "hitlv2configuration.h" -#include "simulatorv2.h" - -HITLGadget::HITLGadget(QString classId, HITLWidget *widget, QWidget *parent) : - IUAVGadget(classId, parent), - m_widget(widget) +StartPage::StartPage(SetupWizard *wizard, QWidget *parent) : + AbstractWizardPage(wizard, parent), + ui(new Ui::StartPage) { - connect(this, SIGNAL(changeConfiguration(void)), m_widget, SLOT(stopButtonClicked(void))); + ui->setupUi(this); + setFont(QFont("Ubuntu",2)); } -HITLGadget::~HITLGadget() +StartPage::~StartPage() { - delete m_widget; -} - -void HITLGadget::loadConfiguration(IUAVGadgetConfiguration* config) -{ - HITLConfiguration *m = qobject_cast(config); - emit changeConfiguration(); - m_widget->setSettingParameters(m->Settings()); + delete ui; } diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2factory.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.h similarity index 61% rename from ground/openpilotgcs/src/plugins/hitlv2/hitlv2factory.h rename to ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.h index cfa91750d..3e9e120cc 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2factory.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.h @@ -1,13 +1,13 @@ /** ****************************************************************************** * - * @file hitlv2factory.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. + * @file startpage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ - * @addtogroup HITLPlugin HITLv2 Plugin + * @addtogroup Setup Wizard Plugin * @{ - * @brief The Hardware In The Loop plugin version 2 + * @brief A Wizard to make the initial setup easy for everyone. *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify @@ -24,29 +24,25 @@ * with this program; if not, write to the Free Software Foundation, Inc., * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ +#ifndef STARTPAGE_H +#define STARTPAGE_H -#ifndef HITLV2FACTORY_H -#define HITLV2FACTORY_H +#include "abstractwizardpage.h" -#include - -namespace Core { -class IUAVGadget; -class IUAVGadgetFactory; +namespace Ui { +class StartPage; } -using namespace Core; - -class HITLFactory : public Core::IUAVGadgetFactory +class StartPage : public AbstractWizardPage { Q_OBJECT + public: - HITLFactory(QObject *parent = 0); - ~HITLFactory(); - - IUAVGadget *createGadget(QWidget *parent); - IUAVGadgetConfiguration *createConfiguration(QSettings* qSettings); - IOptionsPage *createOptionsPage(IUAVGadgetConfiguration *config); + explicit StartPage(SetupWizard *wizard, QWidget *parent = 0); + ~StartPage(); + +private: + Ui::StartPage *ui; }; -#endif // HITLV2FACTORY_H +#endif // STARTPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.ui new file mode 100644 index 000000000..e219d7513 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.ui @@ -0,0 +1,67 @@ + + + StartPage + + + + 0 + 0 + 600 + 400 + + + + + 0 + 0 + + + + + 400 + 400 + + + + WizardPage + + + + + + + 0 + 0 + + + + <!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:'MS Shell Dlg 2'; 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;"><span style=" font-size:12pt; font-weight:600;">Welcome to the OpenPilot Setup Wizard</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><br /></p> +<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:10pt;">This wizard will guide you through the basic steps required to setup your OpenPilot controller for the first time. You will be asked questions about your platform (multirotor/heli/fixed-wing) which this wizard will use to configure your aircraft for your maiden flight. </span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;"><br /></p> +<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:10pt;">This wizard does not configure all of the advanced settings available in the GCS Configuration. All basic and advanced configuration parameters can be modified later by using the GCS Configuration plugin.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;"><br /></p> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600; color:#ff0000;">WARNING: YOU MUST REMOVE ALL PROPELLERS </span></p> +<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600; color:#ff0000;">FROM THE VEHICLE BEFORE PROCEEDING!</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Lucida Grande'; font-size:13pt;"><br /></p> +<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:10pt;">Disregarding this warning puts you at</span><span style=" font-size:10pt; font-weight:600; color:#000000;"> risk of very serious injury</span><span style=" font-size:10pt;">!</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;"><br /></p> +<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:10pt;">Now that your props are removed we can get started. Ready?</span></p></body></html> + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/summarypage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/summarypage.cpp new file mode 100644 index 000000000..c4846e782 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/summarypage.cpp @@ -0,0 +1,60 @@ +/** + ****************************************************************************** + * + * @file summarypage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup SummaryPage + * @{ + * @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 + */ + +#include "summarypage.h" +#include "ui_summarypage.h" +#include "setupwizard.h" +#include "connectiondiagram.h" + +SummaryPage::SummaryPage(SetupWizard *wizard, QWidget *parent) : + AbstractWizardPage(wizard, parent), + ui(new Ui::SummaryPage) +{ + ui->setupUi(this); + connect(ui->illustrationButton, SIGNAL(clicked()), this, SLOT(showDiagram())); +} + +SummaryPage::~SummaryPage() +{ + delete ui; +} + +bool SummaryPage::validatePage() +{ + return true; +} + +void SummaryPage::initializePage() +{ + ui->configurationSummary->setText(getWizard()->getSummaryText()); +} + +void SummaryPage::showDiagram() +{ + ConnectionDiagram diagram(this, getWizard()); + diagram.exec(); +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/summarypage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/summarypage.h new file mode 100644 index 000000000..616f82392 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/summarypage.h @@ -0,0 +1,54 @@ +/** + ****************************************************************************** + * + * @file summarypage.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup SummaryPage + * @{ + * @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 SUMMARYPAGE_H +#define SUMMARYPAGE_H + +#include "abstractwizardpage.h" + +namespace Ui { +class SummaryPage; +} + +class SummaryPage : public AbstractWizardPage +{ + Q_OBJECT + +public: + explicit SummaryPage(SetupWizard *wizard, QWidget *parent = 0); + ~SummaryPage(); + bool validatePage(); + void initializePage(); + +private: + Ui::SummaryPage *ui; + +private slots: + void showDiagram(); +}; + +#endif // SUMMARYPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/summarypage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/summarypage.ui new file mode 100644 index 000000000..659d46c2b --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/summarypage.ui @@ -0,0 +1,108 @@ + + + SummaryPage + + + + 0 + 0 + 600 + 400 + + + + WizardPage + + + + + + <!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:'MS Shell Dlg 2'; 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;"><span style=" font-size:12pt; font-weight:600;">OpenPilot configuration summary</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:12pt; font-weight:600;"><br /></p> +<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:10pt;">The first part of this wizard is now complete. All information required to create a basic OpenPilot controller configuration for a specific vehicle has been collected.</span></p> +<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:10pt;">Below is a summary of the configuration and a button that links to a diagram illustrating how to connect required hardware and the OpenPilot Controller with the current configuration.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;"><br /></p> +<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:10pt;">To continue the wizard and go through some basic configuration steps, please continue to the next step of this wizard.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;"><br /></p> +<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:10pt;">The following steps require that your OpenPilot controller is set up according to the diagram, it is </span><span style=" font-size:10pt; font-weight:600;">connected to the computer</span><span style=" font-size:10pt;"> by USB, and that the vehicle is</span><span style=" font-size:10pt; font-weight:600;"> powered by a battery</span><span style=" font-size:10pt;">.</span></p></body></html> + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + + + + + + 4 + + + + + + 10 + + + + Qt::ScrollBarAlwaysOn + + + Qt::ScrollBarAlwaysOff + + + Qt::TextSelectableByKeyboard|Qt::TextSelectableByMouse + + + + + + + Show connection diagram for configuration + + + QToolButton { border: none } + + + + + + + :/setupwizard/resources/bttn-illustration-up.png + :/setupwizard/resources/bttn-illustration-down.png:/setupwizard/resources/bttn-illustration-up.png + + + + 100 + 100 + + + + false + + + false + + + true + + + Qt::ToolButtonIconOnly + + + + + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/surfacepage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/surfacepage.cpp new file mode 100644 index 000000000..a28724f2f --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/surfacepage.cpp @@ -0,0 +1,42 @@ +/** + ****************************************************************************** + * + * @file surfacepage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup SurfacePage + * @{ + * @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 + */ + +#include "surfacepage.h" +#include "ui_surfacepage.h" + +SurfacePage::SurfacePage(SetupWizard *wizard, QWidget *parent) : + AbstractWizardPage(wizard, parent), + ui(new Ui::SurfacePage) +{ + ui->setupUi(this); + setFinalPage(true); +} + +SurfacePage::~SurfacePage() +{ + delete ui; +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/surfacepage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/surfacepage.h new file mode 100644 index 000000000..593aa1fca --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/surfacepage.h @@ -0,0 +1,49 @@ +/** + ****************************************************************************** + * + * @file surfacepage.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup SurfacePage + * @{ + * @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 SURFACEPAGE_H +#define SURFACEPAGE_H + +#include "abstractwizardpage.h" + +namespace Ui { +class SurfacePage; +} + +class SurfacePage : public AbstractWizardPage +{ + Q_OBJECT + +public: + explicit SurfacePage(SetupWizard *wizard, QWidget *parent = 0); + ~SurfacePage(); + +private: + Ui::SurfacePage *ui; +}; + +#endif // SURFACEPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/surfacepage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/surfacepage.ui new file mode 100644 index 000000000..d592a4eaf --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/surfacepage.ui @@ -0,0 +1,43 @@ + + + SurfacePage + + + + 0 + 0 + 600 + 400 + + + + WizardPage + + + + + 50 + 160 + 500 + 41 + + + + <!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:'MS Shell Dlg 2'; font-size:8.25pt; 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:12pt; font-weight:600;">The Surface Vehicle section of the OpenPilot Setup Wizard is not yet implemented</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"></p></body></html> + + + Qt::AlignHCenter|Qt::AlignTop + + + true + + + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.cpp new file mode 100644 index 000000000..a616a1194 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.cpp @@ -0,0 +1,61 @@ +/** + ****************************************************************************** + * + * @file vehiclepage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup VehiclePage + * @{ + * @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 + */ + +#include "vehiclepage.h" +#include "ui_vehiclepage.h" + +VehiclePage::VehiclePage(SetupWizard *wizard, QWidget *parent) : + AbstractWizardPage(wizard, parent), + ui(new Ui::VehiclePage) +{ + ui->setupUi(this); +} + +VehiclePage::~VehiclePage() +{ + delete ui; +} + +bool VehiclePage::validatePage() +{ + if(ui->multirotorButton->isChecked()) { + getWizard()->setVehicleType(SetupWizard::VEHICLE_MULTI); + } + else if(ui->fixedwingButton->isChecked()) { + getWizard()->setVehicleType(SetupWizard::VEHICLE_FIXEDWING); + } + else if(ui->heliButton->isChecked()) { + getWizard()->setVehicleType(SetupWizard::VEHICLE_HELI); + } + else if(ui->surfaceButton->isChecked()) { + getWizard()->setVehicleType(SetupWizard::VEHICLE_SURFACE); + } + else { + getWizard()->setVehicleType(SetupWizard::VEHICLE_UNKNOWN); + } + return true; +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.h new file mode 100644 index 000000000..5e72a3d21 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.h @@ -0,0 +1,50 @@ +/** + ****************************************************************************** + * + * @file vehiclepage.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup VehiclePage + * @{ + * @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 VEHICLEPAGE_H +#define VEHICLEPAGE_H + +#include "abstractwizardpage.h" + +namespace Ui { +class VehiclePage; +} + +class VehiclePage : public AbstractWizardPage +{ + Q_OBJECT + +public: + explicit VehiclePage(SetupWizard *wizard, QWidget *parent = 0); + ~VehiclePage(); + bool validatePage(); + +private: + Ui::VehiclePage *ui; +}; + +#endif // VEHICLEPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.ui new file mode 100644 index 000000000..a6e0e9354 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.ui @@ -0,0 +1,245 @@ + + + VehiclePage + + + + 0 + 0 + 600 + 400 + + + + WizardPage + + + + + + <!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:'MS Shell Dlg 2'; 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;"><span style=" font-size:12pt; font-weight:600;">Vehicle type selection</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:12pt; font-weight:600;"><br /></p> +<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:10pt;">To continue, the wizard needs to know what type of vehicle the OpenPilot controller board is going to be used with. This step is crucial since much of the following configuration is unique per vehicle type.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><br /></p> +<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:10pt;">Go ahead and select the type of vehicle for which you want to create a configuration.</span></p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;"><br /></p> +<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:10pt;">(The current version only provides functionality for multirotors.)</span></p></body></html> + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + + 10 + + + + Tricopter, Quadcopter, Hexacopter + + + false + + + QToolButton { border: none } + + + Multirotor + + + + :/setupwizard/resources/bttn-multi-up.png + :/setupwizard/resources/bttn-multi-down.png:/setupwizard/resources/bttn-multi-up.png + + + + 100 + 100 + + + + true + + + true + + + true + + + Qt::ToolButtonTextUnderIcon + + + true + + + + + + + false + + + + 10 + + + + CCPM Helicopters + + + QToolButton { border: none } + + + Helicopter + + + + :/setupwizard/resources/bttn-heli-up.png + :/setupwizard/resources/bttn-heli-down.png:/setupwizard/resources/bttn-heli-up.png + + + + 100 + 100 + + + + true + + + true + + + Qt::ToolButtonTextUnderIcon + + + true + + + + + + + false + + + + 10 + + + + Airplane, Sloper, Jet + + + QToolButton { border: none } + + + Fixed wing + + + + :/setupwizard/resources/bttn-plane-up.png + :/setupwizard/resources/bttn-plane-down.png:/setupwizard/resources/bttn-plane-up.png + + + + 100 + 100 + + + + true + + + false + + + true + + + Qt::ToolButtonTextUnderIcon + + + true + + + + + + + false + + + + 10 + + + + Car, Boat, U-Boat + + + QToolButton { border: none } + + + Surface + + + + :/setupwizard/resources/bttn-land-up.png + :/setupwizard/resources/bttn-land-down.png:/setupwizard/resources/bttn-land-up.png + + + + 100 + 100 + + + + true + + + true + + + Qt::ToolButtonTextUnderIcon + + + true + + + + + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-ESC-down.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-ESC-down.png new file mode 100644 index 000000000..26899fb5a Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-ESC-down.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-ESC-up.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-ESC-up.png new file mode 100644 index 000000000..07016ddc1 Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-ESC-up.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-calculate-down.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-calculate-down.png new file mode 100644 index 000000000..5681d474e Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-calculate-down.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-calculate-up.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-calculate-up.png new file mode 100644 index 000000000..c2e2add72 Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-calculate-up.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-flash-down.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-flash-down.png new file mode 100644 index 000000000..601c9e349 Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-flash-down.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-flash-up.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-flash-up.png new file mode 100644 index 000000000..ca01e42e7 Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-flash-up.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-heli-down.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-heli-down.png new file mode 100644 index 000000000..0d75a7ba8 Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-heli-down.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-heli-over.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-heli-over.png new file mode 100644 index 000000000..d979da128 Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-heli-over.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-heli-up.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-heli-up.png new file mode 100644 index 000000000..49236a2b6 Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-heli-up.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-illustration-down.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-illustration-down.png new file mode 100644 index 000000000..a4402d5b0 Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-illustration-down.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-illustration-up.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-illustration-up.png new file mode 100644 index 000000000..5013d30b2 Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-illustration-up.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-land-down.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-land-down.png new file mode 100644 index 000000000..ed2c66934 Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-land-down.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-land-over.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-land-over.png new file mode 100644 index 000000000..8d6336bc4 Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-land-over.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-land-up.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-land-up.png new file mode 100644 index 000000000..7d90f4a2d Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-land-up.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-multi-down.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-multi-down.png new file mode 100644 index 000000000..7da5b4fdc Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-multi-down.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-multi-over.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-multi-over.png new file mode 100644 index 000000000..82a017767 Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-multi-over.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-multi-up.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-multi-up.png new file mode 100644 index 000000000..882d6edfa Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-multi-up.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-plane-down.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-plane-down.png new file mode 100644 index 000000000..42bfddd28 Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-plane-down.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-plane-over.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-plane-over.png new file mode 100644 index 000000000..d99efed99 Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-plane-over.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-plane-up.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-plane-up.png new file mode 100644 index 000000000..4ccb6567d Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-plane-up.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-ppm-down.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-ppm-down.png new file mode 100644 index 000000000..03706d360 Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-ppm-down.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-ppm-up.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-ppm-up.png new file mode 100644 index 000000000..f58e5596b Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-ppm-up.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-pwm-down.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-pwm-down.png new file mode 100644 index 000000000..72656896a Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-pwm-down.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-pwm-up.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-pwm-up.png new file mode 100644 index 000000000..25d3624dd Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-pwm-up.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-sat-down.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-sat-down.png new file mode 100644 index 000000000..05bc35895 Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-sat-down.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-sat-up.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-sat-up.png new file mode 100644 index 000000000..37e16c2cb Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-sat-up.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-save-down.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-save-down.png new file mode 100644 index 000000000..13b6e3fa5 Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-save-down.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-save-up.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-save-up.png new file mode 100644 index 000000000..9e6655d0c Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-save-up.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-sbus-down.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-sbus-down.png new file mode 100644 index 000000000..ffea88361 Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-sbus-down.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-sbus-up.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-sbus-up.png new file mode 100644 index 000000000..9937ac0b4 Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-sbus-up.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-turbo-down.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-turbo-down.png new file mode 100644 index 000000000..2a6f0a8db Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-turbo-down.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-turbo-up.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-turbo-up.png new file mode 100644 index 000000000..7a8013432 Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-turbo-up.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-txwizard-off.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-txwizard-off.png new file mode 100644 index 000000000..bb0aab304 Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-txwizard-off.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-txwizard-on.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-txwizard-on.png new file mode 100644 index 000000000..98eecd4ef Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-txwizard-on.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-upgrade-down.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-upgrade-down.png new file mode 100644 index 000000000..603bac917 Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-upgrade-down.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-upgrade-up.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-upgrade-up.png new file mode 100644 index 000000000..c3177508b Binary files /dev/null and b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-upgrade-up.png differ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg b/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg new file mode 100644 index 000000000..1f2219f3f --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg @@ -0,0 +1,8011 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + image/svg+xml + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Spectrum + Satellite + + + + + + + + + + + + Futaba + S-Bus + + + + + + + + + + + + PPM Signal + + + + + + + + + + + + + + + + + Throttle + Roll + Pitch + Yaw + Flight Mode + + + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/multirotor-shapes.svg b/ground/openpilotgcs/src/plugins/setupwizard/resources/multirotor-shapes.svg new file mode 100644 index 000000000..a3077cbfd --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/resources/multirotor-shapes.svg @@ -0,0 +1,7219 @@ + + + +image/svg+xml \ No newline at end of file diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp new file mode 100644 index 000000000..c0061d83d --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -0,0 +1,325 @@ +/** + ****************************************************************************** + * + * @file setupwizard.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup Setup Wizard Plugin + * @{ + * @brief A Wizard to make the initial setup easy for everyone. + *****************************************************************************/ +/* + * 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 "setupwizard.h" +#include "pages/startpage.h" +#include "pages/endpage.h" +#include "pages/controllerpage.h" +#include "pages/vehiclepage.h" +#include "pages/multipage.h" +#include "pages/fixedwingpage.h" +#include "pages/helipage.h" +#include "pages/surfacepage.h" +#include "pages/inputpage.h" +#include "pages/outputpage.h" +#include "pages/levellingpage.h" +#include "pages/summarypage.h" +#include "pages/savepage.h" +#include "pages/notyetimplementedpage.h" +#include "pages/rebootpage.h" +#include "pages/outputcalibrationpage.h" +#include "extensionsystem/pluginmanager.h" +#include "vehicleconfigurationhelper.h" +#include "actuatorsettings.h" +#include "pages/autoupdatepage.h" +#include "uploader/uploadergadgetfactory.h" + +SetupWizard::SetupWizard(QWidget *parent) : QWizard(parent), VehicleConfigurationSource(), + m_controllerType(CONTROLLER_UNKNOWN), + m_vehicleType(VEHICLE_UNKNOWN), m_inputType(INPUT_UNKNOWN), m_escType(ESC_UNKNOWN), + m_levellingPerformed(false), m_restartNeeded(false), m_connectionManager(0) +{ + setWindowTitle(tr("OpenPilot Setup Wizard")); + setOption(QWizard::IndependentPages, false); + for(quint16 i = 0; i < ActuatorSettings::CHANNELMAX_NUMELEM; i++) + { + m_actuatorSettings << actuatorChannelSettings(); + } + setWizardStyle(QWizard::ModernStyle); + setMinimumSize(600, 450); + resize(600, 450); + createPages(); +} + +int SetupWizard::nextId() const +{ + switch (currentId()) { + case PAGE_START: + if(canAutoUpdate()) { + return PAGE_UPDATE; + } else { + return PAGE_CONTROLLER; + } + case PAGE_UPDATE: + return PAGE_CONTROLLER; + case PAGE_CONTROLLER: { + switch(getControllerType()) + { + case CONTROLLER_CC: + case CONTROLLER_CC3D: + return PAGE_INPUT; + case CONTROLLER_REVO: + case CONTROLLER_PIPX: + default: + return PAGE_NOTYETIMPLEMENTED; + } + } + case PAGE_VEHICLES: { + switch(getVehicleType()) + { + case VEHICLE_MULTI: + return PAGE_MULTI; + case VEHICLE_FIXEDWING: + return PAGE_FIXEDWING; + case VEHICLE_HELI: + return PAGE_HELI; + case VEHICLE_SURFACE: + return PAGE_SURFACE; + default: + return PAGE_NOTYETIMPLEMENTED; + } + } + case PAGE_MULTI: + return PAGE_OUTPUT; + case PAGE_INPUT: + if(isRestartNeeded()) { + saveHardwareSettings(); + return PAGE_REBOOT; + } + else { + return PAGE_VEHICLES; + } + case PAGE_REBOOT: + return PAGE_VEHICLES; + case PAGE_OUTPUT: + return PAGE_SUMMARY; + case PAGE_LEVELLING: + return PAGE_CALIBRATION; + case PAGE_CALIBRATION: + return PAGE_SAVE; + case PAGE_SUMMARY: + return PAGE_LEVELLING; + case PAGE_SAVE: + return PAGE_END; + case PAGE_NOTYETIMPLEMENTED: + return PAGE_END; + default: + return -1; + } +} + +QString SetupWizard::getSummaryText() +{ + QString summary = ""; + summary.append("").append(tr("Controller type: ")).append(""); + switch(getControllerType()) + { + case CONTROLLER_CC: + summary.append(tr("OpenPilot CopterControl")); + break; + case CONTROLLER_CC3D: + summary.append(tr("OpenPilot CopterControl 3D")); + break; + case CONTROLLER_REVO: + summary.append(tr("OpenPilot Revolution")); + break; + case CONTROLLER_PIPX: + summary.append(tr("OpenPilot PipX Radio Modem")); + break; + default: + summary.append(tr("Unknown")); + break; + } + + summary.append("
"); + summary.append("").append(tr("Vehicle type: ")).append(""); + switch (getVehicleType()) + { + case VEHICLE_MULTI: + summary.append(tr("Multirotor")); + + summary.append("
"); + summary.append("").append(tr("Vehicle sub type: ")).append(""); + switch (getVehicleSubType()) + { + case SetupWizard::MULTI_ROTOR_TRI_Y: + summary.append(tr("Tricopter")); + break; + case SetupWizard::MULTI_ROTOR_QUAD_X: + summary.append(tr("Quadcopter X")); + break; + case SetupWizard::MULTI_ROTOR_QUAD_PLUS: + summary.append(tr("Quadcopter +")); + break; + case SetupWizard::MULTI_ROTOR_HEXA: + summary.append(tr("Hexacopter")); + break; + case SetupWizard::MULTI_ROTOR_HEXA_COAX_Y: + summary.append(tr("Hexacopter Coax (Y6)")); + break; + case SetupWizard::MULTI_ROTOR_HEXA_H: + summary.append(tr("Hexacopter X")); + break; + case SetupWizard::MULTI_ROTOR_OCTO: + summary.append(tr("Octocopter")); + break; + case SetupWizard::MULTI_ROTOR_OCTO_COAX_X: + summary.append(tr("Octocopter Coax X")); + break; + case SetupWizard::MULTI_ROTOR_OCTO_COAX_PLUS: + summary.append(tr("Octocopter Coax +")); + break; + case SetupWizard::MULTI_ROTOR_OCTO_V: + summary.append(tr("Octocopter V")); + break; + default: + summary.append(tr("Unknown")); + break; + } + + break; + case VEHICLE_FIXEDWING: + summary.append(tr("Fixed wing")); + break; + case VEHICLE_HELI: + summary.append(tr("Helicopter")); + break; + case VEHICLE_SURFACE: + summary.append(tr("Surface vehicle")); + break; + default: + summary.append(tr("Unknown")); + } + + summary.append("
"); + summary.append("").append(tr("Input type: ")).append(""); + switch (getInputType()) + { + case INPUT_PWM: + summary.append(tr("PWM (One cable per channel)")); + break; + case INPUT_PPM: + summary.append(tr("PPM (One cable for all channels)")); + break; + case INPUT_SBUS: + summary.append(tr("Futaba S.Bus")); + break; + case INPUT_DSM2: + summary.append(tr("Spektrum satellite (DSM2)")); + break; + case INPUT_DSMX10: + summary.append(tr("Spektrum satellite (DSMX10BIT)")); + break; + case INPUT_DSMX11: + summary.append(tr("Spektrum satellite (DSMX11BIT)")); + break; + default: + summary.append(tr("Unknown")); + } + + summary.append("
"); + summary.append("").append(tr("ESC type: ")).append(""); + switch (getESCType()) + { + case ESC_LEGACY: + summary.append(tr("Legacy ESC (50 Hz)")); + break; + case ESC_RAPID: + summary.append(tr("Rapid ESC (400 Hz)")); + break; + default: + summary.append(tr("Unknown")); + } + + /* + summary.append("
"); + summary.append("").append(tr("Reboot required: ")).append(""); + summary.append(isRestartNeeded() ? tr("Yes") : tr("No")); + */ + return summary; +} + +void SetupWizard::createPages() +{ + setPage(PAGE_START, new StartPage(this)); + setPage(PAGE_UPDATE, new AutoUpdatePage(this)); + setPage(PAGE_CONTROLLER, new ControllerPage(this)); + setPage(PAGE_VEHICLES, new VehiclePage(this)); + setPage(PAGE_MULTI, new MultiPage(this)); + setPage(PAGE_FIXEDWING, new FixedWingPage(this)); + setPage(PAGE_HELI, new HeliPage(this)); + setPage(PAGE_SURFACE, new SurfacePage(this)); + setPage(PAGE_INPUT, new InputPage(this)); + setPage(PAGE_OUTPUT, new OutputPage(this)); + setPage(PAGE_LEVELLING, new LevellingPage(this)); + setPage(PAGE_CALIBRATION, new OutputCalibrationPage(this)); + setPage(PAGE_SUMMARY, new SummaryPage(this)); + setPage(PAGE_SAVE, new SavePage(this)); + setPage(PAGE_REBOOT, new RebootPage(this)); + setPage(PAGE_NOTYETIMPLEMENTED, new NotYetImplementedPage(this)); + setPage(PAGE_END, new EndPage(this)); + + setStartId(PAGE_START); + + connect(button(QWizard::CustomButton1), SIGNAL(clicked()), this, SLOT(customBackClicked())); + setButtonText(QWizard::CustomButton1, buttonText(QWizard::BackButton)); + QList button_layout; + button_layout << QWizard::Stretch << QWizard::CustomButton1 << QWizard::NextButton << QWizard::CancelButton << QWizard::FinishButton; + setButtonLayout(button_layout); + connect(this, SIGNAL(currentIdChanged(int)), this, SLOT(pageChanged(int))); +} + +void SetupWizard::customBackClicked() +{ + if(currentId() == PAGE_CALIBRATION) { + static_cast(currentPage())->customBackClicked(); + } + else { + back(); + } +} + +void SetupWizard::pageChanged(int currId) +{ + button(QWizard::CustomButton1)->setVisible(currId != PAGE_START); + button(QWizard::CancelButton)->setVisible(currId != PAGE_END); +} + +bool SetupWizard::saveHardwareSettings() const +{ + VehicleConfigurationHelper helper(const_cast(this)); + return helper.setupHardwareSettings(); +} + +bool SetupWizard::canAutoUpdate() const +{ + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + Q_ASSERT(pm); + UploaderGadgetFactory *uploader = pm->getObject(); + Q_ASSERT(uploader); + return uploader->isAutoUpdateCapable(); +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h new file mode 100644 index 000000000..3f3c93f46 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h @@ -0,0 +1,112 @@ +/** + ****************************************************************************** + * + * @file setupwizard.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup Setup Wizard Plugin + * @{ + * @brief A Wizards to make the initial setup easy for everyone. + *****************************************************************************/ +/* + * 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 SETUPWIZARD_H +#define SETUPWIZARD_H + +#include +#include "levellingutil.h" +#include +#include +#include "vehicleconfigurationsource.h" +#include "vehicleconfigurationhelper.h" + +class SetupWizard : public QWizard, public VehicleConfigurationSource +{ + Q_OBJECT + +public: + SetupWizard(QWidget *parent = 0); + int nextId() const; + + void setControllerType(SetupWizard::CONTROLLER_TYPE type) { m_controllerType = type; } + SetupWizard::CONTROLLER_TYPE getControllerType() const { return m_controllerType; } + + void setVehicleType(SetupWizard::VEHICLE_TYPE type) { m_vehicleType = type; } + SetupWizard::VEHICLE_TYPE getVehicleType() const { return m_vehicleType; } + + void setVehicleSubType(SetupWizard::VEHICLE_SUB_TYPE type) { m_vehicleSubType = type; } + SetupWizard::VEHICLE_SUB_TYPE getVehicleSubType() const { return m_vehicleSubType; } + + void setInputType(SetupWizard::INPUT_TYPE type) { m_inputType = type; } + SetupWizard::INPUT_TYPE getInputType() const { return m_inputType; } + + void setESCType(SetupWizard::ESC_TYPE type) { m_escType = type; } + SetupWizard::ESC_TYPE getESCType() const { return m_escType; } + + void setLevellingBias(accelGyroBias bias) { m_levellingBias = bias; m_levellingPerformed = true; } + bool isLevellingPerformed() const { return m_levellingPerformed; } + accelGyroBias getLevellingBias() const { return m_levellingBias; } + + void setActuatorSettings(QList actuatorSettings) { m_actuatorSettings = actuatorSettings; } + bool isMotorCalibrationPerformed() const { return m_motorCalibrationPerformed; } + QList getActuatorSettings() const { return m_actuatorSettings; } + + void setRestartNeeded(bool needed) { m_restartNeeded = needed; } + bool isRestartNeeded() const {return m_restartNeeded; } + + QString getSummaryText(); + + Core::ConnectionManager* getConnectionManager() { + if (!m_connectionManager) { + m_connectionManager = Core::ICore::instance()->connectionManager(); + Q_ASSERT(m_connectionManager); + } + return m_connectionManager; + } + +private slots: + void customBackClicked(); + void pageChanged(int currId); +private: + enum {PAGE_START, PAGE_CONTROLLER, PAGE_VEHICLES, PAGE_MULTI, PAGE_FIXEDWING, + PAGE_HELI, PAGE_SURFACE, PAGE_INPUT, PAGE_OUTPUT, PAGE_LEVELLING, PAGE_CALIBRATION, + PAGE_SAVE, PAGE_SUMMARY, PAGE_NOTYETIMPLEMENTED, PAGE_REBOOT, PAGE_END, PAGE_UPDATE}; + void createPages(); + bool saveHardwareSettings() const; + bool canAutoUpdate() const; + + CONTROLLER_TYPE m_controllerType; + VEHICLE_TYPE m_vehicleType; + VEHICLE_SUB_TYPE m_vehicleSubType; + INPUT_TYPE m_inputType; + ESC_TYPE m_escType; + + bool m_levellingPerformed; + accelGyroBias m_levellingBias; + + bool m_motorCalibrationPerformed; + QList m_actuatorSettings; + + bool m_restartNeeded; + + bool m_back; + + Core::ConnectionManager *m_connectionManager; +}; + +#endif // SETUPWIZARD_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro new file mode 100644 index 000000000..2f1754541 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro @@ -0,0 +1,88 @@ + +TEMPLATE = lib +TARGET = SetupWizard +QT += svg + + +include(../../openpilotgcsplugin.pri) +include(../../plugins/coreplugin/coreplugin.pri) +include(../../plugins/uavobjectutil/uavobjectutil.pri) +include(../../plugins/config/config.pri) + +LIBS *= -l$$qtLibraryName(Uploader) +HEADERS += setupwizardplugin.h \ + setupwizard.h \ + pages/startpage.h \ + pages/endpage.h \ + pages/controllerpage.h \ + pages/vehiclepage.h \ + pages/notyetimplementedpage.h \ + pages/multipage.h \ + pages/fixedwingpage.h \ + pages/helipage.h \ + pages/surfacepage.h \ + pages/abstractwizardpage.h \ + pages/outputpage.h \ + pages/inputpage.h \ + pages/summarypage.h \ + pages/levellingpage.h \ + levellingutil.h \ + vehicleconfigurationsource.h \ + vehicleconfigurationhelper.h \ + connectiondiagram.h \ + pages/outputcalibrationpage.h \ + outputcalibrationutil.h \ + pages/rebootpage.h \ + pages/savepage.h \ + pages/autoupdatepage.h + +SOURCES += setupwizardplugin.cpp \ + setupwizard.cpp \ + pages/startpage.cpp \ + pages/endpage.cpp \ + pages/controllerpage.cpp \ + pages/vehiclepage.cpp \ + pages/notyetimplementedpage.cpp \ + pages/multipage.cpp \ + pages/fixedwingpage.cpp \ + pages/helipage.cpp \ + pages/surfacepage.cpp \ + pages/abstractwizardpage.cpp \ + pages/outputpage.cpp \ + pages/inputpage.cpp \ + pages/summarypage.cpp \ + pages/levellingpage.cpp \ + levellingutil.cpp \ + vehicleconfigurationsource.cpp \ + vehicleconfigurationhelper.cpp \ + connectiondiagram.cpp \ + pages/outputcalibrationpage.cpp \ + outputcalibrationutil.cpp \ + pages/rebootpage.cpp \ + pages/savepage.cpp \ + pages/autoupdatepage.cpp + +OTHER_FILES += SetupWizard.pluginspec + +FORMS += \ + pages/startpage.ui \ + pages/endpage.ui \ + pages/controllerpage.ui \ + pages/vehiclepage.ui \ + pages/notyetimplementedpage.ui \ + pages/multipage.ui \ + pages/fixedwingpage.ui \ + pages/helipage.ui \ + pages/surfacepage.ui \ + pages/outputpage.ui \ + pages/inputpage.ui \ + pages/summarypage.ui \ + pages/levellingpage.ui \ + connectiondiagram.ui \ + pages/outputcalibrationpage.ui \ + pages/rebootpage.ui \ + pages/savepage.ui \ + pages/autoupdatepage.ui + +RESOURCES += \ + wizardResources.qrc diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.cpp new file mode 100644 index 000000000..defc1e927 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.cpp @@ -0,0 +1,100 @@ +/** + ****************************************************************************** + * + * @file setupwizardplugin.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup SetupWizardPlugin + * @{ + * @brief A Setup Wizard 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 "setupwizardplugin.h" + +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +SetupWizardPlugin::SetupWizardPlugin() : wizardRunning(false) +{ +} + +SetupWizardPlugin::~SetupWizardPlugin() +{ +} + +bool SetupWizardPlugin::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_TOOLS); + + Core::Command* cmd = am->registerAction(new QAction(this), + "SetupWizardPlugin.ShowSetupWizard", + QList() << + Core::Constants::C_GLOBAL_ID); + cmd->setDefaultKeySequence(QKeySequence("Ctrl+V")); + cmd->action()->setText(tr("Vehicle Setup Wizard")); + + Core::ModeManager::instance()->addAction(cmd, 1); + + ac->menu()->addSeparator(); + ac->appendGroup("Wizard"); + ac->addAction(cmd, "Wizard"); + + connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(showSetupWizard())); + return true; +} + +void SetupWizardPlugin::extensionsInitialized() +{ +} + +void SetupWizardPlugin::shutdown() +{ +} + +void SetupWizardPlugin::showSetupWizard() +{ + if (!wizardRunning) { + wizardRunning = true; + SetupWizard *m_wiz = new SetupWizard(); + connect(m_wiz, SIGNAL(finished(int)), this, SLOT(wizardTerminated())); + m_wiz->setAttribute( Qt::WA_DeleteOnClose, true ); + m_wiz->setWindowFlags(m_wiz->windowFlags() | Qt::WindowStaysOnTopHint); + m_wiz->show(); + } +} + +void SetupWizardPlugin::wizardTerminated() +{ + wizardRunning = false; + disconnect(this,SLOT(wizardTerminated())); +} + +Q_EXPORT_PLUGIN(SetupWizardPlugin) diff --git a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2gadget.h b/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.h similarity index 60% rename from ground/openpilotgcs/src/plugins/hitlv2/hitlv2gadget.h rename to ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.h index 45302abb8..b79c0f7c5 100644 --- a/ground/openpilotgcs/src/plugins/hitlv2/hitlv2gadget.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.h @@ -1,13 +1,13 @@ /** ****************************************************************************** * - * @file hitlv2gadget.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010-2012. + * @file setupwizardplugin.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ - * @addtogroup HITLPlugin HITLv2 Plugin + * @addtogroup SetupWizardPlugin * @{ - * @brief The Hardware In The Loop plugin version 2 + * @brief A Setup Wizard Plugin *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify @@ -24,37 +24,30 @@ * with this program; if not, write to the Free Software Foundation, Inc., * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ +#ifndef SETUPWIZARDPLUGIN_H +#define SETUPWIZARDPLUGIN_H -#ifndef HITLV2_H -#define HITLV2_H +#include +#include +#include "setupwizard.h" -#include -#include "hitlv2widget.h" - -class IUAVGadget; -class QWidget; -class QString; -class Simulator; - -using namespace Core; - -class HITLGadget : public Core::IUAVGadget +class SetupWizardPlugin : public ExtensionSystem::IPlugin { Q_OBJECT public: - HITLGadget(QString classId, HITLWidget *widget, QWidget *parent = 0); - ~HITLGadget(); + SetupWizardPlugin(); + ~SetupWizardPlugin(); - QWidget *widget() { return m_widget; } - void loadConfiguration(IUAVGadgetConfiguration* config); + void extensionsInitialized(); + bool initialize(const QStringList & arguments, QString * errorString); + void shutdown(); -signals: - void changeConfiguration(); +private slots: + void showSetupWizard(); + void wizardTerminated(); private: - HITLWidget* m_widget; - Simulator* simulator; + bool wizardRunning; }; - -#endif // HITLV2_H +#endif // SETUPWIZARDPLUGIN_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp new file mode 100644 index 000000000..2c86dc2e1 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -0,0 +1,1204 @@ +/** + ****************************************************************************** + * + * @file vehicleconfigurationhelper.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup VehicleConfigurationHelper + * @{ + * @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 + */ + +#include "vehicleconfigurationhelper.h" +#include "extensionsystem/pluginmanager.h" +#include "hwsettings.h" +#include "actuatorsettings.h" +#include "attitudesettings.h" +#include "mixersettings.h" +#include "systemsettings.h" +#include "manualcontrolsettings.h" +#include "stabilizationsettings.h" + +const qint16 VehicleConfigurationHelper::LEGACY_ESC_FREQUENCE = 50; +const qint16 VehicleConfigurationHelper::RAPID_ESC_FREQUENCE = 400; + +VehicleConfigurationHelper::VehicleConfigurationHelper(VehicleConfigurationSource *configSource) + : m_configSource(configSource), m_uavoManager(0), + m_transactionOK(false), m_transactionTimeout(false), m_currentTransactionObjectID(-1), + m_progress(0) +{ + Q_ASSERT(m_configSource); + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + m_uavoManager = pm->getObject(); + Q_ASSERT(m_uavoManager); +} + +bool VehicleConfigurationHelper::setupVehicle(bool save) +{ + m_progress = 0; + clearModifiedObjects(); + resetVehicleConfig(); + resetGUIData(); + if(!saveChangesToController(save)) { + return false; + } + + m_progress = 0; + applyHardwareConfiguration(); + applyVehicleConfiguration(); + applyActuatorConfiguration(); + applyFlighModeConfiguration(); + applyLevellingConfiguration(); + applyStabilizationConfiguration(); + applyManualControlDefaults(); + + bool result = saveChangesToController(save); + emit saveProgress(m_modifiedObjects.count() + 1, ++m_progress, result ? tr("Done!") : tr("Failed!")); + return result; +} + +bool VehicleConfigurationHelper::setupHardwareSettings(bool save) +{ + m_progress = 0; + clearModifiedObjects(); + applyHardwareConfiguration(); + applyManualControlDefaults(); + + bool result = saveChangesToController(save); + emit saveProgress(m_modifiedObjects.count() + 1, ++m_progress, result ? tr("Done!") : tr("Failed!")); + return result; +} + +void VehicleConfigurationHelper::addModifiedObject(UAVDataObject *object, QString description) +{ + m_modifiedObjects << new QPair(object, description); +} + +void VehicleConfigurationHelper::clearModifiedObjects() +{ + for(int i = 0; i < m_modifiedObjects.count(); i++) { + QPair *pair = m_modifiedObjects.at(i); + delete pair; + } + m_modifiedObjects.clear(); +} + +void VehicleConfigurationHelper::applyHardwareConfiguration() +{ + HwSettings* hwSettings = HwSettings::GetInstance(m_uavoManager); + HwSettings::DataFields data = hwSettings->getData(); + switch(m_configSource->getControllerType()) + { + case VehicleConfigurationSource::CONTROLLER_CC: + case VehicleConfigurationSource::CONTROLLER_CC3D: + // Reset all ports + data.CC_RcvrPort = HwSettings::CC_RCVRPORT_DISABLED; + + //Default mainport to be active telemetry link + data.CC_MainPort = HwSettings::CC_MAINPORT_TELEMETRY; + + data.CC_FlexiPort = HwSettings::CC_FLEXIPORT_DISABLED; + switch(m_configSource->getInputType()) + { + case VehicleConfigurationSource::INPUT_PWM: + data.CC_RcvrPort = HwSettings::CC_RCVRPORT_PWM; + break; + case VehicleConfigurationSource::INPUT_PPM: + data.CC_RcvrPort = HwSettings::CC_RCVRPORT_PPM; + break; + case VehicleConfigurationSource::INPUT_SBUS: + // We have to set teletry on flexport since s.bus needs the mainport. + data.CC_MainPort = HwSettings::CC_MAINPORT_SBUS; + data.CC_FlexiPort = HwSettings::CC_FLEXIPORT_TELEMETRY; + break; + case VehicleConfigurationSource::INPUT_DSMX10: + data.CC_FlexiPort = HwSettings::CC_FLEXIPORT_DSMX10BIT; + break; + case VehicleConfigurationSource::INPUT_DSMX11: + data.CC_FlexiPort = HwSettings::CC_FLEXIPORT_DSMX11BIT; + break; + case VehicleConfigurationSource::INPUT_DSM2: + data.CC_FlexiPort = HwSettings::CC_FLEXIPORT_DSM2; + break; + default: + break; + } + break; + case VehicleConfigurationSource::CONTROLLER_REVO: + // TODO: Implement Revo settings + break; + default: + break; + } + hwSettings->setData(data); + addModifiedObject(hwSettings, tr("Writing hardware settings")); +} + +void VehicleConfigurationHelper::applyVehicleConfiguration() +{ + + switch(m_configSource->getVehicleType()) + { + case VehicleConfigurationSource::VEHICLE_MULTI: + { + switch(m_configSource->getVehicleSubType()) + { + case VehicleConfigurationSource::MULTI_ROTOR_TRI_Y: + setupTriCopter(); + break; + case VehicleConfigurationSource::MULTI_ROTOR_QUAD_X: + case VehicleConfigurationSource::MULTI_ROTOR_QUAD_PLUS: + setupQuadCopter(); + break; + case VehicleConfigurationSource::MULTI_ROTOR_HEXA: + case VehicleConfigurationSource::MULTI_ROTOR_HEXA_COAX_Y: + case VehicleConfigurationSource::MULTI_ROTOR_HEXA_H: + setupHexaCopter(); + break; + case VehicleConfigurationSource::MULTI_ROTOR_OCTO: + case VehicleConfigurationSource::MULTI_ROTOR_OCTO_COAX_X: + case VehicleConfigurationSource::MULTI_ROTOR_OCTO_COAX_PLUS: + case VehicleConfigurationSource::MULTI_ROTOR_OCTO_V: + setupOctoCopter(); + break; + default: + break; + } + break; + } + case VehicleConfigurationSource::VEHICLE_FIXEDWING: + case VehicleConfigurationSource::VEHICLE_HELI: + case VehicleConfigurationSource::VEHICLE_SURFACE: + // TODO: Implement settings for other vehicle types? + break; + default: + break; + } +} + +void VehicleConfigurationHelper::applyActuatorConfiguration() +{ + ActuatorSettings* actSettings = ActuatorSettings::GetInstance(m_uavoManager); + switch(m_configSource->getVehicleType()) { + case VehicleConfigurationSource::VEHICLE_MULTI: { + ActuatorSettings::DataFields data = actSettings->getData(); + + QList actuatorSettings = m_configSource->getActuatorSettings(); + for(quint16 i = 0; i < ActuatorSettings::CHANNELMAX_NUMELEM; i++) { + data.ChannelType[i] = ActuatorSettings::CHANNELTYPE_PWM; + data.ChannelAddr[i] = i; + data.ChannelMin[i] = actuatorSettings[i].channelMin; + data.ChannelNeutral[i] = actuatorSettings[i].channelNeutral; + data.ChannelMax[i] = actuatorSettings[i].channelMax; + } + + data.MotorsSpinWhileArmed = ActuatorSettings::MOTORSSPINWHILEARMED_FALSE; + + for(quint16 i = 0; i < ActuatorSettings::CHANNELUPDATEFREQ_NUMELEM; i++) { + data.ChannelUpdateFreq[i] = LEGACY_ESC_FREQUENCE; + } + + qint16 updateFrequence = LEGACY_ESC_FREQUENCE; + switch(m_configSource->getESCType()) { + case VehicleConfigurationSource::ESC_LEGACY: + updateFrequence = LEGACY_ESC_FREQUENCE; + break; + case VehicleConfigurationSource::ESC_RAPID: + updateFrequence = RAPID_ESC_FREQUENCE; + break; + default: + break; + } + + switch(m_configSource->getVehicleSubType()) { + case VehicleConfigurationSource::MULTI_ROTOR_TRI_Y: + data.ChannelUpdateFreq[0] = updateFrequence; + break; + case VehicleConfigurationSource::MULTI_ROTOR_QUAD_X: + case VehicleConfigurationSource::MULTI_ROTOR_QUAD_PLUS: + data.ChannelUpdateFreq[0] = updateFrequence; + data.ChannelUpdateFreq[1] = updateFrequence; + break; + case VehicleConfigurationSource::MULTI_ROTOR_HEXA: + case VehicleConfigurationSource::MULTI_ROTOR_HEXA_COAX_Y: + case VehicleConfigurationSource::MULTI_ROTOR_HEXA_H: + case VehicleConfigurationSource::MULTI_ROTOR_OCTO: + case VehicleConfigurationSource::MULTI_ROTOR_OCTO_COAX_X: + case VehicleConfigurationSource::MULTI_ROTOR_OCTO_COAX_PLUS: + case VehicleConfigurationSource::MULTI_ROTOR_OCTO_V: + data.ChannelUpdateFreq[0] = updateFrequence; + data.ChannelUpdateFreq[1] = updateFrequence; + data.ChannelUpdateFreq[2] = updateFrequence; + data.ChannelUpdateFreq[3] = updateFrequence; + break; + default: + break; + } + actSettings->setData(data); + addModifiedObject(actSettings, tr("Writing actuator settings")); + break; + } + case VehicleConfigurationSource::VEHICLE_FIXEDWING: + case VehicleConfigurationSource::VEHICLE_HELI: + case VehicleConfigurationSource::VEHICLE_SURFACE: + // TODO: Implement settings for other vehicle types? + break; + default: + break; + } +} + +void VehicleConfigurationHelper::applyFlighModeConfiguration() +{ + ManualControlSettings* controlSettings = ManualControlSettings::GetInstance(m_uavoManager); + Q_ASSERT(controlSettings); + + ManualControlSettings::DataFields data = controlSettings->getData(); + data.Stabilization1Settings[0] = ManualControlSettings::STABILIZATION1SETTINGS_ATTITUDE; + data.Stabilization1Settings[1] = ManualControlSettings::STABILIZATION1SETTINGS_ATTITUDE; + data.Stabilization1Settings[2] = ManualControlSettings::STABILIZATION1SETTINGS_AXISLOCK; + data.Stabilization2Settings[0] = ManualControlSettings::STABILIZATION2SETTINGS_ATTITUDE; + data.Stabilization2Settings[1] = ManualControlSettings::STABILIZATION2SETTINGS_ATTITUDE; + data.Stabilization2Settings[2] = ManualControlSettings::STABILIZATION2SETTINGS_RATE; + data.Stabilization3Settings[0] = ManualControlSettings::STABILIZATION3SETTINGS_RATE; + data.Stabilization3Settings[1] = ManualControlSettings::STABILIZATION3SETTINGS_RATE; + data.Stabilization3Settings[2] = ManualControlSettings::STABILIZATION3SETTINGS_RATE; + data.FlightModeNumber = 3; + data.FlightModePosition[0] = ManualControlSettings::FLIGHTMODEPOSITION_STABILIZED1; + data.FlightModePosition[1] = ManualControlSettings::FLIGHTMODEPOSITION_STABILIZED1; + data.FlightModePosition[2] = ManualControlSettings::FLIGHTMODEPOSITION_STABILIZED1; + data.FlightModePosition[3] = ManualControlSettings::FLIGHTMODEPOSITION_STABILIZED1; + data.FlightModePosition[4] = ManualControlSettings::FLIGHTMODEPOSITION_STABILIZED1; + data.FlightModePosition[5] = ManualControlSettings::FLIGHTMODEPOSITION_STABILIZED1; + controlSettings->setData(data); + addModifiedObject(controlSettings, tr("Writing flight mode settings")); +} + +void VehicleConfigurationHelper::applyLevellingConfiguration() +{ + if(m_configSource->isLevellingPerformed()) + { + accelGyroBias bias = m_configSource->getLevellingBias(); + AttitudeSettings* attitudeSettings = AttitudeSettings::GetInstance(m_uavoManager); + Q_ASSERT(attitudeSettings); + AttitudeSettings::DataFields data = attitudeSettings->getData(); + + data.AccelBias[0] += bias.m_accelerometerXBias; + data.AccelBias[1] += bias.m_accelerometerYBias; + data.AccelBias[2] += bias.m_accelerometerZBias; + data.GyroBias[0] = -bias.m_gyroXBias; + data.GyroBias[1] = -bias.m_gyroYBias; + data.GyroBias[2] = -bias.m_gyroZBias; + + attitudeSettings->setData(data); + addModifiedObject(attitudeSettings, tr("Writing gyro and accelerometer bias settings")); + } +} + +void VehicleConfigurationHelper::applyStabilizationConfiguration() +{ + StabilizationSettings *stabSettings = StabilizationSettings::GetInstance(m_uavoManager); + Q_ASSERT(stabSettings); + StabilizationSettings::DataFields data = stabSettings->getData(); + + StabilizationSettings defaultSettings; + stabSettings->setData(defaultSettings.getData()); + addModifiedObject(stabSettings, tr("Writing stabilization settings")); +} + +void VehicleConfigurationHelper::applyMixerConfiguration(mixerChannelSettings channels[]) +{ + // Set all mixer data + MixerSettings* mSettings = MixerSettings::GetInstance(m_uavoManager); + Q_ASSERT(mSettings); + + // Set Mixer types and values + QString mixerTypePattern = "Mixer%1Type"; + QString mixerVectorPattern = "Mixer%1Vector"; + for(int i = 0; i < 10; i++) { + UAVObjectField *field = mSettings->getField(mixerTypePattern.arg(i + 1)); + Q_ASSERT(field); + field->setValue(field->getOptions().at(channels[i].type)); + + field = mSettings->getField(mixerVectorPattern.arg(i + 1)); + Q_ASSERT(field); + field->setValue((channels[i].throttle1 * 127) / 100, 0); + field->setValue((channels[i].throttle2 * 127) / 100, 1); + field->setValue((channels[i].roll * 127) / 100, 2); + field->setValue((channels[i].pitch * 127) / 100, 3); + field->setValue((channels[i].yaw *127) / 100, 4); + } + + // Apply updates + mSettings->setData(mSettings->getData()); + addModifiedObject(mSettings, tr("Writing mixer settings")); + +} + +void VehicleConfigurationHelper::applyMultiGUISettings(SystemSettings::AirframeTypeOptions airframe, GUIConfigDataUnion guiConfig) +{ + SystemSettings * sSettings = SystemSettings::GetInstance(m_uavoManager); + Q_ASSERT(sSettings); + SystemSettings::DataFields data = sSettings->getData(); + data.AirframeType = airframe; + + for (int i = 0; i < (int)(SystemSettings::GUICONFIGDATA_NUMELEM); i++) { + data.GUIConfigData[i] = guiConfig.UAVObject[i]; + } + + sSettings->setData(data); + addModifiedObject(sSettings, tr("Writing vehicle settings")); +} + +void VehicleConfigurationHelper::applyManualControlDefaults() +{ + ManualControlSettings *mcSettings = ManualControlSettings::GetInstance(m_uavoManager); + Q_ASSERT(mcSettings); + ManualControlSettings::DataFields cData = mcSettings->getData(); + + ManualControlSettings::ChannelGroupsOptions channelType = ManualControlSettings::CHANNELGROUPS_PWM; + switch(m_configSource->getInputType()) + { + case VehicleConfigurationSource::INPUT_PWM: + channelType = ManualControlSettings::CHANNELGROUPS_PWM; + break; + case VehicleConfigurationSource::INPUT_PPM: + channelType = ManualControlSettings::CHANNELGROUPS_PPM; + break; + case VehicleConfigurationSource::INPUT_SBUS: + channelType = ManualControlSettings::CHANNELGROUPS_SBUS; + break; + case VehicleConfigurationSource::INPUT_DSMX10: + case VehicleConfigurationSource::INPUT_DSMX11: + case VehicleConfigurationSource::INPUT_DSM2: + channelType = ManualControlSettings::CHANNELGROUPS_DSMMAINPORT; + break; + default: + break; + } + + cData.ChannelGroups[ManualControlSettings::CHANNELGROUPS_THROTTLE] = channelType; + cData.ChannelGroups[ManualControlSettings::CHANNELGROUPS_ROLL] = channelType; + cData.ChannelGroups[ManualControlSettings::CHANNELGROUPS_YAW] = channelType; + cData.ChannelGroups[ManualControlSettings::CHANNELGROUPS_PITCH] = channelType; + cData.ChannelGroups[ManualControlSettings::CHANNELGROUPS_FLIGHTMODE] = channelType; + + cData.ChannelNumber[ManualControlSettings::CHANNELGROUPS_THROTTLE] = 1; + cData.ChannelNumber[ManualControlSettings::CHANNELGROUPS_ROLL] = 2; + cData.ChannelNumber[ManualControlSettings::CHANNELGROUPS_YAW] = 3; + cData.ChannelNumber[ManualControlSettings::CHANNELGROUPS_PITCH] = 4; + cData.ChannelNumber[ManualControlSettings::CHANNELGROUPS_FLIGHTMODE] = 5; + + mcSettings->setData(cData); + addModifiedObject(mcSettings, tr("Writing manual control defaults")); +} + +bool VehicleConfigurationHelper::saveChangesToController(bool save) +{ + qDebug() << "Saving modified objects to controller. " << m_modifiedObjects.count() << " objects in found."; + const int OUTER_TIMEOUT = 3000 * 20; // 10 seconds timeout for saving all objects + const int INNER_TIMEOUT = 2000; // 1 second timeout on every save attempt + + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + Q_ASSERT(pm); + UAVObjectUtilManager* utilMngr = pm->getObject(); + Q_ASSERT(utilMngr); + + QTimer outerTimeoutTimer; + outerTimeoutTimer.setSingleShot(true); + + QTimer innerTimeoutTimer; + innerTimeoutTimer.setSingleShot(true); + + connect(utilMngr, SIGNAL(saveCompleted(int ,bool)), this, SLOT(uAVOTransactionCompleted(int, bool))); + connect(&innerTimeoutTimer, SIGNAL(timeout()), &m_eventLoop, SLOT(quit())); + connect(&outerTimeoutTimer, SIGNAL(timeout()), this, SLOT(saveChangesTimeout())); + + outerTimeoutTimer.start(OUTER_TIMEOUT); + for(int i = 0; i < m_modifiedObjects.count(); i++) { + QPair *objPair = m_modifiedObjects.at(i); + m_transactionOK = false; + UAVDataObject* obj = objPair->first; + QString objDescription = objPair->second; + if(UAVObject::GetGcsAccess(obj->getMetadata()) != UAVObject::ACCESS_READONLY && obj->isSettings()) { + + emit saveProgress(m_modifiedObjects.count() + 1, ++m_progress, objDescription); + + m_currentTransactionObjectID = obj->getObjID(); + + connect(obj, SIGNAL(transactionCompleted(UAVObject* ,bool)), this, SLOT(uAVOTransactionCompleted(UAVObject*, bool))); + while(!m_transactionOK && !m_transactionTimeout) { + // Allow the transaction to take some time + innerTimeoutTimer.start(INNER_TIMEOUT); + + // Set object updated + obj->updated(); + if(!m_transactionOK) { + m_eventLoop.exec(); + } + innerTimeoutTimer.stop(); + } + disconnect(obj, SIGNAL(transactionCompleted(UAVObject* ,bool)), this, SLOT(uAVOTransactionCompleted(UAVObject*, bool))); + if(m_transactionOK) { + qDebug() << "Object " << obj->getName() << " was successfully updated."; + if(save) { + m_transactionOK = false; + m_currentTransactionObjectID = obj->getObjID(); + // Try to save until success or timeout + while(!m_transactionOK && !m_transactionTimeout) { + // Allow the transaction to take some time + innerTimeoutTimer.start(INNER_TIMEOUT); + + // Persist object in controller + utilMngr->saveObjectToSD(obj); + if(!m_transactionOK) { + m_eventLoop.exec(); + } + innerTimeoutTimer.stop(); + } + m_currentTransactionObjectID = -1; + } + } + + if(!m_transactionOK) { + qDebug() << "Transaction timed out when trying to save: " << obj->getName(); + } + else { + qDebug() << "Object " << obj->getName() << " was successfully saved."; + } + } + else { + qDebug() << "Trying to save a UAVDataObject that is read only or is not a settings object."; + } + if(m_transactionTimeout) { + qDebug() << "Transaction timed out when trying to save " << m_modifiedObjects.count() << " objects."; + break; + } + } + + outerTimeoutTimer.stop(); + disconnect(&outerTimeoutTimer, SIGNAL(timeout()), this, SLOT(saveChangesTimeout())); + disconnect(&innerTimeoutTimer, SIGNAL(timeout()), &m_eventLoop, SLOT(quit())); + disconnect(utilMngr, SIGNAL(saveCompleted(int, bool)), this, SLOT(uAVOTransactionCompleted(int, bool))); + + qDebug() << "Finished saving modified objects to controller. Success = " << m_transactionOK; + + return m_transactionOK; +} + +void VehicleConfigurationHelper::uAVOTransactionCompleted(int oid, bool success) +{ + if(oid == m_currentTransactionObjectID) + { + m_transactionOK = success; + m_eventLoop.quit(); + } +} + +void VehicleConfigurationHelper::uAVOTransactionCompleted(UAVObject *object, bool success) +{ + if(object) { + uAVOTransactionCompleted(object->getObjID(), success); + } +} + +void VehicleConfigurationHelper::saveChangesTimeout() +{ + m_transactionOK = false; + m_transactionTimeout = true; + m_eventLoop.quit(); +} + +void VehicleConfigurationHelper::resetVehicleConfig() +{ + // Reset all vehicle data + MixerSettings* mSettings = MixerSettings::GetInstance(m_uavoManager); + + // Reset feed forward, accel times etc + mSettings->setFeedForward(0.0f); + mSettings->setMaxAccel(1000.0f); + mSettings->setAccelTime(0.0f); + mSettings->setDecelTime(0.0f); + + // Reset throttle curves + QString throttlePattern = "ThrottleCurve%1"; + for(int i = 1; i <= 2; i++) { + UAVObjectField *field = mSettings->getField(throttlePattern.arg(i)); + Q_ASSERT(field); + for(quint32 i = 0; i < field->getNumElements(); i++){ + field->setValue(i * ( 1.0f / (field->getNumElements() - 1)), i); + } + } + + // Reset Mixer types and values + QString mixerTypePattern = "Mixer%1Type"; + QString mixerVectorPattern = "Mixer%1Vector"; + for(int i = 1; i <= 10; i++) { + UAVObjectField *field = mSettings->getField(mixerTypePattern.arg(i)); + Q_ASSERT(field); + field->setValue(field->getOptions().at(0)); + + field = mSettings->getField(mixerVectorPattern.arg(i)); + Q_ASSERT(field); + for(quint32 i = 0; i < field->getNumElements(); i++){ + field->setValue(0, i); + } + } + + // Apply updates + //mSettings->setData(mSettings->getData()); + addModifiedObject(mSettings, tr("Preparing mixer settings")); +} + +void VehicleConfigurationHelper::resetGUIData() +{ + SystemSettings * sSettings = SystemSettings::GetInstance(m_uavoManager); + Q_ASSERT(sSettings); + SystemSettings::DataFields data = sSettings->getData(); + data.AirframeType = SystemSettings::AIRFRAMETYPE_CUSTOM; + for(quint32 i = 0; i < SystemSettings::GUICONFIGDATA_NUMELEM; i++) { + data.GUIConfigData[i] = 0; + } + sSettings->setData(data); + addModifiedObject(sSettings, tr("Preparing vehicle settings")); +} + + +void VehicleConfigurationHelper::setupTriCopter() +{ + // Typical vehicle setup + // 1. Setup mixer data + // 2. Setup GUI data + // 3. Apply changes + + mixerChannelSettings channels[10]; + GUIConfigDataUnion guiSettings = getGUIConfigData(); + + channels[0].type = MIXER_TYPE_MOTOR; + channels[0].throttle1 = 100; + channels[0].throttle2 = 0; + channels[0].roll = 100; + channels[0].pitch = 50; + channels[0].yaw = 0; + + channels[1].type = MIXER_TYPE_MOTOR; + channels[1].throttle1 = 100; + channels[1].throttle2 = 0; + channels[1].roll = -100; + channels[1].pitch = 50; + channels[1].yaw = 0; + + channels[2].type = MIXER_TYPE_MOTOR; + channels[2].throttle1 = 100; + channels[2].throttle2 = 0; + channels[2].roll = 0; + channels[2].pitch = -100; + channels[2].yaw = 0; + + channels[3].type = MIXER_TYPE_SERVO; + channels[3].throttle1 = 0; + channels[3].throttle2 = 0; + channels[3].roll = 0; + channels[3].pitch = 0; + channels[3].yaw = 100; + + guiSettings.multi.VTOLMotorNW = 1; + guiSettings.multi.VTOLMotorNE = 2; + guiSettings.multi.VTOLMotorS = 3; + guiSettings.multi.TRIYaw = 4; + + applyMixerConfiguration(channels); + applyMultiGUISettings(SystemSettings::AIRFRAMETYPE_TRI, guiSettings); +} + +GUIConfigDataUnion VehicleConfigurationHelper::getGUIConfigData() +{ + GUIConfigDataUnion configData; + + SystemSettings * systemSettings = SystemSettings::GetInstance(m_uavoManager); + Q_ASSERT(systemSettings); + SystemSettings::DataFields systemSettingsData = systemSettings->getData(); + + for(int i = 0; i < (int)(SystemSettings::GUICONFIGDATA_NUMELEM); i++) { + configData.UAVObject[i] = 0; //systemSettingsData.GUIConfigData[i]; + } + + return configData; +} + +void VehicleConfigurationHelper::setupQuadCopter() +{ + mixerChannelSettings channels[10]; + GUIConfigDataUnion guiSettings = getGUIConfigData(); + SystemSettings::AirframeTypeOptions frame; + + switch(m_configSource->getVehicleSubType()) + { + case VehicleConfigurationSource::MULTI_ROTOR_QUAD_PLUS: { + frame = SystemSettings::AIRFRAMETYPE_QUADP; + channels[0].type = MIXER_TYPE_MOTOR; + channels[0].throttle1 = 100; + channels[0].throttle2 = 0; + channels[0].roll = 0; + channels[0].pitch = 100; + channels[0].yaw = -50; + + channels[1].type = MIXER_TYPE_MOTOR; + channels[1].throttle1 = 100; + channels[1].throttle2 = 0; + channels[1].roll = -100; + channels[1].pitch = 0; + channels[1].yaw = 50; + + channels[2].type = MIXER_TYPE_MOTOR; + channels[2].throttle1 = 100; + channels[2].throttle2 = 0; + channels[2].roll = 0; + channels[2].pitch = -100; + channels[2].yaw = -50; + + channels[3].type = MIXER_TYPE_MOTOR; + channels[3].throttle1 = 100; + channels[3].throttle2 = 0; + channels[3].roll = 100; + channels[3].pitch = 0; + channels[3].yaw = 50; + + guiSettings.multi.VTOLMotorN = 1; + guiSettings.multi.VTOLMotorE = 2; + guiSettings.multi.VTOLMotorS = 3; + guiSettings.multi.VTOLMotorW = 4; + + break; + } + case VehicleConfigurationSource::MULTI_ROTOR_QUAD_X: { + frame = SystemSettings::AIRFRAMETYPE_QUADX; + channels[0].type = MIXER_TYPE_MOTOR; + channels[0].throttle1 = 100; + channels[0].throttle2 = 0; + channels[0].roll = 50; + channels[0].pitch = 50; + channels[0].yaw = -50; + + channels[1].type = MIXER_TYPE_MOTOR; + channels[1].throttle1 = 100; + channels[1].throttle2 = 0; + channels[1].roll = -50; + channels[1].pitch = 50; + channels[1].yaw = 50; + + channels[2].type = MIXER_TYPE_MOTOR; + channels[2].throttle1 = 100; + channels[2].throttle2 = 0; + channels[2].roll = -50; + channels[2].pitch = -50; + channels[2].yaw = -50; + + channels[3].type = MIXER_TYPE_MOTOR; + channels[3].throttle1 = 100; + channels[3].throttle2 = 0; + channels[3].roll = 50; + channels[3].pitch = -50; + channels[3].yaw = 50; + + guiSettings.multi.VTOLMotorNW = 1; + guiSettings.multi.VTOLMotorNE = 2; + guiSettings.multi.VTOLMotorSE = 3; + guiSettings.multi.VTOLMotorSW = 4; + + break; + } + default: + break; + } + applyMixerConfiguration(channels); + applyMultiGUISettings(frame, guiSettings); +} + +void VehicleConfigurationHelper::setupHexaCopter() +{ + mixerChannelSettings channels[10]; + GUIConfigDataUnion guiSettings = getGUIConfigData(); + SystemSettings::AirframeTypeOptions frame; + + switch(m_configSource->getVehicleSubType()) + { + case VehicleConfigurationSource::MULTI_ROTOR_HEXA: { + frame = SystemSettings::AIRFRAMETYPE_HEXA; + + channels[0].type = MIXER_TYPE_MOTOR; + channels[0].throttle1 = 100; + channels[0].throttle2 = 0; + channels[0].roll = 0; + channels[0].pitch = 33; + channels[0].yaw = -33; + + channels[1].type = MIXER_TYPE_MOTOR; + channels[1].throttle1 = 100; + channels[1].throttle2 = 0; + channels[1].roll = -50; + channels[1].pitch = 33; + channels[1].yaw = 33; + + channels[2].type = MIXER_TYPE_MOTOR; + channels[2].throttle1 = 100; + channels[2].throttle2 = 0; + channels[2].roll = -50; + channels[2].pitch = -33; + channels[2].yaw = -33; + + channels[3].type = MIXER_TYPE_MOTOR; + channels[3].throttle1 = 100; + channels[3].throttle2 = 0; + channels[3].roll = 0; + channels[3].pitch = -33; + channels[3].yaw = 33; + + channels[4].type = MIXER_TYPE_MOTOR; + channels[4].throttle1 = 100; + channels[4].throttle2 = 0; + channels[4].roll = 50; + channels[4].pitch = -33; + channels[4].yaw = -33; + + channels[5].type = MIXER_TYPE_MOTOR; + channels[5].throttle1 = 100; + channels[5].throttle2 = 0; + channels[5].roll = 50; + channels[5].pitch = 33; + channels[5].yaw = 33; + + guiSettings.multi.VTOLMotorN = 1; + guiSettings.multi.VTOLMotorNE = 2; + guiSettings.multi.VTOLMotorSE = 3; + guiSettings.multi.VTOLMotorS = 4; + guiSettings.multi.VTOLMotorSW = 5; + guiSettings.multi.VTOLMotorNW = 6; + + break; + } + case VehicleConfigurationSource::MULTI_ROTOR_HEXA_COAX_Y: { + frame = SystemSettings::AIRFRAMETYPE_HEXACOAX; + + channels[0].type = MIXER_TYPE_MOTOR; + channels[0].throttle1 = 100; + channels[0].throttle2 = 0; + channels[0].roll = 100; + channels[0].pitch = 25; + channels[0].yaw = -66; + + channels[1].type = MIXER_TYPE_MOTOR; + channels[1].throttle1 = 100; + channels[1].throttle2 = 0; + channels[1].roll = 100; + channels[1].pitch = 25; + channels[1].yaw = 66; + + channels[2].type = MIXER_TYPE_MOTOR; + channels[2].throttle1 = 100; + channels[2].throttle2 = 0; + channels[2].roll = -100; + channels[2].pitch = 25; + channels[2].yaw = -66; + + channels[3].type = MIXER_TYPE_MOTOR; + channels[3].throttle1 = 100; + channels[3].throttle2 = 0; + channels[3].roll = -100; + channels[3].pitch = 25; + channels[3].yaw = 66; + + channels[4].type = MIXER_TYPE_MOTOR; + channels[4].throttle1 = 100; + channels[4].throttle2 = 0; + channels[4].roll = 0; + channels[4].pitch = -50; + channels[4].yaw = -66; + + channels[5].type = MIXER_TYPE_MOTOR; + channels[5].throttle1 = 100; + channels[5].throttle2 = 0; + channels[5].roll = 0; + channels[5].pitch = -50; + channels[5].yaw = 66; + + guiSettings.multi.VTOLMotorNW = 1; + guiSettings.multi.VTOLMotorW = 2; + guiSettings.multi.VTOLMotorNE = 3; + guiSettings.multi.VTOLMotorE = 4; + guiSettings.multi.VTOLMotorS = 5; + guiSettings.multi.VTOLMotorSE = 6; + + break; + } + case VehicleConfigurationSource::MULTI_ROTOR_HEXA_H: { + frame = SystemSettings::AIRFRAMETYPE_HEXAX; + + channels[0].type = MIXER_TYPE_MOTOR; + channels[0].throttle1 = 100; + channels[0].throttle2 = 0; + channels[0].roll = -33; + channels[0].pitch = 50; + channels[0].yaw = -33; + + channels[1].type = MIXER_TYPE_MOTOR; + channels[1].throttle1 = 100; + channels[1].throttle2 = 0; + channels[1].roll = -33; + channels[1].pitch = 0; + channels[1].yaw = 33; + + channels[2].type = MIXER_TYPE_MOTOR; + channels[2].throttle1 = 100; + channels[2].throttle2 = 0; + channels[2].roll = -33; + channels[2].pitch = -50; + channels[2].yaw = -33; + + channels[3].type = MIXER_TYPE_MOTOR; + channels[3].throttle1 = 100; + channels[3].throttle2 = 0; + channels[3].roll = -33; + channels[3].pitch = -50; + channels[3].yaw = 33; + + channels[4].type = MIXER_TYPE_MOTOR; + channels[4].throttle1 = 100; + channels[4].throttle2 = 0; + channels[4].roll = 33; + channels[4].pitch = 0; + channels[4].yaw = -33; + + channels[5].type = MIXER_TYPE_MOTOR; + channels[5].throttle1 = 100; + channels[5].throttle2 = 0; + channels[5].roll = 33; + channels[5].pitch = 50; + channels[5].yaw = -33; + + guiSettings.multi.VTOLMotorNE = 1; + guiSettings.multi.VTOLMotorE = 2; + guiSettings.multi.VTOLMotorSE = 3; + guiSettings.multi.VTOLMotorSW = 4; + guiSettings.multi.VTOLMotorW = 5; + guiSettings.multi.VTOLMotorNW = 6; + + break; + } + default: + break; + } + applyMixerConfiguration(channels); + applyMultiGUISettings(frame, guiSettings); +} + +void VehicleConfigurationHelper::setupOctoCopter() +{ + mixerChannelSettings channels[10]; + GUIConfigDataUnion guiSettings = getGUIConfigData(); + SystemSettings::AirframeTypeOptions frame; + + switch(m_configSource->getVehicleSubType()) + { + case VehicleConfigurationSource::MULTI_ROTOR_OCTO: { + frame = SystemSettings::AIRFRAMETYPE_OCTO; + + channels[0].type = MIXER_TYPE_MOTOR; + channels[0].throttle1 = 100; + channels[0].throttle2 = 0; + channels[0].roll = 0; + channels[0].pitch = 33; + channels[0].yaw = -25; + + channels[1].type = MIXER_TYPE_MOTOR; + channels[1].throttle1 = 100; + channels[1].throttle2 = 0; + channels[1].roll = -33; + channels[1].pitch = 33; + channels[1].yaw = 25; + + channels[2].type = MIXER_TYPE_MOTOR; + channels[2].throttle1 = 100; + channels[2].throttle2 = 0; + channels[2].roll = -33; + channels[2].pitch = 0; + channels[2].yaw = -25; + + channels[3].type = MIXER_TYPE_MOTOR; + channels[3].throttle1 = 100; + channels[3].throttle2 = 0; + channels[3].roll = -33; + channels[3].pitch = -33; + channels[3].yaw = 25; + + channels[4].type = MIXER_TYPE_MOTOR; + channels[4].throttle1 = 100; + channels[4].throttle2 = 0; + channels[4].roll = 0; + channels[4].pitch = -33; + channels[4].yaw = -25; + + channels[5].type = MIXER_TYPE_MOTOR; + channels[5].throttle1 = 100; + channels[5].throttle2 = 0; + channels[5].roll = 33; + channels[5].pitch = -33; + channels[5].yaw = 25; + + channels[6].type = MIXER_TYPE_MOTOR; + channels[6].throttle1 = 100; + channels[6].throttle2 = 0; + channels[6].roll = 33; + channels[6].pitch = 0; + channels[6].yaw = -25; + + channels[7].type = MIXER_TYPE_MOTOR; + channels[7].throttle1 = 100; + channels[7].throttle2 = 0; + channels[7].roll = 33; + channels[7].pitch = 33; + channels[7].yaw = 25; + + guiSettings.multi.VTOLMotorN = 1; + guiSettings.multi.VTOLMotorNE = 2; + guiSettings.multi.VTOLMotorE = 3; + guiSettings.multi.VTOLMotorSE = 4; + guiSettings.multi.VTOLMotorS = 5; + guiSettings.multi.VTOLMotorSW = 6; + guiSettings.multi.VTOLMotorW = 7; + guiSettings.multi.VTOLMotorNW = 8; + + break; + } + case VehicleConfigurationSource::MULTI_ROTOR_OCTO_COAX_X: { + frame = SystemSettings::AIRFRAMETYPE_OCTOCOAXX; + + channels[0].type = MIXER_TYPE_MOTOR; + channels[0].throttle1 = 100; + channels[0].throttle2 = 0; + channels[0].roll = 50; + channels[0].pitch = 50; + channels[0].yaw = -50; + + channels[1].type = MIXER_TYPE_MOTOR; + channels[1].throttle1 = 100; + channels[1].throttle2 = 0; + channels[1].roll = 50; + channels[1].pitch = 50; + channels[1].yaw = 50; + + channels[2].type = MIXER_TYPE_MOTOR; + channels[2].throttle1 = 100; + channels[2].throttle2 = 0; + channels[2].roll = -50; + channels[2].pitch = 50; + channels[2].yaw = -50; + + channels[3].type = MIXER_TYPE_MOTOR; + channels[3].throttle1 = 100; + channels[3].throttle2 = 0; + channels[3].roll = -50; + channels[3].pitch = 50; + channels[3].yaw = 50; + + channels[4].type = MIXER_TYPE_MOTOR; + channels[4].throttle1 = 100; + channels[4].throttle2 = 0; + channels[4].roll = -50; + channels[4].pitch = -50; + channels[4].yaw = -50; + + channels[5].type = MIXER_TYPE_MOTOR; + channels[5].throttle1 = 100; + channels[5].throttle2 = 0; + channels[5].roll = -50; + channels[5].pitch = -50; + channels[5].yaw = 50; + + channels[6].type = MIXER_TYPE_MOTOR; + channels[6].throttle1 = 100; + channels[6].throttle2 = 0; + channels[6].roll = 50; + channels[6].pitch = -50; + channels[6].yaw = -50; + + channels[7].type = MIXER_TYPE_MOTOR; + channels[7].throttle1 = 100; + channels[7].throttle2 = 0; + channels[7].roll = 50; + channels[7].pitch = -50; + channels[7].yaw = 50; + + guiSettings.multi.VTOLMotorNW = 1; + guiSettings.multi.VTOLMotorN = 2; + guiSettings.multi.VTOLMotorNE = 3; + guiSettings.multi.VTOLMotorE = 4; + guiSettings.multi.VTOLMotorSE = 5; + guiSettings.multi.VTOLMotorS = 6; + guiSettings.multi.VTOLMotorSW = 7; + guiSettings.multi.VTOLMotorW = 8; + + break; + } + case VehicleConfigurationSource::MULTI_ROTOR_OCTO_COAX_PLUS: { + frame = SystemSettings::AIRFRAMETYPE_OCTOCOAXP; + + channels[0].type = MIXER_TYPE_MOTOR; + channels[0].throttle1 = 100; + channels[0].throttle2 = 0; + channels[0].roll = 0; + channels[0].pitch = 100; + channels[0].yaw = -50; + + channels[1].type = MIXER_TYPE_MOTOR; + channels[1].throttle1 = 100; + channels[1].throttle2 = 0; + channels[1].roll = 0; + channels[1].pitch = 100; + channels[1].yaw = 50; + + channels[2].type = MIXER_TYPE_MOTOR; + channels[2].throttle1 = 100; + channels[2].throttle2 = 0; + channels[2].roll = -100; + channels[2].pitch = 0; + channels[2].yaw = -50; + + channels[3].type = MIXER_TYPE_MOTOR; + channels[3].throttle1 = 100; + channels[3].throttle2 = 0; + channels[3].roll = -100; + channels[3].pitch = 0; + channels[3].yaw = 50; + + channels[4].type = MIXER_TYPE_MOTOR; + channels[4].throttle1 = 100; + channels[4].throttle2 = 0; + channels[4].roll = 0; + channels[4].pitch = -100; + channels[4].yaw = -50; + + channels[5].type = MIXER_TYPE_MOTOR; + channels[5].throttle1 = 100; + channels[5].throttle2 = 0; + channels[5].roll = 0; + channels[5].pitch = -100; + channels[5].yaw = 50; + + channels[6].type = MIXER_TYPE_MOTOR; + channels[6].throttle1 = 100; + channels[6].throttle2 = 0; + channels[6].roll = 100; + channels[6].pitch = 0; + channels[6].yaw = -50; + + channels[7].type = MIXER_TYPE_MOTOR; + channels[7].throttle1 = 100; + channels[7].throttle2 = 0; + channels[7].roll = 100; + channels[7].pitch = 0; + channels[7].yaw = 50; + + guiSettings.multi.VTOLMotorN = 1; + guiSettings.multi.VTOLMotorNE = 2; + guiSettings.multi.VTOLMotorE = 3; + guiSettings.multi.VTOLMotorSE = 4; + guiSettings.multi.VTOLMotorS = 5; + guiSettings.multi.VTOLMotorSW = 6; + guiSettings.multi.VTOLMotorW = 7; + guiSettings.multi.VTOLMotorNW = 8; + + break; + } + case VehicleConfigurationSource::MULTI_ROTOR_OCTO_V: { + frame = SystemSettings::AIRFRAMETYPE_OCTOV; + channels[0].type = MIXER_TYPE_MOTOR; + channels[0].throttle1 = 100; + channels[0].throttle2 = 0; + channels[0].roll = -25; + channels[0].pitch = 8; + channels[0].yaw = -25; + + channels[1].type = MIXER_TYPE_MOTOR; + channels[1].throttle1 = 100; + channels[1].throttle2 = 0; + channels[1].roll = -25; + channels[1].pitch = 25; + channels[1].yaw = 25; + + channels[2].type = MIXER_TYPE_MOTOR; + channels[2].throttle1 = 100; + channels[2].throttle2 = 0; + channels[2].roll = -25; + channels[2].pitch = -25; + channels[2].yaw = -25; + + channels[3].type = MIXER_TYPE_MOTOR; + channels[3].throttle1 = 100; + channels[3].throttle2 = 0; + channels[3].roll = -25; + channels[3].pitch = -8; + channels[3].yaw = 25; + + channels[4].type = MIXER_TYPE_MOTOR; + channels[4].throttle1 = 100; + channels[4].throttle2 = 0; + channels[4].roll = 25; + channels[4].pitch = -8; + channels[4].yaw = -25; + + channels[5].type = MIXER_TYPE_MOTOR; + channels[5].throttle1 = 100; + channels[5].throttle2 = 0; + channels[5].roll = 25; + channels[5].pitch = -25; + channels[5].yaw = 25; + + channels[6].type = MIXER_TYPE_MOTOR; + channels[6].throttle1 = 100; + channels[6].throttle2 = 0; + channels[6].roll = 25; + channels[6].pitch = 25; + channels[6].yaw = -25; + + channels[7].type = MIXER_TYPE_MOTOR; + channels[7].throttle1 = 100; + channels[7].throttle2 = 0; + channels[7].roll = 25; + channels[7].pitch = 8; + channels[7].yaw = 25; + + guiSettings.multi.VTOLMotorN = 1; + guiSettings.multi.VTOLMotorNE = 2; + guiSettings.multi.VTOLMotorE = 3; + guiSettings.multi.VTOLMotorSE = 4; + guiSettings.multi.VTOLMotorS = 5; + guiSettings.multi.VTOLMotorSW = 6; + guiSettings.multi.VTOLMotorW = 7; + guiSettings.multi.VTOLMotorNW = 8; + + break; + } + default: + break; + } + + applyMixerConfiguration(channels); + applyMultiGUISettings(frame, guiSettings); +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h new file mode 100644 index 000000000..44f2125b1 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h @@ -0,0 +1,115 @@ +/** + ****************************************************************************** + * + * @file vehicleconfigurationhelper.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup VehicleConfigurationHelper + * @{ + * @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 VEHICLECONFIGURATIONHELPER_H +#define VEHICLECONFIGURATIONHELPER_H + +#include +#include +#include "vehicleconfigurationsource.h" +#include "uavobjectmanager.h" +#include "systemsettings.h" +#include "cfg_vehicletypes/vehicleconfig.h" +#include "actuatorsettings.h" + +struct mixerChannelSettings { + int type; + int throttle1; + int throttle2; + int roll; + int pitch; + int yaw; + + mixerChannelSettings() : type(), throttle1(), throttle2(), roll(), pitch(), yaw() {} + + mixerChannelSettings(int t, int th1, int th2, int r, int p, int y) + : type(t), throttle1(th1), throttle2(th2), roll(r), pitch(p), yaw(y) {} +}; + +class VehicleConfigurationHelper : public QObject +{ + Q_OBJECT + +public: + VehicleConfigurationHelper(VehicleConfigurationSource* configSource); + bool setupVehicle(bool save = true); + bool setupHardwareSettings(bool save = true); + static const qint16 LEGACY_ESC_FREQUENCE; + static const qint16 RAPID_ESC_FREQUENCE; + +signals: + void saveProgress(int total, int current, QString description); + +private: + static const int MIXER_TYPE_DISABLED = 0; + static const int MIXER_TYPE_MOTOR = 1; + static const int MIXER_TYPE_SERVO = 2; + + VehicleConfigurationSource *m_configSource; + UAVObjectManager *m_uavoManager; + + QList* > m_modifiedObjects; + void addModifiedObject(UAVDataObject* object, QString description); + void clearModifiedObjects(); + + void applyHardwareConfiguration(); + void applyVehicleConfiguration(); + void applyActuatorConfiguration(); + void applyFlighModeConfiguration(); + void applyLevellingConfiguration(); + void applyStabilizationConfiguration(); + void applyManualControlDefaults(); + + void applyMixerConfiguration(mixerChannelSettings channels[]); + + GUIConfigDataUnion getGUIConfigData(); + void applyMultiGUISettings(SystemSettings::AirframeTypeOptions airframe, GUIConfigDataUnion guiConfig); + + bool saveChangesToController(bool save); + QEventLoop m_eventLoop; + bool m_transactionOK; + bool m_transactionTimeout; + int m_currentTransactionObjectID; + int m_progress; + + void resetVehicleConfig(); + void resetGUIData(); + + void setupTriCopter(); + void setupQuadCopter(); + void setupHexaCopter(); + void setupOctoCopter(); + +private slots: + void uAVOTransactionCompleted(UAVObject* object, bool success); + void uAVOTransactionCompleted(int oid, bool success); + void saveChangesTimeout(); + + +}; + +#endif // VEHICLECONFIGURATIONHELPER_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.cpp new file mode 100644 index 000000000..3acb2400d --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.cpp @@ -0,0 +1,32 @@ +/** + ****************************************************************************** + * + * @file vehicleconfigurationsource.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup VehicleConfigurationSource + * @{ + * @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 + */ + +#include "vehicleconfigurationsource.h" + +VehicleConfigurationSource::VehicleConfigurationSource() +{ +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h new file mode 100644 index 000000000..5e36902e9 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h @@ -0,0 +1,85 @@ +/** + ****************************************************************************** + * + * @file vehicleconfigurationsource.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup + * @{ + * @addtogroup VehicleConfigurationSource + * @{ + * @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 VEHICLECONFIGURATIONSOURCE_H +#define VEHICLECONFIGURATIONSOURCE_H + +#include +#include "actuatorsettings.h" + +struct accelGyroBias { + float m_accelerometerXBias; + float m_accelerometerYBias; + float m_accelerometerZBias; + + float m_gyroXBias; + float m_gyroYBias; + float m_gyroZBias; +}; + +struct actuatorChannelSettings { + quint16 channelMin; + quint16 channelNeutral; + quint16 channelMax; + + //Default values + actuatorChannelSettings(): channelMin(1000), channelNeutral(1000), channelMax(1900) {} +}; + + +class VehicleConfigurationSource +{ +public: + VehicleConfigurationSource(); + + enum CONTROLLER_TYPE {CONTROLLER_UNKNOWN, CONTROLLER_CC, CONTROLLER_CC3D, CONTROLLER_REVO, CONTROLLER_PIPX}; + enum VEHICLE_TYPE {VEHICLE_UNKNOWN, VEHICLE_MULTI, VEHICLE_FIXEDWING, VEHICLE_HELI, VEHICLE_SURFACE}; + enum VEHICLE_SUB_TYPE {MULTI_ROTOR_UNKNOWN, MULTI_ROTOR_TRI_Y, MULTI_ROTOR_QUAD_X, MULTI_ROTOR_QUAD_PLUS, + MULTI_ROTOR_HEXA, MULTI_ROTOR_HEXA_H, MULTI_ROTOR_HEXA_COAX_Y, MULTI_ROTOR_OCTO, + MULTI_ROTOR_OCTO_V, MULTI_ROTOR_OCTO_COAX_X, MULTI_ROTOR_OCTO_COAX_PLUS, FIXED_WING_AILERON, + FIXED_WING_VTAIL, HELI_CCPM}; + enum ESC_TYPE {ESC_RAPID, ESC_LEGACY, ESC_UNKNOWN}; + enum INPUT_TYPE {INPUT_PWM, INPUT_PPM, INPUT_SBUS, INPUT_DSMX10, INPUT_DSMX11, INPUT_DSM2, INPUT_UNKNOWN}; + + virtual VehicleConfigurationSource::CONTROLLER_TYPE getControllerType() const = 0; + virtual VehicleConfigurationSource::VEHICLE_TYPE getVehicleType() const = 0; + virtual VehicleConfigurationSource::VEHICLE_SUB_TYPE getVehicleSubType() const = 0; + virtual VehicleConfigurationSource::INPUT_TYPE getInputType() const = 0; + virtual VehicleConfigurationSource::ESC_TYPE getESCType() const = 0; + + virtual bool isLevellingPerformed() const = 0; + virtual accelGyroBias getLevellingBias() const = 0; + + virtual bool isMotorCalibrationPerformed() const = 0; + virtual QList getActuatorSettings() const = 0; + + virtual bool isRestartNeeded() const = 0; + + virtual QString getSummaryText() = 0; +}; + +#endif // VEHICLECONFIGURATIONSOURCE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc b/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc new file mode 100644 index 000000000..1ee031d0e --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc @@ -0,0 +1,42 @@ + + + resources/bttn-heli-down.png + resources/bttn-heli-over.png + resources/bttn-heli-up.png + resources/bttn-land-down.png + resources/bttn-land-over.png + resources/bttn-land-up.png + resources/bttn-multi-down.png + resources/bttn-multi-over.png + resources/bttn-multi-up.png + resources/bttn-plane-down.png + resources/bttn-plane-over.png + resources/bttn-plane-up.png + resources/bttn-ESC-down.png + resources/bttn-ESC-up.png + resources/bttn-ppm-down.png + resources/bttn-ppm-up.png + resources/bttn-pwm-down.png + resources/bttn-pwm-up.png + resources/bttn-sat-down.png + resources/bttn-sat-up.png + resources/bttn-sbus-down.png + resources/bttn-sbus-up.png + resources/bttn-txwizard-off.png + resources/bttn-txwizard-on.png + resources/connection-diagrams.svg + resources/bttn-calculate-down.png + resources/bttn-calculate-up.png + resources/bttn-turbo-down.png + resources/bttn-turbo-up.png + resources/multirotor-shapes.svg + resources/bttn-illustration-down.png + resources/bttn-illustration-up.png + resources/bttn-save-down.png + resources/bttn-save-up.png + resources/bttn-flash-down.png + resources/bttn-flash-up.png + resources/bttn-upgrade-down.png + resources/bttn-upgrade-up.png + + diff --git a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowseroptionspage.ui b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowseroptionspage.ui index 350fc440b..5ecef3160 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowseroptionspage.ui +++ b/ground/openpilotgcs/src/plugins/uavobjectbrowser/uavobjectbrowseroptionspage.ui @@ -6,120 +6,151 @@ 0 0 - 400 - 300 + 482 + 194 Form - - - - - Recently updated color: + + + 0 + + + + + QFrame::NoFrame - - - - - - Manually changed color: + + QFrame::Plain - - - - - - Recently updated timeout (ms): - - - - - - - Qt::Horizontal - - - - 0 - 20 - - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - 0 - 0 - - - - - 64 - 0 - - - - - - - - - - - - 0 - 0 - - - - - 64 - 0 - - - - - - - - - - - - 0 - 0 - - - - 100000000 - - - 100 - - - - - - - Only hilight nodes when value actually changes + + true + + + + 0 + 0 + 482 + 194 + + + + + 0 + + + + + Recently updated color: + + + + + + + + 0 + 0 + + + + + 64 + 0 + + + + + + + + + + + Manually changed color: + + + + + + + + 0 + 0 + + + + + 64 + 0 + + + + + + + + + + + Qt::Horizontal + + + + 0 + 20 + + + + + + + + Recently updated timeout (ms): + + + + + + + + 0 + 0 + + + + 100000000 + + + 100 + + + + + + + Only highlight nodes when value actually changes + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro index c2515343d..1731678f6 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjects.pro @@ -27,6 +27,7 @@ HEADERS += $$UAVOBJECT_SYNTHETICS/accessorydesired.h \ $$UAVOBJECT_SYNTHETICS/baroaltitude.h \ $$UAVOBJECT_SYNTHETICS/baroairspeed.h \ $$UAVOBJECT_SYNTHETICS/airspeedsettings.h \ + $$UAVOBJECT_SYNTHETICS/airspeedactual.h \ $$UAVOBJECT_SYNTHETICS/attitudeactual.h \ $$UAVOBJECT_SYNTHETICS/attitudesimulated.h \ $$UAVOBJECT_SYNTHETICS/altholdsmoothed.h \ @@ -104,6 +105,7 @@ SOURCES += $$UAVOBJECT_SYNTHETICS/accessorydesired.cpp \ $$UAVOBJECT_SYNTHETICS/baroaltitude.cpp \ $$UAVOBJECT_SYNTHETICS/baroairspeed.cpp \ $$UAVOBJECT_SYNTHETICS/airspeedsettings.cpp \ + $$UAVOBJECT_SYNTHETICS/airspeedactual.cpp \ $$UAVOBJECT_SYNTHETICS/attitudeactual.cpp \ $$UAVOBJECT_SYNTHETICS/attitudesimulated.cpp \ $$UAVOBJECT_SYNTHETICS/altholdsmoothed.cpp \ diff --git a/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp b/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp index bacadeb73..240a2fc94 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp @@ -449,6 +449,18 @@ bool UAVObjectUtilManager::descriptionToStructure(QByteArray desc, deviceDescrip struc.fwHash=desc.mid(40,20); struc.uavoHash.clear(); struc.uavoHash=desc.mid(60,20); + qDebug()<<__FUNCTION__<<":description from board:"; + foreach(char x,desc) + { + qDebug()<lblGitTag->setText(onBoardDescription.gitHash); myDevice->lblBuildDate->setText(onBoardDescription.gitDate.insert(4,"-").insert(7,"-")); - if(onBoardDescription.gitTag.startsWith("release",Qt::CaseInsensitive)) + if (onBoardDescription.gitTag.compare("master") == 0) { myDevice->lblDescription->setText(QString("Firmware tag: ")+onBoardDescription.gitTag); QPixmap pix = QPixmap(QString(":uploader/images/application-certificate.svg")); @@ -188,7 +188,7 @@ bool deviceWidget::populateLoadedStructuredDescription(QByteArray desc) { myDevice->lblGitTagL->setText(LoadedDescription.gitHash); myDevice->lblBuildDateL->setText( LoadedDescription.gitDate.insert(4,"-").insert(7,"-")); - if(LoadedDescription.gitTag.startsWith("release",Qt::CaseInsensitive)) + if (LoadedDescription.gitTag.compare("master") == 0) { myDevice->lblDescritpionL->setText(LoadedDescription.gitTag); myDevice->description->setText(LoadedDescription.gitTag); @@ -302,7 +302,7 @@ void deviceWidget::loadFirmware() myDevice->statusLabel->setText(tr("The board has newer firmware than loaded. Are you sure you want to update?")); px.load(QString(":/uploader/images/warning.svg")); } - else if(!LoadedDescription.gitTag.startsWith("release",Qt::CaseInsensitive)) + else if (LoadedDescription.gitTag.compare("master")) { myDevice->statusLabel->setText(tr("The loaded firmware is untagged or custom build. Update only if it was received from a trusted source (official website or your own build)")); px.load(QString(":/uploader/images/warning.svg")); diff --git a/ground/openpilotgcs/src/plugins/uploader/devicewidget.h b/ground/openpilotgcs/src/plugins/uploader/devicewidget.h index d2eab8e28..eaf8c6a0f 100644 --- a/ground/openpilotgcs/src/plugins/uploader/devicewidget.h +++ b/ground/openpilotgcs/src/plugins/uploader/devicewidget.h @@ -42,8 +42,10 @@ #include "devicedescriptorstruct.h" #include #include +#include "uploader_global.h" + using namespace OP_DFU; -class deviceWidget : public QWidget +class UPLOADER_EXPORT deviceWidget : public QWidget { Q_OBJECT public: diff --git a/ground/openpilotgcs/src/plugins/uploader/enums.h b/ground/openpilotgcs/src/plugins/uploader/enums.h new file mode 100644 index 000000000..2c89bdf1d --- /dev/null +++ b/ground/openpilotgcs/src/plugins/uploader/enums.h @@ -0,0 +1,35 @@ +/** + ****************************************************************************** + * + * @file enums.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @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 ENUMS_H +#define ENUMS_H + +namespace uploader +{ + typedef enum { IAP_STATE_READY, IAP_STATE_STEP_1, IAP_STATE_STEP_2, IAP_STEP_RESET, IAP_STATE_BOOTLOADER} IAPStep; + typedef enum { WAITING_DISCONNECT, WAITING_CONNECT, JUMP_TO_BL, LOADING_FW, UPLOADING_FW, UPLOADING_DESC, BOOTING, SUCCESS, FAILURE} AutoUpdateStep; +} +#endif // ENUMS_H diff --git a/ground/openpilotgcs/src/plugins/uploader/images/gcs-board-cc.png b/ground/openpilotgcs/src/plugins/uploader/images/gcs-board-cc.png index c4e77c025..ee096b76e 100644 Binary files a/ground/openpilotgcs/src/plugins/uploader/images/gcs-board-cc.png and b/ground/openpilotgcs/src/plugins/uploader/images/gcs-board-cc.png differ diff --git a/ground/openpilotgcs/src/plugins/uploader/images/gcs-board-cc3d.png b/ground/openpilotgcs/src/plugins/uploader/images/gcs-board-cc3d.png index b9ad6fa4f..69fd4aa8c 100644 Binary files a/ground/openpilotgcs/src/plugins/uploader/images/gcs-board-cc3d.png and b/ground/openpilotgcs/src/plugins/uploader/images/gcs-board-cc3d.png differ diff --git a/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.cpp b/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.cpp index 284345b62..e7952101a 100644 --- a/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.cpp +++ b/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.cpp @@ -103,7 +103,7 @@ void runningDeviceWidget::populate() deviceDescriptorStruct devDesc; if(UAVObjectUtilManager::descriptionToStructure(description,devDesc)) { - if(devDesc.gitTag.startsWith("release",Qt::CaseInsensitive)) + if (devDesc.gitTag.compare("master") == 0) { myDevice->lblFWTag->setText(QString("Firmware tag: ")+devDesc.gitTag); QPixmap pix = QPixmap(QString(":uploader/images/application-certificate.svg")); diff --git a/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.h b/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.h index 58e9583c1..18b354cce 100644 --- a/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.h +++ b/ground/openpilotgcs/src/plugins/uploader/runningdevicewidget.h @@ -39,8 +39,9 @@ #include "uavobjectmanager.h" #include "uavobject.h" #include "uavobjectutilmanager.h" +#include "uploader_global.h" -class runningDeviceWidget : public QWidget +class UPLOADER_EXPORT runningDeviceWidget : public QWidget { Q_OBJECT public: diff --git a/ground/openpilotgcs/src/plugins/uploader/uploader.pri b/ground/openpilotgcs/src/plugins/uploader/uploader.pri new file mode 100644 index 000000000..8425d3649 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/uploader/uploader.pri @@ -0,0 +1,3 @@ +include(uploader_dependencies.pri) + +LIBS *= -l$$qtLibraryName(Uploader) diff --git a/ground/openpilotgcs/src/plugins/uploader/uploader.pro b/ground/openpilotgcs/src/plugins/uploader/uploader.pro index 05742868d..77a85e038 100755 --- a/ground/openpilotgcs/src/plugins/uploader/uploader.pro +++ b/ground/openpilotgcs/src/plugins/uploader/uploader.pro @@ -1,12 +1,8 @@ TEMPLATE = lib TARGET = Uploader +DEFINES += UPLOADER_LIBRARY QT += svg -include(../../openpilotgcsplugin.pri) -include(../../plugins/coreplugin/coreplugin.pri) -include(../../plugins/uavobjects/uavobjects.pri) -include(../../plugins/uavtalk/uavtalk.pri) -include(../../plugins/rawhid/rawhid.pri) -include(../../plugins/uavobjectutil/uavobjectutil.pri) +include(uploader_dependencies.pri) INCLUDEPATH += ../../libs/qextserialport/src HEADERS += uploadergadget.h \ @@ -22,7 +18,9 @@ HEADERS += uploadergadget.h \ SSP/qssp.h \ SSP/qsspt.h \ SSP/common.h \ - runningdevicewidget.h + runningdevicewidget.h \ + uploader_global.h \ + enums.h SOURCES += uploadergadget.cpp \ uploadergadgetconfiguration.cpp \ uploadergadgetfactory.cpp \ @@ -36,7 +34,7 @@ SOURCES += uploadergadget.cpp \ SSP/qssp.cpp \ SSP/qsspt.cpp \ runningdevicewidget.cpp -OTHER_FILES += Uploader.pluginspec +OTHER_FILES += Uploader.pluginspec \ FORMS += \ uploader.ui \ @@ -45,3 +43,6 @@ FORMS += \ RESOURCES += \ uploader.qrc +exists( ../../../../../build/ground/opfw_resource/opfw_resource.qrc ) { +RESOURCES += ../../../../build/ground/opfw_resource/opfw_resource.qrc +} diff --git a/ground/openpilotgcs/src/plugins/uploader/uploader.ui b/ground/openpilotgcs/src/plugins/uploader/uploader.ui index 06c62f147..397573535 100644 --- a/ground/openpilotgcs/src/plugins/uploader/uploader.ui +++ b/ground/openpilotgcs/src/plugins/uploader/uploader.ui @@ -6,7 +6,7 @@ 0 0 - 583 + 822 350 @@ -186,14 +186,14 @@ halting a running board.
<!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:'MS Shell Dlg 2'; font-size:8.25pt; 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-family:'Ubuntu'; font-size:11pt;">To upgrade the firmware in your boards, proceed as follows:</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">- Connect telemetry</span></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">- Once telemetry is running, press &quot;Halt&quot; above</span></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">- You will get a list of devices.</span></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">- You can then upload/download to/from each board as you wish</span></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Ubuntu'; font-size:11pt;">- You can resume operations by pressing &quot;Boot&quot;</span></p></body></html> +</style></head><body style=" font-family:'Ubuntu'; font-size:11pt; 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;">To upgrade the firmware in your boards, proceed as follows:</p> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">- Connect telemetry</p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">- Once telemetry is running, press &quot;Halt&quot; above</p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">- You will get a list of devices.</p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">- You can then upload/download to/from each board as you wish</p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;">- You can resume operations by pressing &quot;Boot&quot;</p></body></html>
@@ -208,8 +208,8 @@ p, li { white-space: pre-wrap; } <!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:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;"> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Ubuntu'; font-size:11pt;"></p></body></html> +</style></head><body style=" font-family:'Ubuntu'; font-size:11pt; font-weight:400; font-style:normal;"> +<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"></p></body></html>
@@ -217,7 +217,7 @@ p, li { white-space: pre-wrap; } - + diff --git a/ground/openpilotgcs/src/plugins/uploader/uploader_dependencies.pri b/ground/openpilotgcs/src/plugins/uploader/uploader_dependencies.pri new file mode 100644 index 000000000..b85fc46a1 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/uploader/uploader_dependencies.pri @@ -0,0 +1,6 @@ +include(../../openpilotgcsplugin.pri) +include(../../plugins/coreplugin/coreplugin.pri) +include(../../plugins/uavobjects/uavobjects.pri) +include(../../plugins/uavtalk/uavtalk.pri) +include(../../plugins/rawhid/rawhid.pri) +include(../../plugins/uavobjectutil/uavobjectutil.pri) diff --git a/ground/openpilotgcs/src/plugins/uploader/uploader_global.h b/ground/openpilotgcs/src/plugins/uploader/uploader_global.h new file mode 100644 index 000000000..ee74a7bac --- /dev/null +++ b/ground/openpilotgcs/src/plugins/uploader/uploader_global.h @@ -0,0 +1,40 @@ +/** + ****************************************************************************** + * + * @file uploader_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 UPLOADER_GLOBAL_H +#define UPLOADER_GLOBAL_H + +#include + +#if defined(UPLOADER_LIBRARY) +# define UPLOADER_EXPORT Q_DECL_EXPORT +#else +# define UPLOADER_EXPORT Q_DECL_IMPORT +#endif + +#endif diff --git a/ground/openpilotgcs/src/plugins/uploader/uploadergadget.h b/ground/openpilotgcs/src/plugins/uploader/uploadergadget.h index f698c81ea..369756a0b 100755 --- a/ground/openpilotgcs/src/plugins/uploader/uploadergadget.h +++ b/ground/openpilotgcs/src/plugins/uploader/uploadergadget.h @@ -30,6 +30,7 @@ #include #include "uploadergadgetwidget.h" +#include "uploader_global.h" class IUAVGadget; class QWidget; @@ -38,7 +39,7 @@ class UploaderGadgetWidget; using namespace Core; -class UploaderGadget : public Core::IUAVGadget +class UPLOADER_EXPORT UploaderGadget : public Core::IUAVGadget { Q_OBJECT public: diff --git a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetconfiguration.h b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetconfiguration.h index 274a73fab..99a8e1ea7 100755 --- a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetconfiguration.h +++ b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetconfiguration.h @@ -30,10 +30,11 @@ #include #include +#include "uploader_global.h" using namespace Core; -class UploaderGadgetConfiguration : public IUAVGadgetConfiguration +class UPLOADER_EXPORT UploaderGadgetConfiguration : public IUAVGadgetConfiguration { Q_OBJECT public: diff --git a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetfactory.cpp b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetfactory.cpp index 692985e5c..a9da79d86 100755 --- a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetfactory.cpp +++ b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetfactory.cpp @@ -26,14 +26,14 @@ */ #include "uploadergadgetfactory.h" -#include "uploadergadgetwidget.h" #include "uploadergadget.h" #include "uploadergadgetconfiguration.h" #include "uploadergadgetoptionspage.h" #include +#include "uploadergadgetwidget.h" UploaderGadgetFactory::UploaderGadgetFactory(QObject *parent) : - IUAVGadgetFactory(QString("Uploader"), tr("Uploader"), parent) + IUAVGadgetFactory(QString("Uploader"), tr("Uploader"), parent),isautocapable(false) { } @@ -44,6 +44,9 @@ UploaderGadgetFactory::~UploaderGadgetFactory() Core::IUAVGadget* UploaderGadgetFactory::createGadget(QWidget *parent) { UploaderGadgetWidget* gadgetWidget = new UploaderGadgetWidget(parent); + isautocapable=gadgetWidget->autoUpdateCapable(); + connect(this,SIGNAL(autoUpdate()),gadgetWidget,SLOT(autoUpdate())); + connect(gadgetWidget,SIGNAL(autoUpdateSignal(uploader::AutoUpdateStep,QVariant)),this,SIGNAL(autoUpdateSignal(uploader::AutoUpdateStep,QVariant))); return new UploaderGadget(QString("Uploader"), gadgetWidget, parent); } @@ -51,4 +54,7 @@ IUAVGadgetConfiguration *UploaderGadgetFactory::createConfiguration(QSettings* q { return new UploaderGadgetConfiguration(QString("Uploader"), qSettings); } - +bool UploaderGadgetFactory::isAutoUpdateCapable() +{ + return isautocapable; +} diff --git a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetfactory.h b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetfactory.h index c836287b1..05fc83029 100755 --- a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetfactory.h +++ b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetfactory.h @@ -29,7 +29,8 @@ #define UPLOADERGADGETFACTORY_H #include - +#include "uploader_global.h" +#include "enums.h" namespace Core { class IUAVGadget; class IUAVGadgetFactory; @@ -37,7 +38,7 @@ class IUAVGadgetFactory; using namespace Core; -class UploaderGadgetFactory : public Core::IUAVGadgetFactory +class UPLOADER_EXPORT UploaderGadgetFactory : public Core::IUAVGadgetFactory { Q_OBJECT public: @@ -46,6 +47,12 @@ public: Core::IUAVGadget *createGadget(QWidget *parent); IUAVGadgetConfiguration *createConfiguration(QSettings* qSettings); + bool isAutoUpdateCapable(); +private: + bool isautocapable; +signals: + void autoUpdateSignal(uploader::AutoUpdateStep,QVariant); + void autoUpdate(); }; #endif // UPLOADERGADGETFACTORY_H diff --git a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetoptionspage.h b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetoptionspage.h index e9df9bd07..16b05962e 100755 --- a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetoptionspage.h +++ b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetoptionspage.h @@ -32,6 +32,7 @@ #include "QString" #include #include +#include "uploader_global.h" namespace Core { class IUAVGadgetConfiguration; @@ -43,7 +44,7 @@ class QSpinBox; using namespace Core; -class UploaderGadgetOptionsPage : public IOptionsPage +class UPLOADER_EXPORT UploaderGadgetOptionsPage : public IOptionsPage { Q_OBJECT public: diff --git a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp index 314914667..715b237b7 100755 --- a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.cpp @@ -71,8 +71,6 @@ UploaderGadgetWidget::UploaderGadgetWidget(QWidget *parent) : QWidget(parent) onAutopilotConnect(); versionMatchCheck(); } - - } @@ -434,6 +432,134 @@ void UploaderGadgetWidget::commonSystemBoot(bool safeboot) delete dfu; // Frees up the USB/Serial port too dfu = NULL; } +bool UploaderGadgetWidget::autoUpdateCapable() +{ + return QDir(":/build").exists(); +} + +bool UploaderGadgetWidget::autoUpdate() +{ + Core::ConnectionManager *cm = Core::ICore::instance()->connectionManager(); + cm->disconnectDevice(); + cm->suspendPolling(); + if (dfu) { + delete dfu; + dfu = NULL; + } + QEventLoop loop; + QTimer timer; + timer.setSingleShot(true); + connect(&timer,SIGNAL(timeout()),&loop,SLOT(quit())); + while(USBMonitor::instance()->availableDevices(0x20a0,-1,-1,-1).length()>0) + { + emit autoUpdateSignal(WAITING_DISCONNECT,QVariant()); + if(QMessageBox::warning(this,tr("OpenPilot Uploader"),tr("Please disconnect all openpilot boards"),QMessageBox::Ok,QMessageBox::Cancel)==QMessageBox::Cancel) + { + emit autoUpdateSignal(FAILURE,QVariant()); + return false; + } + timer.start(500); + loop.exec(); + } + emit autoUpdateSignal(WAITING_CONNECT,0); + autoUpdateConnectTimeout=0; + m_timer = new QTimer(this); + connect(m_timer, SIGNAL(timeout()), this, SLOT(performAuto())); + m_timer->start(1000); + connect(USBMonitor::instance(), SIGNAL(deviceDiscovered(USBPortInfo)),&m_eventloop, SLOT(quit())); + m_eventloop.exec(); + if(!m_timer->isActive()) + { + m_timer->stop(); + emit autoUpdateSignal(FAILURE,QVariant()); + return false; + } + m_timer->stop(); + dfu = new DFUObject(DFU_DEBUG, false, QString()); + dfu->AbortOperation(); + emit autoUpdateSignal(JUMP_TO_BL,QVariant()); + if(!dfu->enterDFU(0)) + { + delete dfu; + dfu = NULL; + cm->resumePolling(); + emit autoUpdateSignal(FAILURE,QVariant()); + return false; + } + if(!dfu->findDevices() || (dfu->numberOfDevices != 1)) + { + delete dfu; + dfu = NULL; + cm->resumePolling(); + emit autoUpdateSignal(FAILURE,QVariant()); + return false; + } + if (dfu->numberOfDevices > 5) { + delete dfu; + dfu = NULL; + cm->resumePolling(); + emit autoUpdateSignal(FAILURE,QVariant()); + return false; + } + QString filename; + emit autoUpdateSignal(LOADING_FW,QVariant()); + switch (dfu->devices[0].ID) + { + case 0x401: + filename="fw_coptercontrol"; + break; + case 0x402: + filename="fw_coptercontrol"; + break; + default: + emit autoUpdateSignal(FAILURE,QVariant()); + return false; + break; + } + filename=":/build/"+filename+"/"+filename+".opfw"; + QByteArray firmware; + if(!QFile::exists(filename)) + { + emit autoUpdateSignal(FAILURE,QVariant()); + return false; + } + QFile file(filename); + if (!file.open(QIODevice::ReadOnly)) { + emit autoUpdateSignal(FAILURE,QVariant()); + return false; + } + firmware = file.readAll(); + connect(dfu, SIGNAL(progressUpdated(int)), this, SLOT(autoUpdateProgress(int))); + connect(dfu, SIGNAL(uploadFinished(OP_DFU::Status)), &m_eventloop, SLOT(quit())); + emit autoUpdateSignal(UPLOADING_FW,QVariant()); + if(!dfu->enterDFU(0)) + { + emit autoUpdateSignal(FAILURE,QVariant()); + return false; + } + dfu->AbortOperation(); + if(!dfu->UploadFirmware(filename,false,0)) + { + emit autoUpdateSignal(FAILURE,QVariant()); + return false; + } + m_eventloop.exec(); + QByteArray desc = firmware.right(100); + emit autoUpdateSignal(UPLOADING_DESC,QVariant()); + if(dfu->UploadDescription(desc)!= OP_DFU::Last_operation_Success) + { + emit autoUpdateSignal(FAILURE,QVariant()); + return false; + } + systemBoot(); + emit autoUpdateSignal(SUCCESS,QVariant()); + return true; +} + +void UploaderGadgetWidget::autoUpdateProgress(int value) +{ + emit autoUpdateSignal(UPLOADING_FW,value); +} /** Attempt a guided procedure to put both boards in BL mode when @@ -558,6 +684,17 @@ void UploaderGadgetWidget::perform() } m_progress->setValue(m_progress->value()+1); } +void UploaderGadgetWidget::performAuto() +{ + ++autoUpdateConnectTimeout; + emit autoUpdateSignal(WAITING_CONNECT,autoUpdateConnectTimeout*5); + if(autoUpdateConnectTimeout==20) + { + m_timer->stop(); + m_eventloop.exit(); + } + +} void UploaderGadgetWidget::cancel() { m_timer->stop(); @@ -679,15 +816,16 @@ void UploaderGadgetWidget::versionMatchCheck() { gcsUavoHashStr.append(QString::number(i,16).right(2)); } - QString gcsVersion = gcsGitDate + " (" + gcsGitHash + "-"+ gcsUavoHashStr.right(8) + ")"; - QString fwVersion = boardDescription.gitDate + " (" + boardDescription.gitHash + "-" + fwUavoHashStr.right(8) + ")"; + QString gcsVersion = gcsGitDate + " (" + gcsGitHash + "-"+ gcsUavoHashStr.left(8) + ")"; + QString fwVersion = boardDescription.gitDate + " (" + boardDescription.gitHash + "-" + fwUavoHashStr.left(8) + ")"; QString warning = QString(tr( "GCS and firmware versions of the UAV objects set do not match which can cause configuration problems. " "GCS version: %1 Firmware version: %2.")).arg(gcsVersion).arg(fwVersion); msg->showMessage(warning); } - } +} + void UploaderGadgetWidget::openHelp() { diff --git a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.h b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.h index 5f5706381..67b988a38 100755 --- a/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.h +++ b/ground/openpilotgcs/src/plugins/uploader/uploadergadgetwidget.h @@ -56,11 +56,12 @@ #include #include #include - +#include "uploader_global.h" +#include "enums.h" using namespace OP_DFU; +using namespace uploader; - -class UploaderGadgetWidget : public QWidget +class UPLOADER_EXPORT UploaderGadgetWidget : public QWidget { Q_OBJECT @@ -68,14 +69,17 @@ class UploaderGadgetWidget : public QWidget public: UploaderGadgetWidget(QWidget *parent = 0); ~UploaderGadgetWidget(); - typedef enum { IAP_STATE_READY, IAP_STATE_STEP_1, IAP_STATE_STEP_2, IAP_STEP_RESET, IAP_STATE_BOOTLOADER} IAPStep; void log(QString str); - + bool autoUpdateCapable(); public slots: void onAutopilotConnect(); void onAutopilotDisconnect(); void populate(); void openHelp(); + bool autoUpdate(); + void autoUpdateProgress(int); +signals: + void autoUpdateSignal(uploader::AutoUpdateStep,QVariant); private: Ui_UploaderWidget *m_config; DFUObject *dfu; @@ -89,6 +93,7 @@ private: QEventLoop m_eventloop; QErrorMessage * msg; void connectSignalSlot(QWidget * widget); + int autoUpdateConnectTimeout; private slots: void onPhisicalHWConnect(); void versionMatchCheck(); @@ -102,6 +107,7 @@ private slots: void systemRescue(); void getSerialPorts(); void perform(); + void performAuto(); void cancel(); void uploadStarted(); void uploadEnded(bool succeed); diff --git a/ground/openpilotgcs/src/plugins/uploader/uploaderplugin.h b/ground/openpilotgcs/src/plugins/uploader/uploaderplugin.h index 33a5c0e9a..253ea9049 100755 --- a/ground/openpilotgcs/src/plugins/uploader/uploaderplugin.h +++ b/ground/openpilotgcs/src/plugins/uploader/uploaderplugin.h @@ -29,10 +29,11 @@ #define UPLOADERPLUGIN_H #include +#include "uploader_global.h" class UploaderGadgetFactory; -class UploaderPlugin : public ExtensionSystem::IPlugin +class UPLOADER_EXPORT UploaderPlugin : public ExtensionSystem::IPlugin { public: UploaderPlugin(); diff --git a/ground/openpilotgcs/src/plugins/welcome/qml/WelcomePageButton.qml b/ground/openpilotgcs/src/plugins/welcome/qml/WelcomePageButton.qml index 4874022be..9e5c1a74f 100644 --- a/ground/openpilotgcs/src/plugins/welcome/qml/WelcomePageButton.qml +++ b/ground/openpilotgcs/src/plugins/welcome/qml/WelcomePageButton.qml @@ -4,7 +4,7 @@ import QtQuick 1.1 Item { id: welcomeButton width: Math.max(116, icon.width) - height: 116 + height: icon.height z: 0 property string baseIconName diff --git a/ground/openpilotgcs/src/plugins/welcome/qml/images/wizard-off.png b/ground/openpilotgcs/src/plugins/welcome/qml/images/wizard-off.png new file mode 100644 index 000000000..6e00e1526 Binary files /dev/null and b/ground/openpilotgcs/src/plugins/welcome/qml/images/wizard-off.png differ diff --git a/ground/openpilotgcs/src/plugins/welcome/qml/images/wizard-on.png b/ground/openpilotgcs/src/plugins/welcome/qml/images/wizard-on.png new file mode 100644 index 000000000..0f85087b3 Binary files /dev/null and b/ground/openpilotgcs/src/plugins/welcome/qml/images/wizard-on.png differ diff --git a/ground/openpilotgcs/src/plugins/welcome/qml/main.qml b/ground/openpilotgcs/src/plugins/welcome/qml/main.qml index f2f2a302c..dc88c42bc 100644 --- a/ground/openpilotgcs/src/plugins/welcome/qml/main.qml +++ b/ground/openpilotgcs/src/plugins/welcome/qml/main.qml @@ -24,27 +24,6 @@ Rectangle { smooth: true } - Column { - id: wizarButtonsColumn - - anchors { - top: parent.top - right: parent.right - margins: 8 - } - spacing: 8 - - WelcomePageButton { - baseIconName: "bttn-vehwizard" - onClicked: welcomePlugin.openPage("VehWizard") - } - - WelcomePageButton { - baseIconName: "bttn-txwizard" - onClicked: welcomePlugin.openPage("TxWizard") - } - } - Column { id: buttonsGrid @@ -58,8 +37,7 @@ Rectangle { Row { //if the buttons grid overlaps vertically with the wizard buttons, //move it left to use only the space left to wizard buttons - property real availableWidth: buttonsGrid.y > wizarButtonsColumn.y+wizarButtonsColumn.height ? - container.width : wizarButtonsColumn.x + property real availableWidth: container.width x: (availableWidth-width)/2 spacing: 16 @@ -69,7 +47,7 @@ Rectangle { anchors.verticalCenterOffset: -2 //it looks better aligned to icons grid //hide the logo on the very small screen to fit the buttons - visible: parent.availableWidth > width + parent.spacing + buttons.width + visible: parent.availableWidth > width + parent.spacing + buttons.width + wizard.width } Grid { @@ -96,7 +74,7 @@ Rectangle { onClicked: welcomePlugin.openPage("System") } - WelcomePageButton { + WelcomePageButton { baseIconName: "scopes" label: "Scopes" onClicked: welcomePlugin.openPage("Scopes") @@ -114,6 +92,14 @@ Rectangle { onClicked: welcomePlugin.openPage("Firmware") } } //icons grid + + WelcomePageButton { + id: wizard + anchors.verticalCenter: parent.verticalCenter + baseIconName: "wizard" + onClicked: welcomePlugin.triggerAction("SetupWizardPlugin.ShowSetupWizard") + } + } // images row CommunityPanel { diff --git a/ground/openpilotgcs/src/plugins/welcome/welcome.qrc b/ground/openpilotgcs/src/plugins/welcome/welcome.qrc index 2fc8bf23c..5007edc6b 100644 --- a/ground/openpilotgcs/src/plugins/welcome/welcome.qrc +++ b/ground/openpilotgcs/src/plugins/welcome/welcome.qrc @@ -30,5 +30,7 @@ qml/images/bttn-txwizard-off.png qml/images/bttn-vehwizard-on.png qml/images/bttn-vehwizard-off.png + qml/images/wizard-off.png + qml/images/wizard-on.png diff --git a/ground/openpilotgcs/src/plugins/welcome/welcomemode.cpp b/ground/openpilotgcs/src/plugins/welcome/welcomemode.cpp index cf36b3036..a109f328a 100644 --- a/ground/openpilotgcs/src/plugins/welcome/welcomemode.cpp +++ b/ground/openpilotgcs/src/plugins/welcome/welcomemode.cpp @@ -92,7 +92,7 @@ QString WelcomeMode::name() const QIcon WelcomeMode::icon() const { - return QIcon(QLatin1String(":/core/images/openpilot_logo_64.png")); + return QIcon(QLatin1String(":/core/images/openpiloticon.png")); } int WelcomeMode::priority() const @@ -127,4 +127,9 @@ void WelcomeMode::openPage(const QString &page) Core::ModeManager::instance()->activateModeByWorkspaceName(page); } +void WelcomeMode::triggerAction(const QString &actionId) +{ + Core::ModeManager::instance()->triggerAction(actionId); +} + } // namespace Welcome diff --git a/ground/openpilotgcs/src/plugins/welcome/welcomemode.h b/ground/openpilotgcs/src/plugins/welcome/welcomemode.h index 24b47613e..c1b259552 100644 --- a/ground/openpilotgcs/src/plugins/welcome/welcomemode.h +++ b/ground/openpilotgcs/src/plugins/welcome/welcomemode.h @@ -65,6 +65,7 @@ public: public slots: void openUrl(const QString &url); void openPage(const QString &page); + void triggerAction(const QString &actionId); private: WelcomeModePrivate *m_d; diff --git a/hardware/Production/CopterControl 3D/Assembly.OutJob b/hardware/Production/CopterControl 3D/Assembly.OutJob new file mode 100644 index 000000000..620489b82 --- /dev/null +++ b/hardware/Production/CopterControl 3D/Assembly.OutJob @@ -0,0 +1,176 @@ +[OutputJobFile] +Version=1.0 + +[OutputGroup1] +Name=Assembly.OutJob +Description= +TargetOutputMedium=PDF +VariantName=[No Variations] +VariantScope=1 +CurrentConfigurationName= +TargetPrinter=Brother HL-2170W +PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1 +OutputMedium1=Print Job +OutputMedium1_Type=Printer +OutputMedium1_Printer= +OutputMedium1_PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1 +OutputMedium2=PDF +OutputMedium2_Type=Publish +OutputMedium3=Folder Structure +OutputMedium3_Type=GeneratedFiles +OutputMedium4=Video +OutputMedium4_Type=Multimedia +OutputType1=Assembly +OutputName1=Assembly Drawings +OutputCategory1=Assembly +OutputDocumentPath1=CopterControl 3D.PcbDoc +OutputVariantName1= +OutputEnabled1=1 +OutputEnabled1_OutputMedium1=0 +OutputEnabled1_OutputMedium2=1 +OutputEnabled1_OutputMedium3=0 +OutputEnabled1_OutputMedium4=0 +OutputDefault1=0 +PageOptions1=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=0|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +Configuration1_Name1=OutputConfigurationParameter1 +Configuration1_Item1=PrintArea=DesignExtent|PrintAreaLowerLeftCornerX=0|PrintAreaLowerLeftCornerY=0|PrintAreaUpperRightCornerX=0|PrintAreaUpperRightCornerY=0|Record=PcbPrintView +Configuration1_Name2=OutputConfigurationParameter2 +Configuration1_Item2=IncludeBottomLayerComponents=False|IncludeMultiLayerComponents=True|IncludeTopLayerComponents=True|Index=0|Mirror=False|Name=Top Assembly Drawing|PadNumberFontSize=14|Record=PcbPrintOut|ShowHoles=False|ShowPadNets=False|ShowPadNumbers=False|SubstituteFonts=True +Configuration1_Name3=OutputConfigurationParameter3 +Configuration1_Item3=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical6|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +Configuration1_Name4=OutputConfigurationParameter4 +Configuration1_Item4=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Hidden|FFill=Hidden|FPad=Hidden|FRegion=Hidden|FText=Hidden|FTrack=Hidden|FVia=Hidden|Layer=TopLayer|Polygon=Hidden|PrintOutIndex=0|Record=PcbPrintLayer +Configuration1_Name5=OutputConfigurationParameter5 +Configuration1_Item5=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=TopOverlay|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +Configuration1_Name6=OutputConfigurationParameter6 +Configuration1_Item6=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Hidden|Layer=MultiLayer|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +Configuration1_Name7=OutputConfigurationParameter7 +Configuration1_Item7=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical1|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +Configuration1_Name8=OutputConfigurationParameter8 +Configuration1_Item8=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical5|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +Configuration1_Name9=OutputConfigurationParameter9 +Configuration1_Item9=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical13|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +Configuration1_Name10=OutputConfigurationParameter10 +Configuration1_Item10=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical14|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +Configuration1_Name11=OutputConfigurationParameter11 +Configuration1_Item11=IncludeBottomLayerComponents=True|IncludeMultiLayerComponents=True|IncludeTopLayerComponents=False|Index=1|Mirror=True|Name=Bottom Assembly Drawing|PadNumberFontSize=14|Record=PcbPrintOut|ShowHoles=False|ShowPadNets=False|ShowPadNumbers=False|SubstituteFonts=True +Configuration1_Name12=OutputConfigurationParameter12 +Configuration1_Item12=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical7|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer +Configuration1_Name13=OutputConfigurationParameter13 +Configuration1_Item13=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Hidden|FFill=Hidden|FPad=Hidden|FRegion=Hidden|FText=Hidden|FTrack=Hidden|FVia=Hidden|Layer=BottomLayer|Polygon=Hidden|PrintOutIndex=1|Record=PcbPrintLayer +Configuration1_Name14=OutputConfigurationParameter14 +Configuration1_Item14=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=BottomOverlay|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer +Configuration1_Name15=OutputConfigurationParameter15 +Configuration1_Item15=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Hidden|Layer=MultiLayer|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer +Configuration1_Name16=OutputConfigurationParameter16 +Configuration1_Item16=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical1|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer +Configuration1_Name17=OutputConfigurationParameter17 +Configuration1_Item17=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical5|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer +Configuration1_Name18=OutputConfigurationParameter18 +Configuration1_Item18=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical13|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer +Configuration1_Name19=OutputConfigurationParameter19 +Configuration1_Item19=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical14|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer +Configuration1_Name20=OutputConfigurationParameter20 +Configuration1_Item20=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical16|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer +OutputType2=PCB 3D Print +OutputName2=PCB 3D Top +OutputCategory2=Documentation +OutputDocumentPath2=CopterControl 3D.PcbDoc +OutputVariantName2= +OutputEnabled2=1 +OutputEnabled2_OutputMedium1=0 +OutputEnabled2_OutputMedium2=2 +OutputEnabled2_OutputMedium3=0 +OutputEnabled2_OutputMedium4=0 +OutputDefault2=0 +PageOptions2=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=5.61|XCorrection=1.00|YCorrection=1.00|PrintKind=0|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +Configuration2_Name1=OutputConfigurationParameter1 +Configuration2_Item1=Record=Pcb3DPrintView|ResX=300|ResY=300|ViewX=14173229|ViewY=14173230|LookAtX=31403926|LookAtY=26533924|LookAtZ=-1000|QuatX=0|QuatY=0|QuatZ=0|QuatW=1|Zoom=4.90361053902321E-5|UnitsPercent=True|UnitsDPI=True|LockResAspect=True|ViewConfigType=.config_3d|CustomCamera=False|ViewFromTop=True|ViewConfig=RECORD\3Board\2CFGALL.CONFIGURATIONKIND\33\2CFGALL.CONFIGURATIONDESC\3Altium%203D%20NB%20Black%20Configuration\2CFG3D.POSITIVETOPSOLDERMASK\3TRUE\2CFG3D.POSITIVEBOTTOMSOLDERMASK\3TRUE\2CFG3D.SHOWCOMPONENTBODIES\3SYSTEM\2CFG3D.SHOWCOMPONENTSTEPMODELS\3SYSTEM\2CFG3D.COMPONENTMODELPREFERENCE\30\2CFG3D.SHOWCOMPONENTSNAPMARKERS\3TRUE\2CFG3D.SHOWCOMPONENTAXES\3TRUE\2CFG3D.SHOWBOARDCORE\3TRUE\2CFG3D.SHOWBOARDPREPREG\3TRUE\2CFG3D.SHOWTOPSILKSCREEN\3TRUE\2CFG3D.SHOWBOTSILKSCREEN\3TRUE\2CFG3D.SHOWORIGINMARKER\3TRUE\2CFG3D.EYEDIST\32000\2CFG3D.SHOWCUTOUTS\3TRUE\2CFG3D.SHOWROUTETOOLPATH\3TRUE\2CFG3D.SHOWROOMS3D\3FALSE\2CFG3D.USESYSCOLORSFOR3D\3FALSE\2CFG3D.WORKSPACECOLOR\311840160\2CFG3D.BOARDCORECOLOR\313491161\2CFG3D.BOARDPREPREGCOLOR\30\2CFG3D.TOPSOLDERMASKCOLOR\30\2CFG3D.BOTSOLDERMASKCOLOR\30\2CFG3D.COPPERCOLOR\33323360\2CFG3D.TOPSILKSCREENCOLOR\315461355\2CFG3D.BOTSILKSCREENCOLOR\315461355\2CFG3D.WORKSPACELUMINANCEVARIATION\330\2CFG3D.WORKSPACECOLOROPACITY\31.000000\2CFG3D.BOARDCORECOLOROPACITY\30.820000\2CFG3D.BOARDPREPREGCOLOROPACITY\30.500000\2CFG3D.TOPSOLDERMASKCOLOROPACITY\30.900000\2CFG3D.BOTSOLDERMASKCOLOROPACITY\30.900000\2CFG3D.COPPERCOLOROPACITY\31.000000\2CFG3D.TOPSILKSCREENCOLOROPACITY\31.000000\2CFG3D.BOTSILKSCREENCOLOROPACITY\31.000000\2CFG3D.BOARDTHICKNESSSCALING\31.000000\2CFG3D.SHOWMECHANICALLAYERS\3FALSE\2CFG3D.MECHANICALLAYERSOPACITY\31.000000 +OutputType3=PCB 3D Print +OutputName3=PCB 3D Bottom +OutputCategory3=Documentation +OutputDocumentPath3=CopterControl 3D.PcbDoc +OutputVariantName3= +OutputEnabled3=1 +OutputEnabled3_OutputMedium1=0 +OutputEnabled3_OutputMedium2=3 +OutputEnabled3_OutputMedium3=0 +OutputEnabled3_OutputMedium4=0 +OutputDefault3=0 +PageOptions3=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=5.61|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +Configuration3_Name1=OutputConfigurationParameter1 +Configuration3_Item1=Record=Pcb3DPrintView|ResX=300|ResY=300|ViewX=14173229|ViewY=14173230|LookAtX=31403926|LookAtY=26533924|LookAtZ=-1000|QuatX=0|QuatY=0|QuatZ=0|QuatW=1|Zoom=4.90361053902321E-5|UnitsPercent=True|UnitsDPI=True|LockResAspect=True|ViewConfigType=.config_3d|CustomCamera=False|ViewFromTop=False|ViewConfig=RECORD\3Board\2CFGALL.CONFIGURATIONKIND\33\2CFGALL.CONFIGURATIONDESC\3Altium%203D%20NB%20Black%20Configuration\2CFG3D.POSITIVETOPSOLDERMASK\3TRUE\2CFG3D.POSITIVEBOTTOMSOLDERMASK\3TRUE\2CFG3D.SHOWCOMPONENTBODIES\3SYSTEM\2CFG3D.SHOWCOMPONENTSTEPMODELS\3SYSTEM\2CFG3D.COMPONENTMODELPREFERENCE\30\2CFG3D.SHOWCOMPONENTSNAPMARKERS\3TRUE\2CFG3D.SHOWCOMPONENTAXES\3TRUE\2CFG3D.SHOWBOARDCORE\3TRUE\2CFG3D.SHOWBOARDPREPREG\3TRUE\2CFG3D.SHOWTOPSILKSCREEN\3TRUE\2CFG3D.SHOWBOTSILKSCREEN\3TRUE\2CFG3D.SHOWORIGINMARKER\3TRUE\2CFG3D.EYEDIST\32000\2CFG3D.SHOWCUTOUTS\3TRUE\2CFG3D.SHOWROUTETOOLPATH\3TRUE\2CFG3D.SHOWROOMS3D\3FALSE\2CFG3D.USESYSCOLORSFOR3D\3FALSE\2CFG3D.WORKSPACECOLOR\311840160\2CFG3D.BOARDCORECOLOR\313491161\2CFG3D.BOARDPREPREGCOLOR\30\2CFG3D.TOPSOLDERMASKCOLOR\30\2CFG3D.BOTSOLDERMASKCOLOR\30\2CFG3D.COPPERCOLOR\33323360\2CFG3D.TOPSILKSCREENCOLOR\315461355\2CFG3D.BOTSILKSCREENCOLOR\315461355\2CFG3D.WORKSPACELUMINANCEVARIATION\330\2CFG3D.WORKSPACECOLOROPACITY\31.000000\2CFG3D.BOARDCORECOLOROPACITY\30.820000\2CFG3D.BOARDPREPREGCOLOROPACITY\30.500000\2CFG3D.TOPSOLDERMASKCOLOROPACITY\30.900000\2CFG3D.BOTSOLDERMASKCOLOROPACITY\30.900000\2CFG3D.COPPERCOLOROPACITY\31.000000\2CFG3D.TOPSILKSCREENCOLOROPACITY\31.000000\2CFG3D.BOTSILKSCREENCOLOROPACITY\31.000000\2CFG3D.BOARDTHICKNESSSCALING\31.000000\2CFG3D.SHOWMECHANICALLAYERS\3FALSE\2CFG3D.MECHANICALLAYERSOPACITY\31.000000 + +[PublishSettings] +OutputFilePath2=\..\Assembly\CopterControl 3D Assembly.PDF +ReleaseManaged2=1 +OutputBasePath2= +OutputPathMedia2=..\Assembly +OutputPathOutputer2=[Output Type] +OutputFileName2=CopterControl 3D Assembly.PDF +OpenOutput2=1 +PromptOverwrite2=1 +PublishMethod2=0 +ZoomLevel2=50 +FitSCHPrintSizeToDoc2=1 +FitPCBPrintSizeToDoc2=1 +GenerateNetsInfo2=1 +MarkPins2=1 +MarkNetLabels2=1 +MarkPortsId2=1 +GenerateTOC=1 +OutputFilePath3=\ +ReleaseManaged3=1 +OutputBasePath3= +OutputPathMedia3= +OutputPathOutputer3=[Output Type] +OutputFileName3= +OpenOutput3=1 +OutputFilePath4=\ +ReleaseManaged4=1 +OutputBasePath4= +OutputPathMedia4= +OutputPathOutputer4=[Output Type] +OutputFileName4= +OpenOutput4=1 +PromptOverwrite4=1 +PublishMethod4=5 +ZoomLevel4=50 +FitSCHPrintSizeToDoc4=1 +FitPCBPrintSizeToDoc4=1 +GenerateNetsInfo4=1 +MarkPins4=1 +MarkNetLabels4=1 +MarkPortsId4=1 +MediaFormat4=Windows Media file (*.wmv,*.wma,*.asf) +FixedDimensions4=1 +Width4=352 +Height4=288 +MultiFile4=0 +FramesPerSecond4=25 +FramesPerSecondDenom4=1 +AviPixelFormat4=7 +AviCompression4=MP42 MS-MPEG4 V2 +AviQuality4=100 +FFmpegVideoCodecId4=13 +FFmpegPixelFormat4=0 +FFmpegQuality4=80 +WmvVideoCodecName4=Windows Media Video V7 +WmvQuality4=80 + +[GeneratedFilesSettings] +RelativeOutputPath2=\..\Assembly\CopterControl 3D Assembly.PDF +OpenOutputs2=1 +RelativeOutputPath3=\ +OpenOutputs3=1 +AddToProject3=1 +TimestampFolder3=0 +UseOutputName3=0 +OpenODBOutput3=0 +OpenGerberOutput3=0 +OpenNCDrillOutput3=0 +OpenIPCOutput3=0 +EnableReload3=0 +RelativeOutputPath4=\ +OpenOutputs4=1 + diff --git a/hardware/Production/CopterControl 3D/Assembly/CopterControl 3D Assembly.pdf b/hardware/Production/CopterControl 3D/Assembly/CopterControl 3D Assembly.pdf new file mode 100644 index 000000000..e9e327d8b Binary files /dev/null and b/hardware/Production/CopterControl 3D/Assembly/CopterControl 3D Assembly.pdf differ diff --git a/hardware/Production/CopterControl 3D/BOM/CopterControl 3D BOM.xls b/hardware/Production/CopterControl 3D/BOM/CopterControl 3D BOM.xls new file mode 100644 index 000000000..dc35b6d73 Binary files /dev/null and b/hardware/Production/CopterControl 3D/BOM/CopterControl 3D BOM.xls differ diff --git a/hardware/Production/CopterControl 3D/CopterControl 3D Schematic.pdf b/hardware/Production/CopterControl 3D/CopterControl 3D Schematic.pdf new file mode 100644 index 000000000..9a74e7fb2 Binary files /dev/null and b/hardware/Production/CopterControl 3D/CopterControl 3D Schematic.pdf differ diff --git a/hardware/Production/CopterControl 3D/CopterControl 3D.PcbDoc b/hardware/Production/CopterControl 3D/CopterControl 3D.PcbDoc new file mode 100644 index 000000000..d83dff63c Binary files /dev/null and b/hardware/Production/CopterControl 3D/CopterControl 3D.PcbDoc differ diff --git a/hardware/Production/CopterControl 3D/CopterControl 3D.PrjPCB b/hardware/Production/CopterControl 3D/CopterControl 3D.PrjPCB new file mode 100644 index 000000000..845d985ac --- /dev/null +++ b/hardware/Production/CopterControl 3D/CopterControl 3D.PrjPCB @@ -0,0 +1,1213 @@ +[Design] +Version=1.0 +HierarchyMode=0 +ChannelRoomNamingStyle=0 +OutputPath=Project Outputs for CopterControl 3D +LogFolderPath= +ReleasesFolder= +ReleaseVaultGUID= +ReleaseVaultName= +ChannelDesignatorFormatString=$Component_$RoomName +ChannelRoomLevelSeperator=_ +OpenOutputs=1 +ArchiveProject=0 +TimestampOutput=0 +SeparateFolders=0 +TemplateLocationPath= +PinSwapBy_Netlabel=1 +PinSwapBy_Pin=1 +AllowPortNetNames=0 +AllowSheetEntryNetNames=1 +AppendSheetNumberToLocalNets=0 +NetlistSinglePinNets=0 +DefaultConfiguration= +UserID=0xFFFFFFFF +DefaultPcbProtel=1 +DefaultPcbPcad=0 +ReorderDocumentsOnCompile=1 +NameNetsHierarchically=0 +PowerPortNamesTakePriority=0 +PushECOToAnnotationFile=1 +DItemRevisionGUID= +ReportSuppressedErrorsInMessages=0 + +[Document1] +DocumentPath=..\Altium\OpenPilot.SchLib +AnnotationEnabled=1 +AnnotateStartValue=1 +AnnotationIndexControlEnabled=0 +AnnotateSuffix= +AnnotateScope=All +AnnotateOrder=-1 +DoLibraryUpdate=1 +DoDatabaseUpdate=1 +ClassGenCCAutoEnabled=1 +ClassGenCCAutoRoomEnabled=1 +ClassGenNCAutoScope=None +DItemRevisionGUID= +GenerateClassCluster=0 + +[Document2] +DocumentPath=..\Altium\OpenPilot.PcbLib +AnnotationEnabled=1 +AnnotateStartValue=1 +AnnotationIndexControlEnabled=0 +AnnotateSuffix= +AnnotateScope=All +AnnotateOrder=-1 +DoLibraryUpdate=1 +DoDatabaseUpdate=1 +ClassGenCCAutoEnabled=1 +ClassGenCCAutoRoomEnabled=1 +ClassGenNCAutoScope=None +DItemRevisionGUID= +GenerateClassCluster=0 + +[Document3] +DocumentPath=CopterControl 3D.SchDoc +AnnotationEnabled=1 +AnnotateStartValue=1 +AnnotationIndexControlEnabled=0 +AnnotateSuffix= +AnnotateScope=All +AnnotateOrder=0 +DoLibraryUpdate=1 +DoDatabaseUpdate=1 +ClassGenCCAutoEnabled=1 +ClassGenCCAutoRoomEnabled=0 +ClassGenNCAutoScope=None +DItemRevisionGUID= +GenerateClassCluster=0 + +[Document4] +DocumentPath=CopterControl 3D.PcbDoc +AnnotationEnabled=1 +AnnotateStartValue=1 +AnnotationIndexControlEnabled=0 +AnnotateSuffix= +AnnotateScope=All +AnnotateOrder=-1 +DoLibraryUpdate=1 +DoDatabaseUpdate=1 +ClassGenCCAutoEnabled=1 +ClassGenCCAutoRoomEnabled=1 +ClassGenNCAutoScope=None +DItemRevisionGUID= +GenerateClassCluster=0 + +[Document5] +DocumentPath=Assembly.OutJob +AnnotationEnabled=1 +AnnotateStartValue=1 +AnnotationIndexControlEnabled=0 +AnnotateSuffix= +AnnotateScope=All +AnnotateOrder=-1 +DoLibraryUpdate=1 +DoDatabaseUpdate=1 +ClassGenCCAutoEnabled=1 +ClassGenCCAutoRoomEnabled=1 +ClassGenNCAutoScope=None +DItemRevisionGUID= +GenerateClassCluster=0 + +[SearchPath1] +Path=..\..\..\..\Program Files (x86)\Altium Designer Summer 09\Library\*.* +IncludeSubFolders=1 + +[PCBConfiguration1] +ReleaseItemId= +CurrentRevision= +Name=Default Configuration +Variant=[No Variations] +GenerateBOM=0 + +[Generic_SmartPDF] +AutoOpenFile=0 +AutoOpenOutJob=-1 + +[Generic_SmartPDFSettings] +ProjectMode=0 +ZoomPrecision=50 +AddNetsInformation=-1 +AddNetPins=-1 +AddNetNetLabels=-1 +AddNetPorts=-1 +ExportBOM=0 +TemplateFilename= +TemplateStoreRelative=-1 +PCB_PrintColor=0 +SCH_PrintColor=0 +SCH_ShowNoErc=0 +SCH_ShowParameter=0 +SCH_ShowProbes=0 +SCH_ShowBlankets=0 +OutputFileName=CopterControl.SchDoc=C:\Users\David\Documents\SVN\WIP\trunk\hardware\production\CopterControl\CopterControl Schematic.pdf +SCH_ExpandLogicalToPhysical=0 +SCH_VariantName=[No Variations] +SCH_ExpandComponentDesignators=-1 +SCH_ExpandNetlabels=0 +SCH_ExpandPorts=0 +SCH_ExpandSheetNumber=0 +SCH_ExpandDocumentNumber=0 +SCH_HasExpandLogicalToPhysicalSheets=-1 +SaveSettingsToOutJob=0 +SCH_NoERCSymbolsToShow="Thin Cross","Thick Cross","Small Cross",Checkbox,Triangle +SCH_ShowNote=-1 +SCH_ShowNoteCollapsed=-1 + +[OutputGroup1] +Name=Netlist Outputs +Description= +TargetPrinter=Brother HL-2170W +PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1 +OutputType1=CadnetixNetlist +OutputName1=Cadnetix Netlist +OutputDocumentPath1= +OutputVariantName1= +OutputDefault1=0 +OutputType2=CalayNetlist +OutputName2=Calay Netlist +OutputDocumentPath2= +OutputVariantName2= +OutputDefault2=0 +OutputType3=EDIF +OutputName3=EDIF for PCB +OutputDocumentPath3= +OutputVariantName3= +OutputDefault3=0 +OutputType4=EESofNetlist +OutputName4=EESof Netlist +OutputDocumentPath4= +OutputVariantName4= +OutputDefault4=0 +OutputType5=IntergraphNetlist +OutputName5=Intergraph Netlist +OutputDocumentPath5= +OutputVariantName5= +OutputDefault5=0 +OutputType6=MentorBoardStationNetlist +OutputName6=Mentor BoardStation Netlist +OutputDocumentPath6= +OutputVariantName6= +OutputDefault6=0 +OutputType7=MultiWire +OutputName7=MultiWire +OutputDocumentPath7= +OutputVariantName7= +OutputDefault7=0 +OutputType8=OrCadPCB2Netlist +OutputName8=Orcad/PCB2 Netlist +OutputDocumentPath8= +OutputVariantName8= +OutputDefault8=0 +OutputType9=PADSNetlist +OutputName9=PADS ASCII Netlist +OutputDocumentPath9= +OutputVariantName9= +OutputDefault9=0 +OutputType10=Pcad +OutputName10=Pcad for PCB +OutputDocumentPath10= +OutputVariantName10= +OutputDefault10=0 +OutputType11=PCADNetlist +OutputName11=PCAD Netlist +OutputDocumentPath11= +OutputVariantName11= +OutputDefault11=0 +OutputType12=PCADnltNetlist +OutputName12=PCADnlt Netlist +OutputDocumentPath12= +OutputVariantName12= +OutputDefault12=0 +OutputType13=Protel2Netlist +OutputName13=Protel2 Netlist +OutputDocumentPath13= +OutputVariantName13= +OutputDefault13=0 +OutputType14=ProtelNetlist +OutputName14=Protel +OutputDocumentPath14= +OutputVariantName14= +OutputDefault14=0 +OutputType15=RacalNetlist +OutputName15=Racal Netlist +OutputDocumentPath15= +OutputVariantName15= +OutputDefault15=0 +OutputType16=RINFNetlist +OutputName16=RINF Netlist +OutputDocumentPath16= +OutputVariantName16= +OutputDefault16=0 +OutputType17=SciCardsNetlist +OutputName17=SciCards Netlist +OutputDocumentPath17= +OutputVariantName17= +OutputDefault17=0 +OutputType18=SIMetrixNetlist +OutputName18=SIMetrix +OutputDocumentPath18= +OutputVariantName18= +OutputDefault18=0 +OutputType19=SIMPLISNetlist +OutputName19=SIMPLIS +OutputDocumentPath19= +OutputVariantName19= +OutputDefault19=0 +OutputType20=TangoNetlist +OutputName20=Tango Netlist +OutputDocumentPath20= +OutputVariantName20= +OutputDefault20=0 +OutputType21=TelesisNetlist +OutputName21=Telesis Netlist +OutputDocumentPath21= +OutputVariantName21= +OutputDefault21=0 +OutputType22=Verilog +OutputName22=Verilog File +OutputDocumentPath22= +OutputVariantName22= +OutputDefault22=0 +OutputType23=VHDL +OutputName23=VHDL File +OutputDocumentPath23= +OutputVariantName23= +OutputDefault23=0 +OutputType24=WireListNetlist +OutputName24=WireList Netlist +OutputDocumentPath24= +OutputVariantName24= +OutputDefault24=0 +OutputType25=XSpiceNetlist +OutputName25=XSpice Netlist +OutputDocumentPath25= +OutputVariantName25= +OutputDefault25=0 + +[OutputGroup2] +Name=Simulator Outputs +Description= +TargetPrinter=Brother HL-2170W +PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1 +OutputType1=AdvSimNetlist +OutputName1=Mixed Sim +OutputDocumentPath1= +OutputVariantName1= +OutputDefault1=0 +OutputType2=SIMetrix_Sim +OutputName2=SIMetrix +OutputDocumentPath2= +OutputVariantName2= +OutputDefault2=0 +OutputType3=SIMPLIS_Sim +OutputName3=SIMPLIS +OutputDocumentPath3= +OutputVariantName3= +OutputDefault3=0 + +[OutputGroup3] +Name=Documentation Outputs +Description= +TargetPrinter=Brother HL-2170W +PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1 +OutputType1=Composite +OutputName1=Composite Drawing +OutputDocumentPath1=C:\Users\David\Documents\SVN\OP-WIP\trunk\hardware\production\CopterControl\CopterControl.PcbDoc +OutputVariantName1= +OutputDefault1=0 +PageOptions1=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=0 +Configuration1_Name1=OutputConfigurationParameter1 +Configuration1_Item1=PrintArea=DesignExtent|PrintAreaLowerLeftCornerX=0|PrintAreaLowerLeftCornerY=0|PrintAreaUpperRightCornerX=0|PrintAreaUpperRightCornerY=0|Record=PcbPrintView +Configuration1_Name2=OutputConfigurationParameter2 +Configuration1_Item2=IncludeBottomLayerComponents=True|IncludeMultiLayerComponents=True|IncludeTopLayerComponents=True|Index=0|Mirror=False|Name=Multilayer Composite Print|PadNumberFontSize=14|Record=PcbPrintOut|ShowHoles=False|ShowPadNets=False|ShowPadNumbers=False|SubstituteFonts=False +Configuration1_Name3=OutputConfigurationParameter3 +Configuration1_Item3=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=TopOverlay|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +Configuration1_Name4=OutputConfigurationParameter4 +Configuration1_Item4=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=BottomOverlay|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +Configuration1_Name5=OutputConfigurationParameter5 +Configuration1_Item5=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=TopLayer|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +Configuration1_Name6=OutputConfigurationParameter6 +Configuration1_Item6=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=MidLayer1|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +Configuration1_Name7=OutputConfigurationParameter7 +Configuration1_Item7=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=BottomLayer|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +Configuration1_Name8=OutputConfigurationParameter8 +Configuration1_Item8=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical1|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +Configuration1_Name9=OutputConfigurationParameter9 +Configuration1_Item9=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical5|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +Configuration1_Name10=OutputConfigurationParameter10 +Configuration1_Item10=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical6|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +Configuration1_Name11=OutputConfigurationParameter11 +Configuration1_Item11=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical7|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +Configuration1_Name12=OutputConfigurationParameter12 +Configuration1_Item12=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical13|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +Configuration1_Name13=OutputConfigurationParameter13 +Configuration1_Item13=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical15|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +Configuration1_Name14=OutputConfigurationParameter14 +Configuration1_Item14=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=MultiLayer|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +OutputType2=Logic Analyser Print +OutputName2=Logic Analyser Prints +OutputDocumentPath2= +OutputVariantName2= +OutputDefault2=0 +PageOptions2=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType3=OpenBus Print +OutputName3=OpenBus Prints +OutputDocumentPath3= +OutputVariantName3= +OutputDefault3=0 +PageOptions3=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType4=PCB 3D Print +OutputName4=PCB 3D Prints +OutputDocumentPath4= +OutputVariantName4=[No Variations] +OutputDefault4=0 +PageOptions4=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType5=PCB Print +OutputName5=PCB Prints +OutputDocumentPath5= +OutputVariantName5= +OutputDefault5=0 +PageOptions5=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType6=Schematic Print +OutputName6=Schematic Prints +OutputDocumentPath6= +OutputVariantName6= +OutputDefault6=0 +PageOptions6=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType7=SimView Print +OutputName7=SimView Prints +OutputDocumentPath7= +OutputVariantName7= +OutputDefault7=0 +PageOptions7=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType8=Wave Print +OutputName8=Wave Prints +OutputDocumentPath8= +OutputVariantName8= +OutputDefault8=0 +PageOptions8=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType9=WaveSim Print +OutputName9=WaveSim Prints +OutputDocumentPath9= +OutputVariantName9= +OutputDefault9=0 +PageOptions9=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType10=Assembler Source Print +OutputName10=Assembler Source Prints +OutputDocumentPath10= +OutputVariantName10= +OutputDefault10=0 +PageOptions10=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType11=C Source Print +OutputName11=C Source Prints +OutputDocumentPath11= +OutputVariantName11= +OutputDefault11=0 +PageOptions11=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType12=C/C++ Header Print +OutputName12=C/C++ Header Prints +OutputDocumentPath12= +OutputVariantName12= +OutputDefault12=0 +PageOptions12=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType13=C++ Source Print +OutputName13=C++ Source Prints +OutputDocumentPath13= +OutputVariantName13= +OutputDefault13=0 +PageOptions13=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType14=PCB 3D Video +OutputName14=PCB 3D Video +OutputDocumentPath14= +OutputVariantName14=[No Variations] +OutputDefault14=0 +PageOptions14=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType15=Report Print +OutputName15=Report Prints +OutputDocumentPath15= +OutputVariantName15= +OutputDefault15=0 +PageOptions15=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType16=Software Platform Print +OutputName16=Software Platform Prints +OutputDocumentPath16= +OutputVariantName16= +OutputDefault16=0 +PageOptions16=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType17=VHDL Print +OutputName17=VHDL Prints +OutputDocumentPath17= +OutputVariantName17= +OutputDefault17=0 +PageOptions17=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 + +[OutputGroup4] +Name=Assembly Outputs +Description= +TargetPrinter=Brother HL-2170W +PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1 +OutputType1=Assembly +OutputName1=Assembly Drawings +OutputDocumentPath1= +OutputVariantName1=[No Variations] +OutputDefault1=0 +PageOptions1=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType2=Pick Place +OutputName2=Generates pick and place files +OutputDocumentPath2= +OutputVariantName2=[No Variations] +OutputDefault2=0 +OutputType3=Test Points For Assembly +OutputName3=Test Point Report +OutputDocumentPath3= +OutputVariantName3=[No Variations] +OutputDefault3=0 + +[OutputGroup5] +Name=Fabrication Outputs +Description= +TargetPrinter=Brother HL-2170W +PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1 +OutputType1=ODB +OutputName1=ODB++ Files +OutputDocumentPath1= +OutputVariantName1=[No Variations] +OutputDefault1=0 +OutputType2=NC Drill +OutputName2=NC Drill Files +OutputDocumentPath2= +OutputVariantName2= +OutputDefault2=0 +Configuration2_Name1=OutputConfigurationParameter1 +Configuration2_Item1=BoardEdgeRoutToolDia=2000000|GenerateBoardEdgeRout=False|GenerateDrilledSlotsG85=False|GenerateEIADrillFile=False|GenerateSeparatePlatedNonPlatedFiles=False|NumberOfDecimals=5|NumberOfUnits=2|OptimizeChangeLocationCommands=True|OriginPosition=Relative|Record=DrillView|Units=Imperial|ZeroesMode=SuppressTrailingZeroes +OutputType3=Test Points +OutputName3=Test Point Report +OutputDocumentPath3= +OutputVariantName3= +OutputDefault3=0 +OutputType4=Plane +OutputName4=Power-Plane Prints +OutputDocumentPath4= +OutputVariantName4= +OutputDefault4=0 +PageOptions4=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType5=Mask +OutputName5=Solder/Paste Mask Prints +OutputDocumentPath5= +OutputVariantName5= +OutputDefault5=0 +PageOptions5=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType6=Drill +OutputName6=Drill Drawing/Guides +OutputDocumentPath6= +OutputVariantName6= +OutputDefault6=0 +PageOptions6=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=4.20|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +Configuration6_Name1=OutputConfigurationParameter1 +Configuration6_Item1=PrintArea=DesignExtent|PrintAreaLowerLeftCornerX=0|PrintAreaLowerLeftCornerY=0|PrintAreaUpperRightCornerX=0|PrintAreaUpperRightCornerY=0|Record=PcbPrintView +Configuration6_Name2=OutputConfigurationParameter2 +Configuration6_Item2=IncludeBottomLayerComponents=True|IncludeMultiLayerComponents=True|IncludeTopLayerComponents=True|Index=0|Mirror=False|Name=Drill Drawing For (Bottom Layer,Top Layer)|PadNumberFontSize=14|Record=PcbPrintOut|ShowHoles=False|ShowPadNets=False|ShowPadNumbers=False|SubstituteFonts=False +Configuration6_Name3=OutputConfigurationParameter3 +Configuration6_Item3=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=BottomLayer|DLayer2=TopLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=DrillDrawing|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +Configuration6_Name4=OutputConfigurationParameter4 +Configuration6_Item4=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical1|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +Configuration6_Name5=OutputConfigurationParameter5 +Configuration6_Item5=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical5|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +Configuration6_Name6=OutputConfigurationParameter6 +Configuration6_Item6=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical6|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +Configuration6_Name7=OutputConfigurationParameter7 +Configuration6_Item7=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical7|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +Configuration6_Name8=OutputConfigurationParameter8 +Configuration6_Item8=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical13|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +Configuration6_Name9=OutputConfigurationParameter9 +Configuration6_Item9=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical15|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +Configuration6_Name10=OutputConfigurationParameter10 +Configuration6_Item10=IncludeBottomLayerComponents=True|IncludeMultiLayerComponents=True|IncludeTopLayerComponents=True|Index=1|Mirror=False|Name=Drill Guide For (Bottom Layer,Top Layer)|PadNumberFontSize=14|Record=PcbPrintOut|ShowHoles=False|ShowPadNets=False|ShowPadNumbers=False|SubstituteFonts=False +Configuration6_Name11=OutputConfigurationParameter11 +Configuration6_Item11=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=BottomLayer|DLayer2=TopLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=DrillGuide|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer +Configuration6_Name12=OutputConfigurationParameter12 +Configuration6_Item12=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical1|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer +Configuration6_Name13=OutputConfigurationParameter13 +Configuration6_Item13=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical5|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer +Configuration6_Name14=OutputConfigurationParameter14 +Configuration6_Item14=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical6|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer +Configuration6_Name15=OutputConfigurationParameter15 +Configuration6_Item15=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical7|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer +Configuration6_Name16=OutputConfigurationParameter16 +Configuration6_Item16=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical13|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer +Configuration6_Name17=OutputConfigurationParameter17 +Configuration6_Item17=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical15|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer +OutputType7=CompositeDrill +OutputName7=Composite Drill Drawing +OutputDocumentPath7= +OutputVariantName7= +OutputDefault7=0 +PageOptions7=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType8=Final +OutputName8=Final Artwork Prints +OutputDocumentPath8= +OutputVariantName8=[No Variations] +OutputDefault8=0 +PageOptions8=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType9=Gerber +OutputName9=Gerber Files +OutputDocumentPath9= +OutputVariantName9=[No Variations] +OutputDefault9=0 +Configuration9_Name1=OutputConfigurationParameter1 +Configuration9_Item1=AddToAllPlots.Set=SerializeLayerHash.Version~2,ClassName~TLayerToBoolean|CentrePlots=False|DrillDrawingSymbol=GraphicsSymbol|DrillDrawingSymbolSize=500000|EmbeddedApertures=True|FilmBorderSize=10000000|FilmXSize=200000000|FilmYSize=160000000|FlashAllFills=False|FlashPadShapes=True|G54OnApertureChange=False|GenerateDRCRulesFile=True|GenerateReliefShapes=True|GerberUnit=Imperial|IncludeUnconnectedMidLayerPads=False|LeadingAndTrailingZeroesMode=SuppressLeadingZeroes|MaxApertureSize=2500000|MinusApertureTolerance=50|Mirror.Set=SerializeLayerHash.Version~2,ClassName~TLayerToBoolean|MirrorDrillDrawingPlots=False|MirrorDrillGuidePlots=False|NumberOfDecimals=5|OptimizeChangeLocationCommands=True|OriginPosition=Relative|Panelize=False|Plot.Set=SerializeLayerHash.Version~2,ClassName~TLayerToBoolean,16973830~1,16973832~1,16973834~1,16777217~1,16842751~1,16973835~1,16973833~1,16973831~1,16908289~1,16908293~1,16973837~1,16973848~1,16973849~1|PlotPositivePlaneLayers=False|PlotUsedDrillDrawingLayerPairs=True|PlotUsedDrillGuideLayerPairs=True|PlusApertureTolerance=50|Record=GerberView|SoftwareArcs=False|Sorted=False + +[OutputGroup6] +Name=Report Outputs +Description= +TargetPrinter=Brother HL-2170W +PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1 +OutputType1=BOM_PartType +OutputName1=Bill of Materials +OutputDocumentPath1= +OutputVariantName1=[No Variations] +OutputDefault1=0 +PageOptions1=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +Configuration1_Name1=Filter +Configuration1_Item1=545046300E5446696C74657257726170706572000D46696C7465722E416374697665090F46696C7465722E43726974657269610A04000000000000000000 +Configuration1_Name2=General +Configuration1_Item2=OpenExported=True|AddToProject=False|ForceFit=False|NotFitted=False|Database=False|IncludePCBData=False|ShowExportOptions=True|TemplateFilename=..\Altium\BOM Digikey.xlt|BatchMode=5|FormWidth=1401|FormHeight=641|SupplierProdQty=1000|SupplierAutoQty=True|SupplierUseCachedPricing=True|SupplierCurrency= +Configuration1_Name3=GroupOrder +Configuration1_Item3=Supplier Part Number 1=True +Configuration1_Name4=OutputConfigurationParameter1 +Configuration1_Item4=Record=BOMPrintView|ShowNoERC=True|ShowParamSet=True|ShowProbe=True|ShowBlanket=True|ExpandDesignator=True|ExpandNetLabel=False|ExpandPort=False|ExpandSheetNum=False|ExpandDocNum=False +Configuration1_Name5=PCBDocument +Configuration1_Item5= +Configuration1_Name6=SortOrder +Configuration1_Item6=Description=Up +Configuration1_Name7=VisibleOrder +Configuration1_Item7=Description=113|Comment=77|Footprint=59|Value=40|Designator=56|Quantity=37|Supplier Part Number 1=174|Supplier Order Qty 1=30|Supplier Stock 1=38|Supplier Unit Price 1=29|Supplier Subtotal 1=30|Supplier 1=23|Manufacturer 1=32|Manufacturer Part Number 1=20 +OutputType2=ComponentCrossReference +OutputName2=Component Cross Reference Report +OutputDocumentPath2= +OutputVariantName2=[No Variations] +OutputDefault2=0 +OutputType3=ReportHierarchy +OutputName3=Report Project Hierarchy +OutputDocumentPath3= +OutputVariantName3=[No Variations] +OutputDefault3=0 +OutputType4=Script +OutputName4=Script Output +OutputDocumentPath4= +OutputVariantName4=[No Variations] +OutputDefault4=0 +OutputType5=SimpleBOM +OutputName5=Simple BOM +OutputDocumentPath5= +OutputVariantName5=[No Variations] +OutputDefault5=0 +OutputType6=SinglePinNetReporter +OutputName6=Report Single Pin Nets +OutputDocumentPath6= +OutputVariantName6=[No Variations] +OutputDefault6=0 + +[OutputGroup7] +Name=Other Outputs +Description= +TargetPrinter=Brother HL-2170W +PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1 +OutputType1=Text Print +OutputName1=Text Print +OutputDocumentPath1= +OutputVariantName1= +OutputDefault1=0 +PageOptions1=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType2=Text Print +OutputName2=Text Print +OutputDocumentPath2= +OutputVariantName2= +OutputDefault2=0 +PageOptions2=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType3=Text Print +OutputName3=Text Print +OutputDocumentPath3= +OutputVariantName3= +OutputDefault3=0 +PageOptions3=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType4=Text Print +OutputName4=Text Print +OutputDocumentPath4= +OutputVariantName4= +OutputDefault4=0 +PageOptions4=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType5=Text Print +OutputName5=Text Print +OutputDocumentPath5= +OutputVariantName5= +OutputDefault5=0 +PageOptions5=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType6=Text Print +OutputName6=Text Print +OutputDocumentPath6= +OutputVariantName6= +OutputDefault6=0 +PageOptions6=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType7=Text Print +OutputName7=Text Print +OutputDocumentPath7= +OutputVariantName7= +OutputDefault7=0 +PageOptions7=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType8=Text Print +OutputName8=Text Print +OutputDocumentPath8= +OutputVariantName8= +OutputDefault8=0 +PageOptions8=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType9=Text Print +OutputName9=Text Print +OutputDocumentPath9= +OutputVariantName9= +OutputDefault9=0 +PageOptions9=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType10=Text Print +OutputName10=Text Print +OutputDocumentPath10= +OutputVariantName10= +OutputDefault10=0 +PageOptions10=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType11=Text Print +OutputName11=Text Print +OutputDocumentPath11= +OutputVariantName11= +OutputDefault11=0 +PageOptions11=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType12=Text Print +OutputName12=Text Print +OutputDocumentPath12= +OutputVariantName12= +OutputDefault12=0 +PageOptions12=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType13=Text Print +OutputName13=Text Print +OutputDocumentPath13= +OutputVariantName13= +OutputDefault13=0 +PageOptions13=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType14=Text Print +OutputName14=Text Print +OutputDocumentPath14= +OutputVariantName14= +OutputDefault14=0 +PageOptions14=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType15=Text Print +OutputName15=Text Print +OutputDocumentPath15= +OutputVariantName15= +OutputDefault15=0 +PageOptions15=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType16=Text Print +OutputName16=Text Print +OutputDocumentPath16= +OutputVariantName16= +OutputDefault16=0 +PageOptions16=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType17=Text Print +OutputName17=Text Print +OutputDocumentPath17= +OutputVariantName17= +OutputDefault17=0 +PageOptions17=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType18=Text Print +OutputName18=Text Print +OutputDocumentPath18= +OutputVariantName18= +OutputDefault18=0 +PageOptions18=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType19=Text Print +OutputName19=Text Print +OutputDocumentPath19= +OutputVariantName19= +OutputDefault19=0 +PageOptions19=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType20=Text Print +OutputName20=Text Print +OutputDocumentPath20= +OutputVariantName20= +OutputDefault20=0 +PageOptions20=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType21=Text Print +OutputName21=Text Print +OutputDocumentPath21= +OutputVariantName21= +OutputDefault21=0 +PageOptions21=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType22=Text Print +OutputName22=Text Print +OutputDocumentPath22= +OutputVariantName22= +OutputDefault22=0 +PageOptions22=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType23=Text Print +OutputName23=Text Print +OutputDocumentPath23= +OutputVariantName23= +OutputDefault23=0 +PageOptions23=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType24=Text Print +OutputName24=Text Print +OutputDocumentPath24= +OutputVariantName24= +OutputDefault24=0 +PageOptions24=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType25=Text Print +OutputName25=Text Print +OutputDocumentPath25= +OutputVariantName25= +OutputDefault25=0 +PageOptions25=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType26=Text Print +OutputName26=Text Print +OutputDocumentPath26= +OutputVariantName26= +OutputDefault26=0 +PageOptions26=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType27=Text Print +OutputName27=Text Print +OutputDocumentPath27= +OutputVariantName27= +OutputDefault27=0 +PageOptions27=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType28=Text Print +OutputName28=Text Print +OutputDocumentPath28= +OutputVariantName28= +OutputDefault28=0 +PageOptions28=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType29=Text Print +OutputName29=Text Print +OutputDocumentPath29= +OutputVariantName29= +OutputDefault29=0 +PageOptions29=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 + +[OutputGroup8] +Name=Validation Outputs +Description= +TargetPrinter=Brother HL-2170W +PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1 +OutputType1=Design Rules Check +OutputName1=Design Rules Check +OutputDocumentPath1= +OutputVariantName1= +OutputDefault1=0 +PageOptions1=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType2=Electrical Rules Check +OutputName2=Electrical Rules Check +OutputDocumentPath2= +OutputVariantName2= +OutputDefault2=0 +PageOptions2=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType3=Differences Report +OutputName3=Differences Report +OutputDocumentPath3= +OutputVariantName3= +OutputDefault3=0 +PageOptions3=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +OutputType4=Footprint Comparison Report +OutputName4=Footprint Comparison Report +OutputDocumentPath4= +OutputVariantName4= +OutputDefault4=0 + +[OutputGroup9] +Name=Export Outputs +Description= +TargetPrinter=Brother HL-2170W +PrinterOptions=Record=PrinterOptions|Copies=1|Duplex=1|TrueTypeOptions=3|Collate=1|PrintWhat=1 +OutputType1=ExportSTEP +OutputName1=Export STEP +OutputDocumentPath1= +OutputVariantName1= +OutputDefault1=0 + +[Modification Levels] +Type1=1 +Type2=1 +Type3=1 +Type4=1 +Type5=1 +Type6=1 +Type7=1 +Type8=1 +Type9=1 +Type10=1 +Type11=1 +Type12=1 +Type13=1 +Type14=1 +Type15=1 +Type16=1 +Type17=1 +Type18=1 +Type19=1 +Type20=1 +Type21=1 +Type22=1 +Type23=1 +Type24=1 +Type25=1 +Type26=1 +Type27=1 +Type28=1 +Type29=1 +Type30=1 +Type31=1 +Type32=1 +Type33=1 +Type34=1 +Type35=1 +Type36=1 +Type37=1 +Type38=1 +Type39=1 +Type40=1 +Type41=1 +Type42=1 +Type43=1 +Type44=1 +Type45=1 +Type46=1 +Type47=1 +Type48=1 +Type49=1 +Type50=1 +Type51=1 +Type52=1 +Type53=1 +Type54=1 +Type55=1 +Type56=1 +Type57=1 +Type58=1 +Type59=1 +Type60=1 +Type61=1 +Type62=1 +Type63=1 +Type64=1 +Type65=1 +Type66=1 +Type67=1 +Type68=1 +Type69=1 +Type70=1 +Type71=1 +Type72=1 +Type73=1 +Type74=1 + +[Difference Levels] +Type1=1 +Type2=1 +Type3=1 +Type4=1 +Type5=1 +Type6=1 +Type7=1 +Type8=1 +Type9=1 +Type10=1 +Type11=1 +Type12=1 +Type13=1 +Type14=1 +Type15=1 +Type16=1 +Type17=1 +Type18=1 +Type19=1 +Type20=1 +Type21=1 +Type22=1 +Type23=1 +Type24=1 +Type25=1 +Type26=1 +Type27=1 +Type28=1 +Type29=1 +Type30=1 +Type31=1 +Type32=1 +Type33=1 +Type34=1 +Type35=1 +Type36=1 +Type37=1 +Type38=1 +Type39=1 +Type40=1 + +[Electrical Rules Check] +Type1=1 +Type2=1 +Type3=2 +Type4=1 +Type5=2 +Type6=2 +Type7=1 +Type8=1 +Type9=1 +Type10=1 +Type11=2 +Type12=2 +Type13=2 +Type14=1 +Type15=1 +Type16=1 +Type17=1 +Type18=1 +Type19=1 +Type20=1 +Type21=1 +Type22=1 +Type23=1 +Type24=1 +Type25=2 +Type26=2 +Type27=2 +Type28=1 +Type29=1 +Type30=1 +Type31=1 +Type32=2 +Type33=2 +Type34=2 +Type35=1 +Type36=2 +Type37=1 +Type38=2 +Type39=2 +Type40=2 +Type41=0 +Type42=2 +Type43=1 +Type44=1 +Type45=2 +Type46=1 +Type47=2 +Type48=2 +Type49=1 +Type50=2 +Type51=1 +Type52=1 +Type53=1 +Type54=1 +Type55=1 +Type56=2 +Type57=1 +Type58=1 +Type59=0 +Type60=1 +Type61=2 +Type62=2 +Type63=1 +Type64=0 +Type65=2 +Type66=3 +Type67=2 +Type68=2 +Type69=1 +Type70=2 +Type71=2 +Type72=2 +Type73=2 +Type74=1 +Type75=2 +Type76=1 +Type77=1 +Type78=1 +Type79=1 +Type80=2 +Type81=3 +Type82=3 +Type83=3 +Type84=3 +Type85=3 +Type86=2 +Type87=2 +Type88=2 +Type89=1 +Type90=1 +Type91=3 +Type92=3 +Type93=2 +Type94=2 +Type95=2 +Type96=2 +Type97=2 +Type98=0 +Type99=1 +Type100=2 + +[ERC Connection Matrix] +L1=NNNNNNNNNNNWNNNWW +L2=NNWNNNNWWWNWNWNWN +L3=NWEENEEEENEWNEEWN +L4=NNENNNWEENNWNENWN +L5=NNNNNNNNNNNNNNNNN +L6=NNENNNNEENNWNENWN +L7=NNEWNNWEENNWNENWN +L8=NWEENEENEEENNEENN +L9=NWEENEEEENEWNEEWW +L10=NWNNNNNENNEWNNEWN +L11=NNENNNNEEENWNENWN +L12=WWWWNWWNWWWNWWWNN +L13=NNNNNNNNNNNWNNNWW +L14=NWEENEEEENEWNEEWW +L15=NNENNNNEEENWNENWW +L16=WWWWNWWNWWWNWWWNW +L17=WNNNNNNNWNNNWWWWN + +[Annotate] +SortOrder=3 +MatchParameter1=Comment +MatchStrictly1=1 +MatchParameter2=Library Reference +MatchStrictly2=1 +PhysicalNamingFormat=$Component_$RoomName +GlobalIndexSortOrder=3 + +[PrjClassGen] +CompClassManualEnabled=0 +CompClassManualRoomEnabled=0 +NetClassAutoBusEnabled=1 +NetClassAutoCompEnabled=0 +NetClassAutoNamedHarnessEnabled=0 +NetClassManualEnabled=1 + +[LibraryUpdateOptions] +SelectedOnly=0 +PartTypes=0 +ComponentLibIdentifierKind0=Library Name And Type +ComponentLibraryIdentifier0=CopterControl.SchLib +ComponentDesignItemID0=CC-STM32F103CBT6 +ComponentSymbolReference0=CC-STM32F103CBT6 +ComponentUpdate0=1 +ComponentIsDeviceSheet0=0 +FullReplace=1 +UpdateDesignatorLock=1 +UpdatePartIDLock=1 +PreserveParameterLocations=1 +DoGraphics=1 +DoParameters=1 +DoModels=1 +AddParameters=0 +RemoveParameters=0 +AddModels=1 +RemoveModels=1 +UpdateCurrentModels=1 +ParameterName0=Comment +ParameterUpdate0=1 +ParameterName1=Component Kind +ParameterUpdate1=1 +ParameterName2=ComponentLink1Description +ParameterUpdate2=1 +ParameterName3=ComponentLink1URL +ParameterUpdate3=1 +ParameterName4=ComponentLink2Description +ParameterUpdate4=1 +ParameterName5=ComponentLink2URL +ParameterUpdate5=1 +ParameterName6=DatasheetVersion +ParameterUpdate6=1 +ParameterName7=Description +ParameterUpdate7=1 +ParameterName8=Library Reference +ParameterUpdate8=1 +ParameterName9=PackageDescription +ParameterUpdate9=1 +ParameterName10=PackageReference +ParameterUpdate10=1 +ParameterName11=PackageVersion +ParameterUpdate11=1 +ParameterName12=Published +ParameterUpdate12=1 +ParameterName13=Publisher +ParameterUpdate13=1 +ParameterName14=Supplier 1 +ParameterUpdate14=1 +ParameterName15=Supplier Part Number 1 +ParameterUpdate15=1 +ModelTypeGroup0=PCBLIB +ModelTypeUpdate0=1 +ModelType0=PCBLIB +ModelName0=LQFP48_L +ModelUpdate0=1 +ModelType1=PCBLIB +ModelName1=LQFP48_M +ModelUpdate1=1 +ModelType2=PCBLIB +ModelName2=LQFP48_N +ModelUpdate2=1 + +[DatabaseUpdateOptions] +SelectedOnly=0 +PartTypes=0 + +[Comparison Options] +ComparisonOptions0=Kind=Net|MinPercent=75|MinMatch=3|ShowMatch=-1|Confirm=-1|UseName=-1|InclAllRules=0 +ComparisonOptions1=Kind=Net Class|MinPercent=75|MinMatch=3|ShowMatch=-1|Confirm=-1|UseName=-1|InclAllRules=0 +ComparisonOptions2=Kind=Component Class|MinPercent=75|MinMatch=3|ShowMatch=-1|Confirm=-1|UseName=-1|InclAllRules=0 +ComparisonOptions3=Kind=Rule|MinPercent=75|MinMatch=3|ShowMatch=-1|Confirm=-1|UseName=-1|InclAllRules=0 +ComparisonOptions4=Kind=Differential Pair|MinPercent=50|MinMatch=1|ShowMatch=0|Confirm=0|UseName=0|InclAllRules=0 +ComparisonOptions5=Kind=Structure Class|MinPercent=75|MinMatch=3|ShowMatch=-1|Confirm=-1|UseName=-1|InclAllRules=0 + +[SmartPDF] +PageOptions=Record=PageOptions|CenterHorizontal=True|CenterVertical=True|PrintScale=1.00|XCorrection=1.00|YCorrection=1.00|PrintKind=1|BorderSize=5000000|LeftOffset=0|BottomOffset=0|Orientation=2|PaperLength=1000|PaperWidth=1000|Scale=100|PaperSource=7|PrintQuality=-4|MediaType=1|DitherType=10|PaperKind=A4|PrintScaleMode=1 +Configuration_Name1=OutputConfigurationParameter1 +Configuration_Item1=PrintArea=DesignExtent|PrintAreaLowerLeftCornerX=0|PrintAreaLowerLeftCornerY=0|PrintAreaUpperRightCornerX=0|PrintAreaUpperRightCornerY=0|Record=PcbPrintView +Configuration_Name2=OutputConfigurationParameter2 +Configuration_Item2=IncludeBottomLayerComponents=False|IncludeMultiLayerComponents=False|IncludeTopLayerComponents=False|Index=0|Mirror=False|Name=Panel Details|PadNumberFontSize=14|Record=PcbPrintOut|ShowHoles=False|ShowPadNets=False|ShowPadNumbers=False|SubstituteFonts=False +Configuration_Name3=OutputConfigurationParameter3 +Configuration_Item3=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical16|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +Configuration_Name4=OutputConfigurationParameter4 +Configuration_Item4=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical1|Polygon=Full|PrintOutIndex=0|Record=PcbPrintLayer +Configuration_Name5=OutputConfigurationParameter5 +Configuration_Item5=IncludeBottomLayerComponents=False|IncludeMultiLayerComponents=False|IncludeTopLayerComponents=False|Index=1|Mirror=False|Name=Top SilkScreen|PadNumberFontSize=14|Record=PcbPrintOut|ShowHoles=False|ShowPadNets=False|ShowPadNumbers=False|SubstituteFonts=False +Configuration_Name6=OutputConfigurationParameter6 +Configuration_Item6=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=TopOverlay|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer +Configuration_Name7=OutputConfigurationParameter7 +Configuration_Item7=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical16|Polygon=Full|PrintOutIndex=1|Record=PcbPrintLayer +Configuration_Name8=OutputConfigurationParameter8 +Configuration_Item8=IncludeBottomLayerComponents=False|IncludeMultiLayerComponents=False|IncludeTopLayerComponents=False|Index=2|Mirror=False|Name=Top Copper|PadNumberFontSize=14|Record=PcbPrintOut|ShowHoles=False|ShowPadNets=False|ShowPadNumbers=False|SubstituteFonts=False +Configuration_Name9=OutputConfigurationParameter9 +Configuration_Item9=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=TopLayer|Polygon=Full|PrintOutIndex=2|Record=PcbPrintLayer +Configuration_Name10=OutputConfigurationParameter10 +Configuration_Item10=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical16|Polygon=Full|PrintOutIndex=2|Record=PcbPrintLayer +Configuration_Name11=OutputConfigurationParameter11 +Configuration_Item11=IncludeBottomLayerComponents=False|IncludeMultiLayerComponents=False|IncludeTopLayerComponents=False|Index=3|Mirror=False|Name=Groud Copper|PadNumberFontSize=14|Record=PcbPrintOut|ShowHoles=False|ShowPadNets=False|ShowPadNumbers=False|SubstituteFonts=False +Configuration_Name12=OutputConfigurationParameter12 +Configuration_Item12=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=MidLayer1|Polygon=Full|PrintOutIndex=3|Record=PcbPrintLayer +Configuration_Name13=OutputConfigurationParameter13 +Configuration_Item13=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical16|Polygon=Full|PrintOutIndex=3|Record=PcbPrintLayer +Configuration_Name14=OutputConfigurationParameter14 +Configuration_Item14=IncludeBottomLayerComponents=False|IncludeMultiLayerComponents=False|IncludeTopLayerComponents=False|Index=4|Mirror=False|Name=Power Layer|PadNumberFontSize=14|Record=PcbPrintOut|ShowHoles=False|ShowPadNets=False|ShowPadNumbers=False|SubstituteFonts=False +Configuration_Name15=OutputConfigurationParameter15 +Configuration_Item15=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=MidLayer2|Polygon=Full|PrintOutIndex=4|Record=PcbPrintLayer +Configuration_Name16=OutputConfigurationParameter16 +Configuration_Item16=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical16|Polygon=Full|PrintOutIndex=4|Record=PcbPrintLayer +Configuration_Name17=OutputConfigurationParameter17 +Configuration_Item17=IncludeBottomLayerComponents=False|IncludeMultiLayerComponents=False|IncludeTopLayerComponents=False|Index=5|Mirror=False|Name=Bottom Copper|PadNumberFontSize=14|Record=PcbPrintOut|ShowHoles=False|ShowPadNets=False|ShowPadNumbers=False|SubstituteFonts=False +Configuration_Name18=OutputConfigurationParameter18 +Configuration_Item18=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=BottomLayer|Polygon=Full|PrintOutIndex=5|Record=PcbPrintLayer +Configuration_Name19=OutputConfigurationParameter19 +Configuration_Item19=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical16|Polygon=Full|PrintOutIndex=5|Record=PcbPrintLayer +Configuration_Name20=OutputConfigurationParameter20 +Configuration_Item20=IncludeBottomLayerComponents=False|IncludeMultiLayerComponents=False|IncludeTopLayerComponents=False|Index=6|Mirror=False|Name=Bottom Silk Screen|PadNumberFontSize=14|Record=PcbPrintOut|ShowHoles=False|ShowPadNets=False|ShowPadNumbers=False|SubstituteFonts=False +Configuration_Name21=OutputConfigurationParameter21 +Configuration_Item21=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=BottomOverlay|Polygon=Full|PrintOutIndex=6|Record=PcbPrintLayer +Configuration_Name22=OutputConfigurationParameter22 +Configuration_Item22=CArc=Full|CFill=Full|Comment=Full|Coordinate=Full|CPad=Full|CRegion=Full|CText=Full|CTrack=Full|CVia=Full|DDSymbolKind=0|DDSymbolSize=500000|DDSymbolSortKind=0|Designator=Full|Dimension=Full|DLayer1=TopLayer|DLayer2=BottomLayer|FArc=Full|FFill=Full|FPad=Full|FRegion=Full|FText=Full|FTrack=Full|FVia=Full|Layer=Mechanical16|Polygon=Full|PrintOutIndex=6|Record=PcbPrintLayer + diff --git a/hardware/Production/CopterControl 3D/CopterControl 3D.SchDoc b/hardware/Production/CopterControl 3D/CopterControl 3D.SchDoc new file mode 100644 index 000000000..7d8d7541b Binary files /dev/null and b/hardware/Production/CopterControl 3D/CopterControl 3D.SchDoc differ diff --git a/hardware/Production/CopterControl 3D/Gerbers/Gerbers for CopterControl 3D.zip b/hardware/Production/CopterControl 3D/Gerbers/Gerbers for CopterControl 3D.zip new file mode 100644 index 000000000..2f148c495 Binary files /dev/null and b/hardware/Production/CopterControl 3D/Gerbers/Gerbers for CopterControl 3D.zip differ diff --git a/make/scripts/version-info.py b/make/scripts/version-info.py index 2f742962b..6fe6b7d9e 100644 --- a/make/scripts/version-info.py +++ b/make/scripts/version-info.py @@ -250,7 +250,7 @@ def xtrim(string, suffix, length): assert n > 0, "length of truncated string+suffix exceeds maximum length" return ''.join([string[:n], '+', suffix]) -def GetHashofDirs(directory, verbose=0): +def GetHashofDirs(directory, verbose=0, raw=0): import hashlib, os SHAhash = hashlib.sha1() if not os.path.exists (directory): @@ -268,7 +268,7 @@ def GetHashofDirs(directory, verbose=0): print 'Hashing', names filepath = os.path.join(root,names) try: - f1 = open(filepath, 'rb') + f1 = open(filepath, 'rU') except: # You can't open the file for some reason f1.close() @@ -298,8 +298,11 @@ def GetHashofDirs(directory, verbose=0): if verbose == 1: print 'Final hash is', SHAhash.hexdigest() - hex_stream = lambda s:",".join(['0x'+hex(ord(c))[2:].zfill(2) for c in s]) - return hex_stream(SHAhash.digest()) + if raw == 1: + return SHAhash.hexdigest() + else: + hex_stream = lambda s:",".join(['0x'+hex(ord(c))[2:].zfill(2) for c in s]) + return hex_stream(SHAhash.digest()) def main(): """This utility uses git repository in the current working directory @@ -380,7 +383,8 @@ dependent targets. BOARD_TYPE = args.type, BOARD_REVISION = args.revision, SHA1 = sha1(args.image), - UAVOSHA1= GetHashofDirs(args.uavodir,0), + UAVOSHA1TXT = GetHashofDirs(args.uavodir,verbose=0,raw=1), + UAVOSHA1 = GetHashofDirs(args.uavodir,verbose=0,raw=0), ) if args.info: diff --git a/package/Makefile b/package/Makefile index b5f706a05..921f516eb 100644 --- a/package/Makefile +++ b/package/Makefile @@ -104,6 +104,12 @@ package: | package_flight package_ground .PHONY: help uavobjects all_clean package_flight package_ground package +# opfw_resource must be generated before the ground package, +# and it depends on flight firmware images +ground_package: | opfw_resource + +opfw_resource: | all_fw + # Decide on a verbosity level based on the V= parameter export AT := @ @@ -130,4 +136,21 @@ ifeq ($(UNAME), Darwin) PLATFORM := osx endif +toprel = $(subst $(realpath $(ROOT_DIR))/,,$(abspath $(1))) +OPFW_FILES := $(foreach fw_targ, $(FW_TARGETS), $(call toprel, $(BUILD_DIR)/$(fw_targ)/$(fw_targ).opfw)) +OPFW_CONTENTS := \ + \ + \ + $(foreach fw_file, $(OPFW_FILES), $(fw_file)) \ + \ + + +.PHONY: opfw_resource +opfw_resource: + @echo Generating OPFW resource file $(call toprel, $(BUILD_DIR)/ground/$@) + $(V1) mkdir -p $(BUILD_DIR)/ground/$@ + $(V1) mkdir -p $(BUILD_DIR)/ground/$@/build + $(V1) echo '$(OPFW_CONTENTS)' > $(BUILD_DIR)/ground/$@/opfw_resource.qrc + $(V1) $(foreach fw_targ, $(FW_TARGETS), mkdir -p $(BUILD_DIR)/ground/$@/build/$(fw_targ);) + $(V1)$(foreach fw_targ, $(FW_TARGETS), cp $(BUILD_DIR)/$(fw_targ)/$(fw_targ).opfw $(BUILD_DIR)/ground/$@/build/$(fw_targ)/;) include $(WHEREAMI)/Makefile.$(PLATFORM) diff --git a/package/osx/libraries b/package/osx/libraries index d6c559682..f12e566f8 100755 --- a/package/osx/libraries +++ b/package/osx/libraries @@ -72,8 +72,12 @@ cp -r "/Library/Frameworks/SDL.framework" "${APP}/Contents/Frameworks/" echo "Changing package identification of SDL" install_name_tool -id \ - @executable_path/../Frameworks/SDL.framework/Versions/A/SDL \ - "${APP}/Contents/Frameworks/SDL.framework/Versions/A/SDL" + @executable_path/../Frameworks/SDL.framework/SDL \ + "${APP}/Contents/Frameworks/SDL.framework/SDL" +install_name_tool -change \ + @rpath/SDL.framework/Versions/A/SDL \ + "@executable_path/../Frameworks/SDL.framework/SDL" \ + "${APP}/Contents/Plugins/libsdlgamepad.1.dylib" # deleting unnecessary files echo "Deleting unnecessary files" diff --git a/package/winx86/openpilotgcs.nsi b/package/winx86/openpilotgcs.nsi index eccd11b0a..17ba934dd 100644 --- a/package/winx86/openpilotgcs.nsi +++ b/package/winx86/openpilotgcs.nsi @@ -325,6 +325,7 @@ Section "un.OpenPilot GCS" UnSecProgram DeleteRegKey HKCU "Software\OpenPilot" ; Remove shortcuts, if any + SetShellVarContext all Delete /rebootok "$DESKTOP\OpenPilot GCS.lnk" Delete /rebootok "$SMPROGRAMS\OpenPilot\*" RMDir /rebootok "$SMPROGRAMS\OpenPilot" @@ -332,17 +333,21 @@ SectionEnd Section "un.Maps cache" UnSecCache ; Remove maps cache + SetShellVarContext current RMDir /r /rebootok "$APPDATA\OpenPilot\mapscache" SectionEnd Section /o "un.Configuration" UnSecConfig ; Remove configuration - Delete /rebootok "$APPDATA\OpenPilot\OpenPilotGCS.db" - Delete /rebootok "$APPDATA\OpenPilot\OpenPilotGCS.xml" + SetShellVarContext current + Delete /rebootok "$APPDATA\OpenPilot\OpenPilotGCS*.db" + Delete /rebootok "$APPDATA\OpenPilot\OpenPilotGCS*.xml" + Delete /rebootok "$APPDATA\OpenPilot\OpenPilotGCS*.ini" SectionEnd Section "-un.Profile" UnSecProfile ; Remove OpenPilot user profile subdirectory if empty + SetShellVarContext current RMDir "$APPDATA\OpenPilot" SectionEnd diff --git a/shared/uavobjectdefinition/airspeedactual.xml b/shared/uavobjectdefinition/airspeedactual.xml new file mode 100644 index 000000000..e612b3e31 --- /dev/null +++ b/shared/uavobjectdefinition/airspeedactual.xml @@ -0,0 +1,13 @@ + + + UAVO for true airspeed, calibrated airspeed, angle of attack, and angle of slip + + + + + + + + + + diff --git a/shared/uavobjectdefinition/hwsettings.xml b/shared/uavobjectdefinition/hwsettings.xml index 32b159e34..a398cf35a 100644 --- a/shared/uavobjectdefinition/hwsettings.xml +++ b/shared/uavobjectdefinition/hwsettings.xml @@ -1,9 +1,9 @@ Selection of optional hardware configurations. - - - + + + @@ -16,7 +16,7 @@ - +