diff --git a/MILESTONES.txt b/MILESTONES.txt index 95f7d5ee8..4480129b1 100644 --- a/MILESTONES.txt +++ b/MILESTONES.txt @@ -169,32 +169,6 @@ C: Kavin Gustafson (k_g) D: October 2012 V: http://www.youtube.com/watch?v=MGO68TqIwKk -M: First successful flight using just a mobile phone -C: Jose (please complete details), demoed in Portugal -D: -V: - -M: First CopterControl over 10km FixedWing navigation flight -C: -D: -V: - -M: First successful flight using the GCS only and no RC TX -C: -D: -V: - -M: First CopterControl Navigation on RC Ground Vechicle -C: -D: -V: - -M: First CopterControl Navigation on RC Water Vechicle -C: -D: -V: - - M: First Revo Navigated flight on a FixedWing C: It got done somewhere along the line, likely Corvus. @@ -231,16 +205,6 @@ C: D: V: -M: First Revo Altitude Hold using Sonar -C: -D: -V: - -M: First use of the Magic Waypoint feature -C: -D: -V: - M: First Auto spot landing on a fixed Wing using Revo C: D: diff --git a/Makefile b/Makefile index 48cb90043..89a7d1cd6 100644 --- a/Makefile +++ b/Makefile @@ -740,6 +740,9 @@ ifneq ($(strip $(filter package clean_package,$(MAKECMDGOALS))),) export PACKAGE_NAME := OpenPilot export PACKAGE_SEP := - + # Copy the Qt libraries regardless whether the building machine needs them to run GCS + export FORCE_COPY_QT := true + # We can only package release builds ifneq ($(GCS_BUILD_CONF),release) $(error Packaging is currently supported for release builds only) diff --git a/WHATSNEW.txt b/WHATSNEW.txt index 5f329b876..ce0845421 100644 --- a/WHATSNEW.txt +++ b/WHATSNEW.txt @@ -1,3 +1,19 @@ +--- RELEASE-14.06.01 --- +This is the first maintenance release for 14.06. +This mainly fixes a bug causing flips when switching to Weaklevel flight mode. + +The full list of features, improvements and bugfixes in this release is accessible here: + +http://progress.openpilot.org/issues/?filter=11660 + +**Bugs + * [OP-1241] - TxPID Does not work for Bank 3 PID settings + * [OP-1432] - Hexa config : "Reverse all motors" do not reflect current config after reload + * [OP-1454] - weak leveling code buggy, causes NAN and crash! + +** New Feature & Improvements + * [OP-1450] - GCS fonts are blurry on OSX and retina displays + --- RELEASE-14.06 --- Peanuts Schnapps --- This is the Mid 2014 release. This version supports the CopterControl, CC3D, Atom and the Revolution Flight controllers as well as the OPLink Modems. @@ -5,7 +21,7 @@ This version supports the CopterControl, CC3D, Atom and the Revolution Flight co This release includes many additions, improvements and fixes, it is the result of many thousands of hours of development and testing. Some key additions in this release: -- Many additions and changes aimed at gps/navigation functionality for the Revolution platform including GPS assisted flight modes: Return To Base, Position Hold, AutoCruise and Position Vario(LOS, FPV and NSEW). +- Many additions and changes aimed at gps/navigation functionality for the Revolution platform including GPS assisted flight modes: Return To Base, Position Hold, AutoCruise and Position Vario(LOS, FPV and NSEW). - Stabilization refactoring and enhancements for even better flight performance. - Completely new sensor calibration routines and greatly enhanced GUI. - Additional 3rd Party Hardware support, notably the MS4525DO based airspeed sensors and WS281x LED drivers. diff --git a/flight/libraries/inc/CoordinateConversions.h b/flight/libraries/inc/CoordinateConversions.h index f64823a43..c8a391f43 100644 --- a/flight/libraries/inc/CoordinateConversions.h +++ b/flight/libraries/inc/CoordinateConversions.h @@ -97,7 +97,7 @@ void rot_mult(float R[3][3], const float vec[3], float vec_out[3]); * @param b * @param result */ -inline void matrix_mult_3x3f(float a[3][3], float b[3][3], float result[3][3]) +static inline void matrix_mult_3x3f(float a[3][3], float b[3][3], float result[3][3]) { result[0][0] = a[0][0] * b[0][0] + a[1][0] * b[0][1] + a[2][0] * b[0][2]; result[0][1] = a[0][1] * b[0][0] + a[1][1] * b[0][1] + a[2][1] * b[0][2]; diff --git a/flight/libraries/rscode/ecc.h b/flight/libraries/rscode/ecc.h index bf56a0b9a..0a6316d8a 100644 --- a/flight/libraries/rscode/ecc.h +++ b/flight/libraries/rscode/ecc.h @@ -66,7 +66,7 @@ extern int pBytes[MAXDEG]; extern int synBytes[MAXDEG]; /* print debugging info */ -extern int DEBUG; +//extern int DEBUG; /* Reed Solomon encode/decode routines */ void initialize_ecc (void); diff --git a/flight/libraries/rscode/rs.c b/flight/libraries/rscode/rs.c index 39c014720..62fd02386 100644 --- a/flight/libraries/rscode/rs.c +++ b/flight/libraries/rscode/rs.c @@ -38,7 +38,7 @@ int synBytes[MAXDEG]; /* generator polynomial */ int genPoly[MAXDEG*2]; -int DEBUG = FALSE; +//int DEBUG = FALSE; static void compute_genpoly (int nbytes, int genpoly[]); diff --git a/flight/pios/inc/pios_debug.h b/flight/pios/inc/pios_debug.h index 8fd7016a9..4d481dfbd 100644 --- a/flight/pios/inc/pios_debug.h +++ b/flight/pios/inc/pios_debug.h @@ -58,7 +58,7 @@ void PIOS_DEBUG_PinHigh(uint8_t pin); void PIOS_DEBUG_PinLow(uint8_t pin); void PIOS_DEBUG_PinValue8Bit(uint8_t value); void PIOS_DEBUG_PinValue4BitL(uint8_t value); -void PIOS_DEBUG_Panic(const char *msg); +void PIOS_DEBUG_Panic(const char *msg) __attribute__((noreturn)); #ifdef DEBUG #define PIOS_DEBUG_Assert(test) if (!(test)) { PIOS_DEBUG_Panic(PIOS_DEBUG_AssertMsg); } diff --git a/flight/pios/osx/inc/pios_debug.h b/flight/pios/osx/inc/pios_debug.h index 1d4b88595..460bf7d0a 100644 --- a/flight/pios/osx/inc/pios_debug.h +++ b/flight/pios/osx/inc/pios_debug.h @@ -38,7 +38,7 @@ void PIOS_DEBUG_PinHigh(uint8_t pin); void PIOS_DEBUG_PinLow(uint8_t pin); void PIOS_DEBUG_PinValue8Bit(uint8_t value); void PIOS_DEBUG_PinValue4BitL(uint8_t value); -void PIOS_DEBUG_Panic(const char *msg); +void PIOS_DEBUG_Panic(const char *msg) __attribute__((noreturn)); #ifdef DEBUG #define PIOS_DEBUG_Assert(test) if (!(test)) { PIOS_DEBUG_Panic(PIOS_DEBUG_AssertMsg); } diff --git a/flight/pios/osx/osx/pios_debug.c b/flight/pios/osx/osx/pios_debug.c index 71120a39d..bb6cd0d9e 100644 --- a/flight/pios/osx/osx/pios_debug.c +++ b/flight/pios/osx/osx/pios_debug.c @@ -82,6 +82,11 @@ void PIOS_DEBUG_Panic(const char *msg) int b = 0; int a = (2 / b); b = a; + + // Stay put + while (1) { + ; + } } /** diff --git a/flight/pios/posix/pios_debug.c b/flight/pios/posix/pios_debug.c index ac67e89a0..1f79c4722 100644 --- a/flight/pios/posix/pios_debug.c +++ b/flight/pios/posix/pios_debug.c @@ -81,6 +81,11 @@ void PIOS_DEBUG_Panic(const char *msg) int b = 0; int a = (2 / b); b = a; + + // Stay put + while (1) { + ; + } } /** diff --git a/flight/pios/stm32f10x/pios_ppm_out.c b/flight/pios/stm32f10x/pios_ppm_out.c index efb6a6a6a..d47934177 100644 --- a/flight/pios/stm32f10x/pios_ppm_out.c +++ b/flight/pios/stm32f10x/pios_ppm_out.c @@ -107,7 +107,7 @@ static const struct pios_tim_callbacks tim_out_callbacks = { int32_t PIOS_PPM_Out_Init(uint32_t *ppm_out_id, const struct pios_ppm_out_cfg *cfg) { - PIOS_DEBUG_Assert(ppm_id); + PIOS_DEBUG_Assert(ppm_out_id); PIOS_DEBUG_Assert(cfg); // Allocate the device structure diff --git a/flight/pios/stm32f4xx/pios_tim.c b/flight/pios/stm32f4xx/pios_tim.c index ec72a9c6f..a5b114b0a 100644 --- a/flight/pios/stm32f4xx/pios_tim.c +++ b/flight/pios/stm32f4xx/pios_tim.c @@ -171,7 +171,7 @@ int32_t PIOS_TIM_InitChannels(uint32_t *tim_id, const struct pios_tim_channel *c */ // commented out for now as f4 starts all clocks GPIO_Init(chan->pin.gpio, &chan->pin.init); - PIOS_DEBUG_Assert(chan->remaP); + PIOS_DEBUG_Assert(chan->remap); // Second parameter should technically be PinSource but they are numerically the same GPIO_PinAFConfig(chan->pin.gpio, chan->pin.pin_source, chan->remap); diff --git a/flight/targets/boards/oplinkmini/firmware/pios_board.c b/flight/targets/boards/oplinkmini/firmware/pios_board.c index ba83a3b45..44c981f45 100644 --- a/flight/targets/boards/oplinkmini/firmware/pios_board.c +++ b/flight/targets/boards/oplinkmini/firmware/pios_board.c @@ -78,6 +78,7 @@ uint8_t *pios_uart_rx_buffer; uint8_t *pios_uart_tx_buffer; uintptr_t pios_uavo_settings_fs_id; +uintptr_t pios_user_fs_id = 0; uint8_t servo_count = 0; diff --git a/flight/targets/boards/osd/firmware/Makefile b/flight/targets/boards/osd/firmware/Makefile index 3744ee56a..928f1310b 100644 --- a/flight/targets/boards/osd/firmware/Makefile +++ b/flight/targets/boards/osd/firmware/Makefile @@ -76,6 +76,8 @@ ifndef TESTAPP SRC += $(OPUAVSYNTHDIR)/gcstelemetrystats.c SRC += $(OPUAVSYNTHDIR)/flighttelemetrystats.c SRC += $(OPUAVSYNTHDIR)/flightstatus.c + SRC += $(OPUAVSYNTHDIR)/flightmodesettings.c + SRC += $(OPUAVSYNTHDIR)/manualcontrolsettings.c SRC += $(OPUAVSYNTHDIR)/systemstats.c SRC += $(OPUAVSYNTHDIR)/systemalarms.c SRC += $(OPUAVSYNTHDIR)/systemsettings.c diff --git a/ground/openpilotgcs/copydata.pro b/ground/openpilotgcs/copydata.pro index d14a816eb..d7fb31c25 100644 --- a/ground/openpilotgcs/copydata.pro +++ b/ground/openpilotgcs/copydata.pro @@ -30,7 +30,10 @@ GCS_LIBRARY_PATH libQt5Qml.so.5 \ libQt5DBus.so.5 \ libQt5QuickParticles.so.5 \ - libqgsttools_p.so.1 + libqgsttools_p.so.1 \ + libicui18n.so.52 \ + libicuuc.so.52 \ + libicudata.so.52 data_copy.commands += -@$(MKDIR) $$targetPath(\"$$GCS_QT_LIBRARY_PATH\") $$addNewline() for(lib, QT_LIBS) { diff --git a/ground/openpilotgcs/openpilotgcs.pri b/ground/openpilotgcs/openpilotgcs.pri index fd97c3c96..66315baf6 100644 --- a/ground/openpilotgcs/openpilotgcs.pri +++ b/ground/openpilotgcs/openpilotgcs.pri @@ -96,13 +96,17 @@ macx { GCS_QT_LIBRARY_PATH = $$GCS_BUILD_TREE/$$GCS_LIBRARY_BASENAME/qt5 GCS_QT_PLUGINS_PATH = $$GCS_BUILD_TREE/$$GCS_LIBRARY_BASENAME/qt5/plugins GCS_QT_QML_PATH = $$GCS_BUILD_TREE/$$GCS_LIBRARY_BASENAME/qt5/qml - lib_dir_is_in_tools = $$[QT_INSTALL_LIBS] - lib_dir_is_in_tools ~= s,$$(TOOLS_DIR)*,TRUE - equals(lib_dir_is_in_tools, "TRUE") { + + TOOLS_DIR = $$clean_path($$GCS_SOURCE_TREE/../../tools) + QT_INSTALL_DIR = $$clean_path($$[QT_INSTALL_LIBS]/../../../..) + equals(QT_INSTALL_DIR, $$TOOLS_DIR) { copyqt = 1 } else { - copyqt = 0 + copyqt = 0 } + + FORCE_COPY_QT = $$(FORCE_COPY_QT) + !isEmpty(FORCE_COPY_QT):copyqt = 1 } GCS_LIBRARY_PATH = $$GCS_BUILD_TREE/$$GCS_LIBRARY_BASENAME/openpilotgcs GCS_PLUGIN_PATH = $$GCS_LIBRARY_PATH/plugins diff --git a/ground/openpilotgcs/share/openpilotgcs/default_configurations/OpenPilotGCS.xml b/ground/openpilotgcs/share/openpilotgcs/default_configurations/OpenPilotGCS.xml index 88032dc41..023642870 100644 --- a/ground/openpilotgcs/share/openpilotgcs/default_configurations/OpenPilotGCS.xml +++ b/ground/openpilotgcs/share/openpilotgcs/default_configurations/OpenPilotGCS.xml @@ -2520,47 +2520,11 @@ - - - LineardialGadget - - Flight Time - - uavGadget - - - - LineardialGadget - - Arm Status - - uavGadget - - - LineardialGadget - - Flight mode - - uavGadget - - 1 - @Variant(AAAACQAAAAIAAAACAAAAYwAAAAIAAAB7) - splitter - - 1 - @Variant(AAAACQAAAAIAAAACAAAAZgAAAAIAAADf) - splitter - - PfdQmlGadget NoTerrain uavGadget - - 2 - @Variant(AAAACQAAAAIAAAACAAAAQAAAAAIAAAG4) - splitter @@ -2582,7 +2546,7 @@ splitter 2 - @Variant(AAAACQAAAAIAAAACAAABqQAAAAIAAADm) + @Variant(AAAACQAAAAIAAAACAAACigAAAAIAAAE0) splitter @@ -2593,7 +2557,7 @@ uavGadget 1 - @Variant(AAAACQAAAAIAAAACAAACdgAAAAIAAAMp) + @Variant(AAAACQAAAAIAAAACAAADXwAAAAIAAAQc) splitter UAVGadgetManagerV1 diff --git a/ground/openpilotgcs/share/openpilotgcs/dials/deluxe/lineardial-vertical.svg b/ground/openpilotgcs/share/openpilotgcs/dials/deluxe/lineardial-vertical.svg index 48392fb0a..d0b256548 100644 --- a/ground/openpilotgcs/share/openpilotgcs/dials/deluxe/lineardial-vertical.svg +++ b/ground/openpilotgcs/share/openpilotgcs/dials/deluxe/lineardial-vertical.svg @@ -14,8 +14,8 @@ height="322.58304" id="svg10068" version="1.1" - inkscape:version="0.48.2 r9819" - sodipodi:docname="lineardial-vertical-old2.svg" + inkscape:version="0.48.5 r10040" + sodipodi:docname="lineardial-vertical.svg" inkscape:export-filename="H:\Documents\Hobbies\W433\My Gauges\vbat-001.png" inkscape:export-xdpi="103.61" inkscape:export-ydpi="103.61" @@ -757,16 +757,16 @@ borderopacity="1.0" inkscape:pageopacity="0.0" inkscape:pageshadow="2" - inkscape:zoom="7.87" - inkscape:cx="0.68217946" - inkscape:cy="151.28502" + inkscape:zoom="5.6568542" + inkscape:cx="26.078149" + inkscape:cy="28.131038" inkscape:document-units="px" - inkscape:current-layer="layer4" + inkscape:current-layer="layer1" showgrid="false" - inkscape:window-width="1680" - inkscape:window-height="957" + inkscape:window-width="1280" + inkscape:window-height="928" inkscape:window-x="0" - inkscape:window-y="0" + inkscape:window-y="27" inkscape:window-maximized="1" inkscape:object-paths="true" showguides="true" @@ -782,7 +782,7 @@ image/svg+xml - + Edouard Lafargue @@ -925,15 +925,15 @@ 0 ? Math.floor((wp_eta - wp_eta_h*3600)/60) : 0) property real wp_eta_s: (wp_eta > 0 ? Math.floor(wp_eta - wp_eta_h*3600 - wp_eta_m*60) : 0) - property real posEast_old - property real posNorth_old - property real total_distance - property bool init_dist: false + property real est_flight_time: Math.round(FlightBatteryState.EstimatedFlightTime) + property real est_time_h: (est_flight_time > 0 ? Math.floor(est_flight_time / 3600) : 0 ) + property real est_time_m: (est_flight_time > 0 ? Math.floor((est_flight_time - est_time_h*3600)/60) : 0) + property real est_time_s: (est_flight_time > 0 ? Math.floor(est_flight_time - est_time_h*3600 - est_time_m*60) : 0) function reset_distance(){ total_distance = 0; @@ -59,7 +65,115 @@ Item { else return time.toString(); } - + + // + // Panel functions + // + + property bool hide_display_rc: false + property bool hide_display_bat: false + property bool hide_display_oplm: false + + function hide_display_rcinput(){ + if (hide_display_rc == false && hide_display_bat == false && hide_display_oplm == false) + hide_display_rc = true; + else + hide_display_rc = false; + battery_bg.z = -1 + oplm_bg.z = -1 + } + + function hide_display_battery(){ + if (hide_display_bat == false && hide_display_rc == false && hide_display_oplm == false) + hide_display_bat = true; + else + hide_display_bat = false; + battery_bg.z = 10 + oplm_bg.z = -1 + } + + function hide_display_oplink(){ + if (hide_display_oplm == false && hide_display_rc == false && hide_display_bat == false) + hide_display_oplm = true; + else + hide_display_oplm = false; + oplm_bg.z = 20 + } + + // Uninitialised, Ok, Warning, Critical, Error + property variant batColors : ["#2c2929", "green", "orange", "red", "red"] + + property real smeter_angle + + // Needed to get correctly int8 value, reset value (-127) on disconnect + property int oplm0_db: OPLinkStatus.LinkState == 4 ? OPLinkStatus.PairSignalStrengths_0 : -127 + property int oplm1_db: OPLinkStatus.LinkState == 4 ? OPLinkStatus.PairSignalStrengths_1 : -127 + property int oplm2_db: OPLinkStatus.LinkState == 4 ? OPLinkStatus.PairSignalStrengths_2 : -127 + property int oplm3_db: OPLinkStatus.LinkState == 4 ? OPLinkStatus.PairSignalStrengths_3 : -127 + + // Filtering for S-meter. Smeter range -127dB <--> -13dB = S9+60dB + + Timer { + id: smeter_filter0 + interval: 100; running: true; repeat: true + onTriggered: smeter_angle = (0.90 * smeter_angle) + (0.1 * (oplm0_db + 13)) + } + + Timer { + id: smeter_filter1 + interval: 100; repeat: true + onTriggered: smeter_angle = (0.90 * smeter_angle) + (0.1 * (oplm1_db + 13)) + } + + Timer { + id: smeter_filter2 + interval: 100; repeat: true + onTriggered: smeter_angle = (0.90 * smeter_angle) + (0.1 * (oplm2_db + 13)) + } + + Timer { + id: smeter_filter3 + interval: 100; repeat: true + onTriggered: smeter_angle = (0.90 * smeter_angle) + (0.1 * (oplm3_db + 13)) + } + + property int smeter_filter + property variant oplm_pair_id : OPLinkStatus.PairIDs_0 + + function select_oplm(index){ + smeter_filter0.running = false; + smeter_filter1.running = false; + smeter_filter2.running = false; + smeter_filter3.running = false; + + switch(index) { + case 0: + smeter_filter0.running = true; + smeter_filter = 0; + oplm_pair_id = OPLinkStatus.PairIDs_0 + break; + case 1: + smeter_filter1.running = true; + smeter_filter = 1; + oplm_pair_id = OPLinkStatus.PairIDs_1 + break; + case 2: + smeter_filter2.running = true; + smeter_filter = 2; + oplm_pair_id = OPLinkStatus.PairIDs_2 + break; + case 3: + smeter_filter3.running = true; + smeter_filter = 3; + oplm_pair_id = OPLinkStatus.PairIDs_3 + break; + } + } + + // End Functions + // + // Start Drawing + SvgElementImage { id: info_bg sceneSize: info.sceneSize @@ -67,21 +181,9 @@ Item { width: parent.width } - SvgElementImage { - id: batinfo_energy - elementName: "warning-low-energy" - sceneSize: info.sceneSize - Rectangle { - anchors.fill: batinfo_energy - border.width: 0 - // Alarm based on FlightBatteryState.EstimatedFlightTime < 120s orange, < 60s red - color: (FlightBatteryState.EstimatedFlightTime <= 120 && FlightBatteryState.EstimatedFlightTime > 60 ? "orange" : - (FlightBatteryState.EstimatedFlightTime <= 60 ? "red": "black")) - - visible: FlightBatteryState.ConsumedEnergy > 0 - } - } - + // + // GPS Info (Top) + // Repeater { id: satNumberBar @@ -103,55 +205,18 @@ Item { elementName: "gps-mode-text" Text { - text: ["No GPS", "No Fix", "Fix2D", "Fix3D"][GPSPositionSensor.Status] + text: ["NO GPS", "NO FIX", "FIX 2D", "FIX 3D"][GPSPositionSensor.Status] anchors.centerIn: parent - font.pixelSize: Math.floor(parent.height*1.2) + font.pixelSize: Math.floor(parent.height*1.3) + font.family: "Arial" + font.weight: Font.DemiBold color: "white" } } - SvgElementPositionItem { - sceneSize: info.sceneSize - elementName: "telemetry-status" - - Text { - text: ["Disconnected","HandshakeReq","HandshakeAck","Connected"][tele_status.toString()] - - anchors.centerIn: parent - font.pixelSize: Math.floor(parent.height*1.2) - color: "white" - } - } - - Repeater { - id: txNumberBar - - property int txRateNumber : GCSTelemetryStats.TxDataRate.toFixed()/10 // 250 max - - model: 25 - SvgElementImage { - property int minTxRateNumber : index+1 - elementName: "tx" + minTxRateNumber - sceneSize: info.sceneSize - visible: txNumberBar.txRateNumber >= minTxRateNumber && ((GCSTelemetryStats.Status ==3 && OPLinkStatus.LinkState == 4 ) - || (GCSTelemetryStats.Status ==3 && OPLinkStatus.LinkState == 1 )) - } - } - - Repeater { - id: rxNumberBar - - property int rxRateNumber : GCSTelemetryStats.RxDataRate.toFixed()/100 // 2500 max - - model: 25 - SvgElementImage { - property int minRxRateNumber : index+1 - elementName: "rx" + minRxRateNumber - sceneSize: info.sceneSize - visible: rxNumberBar.rxRateNumber >= minRxRateNumber && ((GCSTelemetryStats.Status ==3 && OPLinkStatus.LinkState == 4 ) - || (GCSTelemetryStats.Status ==3 && OPLinkStatus.LinkState == 1 )) - } - } + // + // Waypoint Info (Top) + // SvgElementPositionItem { sceneSize: info.sceneSize @@ -163,10 +228,14 @@ Item { Text { text: " "+wp_heading.toFixed(1)+"°" - anchors.centerIn: parent - font.pixelSize: parent.height*1.1 - color: "magenta" + color: "cyan" + + font { + family: "Arial" + pixelSize: Math.floor(parent.height * 1.5) + weight: Font.DemiBold + } } } @@ -180,10 +249,14 @@ Item { Text { text: " "+wp_distance.toFixed(0)+" m" - anchors.centerIn: parent - font.pixelSize: parent.height*1.1 - color: "magenta" + color: "cyan" + + font { + family: "Arial" + pixelSize: Math.floor(parent.height * 1.5) + weight: Font.DemiBold + } } } @@ -195,14 +268,18 @@ Item { y: Math.floor(scaledBounds.y * sceneItem.height) visible: OPLinkStatus.LinkState == 4 //OPLink Connected - MouseArea { id: total_dist_mouseArea; anchors.fill: parent; onClicked: reset_distance()} + MouseArea { id: total_dist_mouseArea; anchors.fill: parent; cursorShape: Qt.PointingHandCursor; onClicked: reset_distance()} Text { text: " "+total_distance.toFixed(0)+" m" - anchors.centerIn: parent - font.pixelSize: parent.height*1.1 - color: "magenta" + color: "cyan" + + font { + family: "Arial" + pixelSize: Math.floor(parent.height * 1.5) + weight: Font.DemiBold + } } Timer { @@ -221,10 +298,14 @@ Item { Text { text: formatTime(wp_eta_h) + ":" + formatTime(wp_eta_m) + ":" + formatTime(wp_eta_s) - anchors.centerIn: parent - font.pixelSize: parent.height*1.1 - color: "magenta" + color: "cyan" + + font { + family: "Arial" + pixelSize: Math.floor(parent.height * 1.5) + weight: Font.DemiBold + } } } @@ -238,10 +319,14 @@ Item { Text { text: (WaypointActive.Index+1)+" / "+PathPlan.WaypointCount - anchors.centerIn: parent - font.pixelSize: parent.height*1.1 - color: "magenta" + color: "cyan" + + font { + family: "Arial" + pixelSize: Math.floor(parent.height * 1.5) + weight: Font.DemiBold + } } } @@ -254,101 +339,28 @@ Item { visible: SystemAlarms.Alarm_PathPlan == 1 Text { - text: ["Fly End Point","Fly Vector","Fly Circle Right","Fly Circle Left","Drive End Point","Drive Vector","Drive Circle Right", - "Drive Circle Left","Fixed Attitude","Set Accessory","Land","Disarm Alarm"][PathDesired.Mode] - + text: ["FLY END POINT","FLY VECTOR","FLY CIRCLE RIGHT","FLY CIRCLE LEFT","DRIVE END POINT","DRIVE VECTOR","DRIVE CIRCLE LEFT", + "DRIVE CIRCLE RIGHT","FIXED ATTITUDE","SET ACCESSORY","LAND","DISARM ALARM"][PathDesired.Mode] anchors.centerIn: parent - font.pixelSize: parent.height*1.1 - color: "magenta" - } - } + color: "cyan" - SvgElementPositionItem { - sceneSize: info.sceneSize - elementName: "battery-volt-text" - visible: FlightBatteryState.Voltage > 0 - - Text { - text: FlightBatteryState.Voltage.toFixed(2) - anchors.centerIn: parent - color: "white" font { family: "Arial" - pixelSize: Math.floor(parent.height * 1.2) + pixelSize: Math.floor(parent.height * 1.5) + weight: Font.DemiBold } } } - SvgElementPositionItem { - sceneSize: info.sceneSize - elementName: "battery-amp-text" - visible: FlightBatteryState.Current > 0 - - Text { - text: FlightBatteryState.Current.toFixed(2) - anchors.centerIn: parent - color: "white" - font { - family: "Arial" - pixelSize: Math.floor(parent.height * 1.2) - } - } - } - - SvgElementPositionItem { - sceneSize: info.sceneSize - elementName: "battery-milliamp-text" - visible: FlightBatteryState.ConsumedEnergy > 0 - - Text { - text: FlightBatteryState.ConsumedEnergy.toFixed() - anchors.centerIn: parent - color: "white" - font { - family: "Arial" - pixelSize: Math.floor(parent.height * 1.2) - } - } - } - - Repeater { - id: throttleNumberBar - - property int throttleNumber : ActuatorDesired.Thrust.toFixed(1)*10 - - model: 10 - SvgElementImage { - property int minThrottleNumber : index+1 - elementName: "eng" + minThrottleNumber - sceneSize: info.sceneSize - - visible: throttleNumberBar.throttleNumber >= minThrottleNumber - } - } - - SvgElementImage { - id: mask_ThrottleBar - elementName: "throttle-mask" - sceneSize: info.sceneSize - } - SvgElementImage { id: mask_SatBar elementName: "satbar-mask" sceneSize: info.sceneSize } - SvgElementImage { - id: mask_telemetryTx - elementName: "tx-mask" - sceneSize: info.sceneSize - } - - SvgElementImage { - id: mask_telemetryRx - elementName: "rx-mask" - sceneSize: info.sceneSize - } + // + // Home info (visible after arming) + // SvgElementImage { id: home_bg @@ -359,7 +371,7 @@ Item { states: State { name: "fading" when: TakeOffLocation.Status !== 0 - PropertyChanges { target: home_bg; x: Math.floor(scaledBounds.x * sceneItem.width) + home_bg.width; } + PropertyChanges { target: home_bg; x: Math.floor(scaledBounds.x * sceneItem.width) + home_bg.width; } } transitions: Transition { @@ -380,7 +392,7 @@ Item { states: State { name: "fading_heading" when: TakeOffLocation.Status !== 0 - PropertyChanges { target: home_heading_text; x: Math.floor(scaledBounds.x * sceneItem.width) + home_bg.width } + PropertyChanges { target: home_heading_text; x: Math.floor(scaledBounds.x * sceneItem.width) + home_bg.width; } } transitions: Transition { @@ -410,7 +422,7 @@ Item { states: State { name: "fading_distance" when: TakeOffLocation.Status !== 0 - PropertyChanges { target: home_distance_text; x: Math.floor(scaledBounds.x * sceneItem.width) + home_bg.width; } + PropertyChanges { target: home_distance_text; x: Math.floor(scaledBounds.x * sceneItem.width) + home_bg.width; } } transitions: Transition { @@ -441,7 +453,7 @@ Item { states: State { name: "fading_distance" when: TakeOffLocation.Status !== 0 - PropertyChanges { target: home_eta_text; x: Math.floor(scaledBounds.x * sceneItem.width) + home_bg.width; } + PropertyChanges { target: home_eta_text; x: Math.floor(scaledBounds.x * sceneItem.width) + home_bg.width; } } transitions: Transition { @@ -461,6 +473,629 @@ Item { } } + // + // Rc-Input panel + // + + SvgElementImage { + id: rc_input_bg + elementName: "rc-input-bg" + sceneSize: info.sceneSize + y: Math.floor(scaledBounds.y * sceneItem.height) + + states: State { + name: "fading" + when: hide_display_rc !== true + PropertyChanges { target: rc_input_bg; x: Math.floor(scaledBounds.x * sceneItem.width) - (rc_input_bg.width * 0.85); } + } + + transitions: Transition { + SequentialAnimation { + id: rc_input_anim + PropertyAnimation { property: "x"; duration: 800 } + } + } + } + + SvgElementImage { + id: rc_input_labels + elementName: "rc-input-labels" + sceneSize: info.sceneSize + y: Math.floor(scaledBounds.y * sceneItem.height) + + states: State { + name: "fading" + when: hide_display_rc !== true + PropertyChanges { target: rc_input_labels; x: Math.floor(scaledBounds.x * sceneItem.width) - (rc_input_bg.width * 0.85); } + } + + transitions: Transition { + SequentialAnimation { + PropertyAnimation { property: "x"; duration: 800 } + } + } + } + + SvgElementImage { + id: rc_input_mousearea + elementName: "rc-input-panel-mousearea" + sceneSize: info.sceneSize + y: Math.floor(scaledBounds.y * sceneItem.height) + + MouseArea { + id: hidedisp_rcinput; + anchors.fill: parent; + cursorShape: hide_display_bat == false && hide_display_oplm == false ? Qt.WhatsThisCursor : Qt.ArrowCursor + onClicked: hide_display_bat == false && hide_display_oplm == false ? hide_display_rcinput() : 0 + } + + states: State { + name: "fading" + when: hide_display_rc !== true + PropertyChanges { target: rc_input_mousearea; x: Math.floor(scaledBounds.x * sceneItem.width) - (rc_input_bg.width * 0.85); } + } + + transitions: Transition { + SequentialAnimation { + PropertyAnimation { property: "x"; duration: 800 } + } + } + } + + SvgElementImage { + id: rc_throttle + elementName: "rc-throttle" + sceneSize: info.sceneSize + + width: scaledBounds.width * sceneItem.width + height: (scaledBounds.height * sceneItem.height) * (ManualControlCommand.Throttle) + + x: scaledBounds.x * sceneItem.width + y: (scaledBounds.y * sceneItem.height) - rc_throttle.height + (scaledBounds.height * sceneItem.height) + + smooth: true + + states: State { + name: "fading" + when: hide_display_rc !== true + PropertyChanges { target: rc_throttle; x: Math.floor(scaledBounds.x * sceneItem.width) - (rc_input_bg.width * 0.85); } + } + + transitions: Transition { + SequentialAnimation { + PropertyAnimation { property: "x"; duration: 800 } + } + } + } + + SvgElementImage { + id: rc_stick + elementName: "rc-stick" + sceneSize: info.sceneSize + + width: scaledBounds.width * sceneItem.width + height: scaledBounds.height * sceneItem.height + + x: (scaledBounds.x * sceneItem.width) + (ManualControlCommand.Roll * rc_stick.width * 2.5) + y: (scaledBounds.y * sceneItem.height) + (ManualControlCommand.Pitch * rc_stick.width * 2.5) + + smooth: true + + //rotate it around his center + transform: Rotation { + angle: ManualControlCommand.Yaw * 90 + origin.y : rc_stick.height / 2 + origin.x : rc_stick.width / 2 + } + + states: State { + name: "fading" + when: hide_display_rc !== true + PropertyChanges { target: rc_stick; x: Math.floor(scaledBounds.x * sceneItem.width) - (rc_input_bg.width * 0.85); } + } + + transitions: Transition { + SequentialAnimation { + PropertyAnimation { property: "x"; duration: 800 } + } + } + } + + // + // Battery panel + // + + SvgElementImage { + id: battery_bg + elementName: "battery-bg" + sceneSize: info.sceneSize + y: Math.floor(scaledBounds.y * sceneItem.height) + z: 10 + + states: State { + name: "fading" + when: hide_display_bat !== true + PropertyChanges { target: battery_bg; x: Math.floor(scaledBounds.x * sceneItem.width) - (battery_bg.width * 0.85); } + } + + transitions: Transition { + SequentialAnimation { + PropertyAnimation { property: "x"; duration: 800 } + } + } + } + + SvgElementPositionItem { + id: battery_volt + sceneSize: info.sceneSize + elementName: "battery-volt-text" + z: 11 + + width: scaledBounds.width * sceneItem.width + height: scaledBounds.height * sceneItem.height + y: scaledBounds.y * sceneItem.height + + states: State { + name: "fading" + when: hide_display_bat !== true + PropertyChanges { target: battery_volt; x: Math.floor(scaledBounds.x * sceneItem.width) - (battery_bg.width * 0.85); } + } + + transitions: Transition { + SequentialAnimation { + PropertyAnimation { property: "x"; duration: 800 } + } + } + + Rectangle { + anchors.fill: parent + color: info.batColors[SystemAlarms.Alarm_Battery] + border.color: "white" + border.width: battery_volt.width * 0.01 + radius: border.width * 4 + + Text { + text: FlightBatteryState.Voltage.toFixed(2) + anchors.centerIn: parent + color: "white" + font { + family: "Arial" + pixelSize: Math.floor(parent.height * 0.6) + } + } + } + } + + SvgElementPositionItem { + id: battery_amp + sceneSize: info.sceneSize + elementName: "battery-amp-text" + z: 12 + + width: scaledBounds.width * sceneItem.width + height: scaledBounds.height * sceneItem.height + y: scaledBounds.y * sceneItem.height + + states: State { + name: "fading" + when: hide_display_bat !== true + PropertyChanges { target: battery_amp; x: Math.floor(scaledBounds.x * sceneItem.width) - (battery_bg.width * 0.85); } + } + + transitions: Transition { + SequentialAnimation { + PropertyAnimation { property: "x"; duration: 800 } + } + } + + Rectangle { + anchors.fill: parent + color: info.batColors[SystemAlarms.Alarm_Battery] + border.color: "white" + border.width: battery_volt.width * 0.01 + radius: border.width * 4 + + Text { + text: FlightBatteryState.Current.toFixed(2) + anchors.centerIn: parent + color: "white" + font { + family: "Arial" + pixelSize: Math.floor(parent.height * 0.6) + } + } + } + } + + SvgElementPositionItem { + id: battery_milliamp + sceneSize: info.sceneSize + elementName: "battery-milliamp-text" + z: 13 + + width: scaledBounds.width * sceneItem.width + height: scaledBounds.height * sceneItem.height + y: scaledBounds.y * sceneItem.height + + states: State { + name: "fading" + when: hide_display_bat !== true + PropertyChanges { target: battery_milliamp; x: Math.floor(scaledBounds.x * sceneItem.width) - (battery_bg.width * 0.85); } + } + + transitions: Transition { + SequentialAnimation { + PropertyAnimation { property: "x"; duration: 800 } + } + } + + Rectangle { + anchors.fill: parent + + // Alarm based on FlightBatteryState.EstimatedFlightTime < 120s orange, < 60s red + color: (FlightBatteryState.EstimatedFlightTime <= 120 && FlightBatteryState.EstimatedFlightTime > 60 ? "orange" : + (FlightBatteryState.EstimatedFlightTime <= 60 ? "red": info.batColors[SystemAlarms.Alarm_Battery])) + + border.color: "white" + border.width: battery_volt.width * 0.01 + radius: border.width * 4 + + Text { + text: FlightBatteryState.ConsumedEnergy.toFixed(0) + anchors.centerIn: parent + color: "white" + font { + family: "Arial" + pixelSize: Math.floor(parent.height * 0.6) + } + } + } + } + + SvgElementPositionItem { + id: battery_estimated_flight_time + sceneSize: info.sceneSize + elementName: "battery-estimated-flight-time" + z: 14 + width: scaledBounds.width * sceneItem.width + height: scaledBounds.height * sceneItem.height + y: scaledBounds.y * sceneItem.height + + states: State { + name: "fading" + when: hide_display_bat !== true + PropertyChanges { target: battery_estimated_flight_time; x: Math.floor(scaledBounds.x * sceneItem.width) - (battery_bg.width * 0.85); } + } + + transitions: Transition { + SequentialAnimation { + PropertyAnimation { property: "x"; duration: 800 } + } + } + + Rectangle { + anchors.fill: parent + //color: info.batColors[SystemAlarms.Alarm_Battery] + + // Alarm based on FlightBatteryState.EstimatedFlightTime < 120s orange, < 60s red + color: (FlightBatteryState.EstimatedFlightTime <= 120 && FlightBatteryState.EstimatedFlightTime > 60 ? "orange" : + (FlightBatteryState.EstimatedFlightTime <= 60 ? "red": info.batColors[SystemAlarms.Alarm_Battery])) + + border.color: "white" + border.width: battery_volt.width * 0.01 + radius: border.width * 4 + + Text { + text: formatTime(est_time_h) + ":" + formatTime(est_time_m) + ":" + formatTime(est_time_s) + anchors.centerIn: parent + color: "white" + font { + family: "Arial" + pixelSize: Math.floor(parent.height * 0.6) + } + } + } + } + + SvgElementImage { + id: battery_labels + elementName: "battery-labels" + sceneSize: info.sceneSize + y: Math.floor(scaledBounds.y * sceneItem.height) + z: 15 + states: State { + name: "fading" + when: hide_display_bat !== true + PropertyChanges { target: battery_labels; x: Math.floor(scaledBounds.x * sceneItem.width) - (battery_bg.width * 0.85); } + } + + transitions: Transition { + SequentialAnimation { + PropertyAnimation { property: "x"; duration: 800 } + } + } + } + + SvgElementImage { + id: battery_mousearea + elementName: "battery-panel-mousearea" + sceneSize: info.sceneSize + y: Math.floor(scaledBounds.y * sceneItem.height) + z: 16 + + MouseArea { + id: hidedisp_battery; + anchors.fill: parent; + cursorShape: hide_display_rc == false && hide_display_oplm == false ? Qt.WhatsThisCursor : Qt.ArrowCursor + onClicked: hide_display_rc == false && hide_display_oplm == false ? hide_display_battery() : 0 + } + + states: State { + name: "fading" + when: hide_display_bat !== true + PropertyChanges { target: battery_mousearea; x: Math.floor(scaledBounds.x * sceneItem.width) - (battery_bg.width * 0.85); } + } + + transitions: Transition { + SequentialAnimation { + PropertyAnimation { property: "x"; duration: 800 } + } + } + } + + // + // OPLM panel + // + + SvgElementImage { + id: oplm_bg + elementName: "oplm-bg" + sceneSize: info.sceneSize + y: Math.floor(scaledBounds.y * sceneItem.height) + z: 20 + + states: State { + name: "fading" + when: hide_display_oplm !== true + PropertyChanges { target: oplm_bg; x: Math.floor(scaledBounds.x * sceneItem.width) - (oplm_bg.width * 0.85); } + } + + transitions: Transition { + SequentialAnimation { + PropertyAnimation { property: "x"; duration: 800 } + } + } + } + + SvgElementImage { + id: smeter_bg + elementName: "smeter-bg" + sceneSize: info.sceneSize + y: Math.floor(scaledBounds.y * sceneItem.height) + z: 21 + + states: State { + name: "fading" + when: hide_display_oplm !== true + PropertyChanges { target: smeter_bg; x: Math.floor(scaledBounds.x * sceneItem.width) - (oplm_bg.width * 0.85); } + } + + transitions: Transition { + SequentialAnimation { + PropertyAnimation { property: "x"; duration: 800 } + } + } + } + + SvgElementImage { + id: smeter_scale + elementName: "smeter-scale" + sceneSize: info.sceneSize + y: Math.floor(scaledBounds.y * sceneItem.height) + z: 22 + + states: State { + name: "fading" + when: hide_display_oplm !== true + PropertyChanges { target: smeter_scale; x: Math.floor(scaledBounds.x * sceneItem.width) - (oplm_bg.width * 0.85); } + } + + transitions: Transition { + SequentialAnimation { + PropertyAnimation { property: "x"; duration: 800 } + } + } + } + + SvgElementImage { + id: smeter_needle + elementName: "smeter-needle" + sceneSize: info.sceneSize + y: Math.floor(scaledBounds.y * sceneItem.height) + z: 23 + + states: State { + name: "fading" + when: hide_display_oplm !== true + PropertyChanges { target: smeter_needle; x: Math.floor(scaledBounds.x * sceneItem.width) - (oplm_bg.width * 0.85); } + } + + transitions: Transition { + SequentialAnimation { + PropertyAnimation { property: "x"; duration: 800 } + } + } + + transform: Rotation { + angle: smeter_angle.toFixed(1) + origin.y : smeter_needle.height + } + } + + SvgElementImage { + id: smeter_mask + elementName: "smeter-mask" + sceneSize: info.sceneSize + y: Math.floor(scaledBounds.y * sceneItem.height) + z: 24 + + states: State { + name: "fading" + when: hide_display_oplm !== true + PropertyChanges { target: smeter_mask; x: Math.floor(scaledBounds.x * sceneItem.width) - (oplm_bg.width * 0.85); } + } + + transitions: Transition { + SequentialAnimation { + PropertyAnimation { property: "x"; duration: 800 } + } + } + } + + SvgElementImage { + id: oplm_button_bg + elementName: "oplm-button-bg" + sceneSize: info.sceneSize + y: Math.floor(scaledBounds.y * sceneItem.height) + z: 25 + + states: State { + name: "fading" + when: hide_display_oplm !== true + PropertyChanges { target: oplm_button_bg; x: Math.floor(scaledBounds.x * sceneItem.width) - (oplm_bg.width * 0.85); } + } + + transitions: Transition { + SequentialAnimation { + PropertyAnimation { property: "x"; duration: 800 } + } + } + } + + Repeater { + model: 4 + + SvgElementImage { + z: 25 + property variant idButton_oplm: "oplm_button_" + index + property variant idButton_oplm_mousearea: "oplm_button_mousearea" + index + property variant button_color: "button"+index+"_color" + + id: idButton_oplm + + elementName: "oplm-button-" + index + sceneSize: info.sceneSize + + Rectangle { + anchors.fill: parent + border.color: "red" + border.width: parent.width * 0.04 + radius: border.width*3 + color: "transparent" + opacity: smeter_filter == index ? 0.5 : 0 + } + + MouseArea { + id: idButton_oplm_mousearea; + anchors.fill: parent; + cursorShape: Qt.PointingHandCursor + onClicked: select_oplm(index) + } + + states: State { + name: "fading" + when: hide_display_oplm !== true + PropertyChanges { target: idButton_oplm; x: Math.floor(scaledBounds.x * sceneItem.width) - (oplm_bg.width * 0.85); } + } + + transitions: Transition { + SequentialAnimation { + PropertyAnimation { property: "x"; duration: 800 } + } + } + } + } + + SvgElementImage { + id: oplm_id_label + elementName: "oplm-id-label" + sceneSize: info.sceneSize + y: Math.floor(scaledBounds.y * sceneItem.height) + z: 26 + states: State { + name: "fading" + when: hide_display_oplm !== true + PropertyChanges { target: oplm_id_label; x: Math.floor(scaledBounds.x * sceneItem.width) - (oplm_bg.width * 0.85); } + } + + transitions: Transition { + SequentialAnimation { + PropertyAnimation { property: "x"; duration: 800 } + } + } + } + + SvgElementPositionItem { + id: oplm_id_text + sceneSize: info.sceneSize + elementName: "oplm-id-text" + z: 27 + + width: scaledBounds.width * sceneItem.width + height: scaledBounds.height * sceneItem.height + y: scaledBounds.y * sceneItem.height + + states: State { + name: "fading" + when: hide_display_oplm !== true + PropertyChanges { target: oplm_id_text; x: Math.floor(scaledBounds.x * sceneItem.width) - (oplm_bg.width * 0.85); } + } + + transitions: Transition { + SequentialAnimation { + PropertyAnimation { property: "x"; duration: 800 } + } + } + + Text { + text: oplm_pair_id > 0 ? oplm_pair_id.toString(16) : "-- -- -- --" + anchors.centerIn: parent + color: "white" + font { + family: "Arial" + pixelSize: Math.floor(parent.height * 1.4) + weight: Font.DemiBold + capitalization: Font.AllUppercase + } + } + } + + SvgElementImage { + id: oplm_mousearea + elementName: "oplm-panel-mousearea" + sceneSize: info.sceneSize + y: Math.floor(scaledBounds.y * sceneItem.height) + z: 26 + + MouseArea { + id: hidedisp_oplm; + anchors.fill: parent; + cursorShape: hide_display_rc == false && hide_display_bat == false ? Qt.WhatsThisCursor : Qt.ArrowCursor + onClicked: hide_display_rc == false && hide_display_bat == false ? hide_display_oplink() : 0 + } + + states: State { + name: "fading" + when: hide_display_oplm !== true + PropertyChanges { target: oplm_mousearea; x: Math.floor(scaledBounds.x * sceneItem.width) - (oplm_bg.width * 0.85); } + } + + transitions: Transition { + SequentialAnimation { + PropertyAnimation { property: "x"; duration: 800 } + } + } + } SvgElementImage { id: info_border diff --git a/ground/openpilotgcs/share/openpilotgcs/pfd/default/VsiScale.qml b/ground/openpilotgcs/share/openpilotgcs/pfd/default/VsiScale.qml index c40591424..033c8cb40 100644 --- a/ground/openpilotgcs/share/openpilotgcs/pfd/default/VsiScale.qml +++ b/ground/openpilotgcs/share/openpilotgcs/pfd/default/VsiScale.qml @@ -3,6 +3,14 @@ import QtQuick 2.0 Item { id: sceneItem property variant sceneSize + property real vert_velocity + + Timer { + interval: 100; running: true; repeat: true + onTriggered: vert_velocity = (0.9 * vert_velocity) + (0.1 * VelocityState.Down) + } + + SvgElementImage { id: vsi_window @@ -13,82 +21,69 @@ Item { x: Math.floor(scaledBounds.x * sceneItem.width) y: Math.floor(scaledBounds.y * sceneItem.height) - property double scaleSteps : 8 - property double scaleStepValue : 1000 - property double scaleStepHeight : height/scaleSteps + } - SvgElementImage { - id: vsi_bar + SvgElementImage { + id: vsi_waypoint + elementName: "vsi-waypoint" + sceneSize: sceneItem.sceneSize - elementName: "vsi-bar" - sceneSize: sceneItem.sceneSize + width: scaledBounds.width * sceneItem.width + height: scaledBounds.height * sceneItem.height - //the scale in 1000 ft/min, convert from VelocityState.Down value in m/s - height: (-VelocityState.Down*3.28*60/vsi_window.scaleStepValue)*vsi_window.scaleStepHeight + x: scaledBounds.x * sceneItem.width + y: scaledBounds.y * sceneItem.height - anchors.bottom: parent.verticalCenter - anchors.left: parent.left - } + smooth: true + visible: VelocityDesired.Down !== 0.0 && FlightStatus.FlightMode > 7 - SvgElementImage { - id: vsi_scale - - elementName: "vsi-scale" - sceneSize: sceneItem.sceneSize - - anchors.verticalCenter: parent.verticalCenter - anchors.left: parent.left - - //Text labels - Column { - anchors.verticalCenter: parent.verticalCenter - anchors.left: parent.right - - Repeater { - model: [3, 2, 1, 0, 1, 2, 3] - Item { - height: vsi_window.scaleStepHeight - width: vsi_window.width - vsi_scale.width //fill area right to scale - - Text { - text: modelData - visible: modelData !== 0 //hide "0" label - color: "white" - font.pixelSize: parent.height * 0.5 - font.family: "Arial" - - anchors.centerIn: parent - } - } - } - } + //rotate it around the center + transform: Rotation { + angle: -VelocityDesired.Down * 5 + origin.y : vsi_waypoint.height / 2 + origin.x : vsi_waypoint.width * 33 } } - SvgElementImage { - id: vsi_centerline - clip: true - smooth: true + id: vsi_scale - elementName: "vsi-centerline" + elementName: "vsi-scale" sceneSize: sceneItem.sceneSize x: Math.floor(scaledBounds.x * sceneItem.width) y: Math.floor(scaledBounds.y * sceneItem.height) + } - Text { - id: vsi_unit_text - text: "ft / m" + SvgElementImage { + id: vsi_arrow + elementName: "vsi-arrow" + sceneSize: sceneItem.sceneSize - color: "white" - font { - family: "Arial" - pixelSize: sceneSize.height * 0.02 + width: scaledBounds.width * sceneItem.width + height: scaledBounds.height * sceneItem.height + + x: scaledBounds.x * sceneItem.width + y: scaledBounds.y * sceneItem.height + + smooth: true + + //rotate it around the center + transform: Rotation { + angle: -vert_velocity * 5 + origin.y : vsi_arrow.height / 2 + origin.x : vsi_arrow.width * 3.15 } - anchors.top: vsi_window.bottom - anchors.left: vsi_window.left - anchors.margins: font.pixelSize * 0.5 + } + + SvgElementImage { + id: foreground + elementName: "foreground" + sceneSize: sceneItem.sceneSize + + x: Math.floor(scaledBounds.x * sceneItem.width) + y: Math.floor(scaledBounds.y * sceneItem.height) + } } diff --git a/ground/openpilotgcs/share/openpilotgcs/pfd/default/Warnings.qml b/ground/openpilotgcs/share/openpilotgcs/pfd/default/Warnings.qml index 82030e16b..c6f4e6476 100644 --- a/ground/openpilotgcs/share/openpilotgcs/pfd/default/Warnings.qml +++ b/ground/openpilotgcs/share/openpilotgcs/pfd/default/Warnings.qml @@ -6,6 +6,45 @@ Item { // Uninitialised, OK, Warning, Error, Critical property variant statusColors : ["gray", "green", "red", "red", "red"] + // DisArmed , Arming, Armed + property variant armColors : ["gray", "orange", "green"] + + // All 'manual modes' are green, 'assisted' modes in cyan + // "MANUAL","STAB 1","STAB 2", "STAB 3", "STAB 4", "STAB 5", "STAB 6", "AUTOTUNE", + // "POS HOLD", "POS VFPV", "POS VLOS", "POS VNSEW", "RTB", "LAND", "PATHPLANNER", "POI", "AUTOCRUISE" + + property variant flightmodeColors : ["gray", "green", "green", "green", "green", "green", "green", "red", + "cyan", "cyan", "cyan", "cyan", "cyan", "cyan", "cyan", "cyan", "cyan"] + + // Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude, + // AltitudeHold,AltitudeVario,CruiseControl + Auto mode (VTOL/Wing pathfollower) + // grey : 'disabled' modes + + property variant thrustmodeColors : ["green", "grey", "grey", "grey", "grey", "grey", "grey", "grey", "grey", + "green", "green", "green", "cyan"] + + // SystemSettings.AirframeType 3 - 17 : VtolPathFollower, check ThrustControl + + property var thrust_mode: FlightStatus.FlightMode < 7 ? StabilizationDesired.StabilizationMode_Thrust : + FlightStatus.FlightMode > 7 && SystemSettings.AirframeType > 2 && SystemSettings.AirframeType < 18 + && VtolPathFollowerSettings.ThrustControl == 1 ? 12 : + FlightStatus.FlightMode > 7 && SystemSettings.AirframeType < 3 ? 12: 0 + + + property real flight_time: Math.round(SystemStats.FlightTime / 1000) + property real time_h: (flight_time > 0 ? Math.floor(flight_time / 3600) : 0 ) + property real time_m: (flight_time > 0 ? Math.floor((flight_time - time_h*3600)/60) : 0) + property real time_s: (flight_time > 0 ? Math.floor(flight_time - time_h*3600 - time_m*60) : 0) + + function formatTime(time) { + if (time === 0) + return "00" + if (time < 10) + return "0" + time; + else + return time.toString(); + } + SvgElementImage { id: warning_bg elementName: "warnings-bg" @@ -14,10 +53,64 @@ Item { anchors.bottom: parent.bottom } + SvgElementPositionItem { + id: warning_time + sceneSize: parent.sceneSize + elementName: "warning-time" + width: scaledBounds.width * sceneItem.width + height: scaledBounds.height * sceneItem.height + x: scaledBounds.x * sceneItem.width + y: scaledBounds.y * sceneItem.height + + Rectangle { + anchors.fill: parent + color: (SystemStats.FlightTime > 0 ? "green" : "grey") + + Text { + anchors.centerIn: parent + text: formatTime(time_h) + ":" + formatTime(time_m) + ":" + formatTime(time_s) + font { + family: "Arial" + pixelSize: Math.floor(parent.height * 0.8) + weight: Font.DemiBold + } + } + } + } + + SvgElementPositionItem { + id: warning_arm + sceneSize: parent.sceneSize + elementName: "warning-arm" + width: scaledBounds.width * sceneItem.width + height: scaledBounds.height * sceneItem.height + x: scaledBounds.x * sceneItem.width + y: scaledBounds.y * sceneItem.height + + Rectangle { + anchors.fill: parent + color: warnings.armColors[FlightStatus.Armed] + + Text { + anchors.centerIn: parent + text: ["DISARMED","ARMING","ARMED"][FlightStatus.Armed] + font { + family: "Arial" + pixelSize: Math.floor(parent.height * 0.74) + weight: Font.DemiBold + } + } + } + } + SvgElementPositionItem { id: warning_rc_input sceneSize: parent.sceneSize elementName: "warning-rc-input" + width: scaledBounds.width * sceneItem.width + height: scaledBounds.height * sceneItem.height + x: scaledBounds.x * sceneItem.width + y: scaledBounds.y * sceneItem.height Rectangle { anchors.fill: parent @@ -28,7 +121,7 @@ Item { text: "RC INPUT" font { family: "Arial" - pixelSize: Math.floor(parent.height * 0.8) + pixelSize: Math.floor(parent.height * 0.74) weight: Font.DemiBold } } @@ -39,6 +132,10 @@ Item { id: warning_master_caution sceneSize: parent.sceneSize elementName: "warning-master-caution" + width: scaledBounds.width * sceneItem.width + height: scaledBounds.height * sceneItem.height + x: scaledBounds.x * sceneItem.width + y: scaledBounds.y * sceneItem.height property bool warningActive: (SystemAlarms.Alarm_BootFault > 1 || SystemAlarms.Alarm_OutOfMemory > 1 || @@ -48,14 +145,15 @@ Item { Rectangle { anchors.fill: parent color: parent.warningActive ? "red" : "red" - opacity: parent.warningActive ? 1.0 : 0.15 + opacity: parent.warningActive ? 1.0 : 0.4 Text { anchors.centerIn: parent text: "MASTER CAUTION" + color: "white" font { family: "Arial" - pixelSize: Math.floor(parent.height * 0.8) + pixelSize: Math.floor(parent.height * 0.74) weight: Font.DemiBold } } @@ -66,6 +164,10 @@ Item { id: warning_autopilot sceneSize: parent.sceneSize elementName: "warning-autopilot" + width: scaledBounds.width * sceneItem.width + height: scaledBounds.height * sceneItem.height + x: scaledBounds.x * sceneItem.width + y: scaledBounds.y * sceneItem.height Rectangle { anchors.fill: parent @@ -76,7 +178,62 @@ Item { text: "AUTOPILOT" font { family: "Arial" - pixelSize: Math.floor(parent.height * 0.8) + pixelSize: Math.floor(parent.height * 0.74) + weight: Font.DemiBold + } + } + } + } + + SvgElementPositionItem { + id: warning_flightmode + sceneSize: parent.sceneSize + elementName: "warning-flightmode" + width: scaledBounds.width * sceneItem.width + height: scaledBounds.height * sceneItem.height + x: scaledBounds.x * sceneItem.width + y: scaledBounds.y * sceneItem.height + + Rectangle { + anchors.fill: parent + color: warnings.flightmodeColors[FlightStatus.FlightMode] + + Text { + anchors.centerIn: parent + text: ["MANUAL","STAB 1","STAB 2", "STAB 3", "STAB 4", "STAB 5", "STAB 6", "AUTOTUNE", "POS HOLD", "POS VFPV", + "POS VLOS", "POS VNSEW", "RTB", "LAND", "PATHPLAN", "POI", "AUTOCRUISE"][FlightStatus.FlightMode] + font { + family: "Arial" + pixelSize: Math.floor(parent.height * 0.74) + weight: Font.DemiBold + } + } + } + } + + SvgElementPositionItem { + id: warning_thrustmode + sceneSize: parent.sceneSize + elementName: "warning-thrustmode" + width: scaledBounds.width * sceneItem.width + height: scaledBounds.height * sceneItem.height + x: scaledBounds.x * sceneItem.width + y: scaledBounds.y * sceneItem.height + + Rectangle { + anchors.fill: parent + color: FlightStatus.FlightMode < 1 ? "grey" : warnings.thrustmodeColors[thrust_mode.toString()] + + // Manual,Rate,Attitude,AxisLock,WeakLeveling,VirtualBar,Rattitude,RelayRate,RelayAttitude, + // AltitudeHold,AltitudeVario,CruiseControl + // grey : 'disabled' modes + Text { + anchors.centerIn: parent + text: ["MANUAL"," "," ", " ", " ", " ", " ", " ", " ", + "ALT HOLD", "ALT VARIO", "CRUISECTRL", "AUTO"][thrust_mode.toString()] + font { + family: "Arial" + pixelSize: Math.floor(parent.height * 0.74) weight: Font.DemiBold } } @@ -91,22 +248,6 @@ Item { visible: SystemAlarms.Alarm_GPS > 1 } - SvgElementImage { - id: warning_telemetry - elementName: "warning-telemetry" - sceneSize: warnings.sceneSize - - visible: SystemAlarms.Alarm_Telemetry > 1 - } - - SvgElementImage { - id: warning_battery - elementName: "warning-battery" - sceneSize: warnings.sceneSize - anchors.right: parent.right - visible: SystemAlarms.Alarm_Battery > 1 - } - SvgElementImage { id: warning_attitude elementName: "warning-attitude" diff --git a/ground/openpilotgcs/share/openpilotgcs/pfd/default/pfd.svg b/ground/openpilotgcs/share/openpilotgcs/pfd/default/pfd.svg index eddbc6a21..560b7ee07 100644 --- a/ground/openpilotgcs/share/openpilotgcs/pfd/default/pfd.svg +++ b/ground/openpilotgcs/share/openpilotgcs/pfd/default/pfd.svg @@ -2,24 +2,79 @@ + + + + + + + + + + + + + + + + + + + @@ -42,6 +97,100 @@ offset="1" id="stop5010" /> + + + + + + + + + + + + + inkscape:snap-object-midpoints="false" + inkscape:snap-center="false" + inkscape:snap-bbox-edge-midpoints="false"> + + + @@ -219,37 +384,37 @@ style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Sans" id="pitch_label10R"> @@ -258,36 +423,36 @@ style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Sans" id="pitch_label20R"> @@ -296,12 +461,12 @@ style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Sans" id="pitch_label-20R"> @@ -309,23 +474,23 @@ @@ -334,37 +499,37 @@ style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Sans" id="pitch_label-10R"> @@ -373,12 +538,12 @@ style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Sans" id="pitch_label30R"> @@ -386,11 +551,11 @@ @@ -412,12 +577,12 @@ style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Sans" id="pitch_label40R"> @@ -425,11 +590,11 @@ @@ -451,37 +616,37 @@ style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Sans" id="pitch_label50R"> @@ -490,37 +655,37 @@ style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Sans" id="pitch_label60R"> @@ -529,12 +694,12 @@ style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Sans" id="pitch_label70R"> @@ -542,23 +707,23 @@ @@ -567,25 +732,25 @@ style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Sans" id="pitch_label80R"> @@ -607,12 +772,12 @@ style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Sans" id="pitch_label90R"> @@ -620,23 +785,23 @@ @@ -645,36 +810,36 @@ style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Sans" id="pitch_label-40R"> @@ -683,36 +848,36 @@ style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Sans" id="pitch_label-30R"> @@ -721,12 +886,12 @@ style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Sans" id="pitch_label-60R"> @@ -734,23 +899,23 @@ @@ -759,12 +924,12 @@ style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Sans" id="pitch_label-50R"> @@ -772,23 +937,23 @@ @@ -797,36 +962,36 @@ style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Sans" id="pitch_label-80R"> @@ -835,24 +1000,24 @@ style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Sans" id="pitch_label-70R"> @@ -860,12 +1025,12 @@ style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Sans" id="pitch_label-90L"> @@ -874,12 +1039,12 @@ style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Sans" id="pitch_label-90R"> @@ -905,7 +1070,7 @@ transform="translate(0.42403,0)"> @@ -914,17 +1079,17 @@ id="home-eta-label" transform="matrix(1,0,0,1.0973877,0,-46.442937)"> @@ -934,22 +1099,22 @@ id="home-distance-label" transform="matrix(1,0,0,1.0577142,0,-27.456636)"> @@ -958,29 +1123,29 @@ style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none;display:inline;font-family:Sans" id="home-label"> @@ -1016,42 +1181,42 @@ id="home-eta-text" transform="matrix(1,0,0,0.99160769,0,2.0646588)"> @@ -1068,37 +1233,37 @@ id="home-distance-text" transform="matrix(1,0,0,0.99160769,0,2.0975587)"> @@ -1115,29 +1280,1338 @@ id="home-heading-text" transform="matrix(1,0,0,0.99160769,15.28151,1.9884587)"> + + + + + + + + + + + + + + + + + + + + + + + PITCH + ROLL + + + + THROTTLE + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + 2 + + + + 3 + + + + 4 + + + + + + + + + + + + + + + + + + + + + + + + + + transform="translate(0,-4)" + sodipodi:insensitive="true"> - - - - - + inkscape:label="#g4460" + transform="matrix(1.1653043,0,0,1,0.08265213,0)"> - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + transform="translate(0,-2.08992)" /> + transform="matrix(1.7146685,0,0,1.7146685,-176.95942,-5.87421)"> @@ -1342,19 +2656,19 @@ + transform="matrix(1.6526792,0,0,1.6526792,-165.99391,-4.9162026)"> @@ -1362,19 +2676,19 @@ + transform="matrix(1.6526792,0,0,1.6526792,-194.69489,-29.916207)"> @@ -1382,31 +2696,31 @@ inkscape:connector-curvature="0" id="path3906" style="font-size:8px;fill:#ffffff" - d="m 290.04935,24.257889 4.93359,0 0,0.664062 -2.07031,0 0,5.167969 -0.79297,0 0,-5.167969 -2.07031,0 0,-0.664062" /> + d="m 290.04935,24.257889 l 4.93359,0 l 0,0.664062 l -2.07031,0 l 0,5.167969 l -0.79297,0 l 0,-5.167969 l -2.07031,0 l 0,-0.664062" /> + d="m 278.05325,24.906326 l 0,4.535157 l 0.95313,0 c 0.80468,0 1.39322,-0.182291 1.76562,-0.546875 c 0.375,-0.364582 0.5625,-0.940102 0.5625,-1.726563 c 0,-0.781246 -0.1875,-1.35286 -0.5625,-1.714844 c -0.3724,-0.364578 -0.96094,-0.54687 -1.76562,-0.546875 l -0.95313,0 m -0.78906,-0.648437 l 1.62109,0 c 1.13021,6e-6 1.95964,0.235682 2.48829,0.707031 c 0.52864,0.468755 0.79296,1.203129 0.79296,2.203125 c 0,1.00521 -0.26563,1.743491 -0.79687,2.214844 c -0.53125,0.471354 -1.35938,0.707031 -2.48438,0.707031 l -1.62109,0 l 0,-5.832031" /> @@ -1414,34 +2728,34 @@ inkscape:connector-curvature="0" id="path3902" style="font-size:8px;fill:#ffffff" - d="m 283.42044,24.257889 0.78906,0 0,5.832031 -0.78906,0 0,-5.832031" /> + d="m 283.42044,24.257889 l 0.78906,0 l 0,5.832031 l -0.78906,0 l 0,-5.832031" /> + d="m 289.27591,24.449295 l 0,0.769531 c -0.29948,-0.143224 -0.58204,-0.249995 -0.84766,-0.320312 c -0.26562,-0.07031 -0.52214,-0.105464 -0.76953,-0.105469 c -0.42969,5e-6 -0.76172,0.08334 -0.99609,0.25 c -0.23177,0.166672 -0.34766,0.403651 -0.34766,0.710938 c 0,0.257816 0.0768,0.453128 0.23047,0.585937 c 0.15625,0.130212 0.45052,0.235681 0.88281,0.316406 l 0.47657,0.09766 c 0.58853,0.111982 1.02213,0.309898 1.30078,0.59375 c 0.28124,0.281252 0.42187,0.658856 0.42187,1.132812 c 0,0.565105 -0.19011,0.99349 -0.57031,1.285156 c -0.37761,0.291667 -0.9323,0.4375 -1.66406,0.4375 c -0.27605,0 -0.57032,-0.03125 -0.88282,-0.09375 c -0.30989,-0.0625 -0.63151,-0.154947 -0.96484,-0.277343 l 0,-0.8125 c 0.32031,0.179688 0.63411,0.315104 0.94141,0.40625 c 0.30729,0.09115 0.60937,0.136719 0.90625,0.136718 c 0.45051,1e-6 0.79817,-0.08854 1.04297,-0.265625 c 0.24478,-0.177082 0.36718,-0.429686 0.36718,-0.757812 c 0,-0.286457 -0.0885,-0.510415 -0.26562,-0.671875 c -0.17448,-0.161456 -0.46224,-0.28255 -0.86328,-0.363281 l -0.48047,-0.09375 c -0.58855,-0.117185 -1.01433,-0.300779 -1.27735,-0.550782 C 285.65351,26.609458 285.522,26.261802 285.522,25.816486 c 0,-0.515621 0.18099,-0.92187 0.54297,-1.21875 c 0.36458,-0.29687 0.86589,-0.445307 1.50391,-0.445313 c 0.27343,6e-6 0.55208,0.02475 0.83594,0.07422 c 0.28385,0.04949 0.57421,0.123703 0.87109,0.222656" /> + transform="matrix(1.6526792,0,0,1.6526792,-155.46815,-5.1260141)"> @@ -1449,275 +2763,128 @@ + transform="matrix(1.7146685,0,0,1.7146685,-265.93598,-6.5942385)"> - - - - + transform="matrix(0.89658208,0,0,1.0166066,0.62788103,-5.1809092)" + style="display:inline" + id="g8787"> + + style="fill:#787878;fill-opacity:1;stroke:#e0dfe1;stroke-width:1.57115781;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1" + d="m 6.071295,40.854862 l 8.702853,-8.702852 l 3.698713,-0.652713 c 1.081677,1.081677 2.282834,2.282834 3.263569,3.263569 c 0.543928,0.543928 -0.435142,3.916284 -0.435142,3.916284 l -8.702853,8.702852 z" + id="path8779" + inkscape:connector-curvature="0" + sodipodi:nodetypes="ccccccc" /> + sodipodi:type="arc" + style="fill:none;stroke:#e0dfe1;stroke-width:2.55313134;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" + id="path8781" + sodipodi:cx="77" + sodipodi:cy="-18" + sodipodi:rx="9" + sodipodi:ry="9" + d="m 86,-18 c 0,4.970563 -4.029437,9 -9,9 c -1.57983,0 -3.131827,-0.4158564 -4.5,-1.205771" + transform="matrix(0.59409,-0.16048456,0.16048456,0.59409,-14.282595,58.387875)" + sodipodi:start="0" + sodipodi:end="2.0943951" + sodipodi:open="true" /> + sodipodi:open="true" + sodipodi:end="2.0943951" + sodipodi:start="0" + transform="matrix(0.94346447,-0.22256175,0.2922493,0.96228953,-38.3717,70.240727)" + d="m 86,-18 c 0,4.970563 -4.029437,9 -9,9 c -1.57983,0 -3.131827,-0.4158564 -4.5,-1.205771" + sodipodi:ry="9" + sodipodi:rx="9" + sodipodi:cy="-18" + sodipodi:cx="77" + id="path8783" + style="fill:none;stroke:#e0dfe1;stroke-width:1.59286559;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" + sodipodi:type="arc" /> - + sodipodi:nodetypes="ccccccc" + inkscape:connector-curvature="0" + id="path8785" + d="m 34.355566,12.570595 l -8.702852,8.702849 L 25,24.972157 c 1.081677,1.081678 2.282835,2.282835 3.263569,3.263569 c 0.543929,0.543929 3.916285,-0.435142 3.916285,-0.435142 l 8.702852,-8.702853 z" + style="fill:#787878;fill-opacity:1;stroke:#e0dfe1;stroke-width:1.57115781;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1" /> - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + style="display:inline" + sodipodi:insensitive="true"> + inkscape:label="waypoint-eta-text" + sodipodi:insensitive="true"> + transform="matrix(1.1017861,0,0,1.1017861,61.29339,14.558341)"> @@ -1726,48 +2893,49 @@ + inkscape:label="waypoint-distance-text" + sodipodi:insensitive="true"> + transform="matrix(1.1017861,0,0,1.1017861,17.436688,-10.441659)"> @@ -1776,23 +2944,24 @@ + inkscape:label="waypoint-heading-text" + sodipodi:insensitive="true"> + transform="matrix(1.1017861,0,0,1.1017861,-11.977973,14.558341)"> @@ -1801,88 +2970,89 @@ + inkscape:label="waypoint-mode-text" + sodipodi:insensitive="true"> + transform="matrix(1.0767613,0,0,1.0767613,127.81017,6.4920314)"> @@ -1892,528 +3062,94 @@ inkscape:groupmode="layer" id="layer56" inkscape:label="waypoint-description-text" - style="display:inline"> + style="display:inline" + sodipodi:insensitive="true"> - - - - - - - - - - - - - + d="m 309.28568,10.810623 l -1.70508,0 l -0.49219,1.957031 l 1.7168,0 l 0.48047,-1.957031 m -0.87891,-3.3339842 l -0.60938,2.4316406 l 1.71094,0 l 0.61524,-2.4316406 l 0.9375,0 l -0.60352,2.4316406 l 1.82813,0 l 0,0.9023436 l -2.05665,0 l -0.48046,1.957031 l 1.86328,0 l 0,0.896485 l -2.0918,0 l -0.60937,2.425781 l -0.9375,0 l 0.60351,-2.425781 l -1.7168,0 l -0.60351,2.425781 l -0.94336,0 l 0.60937,-2.425781 l -1.8457,0 l 0,-0.896485 l 2.0625,0 l 0.49219,-1.957031 l -1.88672,0 l 0,-0.9023436 l 2.11523,0 l 0.59766,-2.4316406 l 0.94922,0" /> + transform="translate(0,16)" + sodipodi:insensitive="true"> + d="m 303.29349,23.12117 c -0.60938,8e-6 -1.06836,0.300789 -1.37696,0.902344 c -0.30469,0.597663 -0.45703,1.498052 -0.45703,2.701172 c 0,1.199222 0.15234,2.099611 0.45703,2.701172 c 0.3086,0.597657 0.76758,0.896485 1.37696,0.896484 c 0.61327,1e-6 1.07226,-0.298827 1.37695,-0.896484 c 0.30859,-0.601561 0.46289,-1.50195 0.46289,-2.701172 c 0,-1.20312 -0.1543,-2.103509 -0.46289,-2.701172 c -0.30469,-0.601555 -0.76368,-0.902336 -1.37695,-0.902344 m 0,-0.9375 c 0.98046,9e-6 1.72851,0.38868 2.24414,1.166016 c 0.51952,0.773444 0.77929,1.898443 0.7793,3.375 c -1e-5,1.472659 -0.25978,2.597658 -0.7793,3.375 c -0.51563,0.773437 -1.26368,1.160156 -2.24414,1.160156 c -0.98047,0 -1.73047,-0.386719 -2.25,-1.160156 c -0.51563,-0.777342 -0.77344,-1.902341 -0.77344,-3.375 c 0,-1.476557 0.25781,-2.601556 0.77344,-3.375 c 0.51953,-0.777336 1.26953,-1.166007 2.25,-1.166016" /> + d="m 310.93411,23.12117 c -0.60938,8e-6 -1.06836,0.300789 -1.37695,0.902344 c -0.30469,0.597663 -0.45703,1.498052 -0.45703,2.701172 c 0,1.199222 0.15234,2.099611 0.45703,2.701172 c 0.30859,0.597657 0.76757,0.896485 1.37695,0.896484 c 0.61328,1e-6 1.07226,-0.298827 1.37696,-0.896484 c 0.30858,-0.601561 0.46288,-1.50195 0.46289,-2.701172 c -10e-6,-1.20312 -0.15431,-2.103509 -0.46289,-2.701172 c -0.3047,-0.601555 -0.76368,-0.902336 -1.37696,-0.902344 m 0,-0.9375 c 0.98047,9e-6 1.72851,0.38868 2.24414,1.166016 c 0.51953,0.773444 0.77929,1.898443 0.7793,3.375 c -1e-5,1.472659 -0.25977,2.597658 -0.7793,3.375 c -0.51563,0.773437 -1.26367,1.160156 -2.24414,1.160156 c -0.98047,0 -1.73047,-0.386719 -2.25,-1.160156 c -0.51562,-0.777342 -0.77344,-1.902341 -0.77343,-3.375 c -1e-5,-1.476557 0.25781,-2.601556 0.77343,-3.375 c 0.51953,-0.777336 1.26953,-1.166007 2.25,-1.166016" /> + d="m 318.57474,23.12117 c -0.60938,8e-6 -1.06836,0.300789 -1.37696,0.902344 c -0.30469,0.597663 -0.45703,1.498052 -0.45703,2.701172 c 0,1.199222 0.15234,2.099611 0.45703,2.701172 c 0.3086,0.597657 0.76758,0.896485 1.37696,0.896484 c 0.61327,1e-6 1.07226,-0.298827 1.37695,-0.896484 c 0.30859,-0.601561 0.46289,-1.50195 0.46289,-2.701172 c 0,-1.20312 -0.1543,-2.103509 -0.46289,-2.701172 c -0.30469,-0.601555 -0.76368,-0.902336 -1.37695,-0.902344 m 0,-0.9375 c 0.98046,9e-6 1.72851,0.38868 2.24414,1.166016 c 0.51952,0.773444 0.77929,1.898443 0.7793,3.375 c -1e-5,1.472659 -0.25978,2.597658 -0.7793,3.375 c -0.51563,0.773437 -1.26368,1.160156 -2.24414,1.160156 c -0.98047,0 -1.73047,-0.386719 -2.25,-1.160156 c -0.51563,-0.777342 -0.77344,-1.902341 -0.77344,-3.375 c 0,-1.476557 0.25781,-2.601556 0.77344,-3.375 c 0.51953,-0.777336 1.26953,-1.166007 2.25,-1.166016" /> + d="m 326.21536,23.12117 c -0.60938,8e-6 -1.06836,0.300789 -1.37695,0.902344 c -0.30469,0.597663 -0.45703,1.498052 -0.45703,2.701172 c 0,1.199222 0.15234,2.099611 0.45703,2.701172 c 0.30859,0.597657 0.76757,0.896485 1.37695,0.896484 c 0.61328,1e-6 1.07226,-0.298827 1.37696,-0.896484 c 0.30858,-0.601561 0.46288,-1.50195 0.46289,-2.701172 c -10e-6,-1.20312 -0.15431,-2.103509 -0.46289,-2.701172 c -0.3047,-0.601555 -0.76368,-0.902336 -1.37696,-0.902344 m 0,-0.9375 c 0.98047,9e-6 1.72851,0.38868 2.24414,1.166016 c 0.51953,0.773444 0.77929,1.898443 0.7793,3.375 c -1e-5,1.472659 -0.25977,2.597658 -0.7793,3.375 c -0.51563,0.773437 -1.26367,1.160156 -2.24414,1.160156 c -0.98047,0 -1.73047,-0.386719 -2.25,-1.160156 c -0.51562,-0.777342 -0.77344,-1.902341 -0.77343,-3.375 c -1e-5,-1.476557 0.25781,-2.601556 0.77343,-3.375 c 0.51953,-0.777336 1.26953,-1.166007 2.25,-1.166016" /> + d="m 333.85599,23.12117 c -0.60938,8e-6 -1.06836,0.300789 -1.37696,0.902344 c -0.30469,0.597663 -0.45703,1.498052 -0.45703,2.701172 c 0,1.199222 0.15234,2.099611 0.45703,2.701172 c 0.3086,0.597657 0.76758,0.896485 1.37696,0.896484 c 0.61327,1e-6 1.07226,-0.298827 1.37695,-0.896484 c 0.30859,-0.601561 0.46289,-1.50195 0.46289,-2.701172 c 0,-1.20312 -0.1543,-2.103509 -0.46289,-2.701172 c -0.30469,-0.601555 -0.76368,-0.902336 -1.37695,-0.902344 m 0,-0.9375 c 0.98046,9e-6 1.72851,0.38868 2.24414,1.166016 c 0.51952,0.773444 0.77929,1.898443 0.7793,3.375 c -1e-5,1.472659 -0.25978,2.597658 -0.7793,3.375 c -0.51563,0.773437 -1.26368,1.160156 -2.24414,1.160156 c -0.98047,0 -1.73047,-0.386719 -2.25,-1.160156 c -0.51563,-0.777342 -0.77344,-1.902341 -0.77344,-3.375 c 0,-1.476557 0.25781,-2.601556 0.77344,-3.375 c 0.51953,-0.777336 1.26953,-1.166007 2.25,-1.166016" /> + d="m 341.49661,23.12117 c -0.60938,8e-6 -1.06836,0.300789 -1.37695,0.902344 c -0.30469,0.597663 -0.45703,1.498052 -0.45703,2.701172 c 0,1.199222 0.15234,2.099611 0.45703,2.701172 c 0.30859,0.597657 0.76757,0.896485 1.37695,0.896484 c 0.61328,1e-6 1.07226,-0.298827 1.37696,-0.896484 c 0.30858,-0.601561 0.46288,-1.50195 0.46289,-2.701172 c -10e-6,-1.20312 -0.15431,-2.103509 -0.46289,-2.701172 c -0.3047,-0.601555 -0.76368,-0.902336 -1.37696,-0.902344 m 0,-0.9375 c 0.98047,9e-6 1.72851,0.38868 2.24414,1.166016 c 0.51953,0.773444 0.77929,1.898443 0.7793,3.375 c -1e-5,1.472659 -0.25977,2.597658 -0.7793,3.375 c -0.51563,0.773437 -1.26367,1.160156 -2.24414,1.160156 c -0.98047,0 -1.73047,-0.386719 -2.25,-1.160156 c -0.51562,-0.777342 -0.77344,-1.902341 -0.77343,-3.375 c -1e-5,-1.476557 0.25781,-2.601556 0.77343,-3.375 c 0.51953,-0.777336 1.26953,-1.166007 2.25,-1.166016" /> + d="m 349.13724,23.12117 c -0.60938,8e-6 -1.06836,0.300789 -1.37696,0.902344 c -0.30469,0.597663 -0.45703,1.498052 -0.45703,2.701172 c 0,1.199222 0.15234,2.099611 0.45703,2.701172 c 0.3086,0.597657 0.76758,0.896485 1.37696,0.896484 c 0.61327,1e-6 1.07226,-0.298827 1.37695,-0.896484 c 0.30859,-0.601561 0.46289,-1.50195 0.46289,-2.701172 c 0,-1.20312 -0.1543,-2.103509 -0.46289,-2.701172 c -0.30469,-0.601555 -0.76368,-0.902336 -1.37695,-0.902344 m 0,-0.9375 c 0.98046,9e-6 1.72851,0.38868 2.24414,1.166016 c 0.51952,0.773444 0.77929,1.898443 0.7793,3.375 c -1e-5,1.472659 -0.25978,2.597658 -0.7793,3.375 c -0.51563,0.773437 -1.26368,1.160156 -2.24414,1.160156 c -0.98047,0 -1.73047,-0.386719 -2.25,-1.160156 c -0.51563,-0.777342 -0.77344,-1.902341 -0.77344,-3.375 c 0,-1.476557 0.25781,-2.601556 0.77344,-3.375 c 0.51953,-0.777336 1.26953,-1.166007 2.25,-1.166016" /> + d="m 356.77786,23.12117 c -0.60938,8e-6 -1.06836,0.300789 -1.37695,0.902344 c -0.30469,0.597663 -0.45703,1.498052 -0.45703,2.701172 c 0,1.199222 0.15234,2.099611 0.45703,2.701172 c 0.30859,0.597657 0.76757,0.896485 1.37695,0.896484 c 0.61328,1e-6 1.07226,-0.298827 1.37696,-0.896484 c 0.30858,-0.601561 0.46288,-1.50195 0.46289,-2.701172 c -10e-6,-1.20312 -0.15431,-2.103509 -0.46289,-2.701172 c -0.3047,-0.601555 -0.76368,-0.902336 -1.37696,-0.902344 m 0,-0.9375 c 0.98047,9e-6 1.72851,0.38868 2.24414,1.166016 c 0.51953,0.773444 0.77929,1.898443 0.7793,3.375 c -1e-5,1.472659 -0.25977,2.597658 -0.7793,3.375 c -0.51563,0.773437 -1.26367,1.160156 -2.24414,1.160156 c -0.98047,0 -1.73047,-0.386719 -2.25,-1.160156 c -0.51562,-0.777342 -0.77344,-1.902341 -0.77343,-3.375 c -1e-5,-1.476557 0.25781,-2.601556 0.77343,-3.375 c 0.51953,-0.777336 1.26953,-1.166007 2.25,-1.166016" /> - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + style="display:inline" + sodipodi:insensitive="true"> + style="display:inline" + sodipodi:insensitive="true"> @@ -2487,18 +3223,19 @@ id="layer52" inkscape:label="gps-mode-text" style="display:inline" - transform="translate(0,-0.972157)"> + transform="translate(0,-0.972157)" + sodipodi:insensitive="true"> + transform="matrix(1.4543578,0,0,1.4543578,-4.981688,1.3723646)"> @@ -2509,120 +3246,37 @@ inkscape:groupmode="layer" id="layer71" inkscape:label="info-border" - style="display:inline"> + style="display:inline" + sodipodi:insensitive="true"> - - - - - - - - - - - - + style="display:inline" + sodipodi:insensitive="true"> - - - @@ -2651,14 +3305,14 @@ inkscape:transform-center-y="-105.12133" inkscape:connector-curvature="0" id="path3444" - d="m 262.55821,71.879346 -6.50008,-11.25848" + d="m 262.55821,71.879346 l -6.50008,-11.25848" style="fill:none;stroke:#ffffff;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" inkscape:transform-center-x="60.69183" /> @@ -2677,7 +3331,7 @@ sodipodi:nodetypes="cc" inkscape:transform-center-x="20.198055" style="fill:none;stroke:#ffffff;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" - d="M 300.02868,57.474202 298.9979,52.82864" + d="M 300.02868,57.474202 L 298.9979,52.82864" id="path3464" inkscape:connector-curvature="0" inkscape:transform-center-y="-109.4812" /> @@ -2687,7 +3341,7 @@ inkscape:transform-center-y="-104.31057" inkscape:connector-curvature="0" id="path3466" - d="m 281.77925,62.464332 -1.94063,-4.28458" + d="m 281.77925,62.464332 l -1.94063,-4.28458" style="fill:none;stroke:#ffffff;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" inkscape:transform-center-x="38.90241" /> @@ -2704,14 +3358,14 @@ inkscape:transform-center-y="-117.24761" inkscape:connector-curvature="0" id="path3491" - d="m 349.73406,60.402428 3.36469,-12.557202" + d="m 349.73406,60.402428 l 3.36469,-12.557202" style="fill:none;stroke:#ffffff;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" inkscape:transform-center-x="31.416405" /> @@ -2720,7 +3374,7 @@ inkscape:transform-center-y="-85.831206" inkscape:connector-curvature="0" id="path3495" - d="m 399.82423,91.345686 11.40936,-9.763523" + d="m 399.82423,91.345686 l 11.40936,-9.763523" style="fill:none;stroke:#ffffff;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" inkscape:transform-center-x="85.83121" sodipodi:nodetypes="cc" /> @@ -2729,7 +3383,7 @@ inkscape:transform-center-y="-51.353944" inkscape:connector-curvature="0" id="path3497" - d="m 330.38014,56.242757 0.76566,-4.817725" + d="m 330.38014,56.242757 l 0.76566,-4.817725" style="fill:none;stroke:#ffffff;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" inkscape:transform-center-x="10.57928" sodipodi:nodetypes="cc" /> @@ -2738,7 +3392,7 @@ inkscape:transform-center-y="-109.4812" inkscape:connector-curvature="0" id="path3499" - d="M 339.97132,57.474202 341.0021,52.82864" + d="M 339.97132,57.474202 L 341.0021,52.82864" style="fill:none;stroke:#ffffff;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" inkscape:transform-center-x="20.198055" sodipodi:nodetypes="cc" /> @@ -2746,7 +3400,7 @@ transform="translate(0,4)" inkscape:transform-center-x="38.90241" style="fill:none;stroke:#ffffff;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" - d="m 358.22075,62.464332 1.94063,-4.28458" + d="m 358.22075,62.464332 l 1.94063,-4.28458" id="path3501" inkscape:connector-curvature="0" inkscape:transform-center-y="-104.31057" @@ -2756,7 +3410,7 @@ inkscape:transform-center-y="-100.52307" inkscape:connector-curvature="0" id="path3503" - d="m 367.00252,66.39497 2.31603,-4.30844" + d="m 367.00252,66.39497 l 2.31603,-4.30844" style="fill:none;stroke:#ffffff;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" inkscape:transform-center-x="47.84564" sodipodi:nodetypes="cc" /> @@ -2765,7 +3419,7 @@ sodipodi:open="true" sodipodi:end="5.5477076" sodipodi:start="3.8773293" - d="m 238.84479,91.530033 c 40.57635,-44.820783 109.80439,-48.261582 154.62518,-7.685239 2.69442,2.439265 5.26569,5.011203 7.70426,7.706256" + d="M 238.84479,91.530033 C 279.42114,46.70925 348.64918,43.268451 393.46997,83.844794 c 2.69442,2.439265 5.26569,5.011203 7.70426,7.706256" sodipodi:ry="109.47147" sodipodi:rx="109.47147" sodipodi:cy="165" @@ -2775,7 +3429,7 @@ sodipodi:type="arc" /> + sodipodi:insensitive="true" + style="display:inline"> @@ -2965,12 +3620,12 @@ sodipodi:nodetypes="cc" inkscape:connector-curvature="0" id="path6065" - d="m 241.40244,372.02206 -8.50092,0" + d="m 241.40244,372.02206 l -8.50092,0" style="fill:none;stroke:#ffffff;stroke-width:1.69943166;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline" /> @@ -3029,11 +3684,11 @@ inkscape:transform-center-y="-85.40481" inkscape:connector-curvature="0" id="path4980" - d="m 319.99877,294.64611 0.16778,9.61226" + d="m 319.99877,294.64611 l 0.16778,9.61226" style="fill:none;stroke:#ffffff;stroke-width:1.69943166;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1;display:inline" /> @@ -3799,12 +4454,12 @@ id="compass330" inkscape:label="#compass330"> @@ -3817,12 +4472,12 @@ id="compass300" inkscape:label="#compass300"> @@ -3834,7 +4489,7 @@ id="compass270" inkscape:label="#compass270"> @@ -3847,12 +4502,12 @@ id="compass240" inkscape:label="#compass240"> @@ -3865,12 +4520,12 @@ id="compass210" inkscape:label="#compass210"> @@ -3882,7 +4537,7 @@ id="compass180" inkscape:label="#compass180"> @@ -3894,12 +4549,12 @@ style="font-size:33.9886322px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Sans" id="compass150"> @@ -3912,12 +4567,12 @@ id="compass120" inkscape:label="#compass120"> @@ -3929,7 +4584,7 @@ id="compass90" inkscape:label="#compass90"> @@ -3941,7 +4596,7 @@ style="font-size:33.9886322px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;display:inline;font-family:Sans" id="compass60"> @@ -3954,7 +4609,7 @@ id="compass30" inkscape:label="#compass-30"> @@ -3974,7 +4629,7 @@ inkscape:label="#g4651"> @@ -4002,11 +4657,11 @@ sodipodi:nodetypes="cccccccc" inkscape:connector-curvature="0" id="path5472" - d="m 319.99619,305.5318 -8.52371,8.73614 6.87739,-0.0531 -4.3e-4,27.16436 3.29307,0 0,-27.16436 6.85084,0.0531 z" + d="m 319.99619,305.5318 l -8.52371,8.73614 l 6.87739,-0.0531 l -4.3e-4,27.16436 l 3.29307,0 l 0,-27.16436 l 6.85084,0.0531 z" style="fill:#bf00bf;fill-opacity:1;stroke:none" /> @@ -4023,17 +4678,17 @@ id="compass-text" transform="translate(0,78)"> @@ -4052,13 +4707,13 @@ inkscape:transform-center-y="-72.71875" inkscape:connector-curvature="0" id="path4626" - d="m 320,372.78125 -3.78125,4.5 3.78125,4.5 3.78125,-4.5 -3.78125,-4.5 z" + d="m 320,372.78125 l -3.78125,4.5 l 3.78125,4.5 l 3.78125,-4.5 l -3.78125,-4.5 z" style="fill:#00ffff;stroke:none" /> @@ -4070,7 +4725,7 @@ @@ -4079,7 +4734,7 @@ inkscape:groupmode="layer" id="layer17" inkscape:label="speed" - style="display:inline" + style="display:none" transform="translate(0,-4)" sodipodi:insensitive="true"> @@ -4153,104 +4808,104 @@ @@ -4258,12 +4913,12 @@ inkscape:label="#path3532" inkscape:connector-curvature="0" id="speed5" - d="M 65.000001,-31 52,-31" + d="M 65.000001,-31 L 52,-31" style="fill:none;stroke:#ffffff;stroke-width:2;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /> @@ -4282,7 +4937,7 @@ sodipodi:nodetypes="cccccccccc" inkscape:connector-curvature="0" id="path10059" - d="m 91,148.5 0,20.5 0,20.5 44,0 0,-9.78125 8.5,-9.46875 0,-2.5 -8.5,-9.46875 0,-9.78125 z" + d="m 91,148.5 l 0,20.5 l 0,20.5 l 44,0 l 0,-9.78125 l 8.5,-9.46875 l 0,-2.5 L 135,158.28125 L 135,148.5 z" style="fill:#000000;stroke:#ffffff" /> @@ -4317,27 +4972,27 @@ id="speed-text" transform="translate(0,42)"> @@ -4362,7 +5017,7 @@ id="altitude-unit" transform="translate(0,42)"> @@ -4372,10 +5027,9 @@ inkscape:groupmode="layer" id="layer32" inkscape:label="altitude-window" - style="display:inline" - sodipodi:insensitive="true"> + style="display:inline"> @@ -4543,7 +5197,7 @@ inkscape:connector-curvature="0" id="path10043" transform="translate(0,4)" - d="m 506.5,144.4375 0,12.75 -9.525,6.5625 0,2.5 9.525,6.5625 0,12.75 43,0 0,-20.5625 0,-20.5625 z" + d="m 506.5,144.4375 l 0,12.75 l -9.525,6.5625 l 0,2.5 l 9.525,6.5625 l 0,12.75 l 43,0 L 549.5,165 l 0,-20.5625 z" style="fill:#000000;stroke:#ffffff" /> @@ -4612,67 +5266,75 @@ inkscape:label="vsi" style="display:inline" sodipodi:insensitive="true"> - - - - - - - - - + inkscape:connector-curvature="0" + sodipodi:nodetypes="zczzz" /> + + + + + + + + + + - + + transform="translate(-18,0)"> + + + + + + + + id="path4666" + d="m 616.46289,142.9203 l -12.55702,-3.36463" + style="fill:none;stroke:#ffffff;stroke-width:1.99999976;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /> + - - + id="path4698" + d="m 610.97895,266.79024 l -12.8025,2.25741" + style="fill:none;stroke:#ffffff;stroke-width:1.99999976;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /> + id="path4700" + d="m 599.41527,229.94209 l -5.49476,0.2399" + style="fill:none;stroke:#ffffff;stroke-width:1.99999976;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /> + + id="path4704" + d="M 607.72377,242.06196 L 594.77325,243.195" + style="fill:none;stroke:#ffffff;stroke-width:1.99999976;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /> + + - - - - - + id="path4712" + d="m 624.27395,314.78359 l -12.21598,4.44623" + style="fill:none;stroke:#ffffff;stroke-width:1.99999976;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - + style="display:inline" + sodipodi:insensitive="true"> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + inkscape:label="#g4860" + transform="translate(1,0)"> + transform="matrix(1.1017863,0,0,1.1017863,-42.744908,-48.294497)"> @@ -4876,9 +5779,9 @@ id="warning-master-caution" inkscape:label="#g4850"> @@ -4886,69 +5789,69 @@ style="font-size:40px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#ffffff;fill-opacity:1;stroke:none;font-family:Sans" id="warning-master-caution-label" inkscape:label="#warning-master-caution-label" - transform="translate(-0.37041,0.11598)"> + transform="matrix(1.1017863,0,0,1.1017863,-33.088618,-48.971446)"> @@ -4963,61 +5866,129 @@ sodipodi:insensitive="true"> + inkscape:label="#g4855" + transform="translate(-0.5,0)"> + id="warning-rc-input-label" + transform="matrix(1.1017863,0,0,1.1017863,-23.124025,-49.099088)"> + + + + + + + + + + + + + + 00.00.00 + + @@ -5057,70 +6028,6 @@ x="306.73804" y="123.74039" /> - - - - - - - - - - - - - - + transform="matrix(1.8539326,0,0,1.6231884,0,-1.947826)"> + d="M 2.3796722,2.8075235 L 86.665165,34.123438" + style="fill:none;stroke:#ff0000;stroke-width:2.14500451;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /> - - - void geometry(void) t1.setIdentity(); t1.linear() = q1.toRotationMatrix(); - v0 << 50, 2, 1;//= ei_random_matrix().cwiseProduct(Vector3(10,2,0.5)); + v0 << 50, 2, 1; // = ei_random_matrix().cwiseProduct(Vector3(10,2,0.5)); t0.scale(v0); t1.prescale(v0); diff --git a/ground/openpilotgcs/src/libs/eigen/test/eigen2/eigen2_geometry_with_eigen2_prefix.cpp b/ground/openpilotgcs/src/libs/eigen/test/eigen2/eigen2_geometry_with_eigen2_prefix.cpp index f83b57249..9ff9f4026 100644 --- a/ground/openpilotgcs/src/libs/eigen/test/eigen2/eigen2_geometry_with_eigen2_prefix.cpp +++ b/ground/openpilotgcs/src/libs/eigen/test/eigen2/eigen2_geometry_with_eigen2_prefix.cpp @@ -149,7 +149,7 @@ template void geometry(void) t1.setIdentity(); t1.linear() = q1.toRotationMatrix(); - v0 << 50, 2, 1;//= ei_random_matrix().cwiseProduct(Vector3(10,2,0.5)); + v0 << 50, 2, 1; // = ei_random_matrix().cwiseProduct(Vector3(10,2,0.5)); t0.scale(v0); t1.prescale(v0); diff --git a/ground/openpilotgcs/src/libs/utils/filesearch.cpp b/ground/openpilotgcs/src/libs/utils/filesearch.cpp index 8a40e96c7..0c3249104 100644 --- a/ground/openpilotgcs/src/libs/utils/filesearch.cpp +++ b/ground/openpilotgcs/src/libs/utils/filesearch.cpp @@ -45,7 +45,7 @@ static inline QString msgCanceled(const QString &searchTerm, int numMatches, int { return QCoreApplication::translate("Utils::FileSearch", "%1: canceled. %n occurrences found in %2 files.", - 0, numMatches). + NULL, numMatches). arg(searchTerm).arg(numFilesSearched); } @@ -53,7 +53,7 @@ static inline QString msgFound(const QString &searchTerm, int numMatches, int nu { return QCoreApplication::translate("Utils::FileSearch", "%1: %n occurrences found in %2 files.", - 0, numMatches). + NULL, numMatches). arg(searchTerm).arg(numFilesSearched); } @@ -61,7 +61,7 @@ static inline QString msgFound(const QString &searchTerm, int numMatches, int nu { return QCoreApplication::translate("Utils::FileSearch", "%1: %n occurrences found in %2 of %3 files.", - 0, numMatches). + NULL, numMatches). arg(searchTerm).arg(numFilesSearched).arg(filesSize); } diff --git a/ground/openpilotgcs/src/libs/utils/xmlconfig.h b/ground/openpilotgcs/src/libs/utils/xmlconfig.h index 98345e38d..0f92f0060 100644 --- a/ground/openpilotgcs/src/libs/utils/xmlconfig.h +++ b/ground/openpilotgcs/src/libs/utils/xmlconfig.h @@ -38,6 +38,7 @@ #include class XMLCONFIG_EXPORT XmlConfig : QObject { + Q_OBJECT public: static const QSettings::Format XmlSettingsFormat; diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp index 42b06f4d0..14b3e9d43 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp @@ -168,7 +168,7 @@ void ConfigMultiRotorWidget::setupUI(QString frameType) m_aircraft->mrRollMixLevel->setValue(100); m_aircraft->mrPitchMixLevel->setValue(100); - setYawMixLevel(50); + setYawMixLevel(100); } else if (frameType == "QuadX" || frameType == "Quad X") { setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad X")); @@ -366,43 +366,12 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) setComboCurrentIndex(m_aircraft->multiMotorChannelBox2, multi.VTOLMotorE); setComboCurrentIndex(m_aircraft->multiMotorChannelBox3, multi.VTOLMotorS); setComboCurrentIndex(m_aircraft->multiMotorChannelBox4, multi.VTOLMotorW); - - // Now, read the 1st mixer R/P/Y levels and initialize the mix sliders. - // This assumes that all vectors are identical - if not, the user should use the "custom" setting. - - int channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1; - if (channel > -1) { - double value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH); - m_aircraft->mrPitchMixLevel->setValue(qRound(value / 1.27)); - - value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); - setYawMixLevel(-qRound(value / 1.27)); - - channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1; - value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); - m_aircraft->mrRollMixLevel->setValue(-qRound(value / 1.27)); - } } else if (frameType == "QuadX") { // Motors 1/2/3/4 are: NW / NE / SE / SW setComboCurrentIndex(m_aircraft->multiMotorChannelBox1, multi.VTOLMotorNW); setComboCurrentIndex(m_aircraft->multiMotorChannelBox2, multi.VTOLMotorNE); setComboCurrentIndex(m_aircraft->multiMotorChannelBox3, multi.VTOLMotorSE); setComboCurrentIndex(m_aircraft->multiMotorChannelBox4, multi.VTOLMotorSW); - - // Now, read the 1st mixer R/P/Y levels and initialize the mix sliders. - // This assumes that all vectors are identical - if not, the user should use the - // "custom" setting. - int channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1; - if (channel > -1) { - double value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH); - m_aircraft->mrPitchMixLevel->setValue(qRound(value / 1.27)); - - value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); - setYawMixLevel(-qRound(value / 1.27)); - - value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); - m_aircraft->mrRollMixLevel->setValue(qRound(value / 1.27)); - } } else if (frameType == "Hexa") { // Motors 1/2/3 4/5/6 are: N / NE / SE / S / SW / NW setComboCurrentIndex(m_aircraft->multiMotorChannelBox1, multi.VTOLMotorN); @@ -411,27 +380,6 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) setComboCurrentIndex(m_aircraft->multiMotorChannelBox4, multi.VTOLMotorS); setComboCurrentIndex(m_aircraft->multiMotorChannelBox5, multi.VTOLMotorSW); setComboCurrentIndex(m_aircraft->multiMotorChannelBox6, multi.VTOLMotorNW); - - // Now, read the 1st mixer R/P/Y levels and initialize the mix sliders. - // This assumes that all vectors are identical - if not, the user should use the - // "custom" setting. - - int channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1; - if (channel > -1) { - // get motor 1 value for Pitch - double value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH); - m_aircraft->mrPitchMixLevel->setValue(qRound(value / 1.27)); - - // get motor 2 value for Yaw and Roll - channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1; - value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); - setYawMixLevel(qRound(value / 1.27)); - - // change channels - channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1; - value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); - m_aircraft->mrRollMixLevel->setValue(-qRound(value / 1.27)); - } } else if (frameType == "HexaX") { // Motors 1/2/3 4/5/6 are: NE / E / SE / SW / W / NW setComboCurrentIndex(m_aircraft->multiMotorChannelBox1, multi.VTOLMotorNE); @@ -440,26 +388,6 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) setComboCurrentIndex(m_aircraft->multiMotorChannelBox4, multi.VTOLMotorSW); setComboCurrentIndex(m_aircraft->multiMotorChannelBox5, multi.VTOLMotorW); setComboCurrentIndex(m_aircraft->multiMotorChannelBox6, multi.VTOLMotorNW); - - // Now, read the 1st mixer R/P/Y levels and initialize the mix sliders. - // This assumes that all vectors are identical - if not, the user should use the - // "custom" setting. - - int channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1; - if (channel > -1) { - // get motor 1 value for Pitch - double value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH); - m_aircraft->mrPitchMixLevel->setValue(qRound(value / 1.27)); - - // get motor 2 value for Yaw and Roll - channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1; - value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); - setYawMixLevel(qRound(value / 1.27)); - - channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1; - value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); - m_aircraft->mrRollMixLevel->setValue(-qRound(value / 1.27)); - } } else if (frameType == "HexaH") { // Motors 1/2/3 4/5/6 are: NE / E / SE / SW / W / NW setComboCurrentIndex(m_aircraft->multiMotorChannelBox1, multi.VTOLMotorNE); @@ -496,22 +424,6 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) setComboCurrentIndex(m_aircraft->multiMotorChannelBox4, multi.VTOLMotorE); setComboCurrentIndex(m_aircraft->multiMotorChannelBox5, multi.VTOLMotorS); setComboCurrentIndex(m_aircraft->multiMotorChannelBox6, multi.VTOLMotorSE); - - // Now, read the 1st mixer R/P/Y levels and initialize the mix sliders. - // This assumes that all vectors are identical - if not, the user should use the - // "custom" setting. - int channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1; - if (channel > -1) { - double value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH); - 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(qRound(value / 1.27)); - } } else if (frameType == "Octo" || frameType == "OctoV" || frameType == "OctoCoaxP") { // Motors 1 to 8 are N / NE / E / etc setComboCurrentIndex(m_aircraft->multiMotorChannelBox1, multi.VTOLMotorN); @@ -522,47 +434,6 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) setComboCurrentIndex(m_aircraft->multiMotorChannelBox6, multi.VTOLMotorSW); setComboCurrentIndex(m_aircraft->multiMotorChannelBox7, multi.VTOLMotorW); setComboCurrentIndex(m_aircraft->multiMotorChannelBox8, multi.VTOLMotorNW); - - // Now, read the 1st mixer R/P/Y levels and initialize the mix sliders. - // This assumes that all vectors are identical - if not, the user should use the - // "custom" setting. - int channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1; - if (channel > -1) { - if (frameType == "Octo") { - double value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH); - m_aircraft->mrPitchMixLevel->setValue(qRound(value / 1.27)); - - value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); - setYawMixLevel(-qRound(value / 1.27)); - - // Get M3 Roll value - channel = m_aircraft->multiMotorChannelBox3->currentIndex() - 1; - value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); - m_aircraft->mrRollMixLevel->setValue(-qRound(value / 1.27)); - } else if (frameType == "OctoV") { - double value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH); - m_aircraft->mrPitchMixLevel->setValue(qRound(value / 1.27)); - - value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); - setYawMixLevel(-qRound(value / 1.27)); - - // change channels - channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1; - value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); - m_aircraft->mrRollMixLevel->setValue(-qRound(value / 1.27)); - } else if (frameType == "OctoCoaxP") { - double value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH); - m_aircraft->mrPitchMixLevel->setValue(qRound(value / 1.27)); - - value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); - setYawMixLevel(-qRound(value / 1.27)); - - // change channels - channel = m_aircraft->multiMotorChannelBox3->currentIndex() - 1; - value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); - m_aircraft->mrRollMixLevel->setValue(-qRound(value / 1.27)); - } - } } else if (frameType == "OctoX") { // Motors 1 to 8 are NNE / ENE / ESE / etc setComboCurrentIndex(m_aircraft->multiMotorChannelBox1, multi.VTOLMotorNNE); @@ -573,24 +444,6 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) setComboCurrentIndex(m_aircraft->multiMotorChannelBox6, multi.VTOLMotorWSW); setComboCurrentIndex(m_aircraft->multiMotorChannelBox7, multi.VTOLMotorWNW); setComboCurrentIndex(m_aircraft->multiMotorChannelBox8, multi.VTOLMotorNNW); - - - // Now, read the 1st mixer R/P/Y levels and initialize the mix sliders. - // This assumes that all vectors are identical - if not, the user should use the - // "custom" setting. - int channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1; - if (channel > -1) { - double value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH); - m_aircraft->mrPitchMixLevel->setValue(qRound(value / 1.27)); - - value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); - setYawMixLevel(-qRound(value / 1.27)); - - // Get M2 Roll value - channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1; - value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); - m_aircraft->mrRollMixLevel->setValue(-qRound(value / 1.27)); - } } else if (frameType == "OctoCoaxX") { // Motors 1 to 8 are N / NE / E / etc setComboCurrentIndex(m_aircraft->multiMotorChannelBox1, multi.VTOLMotorNW); @@ -601,39 +454,19 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) setComboCurrentIndex(m_aircraft->multiMotorChannelBox6, multi.VTOLMotorS); setComboCurrentIndex(m_aircraft->multiMotorChannelBox7, multi.VTOLMotorSW); setComboCurrentIndex(m_aircraft->multiMotorChannelBox8, multi.VTOLMotorW); - - // Now, read the 1st mixer R/P/Y levels and initialize the mix sliders. - // This assumes that all vectors are identical - if not, the user should use the - // "custom" setting. - int channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1; - if (channel > -1) { - double value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH); - m_aircraft->mrPitchMixLevel->setValue(qRound(value / 1.27)); - - value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); - setYawMixLevel(-qRound(value / 1.27)); - - value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); - m_aircraft->mrRollMixLevel->setValue(qRound(value / 1.27)); - } } else if (frameType == "Tri") { // Motors 1 to 8 are N / NE / E / etc setComboCurrentIndex(m_aircraft->multiMotorChannelBox1, multi.VTOLMotorNW); setComboCurrentIndex(m_aircraft->multiMotorChannelBox2, multi.VTOLMotorNE); setComboCurrentIndex(m_aircraft->multiMotorChannelBox3, multi.VTOLMotorS); - setComboCurrentIndex(m_aircraft->multiMotorChannelBox4, multi.VTOLMotorS); setComboCurrentIndex(m_aircraft->triYawChannelBox, multi.TRIYaw); - - int channel = m_aircraft->multiMotorChannelBox1->currentIndex() - 1; - if (channel > -1) { - double value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH); - m_aircraft->mrPitchMixLevel->setValue(qRound(2 * value / 1.27)); - - value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); - m_aircraft->mrRollMixLevel->setValue(qRound(value / 1.27)); - } } + // Now, read mixing values stored on board and applies values on sliders. + m_aircraft->mrPitchMixLevel->setValue(getMixerValue(mixer, "MixerValuePitch")); + m_aircraft->mrRollMixLevel->setValue(getMixerValue(mixer, "MixerValueRoll")); + m_aircraft->mrYawMixLevel->setValue(getMixerValue(mixer, "MixerValueYaw")); + updateAirframe(frameType); } @@ -890,7 +723,9 @@ QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets() int channel = m_aircraft->triYawChannelBox->currentIndex() - 1; if (channel > -1) { setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, 127); + + // Tricopter : Yaw mix slider value applies to servo (was fixed) + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, getMixerValue(mixer, "MixerValueYaw") * 1.27); } m_aircraft->mrStatusLabel->setText(tr("Configuration OK")); @@ -969,13 +804,18 @@ void ConfigMultiRotorWidget::setupQuadMotor(int channel, double pitch, double ro Q_ASSERT(mixer); + // Normalize mixer values, allow a well balanced mixer saved + pitch = (pitch < 0) ? qFloor(pitch * 127) : qCeil(pitch * 127); + roll = (roll < 0) ? qFloor(roll * 127) : qCeil(roll * 127); + yaw = (yaw < 0) ? qFloor(yaw * 127) : qCeil(yaw * 127); + setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_MOTOR); setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE1, 127); setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE2, 0); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, roll * 127); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, pitch * 127); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, yaw * 127); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, roll); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, pitch); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, yaw); } /** @@ -1184,6 +1024,10 @@ bool ConfigMultiRotorWidget::setupMultiRotorMixer(double mixerFactors[8][3]) invertMotors = m_aircraft->MultirotorRevMixerCheckBox->isChecked(); double yFactor = (invertMotors ? -1.0 : 1.0) * (double)m_aircraft->mrYawMixLevel->value() / 100.0; + setMixerValue(mixer, "MixerValueRoll", m_aircraft->mrRollMixLevel->value()); + setMixerValue(mixer, "MixerValuePitch", m_aircraft->mrPitchMixLevel->value()); + setMixerValue(mixer, "MixerValueYaw", m_aircraft->mrYawMixLevel->value()); + QList mmList; mmList << m_aircraft->multiMotorChannelBox1 << m_aircraft->multiMotorChannelBox2 << m_aircraft->multiMotorChannelBox3 << m_aircraft->multiMotorChannelBox4 diff --git a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.cpp b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.cpp index cdd08adce..04173842b 100644 --- a/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.cpp +++ b/ground/openpilotgcs/src/plugins/pfdqml/pfdqmlgadgetwidget.cpp @@ -67,7 +67,14 @@ PfdQmlGadgetWidget::PfdQmlGadgetWidget(QWindow *parent) : "TakeOffLocation" << "PathPlan" << "WaypointActive" << - "OPLinkStatus"; + "OPLinkStatus" << + "FlightStatus" << + "SystemStats" << + "StabilizationDesired" << + "VtolPathFollowerSettings" << + "HwSettings" << + "ManualControlCommand" << + "SystemSettings"; ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); UAVObjectManager *objManager = pm->getObject(); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp index c5c8b8536..f609379f6 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -39,6 +39,7 @@ #include "stabilizationsettingsbank1.h" #include "revocalibration.h" #include "accelgyrosettings.h" +#include const qint16 VehicleConfigurationHelper::LEGACY_ESC_FREQUENCE = 50; const qint16 VehicleConfigurationHelper::RAPID_ESC_FREQUENCE = 400; @@ -520,9 +521,79 @@ void VehicleConfigurationHelper::applyMixerConfiguration(mixerChannelSettings ch 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); + + // Normalize mixer values, allow a well balanced mixer saved + if (channels[i].roll < 0) { + field->setValue(qFloor((double)(channels[i].roll * 127) / 100), 2); + } else { + field->setValue(qCeil((double)(channels[i].roll * 127) / 100), 2); + } + + if (channels[i].pitch < 0) { + field->setValue(qFloor((double)(channels[i].pitch * 127) / 100), 3); + } else { + field->setValue(qCeil((double)(channels[i].pitch * 127) / 100), 3); + } + + if (channels[i].yaw < 0) { + field->setValue(qFloor((double)(channels[i].yaw * 127) / 100), 4); + } else { + field->setValue(qCeil((double)(channels[i].yaw * 127) / 100), 4); + } + } + + MixerSettings *mixSettings = MixerSettings::GetInstance(m_uavoManager); + + // Save mixer values for sliders + switch (m_configSource->getVehicleType()) { + case VehicleConfigurationSource::VEHICLE_MULTI: + { + switch (m_configSource->getVehicleSubType()) { + case VehicleConfigurationSource::MULTI_ROTOR_TRI_Y: + case VehicleConfigurationSource::MULTI_ROTOR_HEXA: + case VehicleConfigurationSource::MULTI_ROTOR_HEXA_H: + case VehicleConfigurationSource::MULTI_ROTOR_HEXA_X: + mixSettings->setMixerValueRoll(100); + mixSettings->setMixerValuePitch(100); + mixSettings->setMixerValueYaw(100); + break; + case VehicleConfigurationSource::MULTI_ROTOR_QUAD_X: + mixSettings->setMixerValueRoll(50); + mixSettings->setMixerValuePitch(50); + mixSettings->setMixerValueYaw(50); + break; + case VehicleConfigurationSource::MULTI_ROTOR_QUAD_PLUS: + mixSettings->setMixerValueRoll(100); + mixSettings->setMixerValuePitch(100); + mixSettings->setMixerValueYaw(50); + break; + case VehicleConfigurationSource::MULTI_ROTOR_HEXA_COAX_Y: + mixSettings->setMixerValueRoll(100); + mixSettings->setMixerValuePitch(50); + mixSettings->setMixerValueYaw(66); + break; + case VehicleConfigurationSource::MULTI_ROTOR_OCTO: + case VehicleConfigurationSource::MULTI_ROTOR_OCTO_X: + mixSettings->setMixerValueRoll(100); + mixSettings->setMixerValuePitch(100); + mixSettings->setMixerValueYaw(100); + break; + case VehicleConfigurationSource::MULTI_ROTOR_OCTO_COAX_X: + case VehicleConfigurationSource::MULTI_ROTOR_OCTO_COAX_PLUS: + case VehicleConfigurationSource::MULTI_ROTOR_OCTO_V: + break; + default: + break; + } + break; + } + case VehicleConfigurationSource::VEHICLE_FIXEDWING: + case VehicleConfigurationSource::VEHICLE_HELI: + case VehicleConfigurationSource::VEHICLE_SURFACE: + // TODO: Implement mixer / sliders settings for other vehicle types? + break; + default: + break; } // Apply updates @@ -1094,7 +1165,7 @@ void VehicleConfigurationHelper::setupHexaCopter() } case VehicleConfigurationSource::MULTI_ROTOR_HEXA_X: { - frame = SystemSettings::AIRFRAMETYPE_HEXAH; + frame = SystemSettings::AIRFRAMETYPE_HEXAX; // HexaX according to new mixer table and pitch-roll-yaw mixing at 100% // Pitch Roll Yaw // M1 { 1, -0.5, -1 }, diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h index 49dee8ec5..5b692c30c 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h @@ -69,7 +69,8 @@ signals: private: static const int MIXER_TYPE_DISABLED = 0; static const int MIXER_TYPE_MOTOR = 1; - static const int MIXER_TYPE_SERVO = 2; + static const int MIXER_TYPE_REVERSABLEMOTOR = 2; + static const int MIXER_TYPE_SERVO = 3; static const float DEFAULT_ENABLED_ACCEL_TAU = 0.1; VehicleConfigurationSource *m_configSource; diff --git a/ground/openpilotgcs/src/plugins/uploader/SSP/qssp.cpp b/ground/openpilotgcs/src/plugins/uploader/SSP/qssp.cpp index 517772ad9..3c68b0449 100644 --- a/ground/openpilotgcs/src/plugins/uploader/SSP/qssp.cpp +++ b/ground/openpilotgcs/src/plugins/uploader/SSP/qssp.cpp @@ -47,7 +47,7 @@ // Make larger sized integers from smaller sized integers #define MAKEWORD16(ub, lb) ((uint16_t)0x0000 | ((uint16_t)(ub) << 8) | (uint16_t)(lb)) #define MAKEWORD32(uw, lw) ((uint32_t)(0x0UL | ((uint32_t)(uw) << 16) | (uint32_t)(lw))) -#define MAKEWORD32B(b3, b2, b1, b0) ((uint32_t)((uint32_t)(b3) << 24) | ((uint32_t)(b2) << 16) | ((uint32_t)(b1) << 8) | ((uint32_t)(b0)) +#define MAKEWORD32B(b3, b2, b1, b0) ((uint32_t)((uint32_t)(b3) << 24) | ((uint32_t)(b2) << 16) | ((uint32_t)(b1) << 8) | ((uint32_t)(b0))) // Used to extract smaller integers from larger sized intergers diff --git a/make/tools.mk b/make/tools.mk index 2451afcbb..d66dd388d 100644 --- a/make/tools.mk +++ b/make/tools.mk @@ -437,9 +437,8 @@ qt_sdk_install: qt_sdk_clean | $(DL_DIR) $(TOOLS_DIR) $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt/5.3.1ThirdPartySoftware_Listing.7z" | grep -v Extracting $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.readme/1.0.0-0readme.7z" | grep -v Extracting $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.$(6)/5.3.1-0qt5_essentials.7z" | grep -v Extracting - $(V1) if [ -f "$(1)/qt.53.$(6)/5.3.1-0icu_51_1_ubuntu_11_10_64.7z" ]; then $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.$(6)/5.3.1-0icu_51_1_ubuntu_11_10_64.7z" | grep -v Extracting; fi - $(V1) if [ -f "$(1)/qt.53.$(6)/5.3.1-0icu_51_1_ubuntu_11_10_32.7z" ]; then $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.$(6)/5.3.1-0icu_51_1_ubuntu_11_10_32.7z" | grep -v Extracting; fi -# $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.$(6).essentials/5.3.1icu_path_patcher.sh.7z" | grep -v Extracting + $(V1) if [ -f "$(1)/qt.53.$(6)/5.3.1-0icu_52_1_ubuntu_11_10_64.7z" ]; then $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.$(6)/5.3.1-0icu_52_1_ubuntu_11_10_64.7z" | grep -v Extracting; fi + $(V1) if [ -f "$(1)/qt.53.$(6)/5.3.1-0icu_52_1_ubuntu_11_10_32.7z" ]; then $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.$(6)/5.3.1-0icu_52_1_ubuntu_11_10_32.7z" | grep -v Extracting; fi $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.$(6)/5.3.1-0qt5_addons.7z" | grep -v Extracting # go to OpenPilot/tools/5.3.1/gcc_64 and call patcher.sh @$(ECHO) @@ -493,7 +492,7 @@ define MAC_QT_INSTALL_TEMPLATE qt_sdk_install: qt_sdk_clean | $(DL_DIR) $(TOOLS_DIR) $(V1) if ! $(SEVENZIP) >/dev/null 2>&1; then \ - $(ECHO) $(MSG_NOTICE) "Please install the p7zip for your distribution. i.e.: sudo brew install p7zip." && \ + $(ECHO) $(MSG_NOTICE) "Please install the p7zip for your distribution. i.e.: brew install p7zip." && \ exit 1; \ fi $(call DOWNLOAD_TEMPLATE,$(3),$(5),"$(4)") diff --git a/package/linux/45-openpilot-permissions.rules b/package/linux/45-openpilot-permissions.rules index 9015612a6..fdca37665 100644 --- a/package/linux/45-openpilot-permissions.rules +++ b/package/linux/45-openpilot-permissions.rules @@ -1,22 +1,41 @@ - # OpenPilot openpilot flight control board - SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="4117", MODE="0664", GROUP="plugdev" - SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415a", MODE="0664", GROUP="plugdev" - # OpenPilot coptercontrol flight control board - SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415b", MODE="0664", GROUP="plugdev" - # OpenPilot OPLink Mini radio modem board - SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415c", MODE="0664", GROUP="plugdev" - # OpenPilot Revolution board - SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415e", MODE="0664", GROUP="plugdev" - - # Other OpenPilot reserved pids - SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415d", MODE="0664", GROUP="plugdev" - SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="4194", MODE="0664", GROUP="plugdev" - SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="4195", MODE="0664", GROUP="plugdev" - - - # unprogrammed openpilot flight control board - SUBSYSTEM=="usb", ATTRS{idVendor}=="0483", ATTRS{idProduct}=="5750", MODE="0664", GROUP="plugdev" - # FTDI FT2232C Dual USB-UART/FIFO IC - SUBSYSTEM=="usb", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6010", MODE="0664", GROUP="plugdev" - # Olimex Ltd. OpenOCD JTAG TINY - SUBSYSTEM=="usb", ATTRS{idVendor}=="15ba", ATTRS{idProduct}=="0004", MODE="0664", GROUP="plugdev" +# Skip this section below if this device is not connected by USB +SUBSYSTEM!="usb", GOTO="op_rules_end" + +# OpenPilot openpilot flight control board +SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="4117", GOTO="op_rules" +SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415a", GOTO="op_rules" + +# OpenPilot coptercontrol flight control board +SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415b", GOTO="op_rules" + +# OpenPilot OPLink Mini radio modem board +SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415c", GOTO="op_rules" + +# OpenPilot Revolution board +SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415e", GOTO="op_rules" + +# Other OpenPilot reserved pids +SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415d", GOTO="op_rules" +SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="4194", GOTO="op_rules" +SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="4195", GOTO="op_rules" + + +# unprogrammed openpilot flight control board +SUBSYSTEM=="usb", ATTRS{idVendor}=="0483", ATTRS{idProduct}=="5750", GOTO="op_rules" +# FTDI FT2232C Dual USB-UART/FIFO IC +SUBSYSTEM=="usb", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6010", GOTO="op_rules" +# Olimex Ltd. OpenOCD JTAG TINY +SUBSYSTEM=="usb", ATTRS{idVendor}=="15ba", ATTRS{idProduct}=="0004", GOTO="op_rules" + +GOTO="op_rules_end" + +LABEL="op_rules" +# Allow any seated user to access the board. +# uaccess: modern ACL-enabled udev +# udev-acl: for Ubuntu 12.10 and older +TAG+="uaccess", TAG+="udev-acl" + +# Grant members of the "plugdev" group access to receiver (useful for SSH users) +#MODE="0664", GROUP="plugdev" + +LABEL="op_rules_end" diff --git a/package/linux/deb_common/openpilot.udev b/package/linux/deb_common/openpilot.udev index a7852b192..fdca37665 100644 --- a/package/linux/deb_common/openpilot.udev +++ b/package/linux/deb_common/openpilot.udev @@ -1,18 +1,41 @@ - # OpenPilot Flight Control board - SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="4117", MODE="0664", GROUP="plugdev" - # OpenPilot OP board - SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415a", MODE="0664", GROUP="plugdev" - # OpenPilot CopterControl flight control board - SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415b", MODE="0664", GROUP="plugdev" - # OpenPilot OPlink Mini radio modem board - SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415c", MODE="0664", GROUP="plugdev" - # OpenPilot CopterControl3D flight control board - SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415d", MODE="0664", GROUP="plugdev" - # OpenPilot Revolution flight control board - SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415e", MODE="0664", GROUP="plugdev" - # unprogrammed openpilot flight control board - SUBSYSTEM=="usb", ATTRS{idVendor}=="0483", ATTRS{idProduct}=="5750", MODE="0664", GROUP="plugdev" - # FTDI FT2232C Dual USB-UART/FIFO IC - SUBSYSTEM=="usb", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6010", MODE="0664", GROUP="plugdev" - # Olimex Ltd. OpenOCD JTAG TINY - SUBSYSTEM=="usb", ATTRS{idVendor}=="15ba", ATTRS{idProduct}=="0004", MODE="0664", GROUP="plugdev" +# Skip this section below if this device is not connected by USB +SUBSYSTEM!="usb", GOTO="op_rules_end" + +# OpenPilot openpilot flight control board +SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="4117", GOTO="op_rules" +SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415a", GOTO="op_rules" + +# OpenPilot coptercontrol flight control board +SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415b", GOTO="op_rules" + +# OpenPilot OPLink Mini radio modem board +SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415c", GOTO="op_rules" + +# OpenPilot Revolution board +SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415e", GOTO="op_rules" + +# Other OpenPilot reserved pids +SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="415d", GOTO="op_rules" +SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="4194", GOTO="op_rules" +SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="4195", GOTO="op_rules" + + +# unprogrammed openpilot flight control board +SUBSYSTEM=="usb", ATTRS{idVendor}=="0483", ATTRS{idProduct}=="5750", GOTO="op_rules" +# FTDI FT2232C Dual USB-UART/FIFO IC +SUBSYSTEM=="usb", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6010", GOTO="op_rules" +# Olimex Ltd. OpenOCD JTAG TINY +SUBSYSTEM=="usb", ATTRS{idVendor}=="15ba", ATTRS{idProduct}=="0004", GOTO="op_rules" + +GOTO="op_rules_end" + +LABEL="op_rules" +# Allow any seated user to access the board. +# uaccess: modern ACL-enabled udev +# udev-acl: for Ubuntu 12.10 and older +TAG+="uaccess", TAG+="udev-acl" + +# Grant members of the "plugdev" group access to receiver (useful for SSH users) +#MODE="0664", GROUP="plugdev" + +LABEL="op_rules_end" diff --git a/shared/uavobjectdefinition/mixersettings.xml b/shared/uavobjectdefinition/mixersettings.xml index 16143bf2d..5bfff7e12 100644 --- a/shared/uavobjectdefinition/mixersettings.xml +++ b/shared/uavobjectdefinition/mixersettings.xml @@ -2,6 +2,9 @@ Settings for the @ref ActuatorModule that controls the channel assignments for the mixer based on AircraftType + + +