diff --git a/.gitignore b/.gitignore index b2583f3b1..bab962c2b 100644 --- a/.gitignore +++ b/.gitignore @@ -1,72 +1,73 @@ -# Ignore artifacts of top-level Makefile -/downloads -/tools -/build - -# Exclude temporary and system files -Thumbs.db -.DS_Store -GPATH -GRTAGS -GSYMS -GTAGS -core - -# flight -/flight/*.pnproj -/flight/*.pnps -/flight/.cproject -/flight/.metadata -/flight/.project -/flight/.settings -/flight/Project/OpenPilotOSX/OpenPilotOSX.xcodeproj/*.mode1v3 -/flight/Project/OpenPilotOSX/OpenPilotOSX.xcodeproj/*.pbxuser - -# ground -openpilotgcs-build-desktop -ground/openpilotgcs/.cproject -ground/openpilotgcs/.project -ground/openpilotgcs/.settings - -# Ignore some of the .pro.user files -*.pro.user -/ground/openpilotgcs/openpilotgcs.pro.user -/ground/uavobjgenerator/uavobjgenerator.pro.user -/ground/uavobjects/uavobjects.pro.user -/ground/ground.pro.user - -# Misc artifacts -/ground/openpilotgcs/share/openpilotgcs/sounds/normalize.exe -/ground/openpilotgcs/share/openpilotgcs/sounds/default/normalize.exe -/ground/openpilotgcs/share/openpilotgcs/translations/extract-mimetypes.xq -/ground/openpilotgcs/src/experimental/tools/DocumentationHelper/ui_mainwindow.h -/ground/openpilotgcs/src/libs/qextserialport/.hg -/ground/openpilotgcs/src/libs/qextserialport/.hgtags -/ground/openpilotgcs/src/libs/qwt/qwt.prf -/ground/openpilotgcs/src/libs/qwt/designer -/ground/openpilotgcs/src/plugins/ipconnection/ui_ipconnectionoptionspage.h - -# Ignore intermediate files generated by command-line android builds -# Couldn't figure out how to force these files into the ./build directory -/androidgcs/build.xml -/androidgcs/local.properties -/androidgcs/proguard-project.txt - -# Ignore build output from Eclipse android builds -/androidgcs/bin/ -/androidgcs/gen/ - -# Ignore Eclipse Projects and Metadata -/.cproject -/.project -/.metadata -/.settings -/.pydevproject - -# Ignore Eclipse temp folder, git plugin based? -RemoteSystemsTempFiles - -# Ignore patch-related files -*.rej -*.orig -*.diff~ +# Ignore artifacts of top-level Makefile +/downloads +/tools +/build + +# Exclude temporary and system files +Thumbs.db +.DS_Store +GPATH +GRTAGS +GSYMS +GTAGS +core + +# flight +/flight/*.pnproj +/flight/*.pnps +/flight/.cproject +/flight/.metadata +/flight/.project +/flight/.settings +/flight/Project/OpenPilotOSX/OpenPilotOSX.xcodeproj/*.mode1v3 +/flight/Project/OpenPilotOSX/OpenPilotOSX.xcodeproj/*.pbxuser + +# ground +openpilotgcs-build-desktop +ground/openpilotgcs/.cproject +ground/openpilotgcs/.project +ground/openpilotgcs/.settings + +# Ignore some of the .pro.user files +*.pro.user +/ground/openpilotgcs/openpilotgcs.pro.user +/ground/uavobjgenerator/uavobjgenerator.pro.user +/ground/uavobjects/uavobjects.pro.user +/ground/ground.pro.user +/ground/openpilotgcs/src/libs/sdlgamepad.pro.user + +# Misc artifacts +/ground/openpilotgcs/share/openpilotgcs/sounds/normalize.exe +/ground/openpilotgcs/share/openpilotgcs/sounds/default/normalize.exe +/ground/openpilotgcs/share/openpilotgcs/translations/extract-mimetypes.xq +/ground/openpilotgcs/src/experimental/tools/DocumentationHelper/ui_mainwindow.h +/ground/openpilotgcs/src/libs/qextserialport/.hg +/ground/openpilotgcs/src/libs/qextserialport/.hgtags +/ground/openpilotgcs/src/libs/qwt/qwt.prf +/ground/openpilotgcs/src/libs/qwt/designer +/ground/openpilotgcs/src/plugins/ipconnection/ui_ipconnectionoptionspage.h + +# Ignore intermediate files generated by command-line android builds +# Couldn't figure out how to force these files into the ./build directory +/androidgcs/build.xml +/androidgcs/local.properties +/androidgcs/proguard-project.txt + +# Ignore build output from Eclipse android builds +/androidgcs/bin/ +/androidgcs/gen/ + +# Ignore Eclipse Projects and Metadata +/.cproject +/.project +/.metadata +/.settings +/.pydevproject + +# Ignore Eclipse temp folder, git plugin based? +RemoteSystemsTempFiles + +# Ignore patch-related files +*.rej +*.orig +*.diff~ diff --git a/MILESTONES.txt b/MILESTONES.txt index 4480129b1..c165cfe5f 100644 --- a/MILESTONES.txt +++ b/MILESTONES.txt @@ -177,15 +177,56 @@ C: Eric Price (Corvus Corax) D: March 2012 V: +M: First Revo 20km Navigated flight on a FixedWing +C: Eric Price / Team OP +D: Greece 2013 +V: https://vimeo.com/71956880 + +M: First Auto spot landing on a fixed Wing using Revo +C: Eric Price (Corvus Corax) +D: Greece 2013 +V: + M: First Revo Navigated flight on a MultiRotor C: It got done somewhere along the line, James or Sami M: First Revo 1km Navigated flight on a MultiRotor +C: Jackson Russell +D: Greece 2013 +V: + +M: First Revo 5km Navigated flight on a MultiRotor +C: RoddersNZ +D: September 2014 +V: https://www.youtube.com/watch?v=DYawRGz5KYM + +M: First Revo 6km Navigated flight on a MultiRotor C: D: V: -M: First Revo 5km Navigated flight on a MultiRotor +M: First Revo 7km Navigated flight on a MultiRotor +C: +D: +V: + +M: First Revo 8km Navigated flight on a MultiRotor +C: +D: +V: + +M: First Revo 9km Navigated flight on a MultiRotor +C: +D: +V: + +M: First Revo 10km Navigated flight on a MultiRotor +C: +D: +V: + + +M: First Revo Position Hold on a Heli C: D: V: @@ -205,23 +246,8 @@ C: D: V: -M: First Auto spot landing on a fixed Wing using Revo -C: -D: -V: - -M: First Auto take-off on a MultiRotor using Revo -C: -D: -V: - M: First Auto landing on a MultiRotor using Revo -C: Sami (please complete details) -D: -V: - -M: First Auto take-off on a Heli using Revo -C: +C: Sami D: V: diff --git a/flight/libraries/alarms.c b/flight/libraries/alarms.c index 8805ee8a6..db555ad8e 100644 --- a/flight/libraries/alarms.c +++ b/flight/libraries/alarms.c @@ -28,7 +28,6 @@ */ #include -#include #include "inc/alarms.h" // Private constants @@ -83,9 +82,9 @@ int32_t AlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsAlarmOptions severity SystemAlarmsAlarmGet(&alarms); uint16_t flightTime = (uint16_t)xTaskGetTickCount() * (uint16_t)portTICK_RATE_MS; // this deliberately overflows every 2^16 milliseconds to save memory if (((uint16_t)(flightTime - lastAlarmChange[alarm]) > PIOS_ALARM_GRACETIME && - cast_struct_to_array(alarms, alarms.Actuator)[alarm] != severity) - || cast_struct_to_array(alarms, alarms.Actuator)[alarm] < severity) { - cast_struct_to_array(alarms, alarms.Actuator)[alarm] = severity; + SystemAlarmsAlarmToArray(alarms)[alarm] != severity) + || SystemAlarmsAlarmToArray(alarms)[alarm] < severity) { + SystemAlarmsAlarmToArray(alarms)[alarm] = severity; lastAlarmChange[alarm] = flightTime; SystemAlarmsAlarmSet(&alarms); } @@ -122,11 +121,11 @@ int32_t ExtendedAlarmsSet(SystemAlarmsAlarmElem alarm, SystemAlarmsGet(&alarms); uint16_t flightTime = (uint16_t)xTaskGetTickCount() * (uint16_t)portTICK_RATE_MS; // this deliberately overflows every 2^16 milliseconds to save memory if (((uint16_t)(flightTime - lastAlarmChange[alarm]) > PIOS_ALARM_GRACETIME && - cast_struct_to_array(alarms.Alarm, alarms.Alarm.Actuator)[alarm] != severity) - || cast_struct_to_array(alarms.Alarm, alarms.Alarm.Actuator)[alarm] < severity) { - cast_struct_to_array(alarms.ExtendedAlarmStatus, alarms.ExtendedAlarmStatus.BootFault)[alarm] = status; - cast_struct_to_array(alarms.ExtendedAlarmSubStatus, alarms.ExtendedAlarmStatus.BootFault)[alarm] = subStatus; - cast_struct_to_array(alarms.Alarm, alarms.Alarm.Actuator)[alarm] = severity; + SystemAlarmsAlarmToArray(alarms.Alarm)[alarm] != severity) + || SystemAlarmsAlarmToArray(alarms.Alarm)[alarm] < severity) { + SystemAlarmsExtendedAlarmStatusToArray(alarms.ExtendedAlarmStatus)[alarm] = status; + SystemAlarmsExtendedAlarmSubStatusToArray(alarms.ExtendedAlarmSubStatus)[alarm] = subStatus; + SystemAlarmsAlarmToArray(alarms.Alarm)[alarm] = severity; lastAlarmChange[alarm] = flightTime; SystemAlarmsSet(&alarms); } @@ -152,7 +151,7 @@ SystemAlarmsAlarmOptions AlarmsGet(SystemAlarmsAlarmElem alarm) // Read alarm SystemAlarmsAlarmGet(&alarms); - return cast_struct_to_array(alarms, alarms.Actuator)[alarm]; + return SystemAlarmsAlarmToArray(alarms)[alarm]; } /** @@ -244,7 +243,7 @@ static int32_t hasSeverity(SystemAlarmsAlarmOptions severity) // Go through alarms and check if any are of the given severity or higher for (uint32_t n = 0; n < SYSTEMALARMS_ALARM_NUMELEM; ++n) { - if (cast_struct_to_array(alarms, alarms.Actuator)[n] >= severity) { + if (SystemAlarmsAlarmToArray(alarms)[n] >= severity) { xSemaphoreGiveRecursive(lock); return 1; } @@ -272,8 +271,8 @@ SystemAlarmsAlarmOptions AlarmsGetHighestSeverity() // Go through alarms and find the highest severity uint32_t n = 0; while (n < SYSTEMALARMS_ALARM_NUMELEM && highest != SYSTEMALARMS_ALARM_CRITICAL) { - if (cast_struct_to_array(alarmsData, alarmsData.Actuator)[n] > highest) { - highest = cast_struct_to_array(alarmsData, alarmsData.Actuator)[n]; + if (SystemAlarmsAlarmToArray(alarmsData)[n] > highest) { + highest = SystemAlarmsAlarmToArray(alarmsData)[n]; } n++; } diff --git a/flight/libraries/notification.c b/flight/libraries/notification.c index 9015e4dd3..2d11d224a 100644 --- a/flight/libraries/notification.c +++ b/flight/libraries/notification.c @@ -25,7 +25,6 @@ */ #include "inc/notification.h" #include -#include #include #include #include diff --git a/flight/modules/CameraStab/camerastab.c b/flight/modules/CameraStab/camerastab.c index 9d479c530..27ba36d28 100644 --- a/flight/modules/CameraStab/camerastab.c +++ b/flight/modules/CameraStab/camerastab.c @@ -52,7 +52,6 @@ #include "camerastabsettings.h" #include "cameradesired.h" #include "hwsettings.h" -#include // // Configuration @@ -172,22 +171,22 @@ static void attitudeUpdated(UAVObjEvent *ev) // process axes for (uint8_t i = 0; i < CAMERASTABSETTINGS_INPUT_NUMELEM; i++) { // read and process control input - if (cast_struct_to_array(cameraStab.Input, cameraStab.Input.Roll)[i] != CAMERASTABSETTINGS_INPUT_NONE) { - if (AccessoryDesiredInstGet(cast_struct_to_array(cameraStab.Input, cameraStab.Input.Roll)[i] - + if (CameraStabSettingsInputToArray(cameraStab.Input)[i] != CAMERASTABSETTINGS_INPUT_NONE) { + if (AccessoryDesiredInstGet(CameraStabSettingsInputToArray(cameraStab.Input)[i] - CAMERASTABSETTINGS_INPUT_ACCESSORY0, &accessory) == 0) { float input_rate; - switch (cast_struct_to_array(cameraStab.StabilizationMode, cameraStab.StabilizationMode.Roll)[i]) { + switch (CameraStabSettingsStabilizationModeToArray(cameraStab.StabilizationMode)[i]) { case CAMERASTABSETTINGS_STABILIZATIONMODE_ATTITUDE: csd->inputs[i] = accessory.AccessoryVal * - cast_struct_to_array(cameraStab.InputRange, cameraStab.InputRange.Roll)[i]; + CameraStabSettingsInputRangeToArray(cameraStab.InputRange)[i]; break; case CAMERASTABSETTINGS_STABILIZATIONMODE_AXISLOCK: input_rate = accessory.AccessoryVal * - cast_struct_to_array(cameraStab.InputRate, cameraStab.InputRate.Roll)[i]; + CameraStabSettingsInputRateToArray(cameraStab.InputRate)[i]; if (fabsf(input_rate) > cameraStab.MaxAxisLockRate) { csd->inputs[i] = boundf(csd->inputs[i] + input_rate * 0.001f * dT_millis, - -cast_struct_to_array(cameraStab.InputRange, cameraStab.InputRange.Roll)[i], - cast_struct_to_array(cameraStab.InputRange, cameraStab.InputRange.Roll)[i]); + -CameraStabSettingsInputRangeToArray(cameraStab.InputRange)[i], + CameraStabSettingsInputRangeToArray(cameraStab.InputRange)[i]); } break; default: @@ -214,14 +213,14 @@ static void attitudeUpdated(UAVObjEvent *ev) } #ifdef USE_GIMBAL_LPF - if (cast_struct_to_array(cameraStab.ResponseTime, cameraStab.ResponseTime.Roll)[i]) { - float rt = (float)cast_struct_to_array(cameraStab.ResponseTime, cameraStab.ResponseTime.Roll)[i]; + if (CameraStabSettingsResponseTimeToArray(cameraStab.ResponseTime)[i]) { + float rt = (float)CameraStabSettingsResponseTimeToArray(cameraStab.ResponseTime)[i]; attitude = csd->attitudeFiltered[i] = ((rt * csd->attitudeFiltered[i]) + (dT_millis * attitude)) / (rt + dT_millis); } #endif #ifdef USE_GIMBAL_FF - if (cast_struct_to_array(cameraStab.FeedForward, cameraStab.FeedForward.Roll)[i]) { + if (CameraStabSettingsFeedForwardToArray(cameraStab.FeedForward)[i]) { applyFeedForward(i, dT_millis, &attitude, &cameraStab); } #endif @@ -229,7 +228,7 @@ static void attitudeUpdated(UAVObjEvent *ev) // bounding for elevon mixing occurs on the unmixed output // to limit the range of the mixed output you must limit the range // of both the unmixed pitch and unmixed roll - float output = boundf((attitude + csd->inputs[i]) / cast_struct_to_array(cameraStab.OutputRange, cameraStab.OutputRange.Roll)[i], -1.0f, 1.0f); + float output = boundf((attitude + csd->inputs[i]) / CameraStabSettingsOutputRangeToArray(cameraStab.OutputRange)[i], -1.0f, 1.0f); // set output channels switch (i) { @@ -316,12 +315,12 @@ void applyFeedForward(uint8_t index, float dT_millis, float *attitude, CameraSta // apply feed forward float accumulator = csd->ffFilterAccumulator[index]; accumulator += (*attitude - csd->ffLastAttitude[index]) * - (float)cast_struct_to_array(cameraStab->FeedForward, cameraStab->FeedForward.Roll)[index] * gimbalTypeCorrection; + (float)CameraStabSettingsFeedForwardToArray(cameraStab->FeedForward)[index] * gimbalTypeCorrection; csd->ffLastAttitude[index] = *attitude; *attitude += accumulator; - float filter = (float)((accumulator > 0.0f) ? cast_struct_to_array(cameraStab->AccelTime, cameraStab->AccelTime.Roll)[index] : - cast_struct_to_array(cameraStab->DecelTime, cameraStab->DecelTime.Roll)[index]) / dT_millis; + float filter = (float)((accumulator > 0.0f) ? CameraStabSettingsAccelTimeToArray(cameraStab->AccelTime)[index] : + CameraStabSettingsDecelTimeToArray(cameraStab->DecelTime)[index]) / dT_millis; if (filter < 1.0f) { filter = 1.0f; } diff --git a/flight/modules/ComUsbBridge/ComUsbBridge.c b/flight/modules/ComUsbBridge/ComUsbBridge.c index 5c0541b80..ad3cad4ce 100644 --- a/flight/modules/ComUsbBridge/ComUsbBridge.c +++ b/flight/modules/ComUsbBridge/ComUsbBridge.c @@ -42,7 +42,7 @@ static void com2UsbBridgeTask(void *parameters); static void usb2ComBridgeTask(void *parameters); -static void updateSettings(); +static void updateSettings(UAVObjEvent *ev); // **************** // Private constants @@ -106,8 +106,7 @@ static int32_t comUsbBridgeInitialize(void) HwSettingsOptionalModulesGet(&optionalModules); - if (usart_port && vcp_port && - (optionalModules.ComUsbBridge == HWSETTINGS_OPTIONALMODULES_ENABLED)) { + if (usart_port && vcp_port) { bridge_enabled = true; } else { bridge_enabled = false; @@ -119,8 +118,8 @@ static int32_t comUsbBridgeInitialize(void) PIOS_Assert(com2usb_buf); usb2com_buf = pios_malloc(BRIDGE_BUF_LEN); PIOS_Assert(usb2com_buf); - - updateSettings(); + HwSettingsConnectCallback(&updateSettings); + updateSettings(0); } return 0; @@ -170,7 +169,7 @@ static void usb2ComBridgeTask(__attribute__((unused)) void *parameters) } -static void updateSettings() +static void updateSettings(__attribute__((unused)) UAVObjEvent *ev) { if (usart_port) { // Retrieve settings diff --git a/flight/modules/ManualControl/armhandler.c b/flight/modules/ManualControl/armhandler.c index 7dbf79336..dbaefa779 100644 --- a/flight/modules/ManualControl/armhandler.c +++ b/flight/modules/ManualControl/armhandler.c @@ -29,7 +29,6 @@ */ #include "inc/manualcontrol.h" -#include #include #include #include @@ -259,7 +258,7 @@ static bool okToArm(void) // Check each alarm for (int i = 0; i < SYSTEMALARMS_ALARM_NUMELEM; i++) { - if (cast_struct_to_array(alarms.Alarm, alarms.Alarm.Actuator)[i] >= SYSTEMALARMS_ALARM_CRITICAL) { // found an alarm thats set + if (SystemAlarmsAlarmToArray(alarms.Alarm)[i] >= SYSTEMALARMS_ALARM_CRITICAL) { // found an alarm thats set if (i == SYSTEMALARMS_ALARM_GPS || i == SYSTEMALARMS_ALARM_TELEMETRY) { continue; } diff --git a/flight/modules/ManualControl/stabilizedhandler.c b/flight/modules/ManualControl/stabilizedhandler.c index 2ab4222f9..582929425 100644 --- a/flight/modules/ManualControl/stabilizedhandler.c +++ b/flight/modules/ManualControl/stabilizedhandler.c @@ -29,7 +29,6 @@ */ #include "inc/manualcontrol.h" -#include #include #include #include @@ -70,27 +69,27 @@ void stabilizedHandler(bool newinit) FlightStatusGet(&flightStatus); switch (flightStatus.FlightMode) { case FLIGHTSTATUS_FLIGHTMODE_STABILIZED1: - stab_settings = cast_struct_to_array(settings.Stabilization1Settings, settings.Stabilization1Settings.Roll); + stab_settings = FlightModeSettingsStabilization1SettingsToArray(settings.Stabilization1Settings); break; case FLIGHTSTATUS_FLIGHTMODE_STABILIZED2: - stab_settings = cast_struct_to_array(settings.Stabilization2Settings, settings.Stabilization2Settings.Roll); + stab_settings = FlightModeSettingsStabilization2SettingsToArray(settings.Stabilization2Settings); break; case FLIGHTSTATUS_FLIGHTMODE_STABILIZED3: - stab_settings = cast_struct_to_array(settings.Stabilization3Settings, settings.Stabilization3Settings.Roll); + stab_settings = FlightModeSettingsStabilization3SettingsToArray(settings.Stabilization3Settings); break; case FLIGHTSTATUS_FLIGHTMODE_STABILIZED4: - stab_settings = cast_struct_to_array(settings.Stabilization4Settings, settings.Stabilization4Settings.Roll); + stab_settings = FlightModeSettingsStabilization4SettingsToArray(settings.Stabilization4Settings); break; case FLIGHTSTATUS_FLIGHTMODE_STABILIZED5: - stab_settings = cast_struct_to_array(settings.Stabilization5Settings, settings.Stabilization5Settings.Roll); + stab_settings = FlightModeSettingsStabilization5SettingsToArray(settings.Stabilization5Settings); break; case FLIGHTSTATUS_FLIGHTMODE_STABILIZED6: - stab_settings = cast_struct_to_array(settings.Stabilization6Settings, settings.Stabilization6Settings.Roll); + stab_settings = FlightModeSettingsStabilization6SettingsToArray(settings.Stabilization6Settings); break; default: // Major error, this should not occur because only enter this block when one of these is true AlarmsSet(SYSTEMALARMS_ALARM_MANUALCONTROL, SYSTEMALARMS_ALARM_CRITICAL); - stab_settings = cast_struct_to_array(settings.Stabilization1Settings, settings.Stabilization1Settings.Roll); + stab_settings = FlightModeSettingsStabilization1SettingsToArray(settings.Stabilization1Settings); return; } diff --git a/flight/modules/PathFollower/pathfollower.c b/flight/modules/PathFollower/pathfollower.c index 67226589b..bd6372b17 100644 --- a/flight/modules/PathFollower/pathfollower.c +++ b/flight/modules/PathFollower/pathfollower.c @@ -51,7 +51,6 @@ #include #include #include -#include #include #include #include @@ -377,7 +376,7 @@ static uint8_t updateAutoPilotVtol() } // vertical positon control PID loops works the same in both regular and fallback modes, setup according to settings - pid_configure(&global.PIDposV, vtolPathFollowerSettings.VerticalPosPI.Kp, vtolPathFollowerSettings.HorizontalPosPI.Ki, 0.0f, vtolPathFollowerSettings.HorizontalPosPI.ILimit); + pid_configure(&global.PIDposV, vtolPathFollowerSettings.VerticalPosPI.Kp, vtolPathFollowerSettings.VerticalPosPI.Ki, 0.0f, vtolPathFollowerSettings.VerticalPosPI.ILimit); switch (followermode) { case FOLLOWER_REGULAR: diff --git a/flight/modules/PathPlanner/pathplanner.c b/flight/modules/PathPlanner/pathplanner.c index 32d2afbae..2ab9f1a61 100644 --- a/flight/modules/PathPlanner/pathplanner.c +++ b/flight/modules/PathPlanner/pathplanner.c @@ -43,7 +43,6 @@ #include "waypoint.h" #include "waypointactive.h" #include "flightmodesettings.h" -#include #include "paths.h" #include "plans.h" diff --git a/flight/modules/Receiver/receiver.c b/flight/modules/Receiver/receiver.c index 6f79ba16d..cf3230751 100644 --- a/flight/modules/Receiver/receiver.c +++ b/flight/modules/Receiver/receiver.c @@ -33,7 +33,6 @@ */ #include -#include #include #include #include @@ -210,12 +209,12 @@ static void receiverTask(__attribute__((unused)) void *parameters) for (uint8_t n = 0; n < MANUALCONTROLSETTINGS_CHANNELGROUPS_NUMELEM && n < MANUALCONTROLCOMMAND_CHANNEL_NUMELEM; ++n) { extern uint32_t pios_rcvr_group_map[]; - if (cast_struct_to_array(settings.ChannelGroups, settings.ChannelGroups.Roll)[n] >= MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE) { + if (ManualControlSettingsChannelGroupsToArray(settings.ChannelGroups)[n] >= MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE) { cmd.Channel[n] = PIOS_RCVR_INVALID; } else { cmd.Channel[n] = PIOS_RCVR_Read(pios_rcvr_group_map[ - cast_struct_to_array(settings.ChannelGroups, settings.ChannelGroups.Pitch)[n]], - cast_struct_to_array(settings.ChannelNumber, settings.ChannelNumber.Pitch)[n]); + ManualControlSettingsChannelGroupsToArray(settings.ChannelGroups)[n]], + ManualControlSettingsChannelNumberToArray(settings.ChannelNumber)[n]); } // If a channel has timed out this is not valid data and we shouldn't update anything @@ -224,9 +223,9 @@ static void receiverTask(__attribute__((unused)) void *parameters) valid_input_detected = false; } else { scaledChannel[n] = scaleChannel(cmd.Channel[n], - cast_struct_to_array(settings.ChannelMax, settings.ChannelMax.Pitch)[n], - cast_struct_to_array(settings.ChannelMin, settings.ChannelMin.Pitch)[n], - cast_struct_to_array(settings.ChannelNeutral, settings.ChannelNeutral.Pitch)[n]); + ManualControlSettingsChannelMaxToArray(settings.ChannelMax)[n], + ManualControlSettingsChannelMinToArray(settings.ChannelMin)[n], + ManualControlSettingsChannelNeutralToArray(settings.ChannelNeutral)[n]); } } @@ -445,8 +444,8 @@ static void receiverTask(__attribute__((unused)) void *parameters) if (pios_usb_rctx_id) { PIOS_USB_RCTX_Update(pios_usb_rctx_id, cmd.Channel, - cast_struct_to_array(settings.ChannelMin, settings.ChannelMin.Roll), - cast_struct_to_array(settings.ChannelMax, settings.ChannelMax.Roll), + ManualControlSettingsChannelMinToArray(settings.ChannelMin), + ManualControlSettingsChannelMaxToArray(settings.ChannelMax), NELEMENTS(cmd.Channel)); } #endif /* PIOS_INCLUDE_USB_RCTX */ @@ -661,8 +660,8 @@ static void applyDeadband(float *value, float deadband) */ static void applyLPF(float *value, ManualControlSettingsResponseTimeElem channel, ManualControlSettingsData *settings, float dT) { - if (cast_struct_to_array(settings->ResponseTime, settings->ResponseTime.Roll)[channel]) { - float rt = (float)cast_struct_to_array(settings->ResponseTime, settings->ResponseTime.Roll)[channel]; + if (ManualControlSettingsResponseTimeToArray(settings->ResponseTime)[channel]) { + float rt = (float)ManualControlSettingsResponseTimeToArray(settings->ResponseTime)[channel]; inputFiltered[channel] = ((rt * inputFiltered[channel]) + (dT * (*value))) / (rt + dT); *value = inputFiltered[channel]; } diff --git a/flight/modules/Sensors/sensors.c b/flight/modules/Sensors/sensors.c index b24e34317..fb51af90e 100644 --- a/flight/modules/Sensors/sensors.c +++ b/flight/modules/Sensors/sensors.c @@ -62,7 +62,6 @@ #include #include -#include // Private constants #define STACK_SIZE_BYTES 1000 @@ -495,7 +494,7 @@ static void settingsUpdatedCb(__attribute__((unused)) UAVObjEvent *objEv) } else { Quaternion2R(rotationQuat, R); } - matrix_mult_3x3f((float(*)[3])cast_struct_to_array(cal.mag_transform, cal.mag_transform.r0c0), R, mag_transform); + matrix_mult_3x3f((float(*)[3])RevoCalibrationmag_transformToArray(cal.mag_transform), R, mag_transform); } /** * @} diff --git a/flight/modules/Stabilization/inc/stabilization.h b/flight/modules/Stabilization/inc/stabilization.h index 8314ae97e..44ab8917c 100644 --- a/flight/modules/Stabilization/inc/stabilization.h +++ b/flight/modules/Stabilization/inc/stabilization.h @@ -76,7 +76,7 @@ extern StabilizationData stabSettings; // must be same as eventdispatcher to avoid needing additional mutexes #define CBTASK_PRIORITY CALLBACK_TASK_FLIGHTCONTROL -// outer loop only executes every 4th uavobject update to safe CPU +// outer loop only executes every 4th uavobject update to save CPU #define OUTERLOOP_SKIPCOUNT 4 #endif // STABILIZATION_H diff --git a/flight/modules/Stabilization/innerloop.c b/flight/modules/Stabilization/innerloop.c index e7254b933..68d6499da 100644 --- a/flight/modules/Stabilization/innerloop.c +++ b/flight/modules/Stabilization/innerloop.c @@ -32,7 +32,6 @@ */ #include -#include #include #include #include @@ -165,21 +164,21 @@ static void stabilizationInnerloopTask() dT = PIOS_DELTATIME_GetAverageSeconds(&timeval); for (t = 0; t < AXES; t++) { - bool reinit = (cast_struct_to_array(enabled, enabled.Roll)[t] != previous_mode[t]); - previous_mode[t] = cast_struct_to_array(enabled, enabled.Roll)[t]; + bool reinit = (StabilizationStatusInnerLoopToArray(enabled)[t] != previous_mode[t]); + previous_mode[t] = StabilizationStatusInnerLoopToArray(enabled)[t]; if (t < STABILIZATIONSTATUS_INNERLOOP_THRUST) { if (reinit) { stabSettings.innerPids[t].iAccumulator = 0; } - switch (cast_struct_to_array(enabled, enabled.Roll)[t]) { + switch (StabilizationStatusInnerLoopToArray(enabled)[t]) { case STABILIZATIONSTATUS_INNERLOOP_VIRTUALFLYBAR: stabilization_virtual_flybar(gyro_filtered[t], rate[t], &actuatorDesiredAxis[t], dT, reinit, t, &stabSettings.settings); break; case STABILIZATIONSTATUS_INNERLOOP_RELAYTUNING: rate[t] = boundf(rate[t], - -cast_struct_to_array(stabSettings.stabBank.MaximumRate, stabSettings.stabBank.MaximumRate.Roll)[t], - cast_struct_to_array(stabSettings.stabBank.MaximumRate, stabSettings.stabBank.MaximumRate.Roll)[t] + -StabilizationBankMaximumRateToArray(stabSettings.stabBank.MaximumRate)[t], + StabilizationBankMaximumRateToArray(stabSettings.stabBank.MaximumRate)[t] ); stabilization_relay_rate(rate[t] - gyro_filtered[t], &actuatorDesiredAxis[t], t, reinit); break; @@ -198,8 +197,8 @@ static void stabilizationInnerloopTask() case STABILIZATIONSTATUS_INNERLOOP_RATE: // limit rate to maximum configured limits (once here instead of 5 times in outer loop) rate[t] = boundf(rate[t], - -cast_struct_to_array(stabSettings.stabBank.MaximumRate, stabSettings.stabBank.MaximumRate.Roll)[t], - cast_struct_to_array(stabSettings.stabBank.MaximumRate, stabSettings.stabBank.MaximumRate.Roll)[t] + -StabilizationBankMaximumRateToArray(stabSettings.stabBank.MaximumRate)[t], + StabilizationBankMaximumRateToArray(stabSettings.stabBank.MaximumRate)[t] ); actuatorDesiredAxis[t] = pid_apply_setpoint(&stabSettings.innerPids[t], speedScaleFactor, rate[t], gyro_filtered[t], dT); break; @@ -209,7 +208,7 @@ static void stabilizationInnerloopTask() break; } } else { - switch (cast_struct_to_array(enabled, enabled.Roll)[t]) { + switch (StabilizationStatusInnerLoopToArray(enabled)[t]) { case STABILIZATIONSTATUS_INNERLOOP_CRUISECONTROL: actuatorDesiredAxis[t] = cruisecontrol_apply_factor(rate[t]); break; diff --git a/flight/modules/Stabilization/outerloop.c b/flight/modules/Stabilization/outerloop.c index 7d865b556..a1f8d37c1 100644 --- a/flight/modules/Stabilization/outerloop.c +++ b/flight/modules/Stabilization/outerloop.c @@ -32,7 +32,6 @@ */ #include -#include #include #include #include @@ -115,7 +114,7 @@ static void stabilizationOuterloopTask() float q_error[4]; for (t = 0; t < 3; t++) { - switch (cast_struct_to_array(enabled, enabled.Roll)[t]) { + switch (StabilizationStatusOuterLoopToArray(enabled)[t]) { case STABILIZATIONSTATUS_OUTERLOOP_ATTITUDE: case STABILIZATIONSTATUS_OUTERLOOP_RATTITUDE: case STABILIZATIONSTATUS_OUTERLOOP_WEAKLEVELING: @@ -150,14 +149,14 @@ static void stabilizationOuterloopTask() #endif /* if defined(PIOS_QUATERNION_STABILIZATION) */ } for (t = 0; t < AXES; t++) { - bool reinit = (cast_struct_to_array(enabled, enabled.Roll)[t] != previous_mode[t]); - previous_mode[t] = cast_struct_to_array(enabled, enabled.Roll)[t]; + bool reinit = (StabilizationStatusOuterLoopToArray(enabled)[t] != previous_mode[t]); + previous_mode[t] = StabilizationStatusOuterLoopToArray(enabled)[t]; if (t < STABILIZATIONSTATUS_OUTERLOOP_THRUST) { if (reinit) { stabSettings.outerPids[t].iAccumulator = 0; } - switch (cast_struct_to_array(enabled, enabled.Roll)[t]) { + switch (StabilizationStatusOuterLoopToArray(enabled)[t]) { case STABILIZATIONSTATUS_OUTERLOOP_ATTITUDE: rateDesiredAxis[t] = pid_apply(&stabSettings.outerPids[t], local_error[t], dT); break; @@ -167,11 +166,11 @@ static void stabilizationOuterloopTask() stickinput[0] = boundf(stabilizationDesiredAxis[0] / stabSettings.stabBank.RollMax, -1.0f, 1.0f); stickinput[1] = boundf(stabilizationDesiredAxis[1] / stabSettings.stabBank.PitchMax, -1.0f, 1.0f); stickinput[2] = boundf(stabilizationDesiredAxis[2] / stabSettings.stabBank.YawMax, -1.0f, 1.0f); - float rateDesiredAxisRate = stickinput[t] * cast_struct_to_array(stabSettings.stabBank.ManualRate, stabSettings.stabBank.ManualRate.Roll)[t]; + float rateDesiredAxisRate = stickinput[t] * StabilizationBankManualRateToArray(stabSettings.stabBank.ManualRate)[t]; // limit corrective rate to maximum rates to not give it overly large impact over manual rate when joined together rateDesiredAxis[t] = boundf(pid_apply(&stabSettings.outerPids[t], local_error[t], dT), - -cast_struct_to_array(stabSettings.stabBank.ManualRate, stabSettings.stabBank.ManualRate.Roll)[t], - cast_struct_to_array(stabSettings.stabBank.ManualRate, stabSettings.stabBank.ManualRate.Roll)[t] + -StabilizationBankManualRateToArray(stabSettings.stabBank.ManualRate)[t], + StabilizationBankManualRateToArray(stabSettings.stabBank.ManualRate)[t] ); // Compute the weighted average rate desired // Using max() rather than sqrt() for cpu speed; @@ -232,7 +231,7 @@ static void stabilizationOuterloopTask() stickinput[0] = boundf(stabilizationDesiredAxis[0] / stabSettings.stabBank.RollMax, -1.0f, 1.0f); stickinput[1] = boundf(stabilizationDesiredAxis[1] / stabSettings.stabBank.PitchMax, -1.0f, 1.0f); stickinput[2] = boundf(stabilizationDesiredAxis[2] / stabSettings.stabBank.YawMax, -1.0f, 1.0f); - float rate_input = stickinput[t] * cast_struct_to_array(stabSettings.stabBank.ManualRate, stabSettings.stabBank.ManualRate.Roll)[t]; + float rate_input = stickinput[t] * StabilizationBankManualRateToArray(stabSettings.stabBank.ManualRate)[t]; float weak_leveling = local_error[t] * stabSettings.settings.WeakLevelingKp; weak_leveling = boundf(weak_leveling, -stabSettings.settings.MaxWeakLevelingRate, stabSettings.settings.MaxWeakLevelingRate); @@ -246,7 +245,7 @@ static void stabilizationOuterloopTask() break; } } else { - switch (cast_struct_to_array(enabled, enabled.Roll)[t]) { + switch (StabilizationStatusOuterLoopToArray(enabled)[t]) { #ifdef REVOLUTION case STABILIZATIONSTATUS_OUTERLOOP_ALTITUDE: rateDesiredAxis[t] = stabilizationAltitudeHold(stabilizationDesiredAxis[t], ALTITUDEHOLD, reinit); @@ -286,10 +285,10 @@ static void stabilizationOuterloopTask() static void AttitudeStateUpdatedCb(__attribute__((unused)) UAVObjEvent *ev) { - // to reduce CPU utilisation, outer loop is not executed every state update - static uint8_t cpusafer = 0; + // to reduce CPU utilization, outer loop is not executed on every state update + static uint8_t cpusaver = 0; - if ((cpusafer++ % OUTERLOOP_SKIPCOUNT) == 0) { + if ((cpusaver++ % OUTERLOOP_SKIPCOUNT) == 0) { // this does not need mutex protection as both eventdispatcher and stabi run in same callback task! AttitudeStateGet(&attitude); PIOS_CALLBACKSCHEDULER_Dispatch(callbackHandle); diff --git a/flight/modules/Stabilization/relay_tuning.c b/flight/modules/Stabilization/relay_tuning.c index 316340f1b..d4e4c8320 100644 --- a/flight/modules/Stabilization/relay_tuning.c +++ b/flight/modules/Stabilization/relay_tuning.c @@ -32,7 +32,6 @@ */ #include "openpilot.h" -#include #include "stabilization.h" #include "relaytuning.h" #include "relaytuningsettings.h" @@ -72,8 +71,8 @@ int stabilization_relay_rate(float error, float *output, int axis, bool reinit) // On first run initialize estimates to something reasonable if (reinit) { rateRelayRunning[axis] = false; - cast_struct_to_array(relay.Period, relay.Period.Roll)[axis] = 200; - cast_struct_to_array(relay.Gain, relay.Gain.Roll)[axis] = 0; + RelayTuningPeriodToArray(relay.Period)[axis] = 200; + RelayTuningGainToArray(relay.Gain)[axis] = 0; accum_sin = 0; accum_cos = 0; @@ -96,14 +95,14 @@ int stabilization_relay_rate(float error, float *output, int axis, bool reinit) /**** The code below here is to estimate the properties of the oscillation ****/ // Make sure the period can't go below limit - if (cast_struct_to_array(relay.Period, relay.Period.Roll)[axis] < DEGLITCH_TIME) { - cast_struct_to_array(relay.Period, relay.Period.Roll)[axis] = DEGLITCH_TIME; + if (RelayTuningPeriodToArray(relay.Period)[axis] < DEGLITCH_TIME) { + RelayTuningPeriodToArray(relay.Period)[axis] = DEGLITCH_TIME; } // Project the error onto a sine and cosine of the same frequency // to accumulate the average amplitude int32_t dT = thisTime - lastHighTime; - float phase = ((float)360 * (float)dT) / cast_struct_to_array(relay.Period, relay.Period.Roll)[axis]; + float phase = ((float)360 * (float)dT) / RelayTuningPeriodToArray(relay.Period)[axis]; if (phase >= 360) { phase = 0; } @@ -126,15 +125,15 @@ int stabilization_relay_rate(float error, float *output, int axis, bool reinit) if (rateRelayRunning[axis] == false) { rateRelayRunning[axis] = true; - cast_struct_to_array(relay.Period, relay.Period.Roll)[axis] = 200; - cast_struct_to_array(relay.Gain, relay.Gain.Roll)[axis] = 0; + RelayTuningPeriodToArray(relay.Period)[axis] = 200; + RelayTuningGainToArray(relay.Gain)[axis] = 0; } else { // Low pass filter each amplitude and period - cast_struct_to_array(relay.Gain, relay.Gain.Roll)[axis] = - cast_struct_to_array(relay.Gain, relay.Gain.Roll)[axis] * + RelayTuningGainToArray(relay.Gain)[axis] = + RelayTuningGainToArray(relay.Gain)[axis] * AMPLITUDE_ALPHA + this_gain * (1 - AMPLITUDE_ALPHA); - cast_struct_to_array(relay.Period, relay.Period.Roll)[axis] = - cast_struct_to_array(relay.Period, relay.Period.Roll)[axis] * + RelayTuningPeriodToArray(relay.Period)[axis] = + RelayTuningPeriodToArray(relay.Period)[axis] * PERIOD_ALPHA + dT * (1 - PERIOD_ALPHA); } lastHighTime = thisTime; diff --git a/flight/modules/Stabilization/stabilization.c b/flight/modules/Stabilization/stabilization.c index 92b9081d0..202a5c89f 100644 --- a/flight/modules/Stabilization/stabilization.c +++ b/flight/modules/Stabilization/stabilization.c @@ -33,7 +33,6 @@ #include -#include #include #include #include @@ -134,54 +133,54 @@ static void StabilizationDesiredUpdatedCb(__attribute__((unused)) UAVObjEvent *e StabilizationDesiredStabilizationModeGet(&mode); for (t = 0; t < AXES; t++) { - switch (cast_struct_to_array(mode, mode.Roll)[t]) { + switch (StabilizationDesiredStabilizationModeToArray(mode)[t]) { case STABILIZATIONDESIRED_STABILIZATIONMODE_MANUAL: - cast_struct_to_array(status.OuterLoop, status.OuterLoop.Roll)[t] = STABILIZATIONSTATUS_OUTERLOOP_DIRECT; - cast_struct_to_array(status.InnerLoop, status.InnerLoop.Roll)[t] = STABILIZATIONSTATUS_INNERLOOP_DIRECT; + StabilizationStatusOuterLoopToArray(status.OuterLoop)[t] = STABILIZATIONSTATUS_OUTERLOOP_DIRECT; + StabilizationStatusInnerLoopToArray(status.InnerLoop)[t] = STABILIZATIONSTATUS_INNERLOOP_DIRECT; break; case STABILIZATIONDESIRED_STABILIZATIONMODE_RATE: - cast_struct_to_array(status.OuterLoop, status.OuterLoop.Roll)[t] = STABILIZATIONSTATUS_OUTERLOOP_DIRECT; - cast_struct_to_array(status.InnerLoop, status.InnerLoop.Roll)[t] = STABILIZATIONSTATUS_INNERLOOP_RATE; + StabilizationStatusOuterLoopToArray(status.OuterLoop)[t] = STABILIZATIONSTATUS_OUTERLOOP_DIRECT; + StabilizationStatusInnerLoopToArray(status.InnerLoop)[t] = STABILIZATIONSTATUS_INNERLOOP_RATE; break; case STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE: - cast_struct_to_array(status.OuterLoop, status.OuterLoop.Roll)[t] = STABILIZATIONSTATUS_OUTERLOOP_ATTITUDE; - cast_struct_to_array(status.InnerLoop, status.InnerLoop.Roll)[t] = STABILIZATIONSTATUS_INNERLOOP_RATE; + StabilizationStatusOuterLoopToArray(status.OuterLoop)[t] = STABILIZATIONSTATUS_OUTERLOOP_ATTITUDE; + StabilizationStatusInnerLoopToArray(status.InnerLoop)[t] = STABILIZATIONSTATUS_INNERLOOP_RATE; break; case STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK: - cast_struct_to_array(status.OuterLoop, status.OuterLoop.Roll)[t] = STABILIZATIONSTATUS_OUTERLOOP_DIRECT; - cast_struct_to_array(status.InnerLoop, status.InnerLoop.Roll)[t] = STABILIZATIONSTATUS_INNERLOOP_AXISLOCK; + StabilizationStatusOuterLoopToArray(status.OuterLoop)[t] = STABILIZATIONSTATUS_OUTERLOOP_DIRECT; + StabilizationStatusInnerLoopToArray(status.InnerLoop)[t] = STABILIZATIONSTATUS_INNERLOOP_AXISLOCK; break; case STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING: - cast_struct_to_array(status.OuterLoop, status.OuterLoop.Roll)[t] = STABILIZATIONSTATUS_OUTERLOOP_WEAKLEVELING; - cast_struct_to_array(status.InnerLoop, status.InnerLoop.Roll)[t] = STABILIZATIONSTATUS_INNERLOOP_RATE; + StabilizationStatusOuterLoopToArray(status.OuterLoop)[t] = STABILIZATIONSTATUS_OUTERLOOP_WEAKLEVELING; + StabilizationStatusInnerLoopToArray(status.InnerLoop)[t] = STABILIZATIONSTATUS_INNERLOOP_RATE; break; case STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR: - cast_struct_to_array(status.OuterLoop, status.OuterLoop.Roll)[t] = STABILIZATIONSTATUS_OUTERLOOP_DIRECT; - cast_struct_to_array(status.InnerLoop, status.InnerLoop.Roll)[t] = STABILIZATIONSTATUS_INNERLOOP_VIRTUALFLYBAR; + StabilizationStatusOuterLoopToArray(status.OuterLoop)[t] = STABILIZATIONSTATUS_OUTERLOOP_DIRECT; + StabilizationStatusInnerLoopToArray(status.InnerLoop)[t] = STABILIZATIONSTATUS_INNERLOOP_VIRTUALFLYBAR; break; case STABILIZATIONDESIRED_STABILIZATIONMODE_RATTITUDE: - cast_struct_to_array(status.OuterLoop, status.OuterLoop.Roll)[t] = STABILIZATIONSTATUS_OUTERLOOP_RATTITUDE; - cast_struct_to_array(status.InnerLoop, status.InnerLoop.Roll)[t] = STABILIZATIONSTATUS_INNERLOOP_RATE; + StabilizationStatusOuterLoopToArray(status.OuterLoop)[t] = STABILIZATIONSTATUS_OUTERLOOP_RATTITUDE; + StabilizationStatusInnerLoopToArray(status.InnerLoop)[t] = STABILIZATIONSTATUS_INNERLOOP_RATE; break; case STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYRATE: - cast_struct_to_array(status.OuterLoop, status.OuterLoop.Roll)[t] = STABILIZATIONSTATUS_OUTERLOOP_DIRECT; - cast_struct_to_array(status.InnerLoop, status.InnerLoop.Roll)[t] = STABILIZATIONSTATUS_INNERLOOP_RELAYTUNING; + StabilizationStatusOuterLoopToArray(status.OuterLoop)[t] = STABILIZATIONSTATUS_OUTERLOOP_DIRECT; + StabilizationStatusInnerLoopToArray(status.InnerLoop)[t] = STABILIZATIONSTATUS_INNERLOOP_RELAYTUNING; break; case STABILIZATIONDESIRED_STABILIZATIONMODE_RELAYATTITUDE: - cast_struct_to_array(status.OuterLoop, status.OuterLoop.Roll)[t] = STABILIZATIONSTATUS_OUTERLOOP_ATTITUDE; - cast_struct_to_array(status.InnerLoop, status.InnerLoop.Roll)[t] = STABILIZATIONSTATUS_INNERLOOP_RELAYTUNING; + StabilizationStatusOuterLoopToArray(status.OuterLoop)[t] = STABILIZATIONSTATUS_OUTERLOOP_ATTITUDE; + StabilizationStatusInnerLoopToArray(status.InnerLoop)[t] = STABILIZATIONSTATUS_INNERLOOP_RELAYTUNING; break; case STABILIZATIONDESIRED_STABILIZATIONMODE_ALTITUDEHOLD: - cast_struct_to_array(status.OuterLoop, status.OuterLoop.Roll)[t] = STABILIZATIONSTATUS_OUTERLOOP_ALTITUDE; - cast_struct_to_array(status.InnerLoop, status.InnerLoop.Roll)[t] = STABILIZATIONSTATUS_INNERLOOP_CRUISECONTROL; + StabilizationStatusOuterLoopToArray(status.OuterLoop)[t] = STABILIZATIONSTATUS_OUTERLOOP_ALTITUDE; + StabilizationStatusInnerLoopToArray(status.InnerLoop)[t] = STABILIZATIONSTATUS_INNERLOOP_CRUISECONTROL; break; case STABILIZATIONDESIRED_STABILIZATIONMODE_ALTITUDEVARIO: - cast_struct_to_array(status.OuterLoop, status.OuterLoop.Roll)[t] = STABILIZATIONSTATUS_OUTERLOOP_ALTITUDEVARIO; - cast_struct_to_array(status.InnerLoop, status.InnerLoop.Roll)[t] = STABILIZATIONSTATUS_INNERLOOP_CRUISECONTROL; + StabilizationStatusOuterLoopToArray(status.OuterLoop)[t] = STABILIZATIONSTATUS_OUTERLOOP_ALTITUDEVARIO; + StabilizationStatusInnerLoopToArray(status.InnerLoop)[t] = STABILIZATIONSTATUS_INNERLOOP_CRUISECONTROL; break; case STABILIZATIONDESIRED_STABILIZATIONMODE_CRUISECONTROL: - cast_struct_to_array(status.OuterLoop, status.OuterLoop.Roll)[t] = STABILIZATIONSTATUS_OUTERLOOP_DIRECT; - cast_struct_to_array(status.InnerLoop, status.InnerLoop.Roll)[t] = STABILIZATIONSTATUS_INNERLOOP_CRUISECONTROL; + StabilizationStatusOuterLoopToArray(status.OuterLoop)[t] = STABILIZATIONSTATUS_OUTERLOOP_DIRECT; + StabilizationStatusInnerLoopToArray(status.InnerLoop)[t] = STABILIZATIONSTATUS_INNERLOOP_CRUISECONTROL; break; } } diff --git a/flight/modules/Stabilization/virtualflybar.c b/flight/modules/Stabilization/virtualflybar.c index cc1a284f1..a815fe034 100644 --- a/flight/modules/Stabilization/virtualflybar.c +++ b/flight/modules/Stabilization/virtualflybar.c @@ -32,7 +32,6 @@ #include "openpilot.h" #include -#include #include "stabilization.h" #include "stabilizationsettings.h" @@ -78,7 +77,7 @@ int stabilization_virtual_flybar(float gyro, float command, float *output, float } // Command signal is composed of stick input added to the gyro and virtual flybar - *output = command * cast_struct_to_array(settings->VbarSensitivity, settings->VbarSensitivity.Roll)[axis] - + *output = command * StabilizationSettingsVbarSensitivityToArray(settings->VbarSensitivity)[axis] - gyro_gain * (vbar_integral[axis] * ki + gyro * kp); return 0; diff --git a/flight/modules/StateEstimation/filterekf.c b/flight/modules/StateEstimation/filterekf.c index 320a9ef35..3931226e4 100644 --- a/flight/modules/StateEstimation/filterekf.c +++ b/flight/modules/StateEstimation/filterekf.c @@ -31,7 +31,6 @@ */ #include "inc/stateestimation.h" -#include #include #include @@ -165,17 +164,17 @@ static int32_t maininit(stateFilter *self) int t; // plausibility check for (t = 0; t < EKFCONFIGURATION_P_NUMELEM; t++) { - if (invalid_var(cast_struct_to_array(this->ekfConfiguration.P, this->ekfConfiguration.P.AttitudeQ1)[t])) { + if (invalid_var(EKFConfigurationPToArray(this->ekfConfiguration.P)[t])) { return 2; } } for (t = 0; t < EKFCONFIGURATION_Q_NUMELEM; t++) { - if (invalid_var(cast_struct_to_array(this->ekfConfiguration.Q, this->ekfConfiguration.Q.AccelX)[t])) { + if (invalid_var(EKFConfigurationQToArray(this->ekfConfiguration.Q)[t])) { return 2; } } for (t = 0; t < EKFCONFIGURATION_R_NUMELEM; t++) { - if (invalid_var(cast_struct_to_array(this->ekfConfiguration.R, this->ekfConfiguration.R.BaroZ)[t])) { + if (invalid_var(EKFConfigurationRToArray(this->ekfConfiguration.R)[t])) { return 2; } } @@ -295,7 +294,7 @@ static filterResult filter(stateFilter *self, stateEstimation *state) INSSetState(this->work.pos, (float *)zeros, this->work.attitude, (float *)zeros, (float *)zeros); - INSResetP(cast_struct_to_array(this->ekfConfiguration.P, this->ekfConfiguration.P.AttitudeQ1)); + INSResetP(EKFConfigurationPToArray(this->ekfConfiguration.P)); } else { // Run prediction a bit before any corrections @@ -422,12 +421,12 @@ static filterResult filter(stateFilter *self, stateEstimation *state) EKFStateVarianceData vardata; EKFStateVarianceGet(&vardata); - INSGetP(cast_struct_to_array(vardata.P, vardata.P.AttitudeQ1)); + INSGetP(EKFStateVariancePToArray(vardata.P)); EKFStateVarianceSet(&vardata); int t; for (t = 0; t < EKFSTATEVARIANCE_P_NUMELEM; t++) { - if (!IS_REAL(cast_struct_to_array(vardata.P, vardata.P.AttitudeQ1)[t]) || cast_struct_to_array(vardata.P, vardata.P.AttitudeQ1)[t] <= 0.0f) { - INSResetP(cast_struct_to_array(this->ekfConfiguration.P, this->ekfConfiguration.P.AttitudeQ1)); + if (!IS_REAL(EKFStateVariancePToArray(vardata.P)[t]) || EKFStateVariancePToArray(vardata.P)[t] <= 0.0f) { + INSResetP(EKFConfigurationPToArray(this->ekfConfiguration.P)); this->init_stage = -1; break; } diff --git a/flight/modules/System/systemmod.c b/flight/modules/System/systemmod.c index aa6a8f54d..97ff55f3d 100644 --- a/flight/modules/System/systemmod.c +++ b/flight/modules/System/systemmod.c @@ -39,7 +39,6 @@ */ #include -#include // private includes #include "inc/systemmod.h" #include "notification.h" @@ -420,9 +419,9 @@ static void taskMonitorForEachCallback(uint16_t task_id, const struct pios_task_ // By convention, there is a direct mapping between task monitor task_id's and members // of the TaskInfoXXXXElem enums PIOS_DEBUG_Assert(task_id < TASKINFO_RUNNING_NUMELEM); - cast_struct_to_array(taskData->Running, taskData->Running.System)[task_id] = task_info->is_running ? TASKINFO_RUNNING_TRUE : TASKINFO_RUNNING_FALSE; - ((uint16_t *)&taskData->StackRemaining)[task_id] = task_info->stack_remaining; - ((uint8_t *)&taskData->RunningTime)[task_id] = task_info->running_time_percentage; + TaskInfoRunningToArray(taskData->Running)[task_id] = task_info->is_running ? TASKINFO_RUNNING_TRUE : TASKINFO_RUNNING_FALSE; + ((uint16_t *)&taskData->StackRemaining)[task_id] = task_info->stack_remaining; + ((uint8_t *)&taskData->RunningTime)[task_id] = task_info->running_time_percentage; } static void callbackSchedulerForEachCallback(int16_t callback_id, const struct pios_callback_info *callback_info, void *context) diff --git a/flight/modules/TxPID/txpid.c b/flight/modules/TxPID/txpid.c index 20670ae1b..a1e5fd995 100644 --- a/flight/modules/TxPID/txpid.c +++ b/flight/modules/TxPID/txpid.c @@ -51,7 +51,6 @@ */ #include "openpilot.h" -#include #include "txpidsettings.h" #include "accessorydesired.h" #include "manualcontrolcommand.h" @@ -195,26 +194,26 @@ static void updatePIDs(UAVObjEvent *ev) // Loop through every enabled instance for (uint8_t i = 0; i < TXPIDSETTINGS_PIDS_NUMELEM; i++) { - if (cast_struct_to_array(inst.PIDs, inst.PIDs.Instance1)[i] != TXPIDSETTINGS_PIDS_DISABLED) { + if (TxPIDSettingsPIDsToArray(inst.PIDs)[i] != TXPIDSETTINGS_PIDS_DISABLED) { float value; - if (cast_struct_to_array(inst.Inputs, inst.Inputs.Instance1)[i] == TXPIDSETTINGS_INPUTS_THROTTLE) { + if (TxPIDSettingsInputsToArray(inst.Inputs)[i] == TXPIDSETTINGS_INPUTS_THROTTLE) { ManualControlCommandThrottleGet(&value); value = scale(value, inst.ThrottleRange.Min, inst.ThrottleRange.Max, - cast_struct_to_array(inst.MinPID, inst.MinPID.Instance1)[i], - cast_struct_to_array(inst.MaxPID, inst.MaxPID.Instance1)[i]); + TxPIDSettingsMinPIDToArray(inst.MinPID)[i], + TxPIDSettingsMaxPIDToArray(inst.MaxPID)[i]); } else if (AccessoryDesiredInstGet( - cast_struct_to_array(inst.Inputs, inst.Inputs.Instance1)[i] - TXPIDSETTINGS_INPUTS_ACCESSORY0, + TxPIDSettingsInputsToArray(inst.Inputs)[i] - TXPIDSETTINGS_INPUTS_ACCESSORY0, &accessory) == 0) { value = scale(accessory.AccessoryVal, -1.0f, 1.0f, - cast_struct_to_array(inst.MinPID, inst.MinPID.Instance1)[i], - cast_struct_to_array(inst.MaxPID, inst.MaxPID.Instance1)[i]); + TxPIDSettingsMinPIDToArray(inst.MinPID)[i], + TxPIDSettingsMaxPIDToArray(inst.MaxPID)[i]); } else { continue; } - switch (cast_struct_to_array(inst.PIDs, inst.PIDs.Instance1)[i]) { + switch (TxPIDSettingsPIDsToArray(inst.PIDs)[i]) { case TXPIDSETTINGS_PIDS_ROLLRATEKP: needsUpdateBank |= update(&bank.RollRatePID.Kp, value); break; diff --git a/flight/pios/common/pios_sbus.c b/flight/pios/common/pios_sbus.c index 640ddb748..69089e9cd 100644 --- a/flight/pios/common/pios_sbus.c +++ b/flight/pios/common/pios_sbus.c @@ -250,7 +250,7 @@ static void PIOS_SBus_UpdateState(struct pios_sbus_state *state, uint8_t b) state->received_data[state->byte_count - 1] = b; state->byte_count++; } else { - if (b == SBUS_EOF_BYTE || (b % SBUS_R7008SB_EOF_COUNTER_MASK) == SBUS_R7008SB_EOF_BYTE) { + if (b == SBUS_EOF_BYTE || (b & SBUS_R7008SB_EOF_COUNTER_MASK) == 0) { /* full frame received */ uint8_t flags = state->received_data[SBUS_FRAME_LENGTH - 3]; if (flags & SBUS_FLAG_FL) { diff --git a/flight/pios/inc/pios_sbus_priv.h b/flight/pios/inc/pios_sbus_priv.h index 5f104e25f..791683831 100644 --- a/flight/pios/inc/pios_sbus_priv.h +++ b/flight/pios/inc/pios_sbus_priv.h @@ -66,8 +66,7 @@ #define SBUS_FLAG_FL 0x04 #define SBUS_FLAG_FS 0x08 -#define SBUS_R7008SB_EOF_COUNTER_MASK 0xCF -#define SBUS_R7008SB_EOF_BYTE 0x04 +#define SBUS_R7008SB_EOF_COUNTER_MASK 0xCB /* * S.Bus protocol provides 16 proportional and 2 discrete channels. diff --git a/flight/pios/inc/pios_struct_helper.h b/flight/pios/inc/pios_struct_helper.h index 65bae405a..1198b6fb1 100644 --- a/flight/pios/inc/pios_struct_helper.h +++ b/flight/pios/inc/pios_struct_helper.h @@ -17,13 +17,4 @@ (type *)((char *)__mptr - offsetof(type, member)); } \ ) -/** - * cast_struct_to_array casts an homogeneous structure instance to an array - * of typeof(struct_field). struct_field need to be any of the fields - * containing inside the struct - * @instance: homogeneous structure to cast - * @struct_field: a field contained inside the structure - */ -#define cast_struct_to_array(instance, struct_field) \ - ((typeof(struct_field) *) & (instance)) #endif /* PIOS_STRUCT_HELPER_H */ diff --git a/flight/uavobjects/inc/uavobjectmanager.h b/flight/uavobjects/inc/uavobjectmanager.h index bbd3fc5b7..442c59cb5 100644 --- a/flight/uavobjects/inc/uavobjectmanager.h +++ b/flight/uavobjects/inc/uavobjectmanager.h @@ -51,6 +51,43 @@ typedef void *UAVObjHandle; #define MetaObjectId(id) ((id) + 1) +/** + * helper macro to access multi-element fields as array + */ +#define UAVObjectFieldToArray(type, var) \ + (*({ type *const dummy = &(var); \ + &(((type##Array *)dummy)->array); } \ + )) + +// we have limited trust in our compiler +// make sure this macro actually works on all platforms + +typedef struct __attribute__((__packed__)) { + uint16_t element1; + uint16_t element2; + uint16_t element3; +} +__DummyUAVObjectFieldData; + +typedef struct __attribute__((__packed__)) { + uint16_t array[3]; +} +__DummyUAVObjectFieldDataArray; + +#define __DummyTA(var) UAVObjectFieldToArray(__DummyUAVObjectFieldData, var) + +__attribute__((unused)) static void __DummyTAtest(void) +{ + __DummyUAVObjectFieldData t; + + PIOS_STATIC_ASSERT(sizeof(t) == sizeof(__DummyTA(t))); + PIOS_STATIC_ASSERT(sizeof(t.element1) == sizeof(__DummyTA(t)[0])); + PIOS_STATIC_ASSERT((void *)&t == (void *)&__DummyTA(t)); + PIOS_STATIC_ASSERT((void *)&t.element1 == (void *)&__DummyTA(t)[0]); + PIOS_STATIC_ASSERT((void *)&t.element2 == (void *)&__DummyTA(t)[1]); + PIOS_STATIC_ASSERT((void *)&t.element3 == (void *)&__DummyTA(t)[2]); +} + /** * Object update mode, used by multiple modules (e.g. telemetry and logger) */ diff --git a/ground/openpilotgcs/openpilotgcs.pri b/ground/openpilotgcs/openpilotgcs.pri index 66315baf6..577e44db9 100644 --- a/ground/openpilotgcs/openpilotgcs.pri +++ b/ground/openpilotgcs/openpilotgcs.pri @@ -97,7 +97,8 @@ macx { GCS_QT_PLUGINS_PATH = $$GCS_BUILD_TREE/$$GCS_LIBRARY_BASENAME/qt5/plugins GCS_QT_QML_PATH = $$GCS_BUILD_TREE/$$GCS_LIBRARY_BASENAME/qt5/qml - TOOLS_DIR = $$clean_path($$GCS_SOURCE_TREE/../../tools) + TOOLS_DIR = $$(OPENPILOT_TOOLS_DIR) + isEmpty(TOOLS_DIR):TOOLS_DIR = $$clean_path($$GCS_SOURCE_TREE/../../tools) QT_INSTALL_DIR = $$clean_path($$[QT_INSTALL_LIBS]/../../../..) equals(QT_INSTALL_DIR, $$TOOLS_DIR) { copyqt = 1 diff --git a/ground/openpilotgcs/share/openpilotgcs/default_configurations/OpenPilotGCS.xml b/ground/openpilotgcs/share/openpilotgcs/default_configurations/OpenPilotGCS.xml index 88032dc41..031abd755 100644 --- a/ground/openpilotgcs/share/openpilotgcs/default_configurations/OpenPilotGCS.xml +++ b/ground/openpilotgcs/share/openpilotgcs/default_configurations/OpenPilotGCS.xml @@ -1779,7 +1779,7 @@ false mapquad.png true - true + false @@ -1799,7 +1799,7 @@ false airplanepip.png true - true + false @@ -1819,7 +1819,7 @@ false mapquad.png true - true + false @@ -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/sdlgamepad/sdlgamepad.pro.user b/ground/openpilotgcs/src/libs/sdlgamepad/sdlgamepad.pro.user deleted file mode 100644 index 96217e1ea..000000000 --- a/ground/openpilotgcs/src/libs/sdlgamepad/sdlgamepad.pro.user +++ /dev/null @@ -1,112 +0,0 @@ - - - - ProjectExplorer.Project.ActiveTarget - 0 - - - ProjectExplorer.Project.EditorSettings - - System - - - - ProjectExplorer.Project.Target.0 - - Desktop - Qt4ProjectManager.Target.DesktopTarget - 0 - 0 - - - qmake - QtProjectManager.QMakeBuildStep - - - - Make - Qt4ProjectManager.MakeStep - false - - - - 2 - - Make - Qt4ProjectManager.MakeStep - true - - clean - - - - 1 - false - - Debug - Qt4ProjectManager.Qt4BuildConfiguration - 2 - /Users/jcotton81/Documents/Programming/OpenPilot/ground/src/plugins/gcscontrol/sdlgamepad-build-desktop - 2 - 0 - true - - - - qmake - QtProjectManager.QMakeBuildStep - - - - Make - Qt4ProjectManager.MakeStep - false - - - - 2 - - Make - Qt4ProjectManager.MakeStep - true - - clean - - - - 1 - false - - Release - Qt4ProjectManager.Qt4BuildConfiguration - 0 - /Users/jcotton81/Documents/Programming/OpenPilot/ground/src/plugins/gcscontrol/sdlgamepad-build-desktop - 2 - 0 - true - - 2 - - - 2 - - false - - - false - $BUILDDIR - Custom Executable - ProjectExplorer.CustomExecutableRunConfiguration - - 1 - - - - ProjectExplorer.Project.TargetCount - 1 - - - ProjectExplorer.Project.Updater.FileVersion - 4 - - 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 8216ca7d3..e1189d79d 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); @@ -468,26 +396,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 == "HexaCoax") { // Motors 1/2/3 4/5/6 are: NW/W NE/E S/SE setComboCurrentIndex(m_aircraft->multiMotorChannelBox1, multi.VTOLMotorNW); @@ -496,22 +404,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 +414,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 +424,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 +434,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 +703,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 +784,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 +1004,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/config/configoutputwidget.cpp b/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp index c06d28e5b..3cd43c4a3 100644 --- a/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configoutputwidget.cpp @@ -126,6 +126,17 @@ void ConfigOutputWidget::enableControls(bool enable) ui->channelOutTest->setEnabled(enable); } +/** + Force update all channels with the values in the OutputChannelForms. + */ +void ConfigOutputWidget::sendAllChannelTests() +{ + for (unsigned int i = 0; i < ActuatorCommand::CHANNEL_NUMELEM; i++) { + OutputChannelForm *form = getOutputChannelForm(i); + sendChannelTest(i, form->neutral()); + } +} + /** Toggles the channel testing mode by making the GCS take over the ActuatorCommand objects @@ -178,6 +189,11 @@ void ConfigOutputWidget::runChannelTests(bool state) } obj->setMetadata(mdata); obj->updated(); + + // Setup the correct initial channel values when the channel testing mode is turned on. + if (state) { + sendAllChannelTests(); + } } OutputChannelForm *ConfigOutputWidget::getOutputChannelForm(const int index) const diff --git a/ground/openpilotgcs/src/plugins/config/configoutputwidget.h b/ground/openpilotgcs/src/plugins/config/configoutputwidget.h index fda2922c6..3105b25d9 100644 --- a/ground/openpilotgcs/src/plugins/config/configoutputwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configoutputwidget.h @@ -58,7 +58,11 @@ private: void updateChannelInSlider(QSlider *slider, QLabel *min, QLabel *max, QCheckBox *rev, int value); void assignOutputChannel(UAVDataObject *obj, QString &str); + OutputChannelForm *getOutputChannelForm(const int index) const; + + void sendAllChannelTests(); + int mccDataRate; UAVObject::Metadata accInitialData; diff --git a/ground/openpilotgcs/src/plugins/config/configrevohwwidget.cpp b/ground/openpilotgcs/src/plugins/config/configrevohwwidget.cpp index d7e947216..902716058 100644 --- a/ground/openpilotgcs/src/plugins/config/configrevohwwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configrevohwwidget.cpp @@ -123,15 +123,6 @@ void ConfigRevoHWWidget::updateObjectsFromWidgets() data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = HwSettings::OPTIONALMODULES_DISABLED; } - // If any port is configured to be ComBridge port, enable UsbComBridge module if it is not enabled. - // Otherwise disable UsbComBridge module. - if (m_ui->cbFlexi->currentIndex() == HwSettings::RM_FLEXIPORT_COMBRIDGE || m_ui->cbMain->currentIndex() == HwSettings::RM_MAINPORT_COMBRIDGE || - m_ui->cbUSBVCPFunction->currentIndex() == HwSettings::USB_VCPPORT_COMBRIDGE) { - data.OptionalModules[HwSettings::OPTIONALMODULES_COMUSBBRIDGE] = HwSettings::OPTIONALMODULES_ENABLED; - } else { - data.OptionalModules[HwSettings::OPTIONALMODULES_COMUSBBRIDGE] = HwSettings::OPTIONALMODULES_DISABLED; - } - hwSettings->setData(data); } diff --git a/ground/openpilotgcs/src/plugins/config/inputchannelform.ui b/ground/openpilotgcs/src/plugins/config/inputchannelform.ui index 2f4db720c..0a3fc987e 100644 --- a/ground/openpilotgcs/src/plugins/config/inputchannelform.ui +++ b/ground/openpilotgcs/src/plugins/config/inputchannelform.ui @@ -120,6 +120,9 @@ margin:1px; QAbstractSpinBox::UpDownArrows + + false + 9999 @@ -670,6 +673,9 @@ margin:1px; QAbstractSpinBox::UpDownArrows + + false + 9999 @@ -762,6 +768,9 @@ margin:1px; Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + false + 9999 diff --git a/ground/openpilotgcs/src/plugins/logging/loggingplugin.cpp b/ground/openpilotgcs/src/plugins/logging/loggingplugin.cpp index 749038014..e6238b87f 100644 --- a/ground/openpilotgcs/src/plugins/logging/loggingplugin.cpp +++ b/ground/openpilotgcs/src/plugins/logging/loggingplugin.cpp @@ -76,8 +76,10 @@ QIODevice *LoggingConnection::openDevice(const QString &deviceName) QString fileName = QFileDialog::getOpenFileName(NULL, tr("Open file"), QString(""), tr("OpenPilot Log (*.opl)")); if (!fileName.isNull()) { startReplay(fileName); + return &logFile; } - return &logFile; + + return NULL; } void LoggingConnection::startReplay(QString file) 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 119d58120..4fd26406e 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -37,6 +37,7 @@ #include "stabilizationsettings.h" #include "revocalibration.h" #include "accelgyrosettings.h" +#include const qint16 VehicleConfigurationHelper::LEGACY_ESC_FREQUENCE = 50; const qint16 VehicleConfigurationHelper::RAPID_ESC_FREQUENCE = 400; @@ -440,9 +441,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 @@ -1014,7 +1085,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 1ed1aa576..307dd917a 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h @@ -66,7 +66,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/ground/openpilotgcs/src/plugins/welcome/qml/main.qml b/ground/openpilotgcs/src/plugins/welcome/qml/main.qml index 7a58a8fa3..97ddb8e5d 100644 --- a/ground/openpilotgcs/src/plugins/welcome/qml/main.qml +++ b/ground/openpilotgcs/src/plugins/welcome/qml/main.qml @@ -30,10 +30,10 @@ Rectangle { anchors.horizontalCenter: parent.horizontalCenter // distribute a vertical space between the icons blocks an community widget as: // top - 48% - Icons - 27% - CommunityWidget - 25% - bottom - y: (parent.height - buttons.height - communityPanel.height) * 0.48 + y: (parent.height - buttons.height - communityPanel.height - versionInfo.height) * 0.48 width: parent.width height: 600 - spacing: (parent.height - buttons.height - communityPanel.height) * 0.1 + spacing: (parent.height - buttons.height - communityPanel.height - versionInfo.height) * 0.1 Row { //if the buttons grid overlaps vertically with the wizard buttons, @@ -109,5 +109,48 @@ Rectangle { width: Math.min(sourceSize.width, container.width) height: Math.min(450, container.height*0.5) } + + Row { + id: versionInfo + + height: 18 + anchors.horizontalCenter: parent.horizontalCenter + width: textOpVersion.width + textOpVersionAvailable.width + spacing: 16 + + Text { + id: textOpVersion + color: "#c4c0c0" + text: welcomePlugin.versionString + verticalAlignment: Text.AlignTop + anchors.left: parent.anchors.left + font.bold: true + styleColor: "#00000000" + horizontalAlignment: Text.AlignHCenter + font.pixelSize: 14 + } + Text { + id: textOpVersionAvailable + color: "#5fcf07" + text: welcomePlugin.newVersionText + anchors.rightMargin: 0 + font.bold: true + font.underline: true + styleColor: "#00000000" + horizontalAlignment: Text.AlignHCenter + font.pixelSize: 14 + anchors.left: textOpVersion.right + MouseArea{ + id: mouseAreaOpVersionAvailable + hoverEnabled: true + cursorShape: Qt.PointingHandCursor + width: parent.width + height: parent.height + onClicked: { + welcomePlugin.openUrl("http://wiki.openpilot.org/display/BUILDS/OpenPilot+Software+Downloads") + } + } + } + } } } diff --git a/ground/openpilotgcs/src/plugins/welcome/welcome_dependencies.pri b/ground/openpilotgcs/src/plugins/welcome/welcome_dependencies.pri index 7f369f632..04c4323a7 100644 --- a/ground/openpilotgcs/src/plugins/welcome/welcome_dependencies.pri +++ b/ground/openpilotgcs/src/plugins/welcome/welcome_dependencies.pri @@ -1,2 +1,3 @@ include(../../plugins/coreplugin/coreplugin.pri) include(../../libs/utils/utils.pri) +include(../../libs/version_info/version_info.pri) diff --git a/ground/openpilotgcs/src/plugins/welcome/welcomemode.cpp b/ground/openpilotgcs/src/plugins/welcome/welcomemode.cpp index 381fd226a..5fab6684e 100644 --- a/ground/openpilotgcs/src/plugins/welcome/welcomemode.cpp +++ b/ground/openpilotgcs/src/plugins/welcome/welcomemode.cpp @@ -45,6 +45,9 @@ #include #include +#include +#include + #include #include #include @@ -68,13 +71,29 @@ WelcomeModePrivate::WelcomeModePrivate() // --- WelcomeMode WelcomeMode::WelcomeMode() : m_d(new WelcomeModePrivate), - m_priority(Core::Constants::P_MODE_WELCOME) + m_priority(Core::Constants::P_MODE_WELCOME), + m_newVersionText("") { m_d->quickView = new QQuickView; m_d->quickView->setResizeMode(QQuickView::SizeRootObjectToView); m_d->quickView->engine()->rootContext()->setContextProperty("welcomePlugin", this); m_d->quickView->setSource(QUrl("qrc:/welcome/qml/main.qml")); m_container = NULL; + + QNetworkAccessManager *networkAccessManager = new QNetworkAccessManager; + + // Only attempt to request our version info if the network is accessible + if (networkAccessManager->networkAccessible() == QNetworkAccessManager::Accessible) { + connect(networkAccessManager, SIGNAL(finished(QNetworkReply *)), this, SLOT(networkResponseReady(QNetworkReply *))); + + // This will delete the network access manager instance when we're done + connect(networkAccessManager, SIGNAL(finished(QNetworkReply *)), networkAccessManager, SLOT(deleteLater())); + + networkAccessManager->get(QNetworkRequest(QUrl("http://www.openpilot.org/opver"))); + } else { + // No network, can delete this now as we don't need it. + delete networkAccessManager; + } } WelcomeMode::~WelcomeMode() @@ -135,4 +154,19 @@ void WelcomeMode::triggerAction(const QString &actionId) { Core::ModeManager::instance()->triggerAction(actionId); } + +void WelcomeMode::networkResponseReady(QNetworkReply *reply) +{ + if (reply != NULL) { + QString version(reply->readAll()); + version = version.trimmed(); + + reply->deleteLater(); + + if (version != VersionInfo::tagOrHash8()) { + m_newVersionText = tr("Update Available: %1").arg(version); + emit newVersionTextChanged(); + } + } +} } // namespace Welcome diff --git a/ground/openpilotgcs/src/plugins/welcome/welcomemode.h b/ground/openpilotgcs/src/plugins/welcome/welcomemode.h index b6e837cc9..a51cf3909 100644 --- a/ground/openpilotgcs/src/plugins/welcome/welcomemode.h +++ b/ground/openpilotgcs/src/plugins/welcome/welcomemode.h @@ -29,6 +29,7 @@ #ifndef WELCOMEMODE_H #define WELCOMEMODE_H +#include "version_info/version_info.h" #include "welcome_global.h" #include @@ -37,13 +38,15 @@ QT_BEGIN_NAMESPACE class QWidget; class QUrl; +class QNetworkReply; QT_END_NAMESPACE namespace Welcome { struct WelcomeModePrivate; class WELCOME_EXPORT WelcomeMode : public Core::IMode { - Q_OBJECT + Q_OBJECT Q_PROPERTY(QString versionString READ versionString) + Q_PROPERTY(QString newVersionText READ newVersionText NOTIFY newVersionTextChanged) public: WelcomeMode(); @@ -65,6 +68,17 @@ public: { m_priority = priority; } + QString versionString() const + { + return tr("OpenPilot GCS Version: %1 ").arg(VersionInfo::tagOrHash8()); + } + QString newVersionText() const + { + return m_newVersionText; + } + +signals: + void newVersionTextChanged(); public slots: void openUrl(const QString &url); @@ -75,6 +89,10 @@ private: QWidget *m_container; WelcomeModePrivate *m_d; int m_priority; + QString m_newVersionText; + +private slots: + void networkResponseReady(QNetworkReply *reply); }; } // namespace Welcome diff --git a/ground/uavobjgenerator/generators/flight/uavobjectgeneratorflight.cpp b/ground/uavobjgenerator/generators/flight/uavobjectgeneratorflight.cpp index 72d4c1a63..1cc41bbf7 100644 --- a/ground/uavobjgenerator/generators/flight/uavobjectgeneratorflight.cpp +++ b/ground/uavobjgenerator/generators/flight/uavobjectgeneratorflight.cpp @@ -131,7 +131,11 @@ bool UAVObjectGeneratorFlight::process_object(ObjectInfo *info) for (int f = 0; f < info->fields[n]->elementNames.count(); f++) { structType.append(QString(" %1 %2;\n").arg(type).arg(info->fields[n]->elementNames[f])); } - structType.append(QString("} %1 ;\n\n").arg(structTypeName)); + structType.append(QString("} %1 ;\n").arg(structTypeName)); + structType.append(QString("typedef struct __attribute__ ((__packed__)) {\n")); + structType.append(QString(" %1 array[%2];\n").arg(type).arg(info->fields[n]->elementNames.count())); + structType.append(QString("} %1Array ;\n").arg(structTypeName)); + structType.append(QString("#define %1%2ToArray( var ) UAVObjectFieldToArray( %3, var )\n\n").arg(info->name).arg(info->fields[n]->name).arg(structTypeName)); dataStructures.append(structType); diff --git a/shared/uavobjectdefinition/hwsettings.xml b/shared/uavobjectdefinition/hwsettings.xml index c41187009..7fa821da4 100644 --- a/shared/uavobjectdefinition/hwsettings.xml +++ b/shared/uavobjectdefinition/hwsettings.xml @@ -15,14 +15,14 @@ - + - + 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 + + + diff --git a/shared/uavobjectdefinition/stabilizationsettingsbank1.xml b/shared/uavobjectdefinition/stabilizationsettingsbank1.xml index 48a912615..7c8a71e64 100644 --- a/shared/uavobjectdefinition/stabilizationsettingsbank1.xml +++ b/shared/uavobjectdefinition/stabilizationsettingsbank1.xml @@ -2,15 +2,15 @@ Currently selected PID bank - - - - + + + + - - - + + + diff --git a/shared/uavobjectdefinition/stabilizationsettingsbank2.xml b/shared/uavobjectdefinition/stabilizationsettingsbank2.xml index 4d583c96d..75b777fa5 100644 --- a/shared/uavobjectdefinition/stabilizationsettingsbank2.xml +++ b/shared/uavobjectdefinition/stabilizationsettingsbank2.xml @@ -2,15 +2,15 @@ Currently selected PID bank - - - - + + + + - - - + + + diff --git a/shared/uavobjectdefinition/stabilizationsettingsbank3.xml b/shared/uavobjectdefinition/stabilizationsettingsbank3.xml index a2346b984..7b0d52e28 100644 --- a/shared/uavobjectdefinition/stabilizationsettingsbank3.xml +++ b/shared/uavobjectdefinition/stabilizationsettingsbank3.xml @@ -2,15 +2,15 @@ Currently selected PID bank - - - - + + + + - - - + + + diff --git a/shared/uavobjectdefinition/vtolpathfollowersettings.xml b/shared/uavobjectdefinition/vtolpathfollowersettings.xml index fec77cb55..051d125c0 100644 --- a/shared/uavobjectdefinition/vtolpathfollowersettings.xml +++ b/shared/uavobjectdefinition/vtolpathfollowersettings.xml @@ -6,7 +6,7 @@ - +