diff --git a/src/AutoPilotPlugins/APM/APMAirframeComponentController.cc b/src/AutoPilotPlugins/APM/APMAirframeComponentController.cc index 47a6422..e84640f 100644 --- a/src/AutoPilotPlugins/APM/APMAirframeComponentController.cc +++ b/src/AutoPilotPlugins/APM/APMAirframeComponentController.cc @@ -188,6 +188,11 @@ APMAirframeType *APMAirframeComponentController::currentAirframeType() const return _currentAirframeType; } +QString APMAirframeComponentController::currentAirframeTypeName() const +{ + return _vehicle->vehicleTypeName(); +} + APMAirframe *APMAirframeComponentController::currentAirframe() const { return _currentAirframe; diff --git a/src/AutoPilotPlugins/APM/APMAirframeComponentController.h b/src/AutoPilotPlugins/APM/APMAirframeComponentController.h index ef799ab..613f55d 100644 --- a/src/AutoPilotPlugins/APM/APMAirframeComponentController.h +++ b/src/AutoPilotPlugins/APM/APMAirframeComponentController.h @@ -70,6 +70,7 @@ signals: public slots: APMAirframeType *currentAirframeType() const; + Q_INVOKABLE QString currentAirframeTypeName() const; APMAirframe *currentAirframe() const; void setCurrentAirframeType(APMAirframeType *t); void setCurrentAirframe(APMAirframe *t); diff --git a/src/AutoPilotPlugins/APM/APMAirframeComponentSummary.qml b/src/AutoPilotPlugins/APM/APMAirframeComponentSummary.qml index effced4..90fed8b 100644 --- a/src/AutoPilotPlugins/APM/APMAirframeComponentSummary.qml +++ b/src/AutoPilotPlugins/APM/APMAirframeComponentSummary.qml @@ -28,11 +28,11 @@ FactPanel { VehicleSummaryRow { id: nameRow; labelText: qsTr("Frame Type:") - valueText: sysIdFact.valueString === "0" ? "Plus" + valueText: controller.currentAirframeTypeName() + " " + (sysIdFact.valueString === "0" ? "Plus" : sysIdFact.valueString === "1" ? "X" : sysIdFact.valueString === "2" ? "V" : sysIdFact.valueString == "3" ? "H" - :/* Fact.value == 10 */ "New Y6"; + : /* Fact.value == 10 */ "New Y6"); } } diff --git a/src/AutoPilotPlugins/PX4/Images/DatalinkLoss.svg b/src/AutoPilotPlugins/PX4/Images/DatalinkLoss.svg index c1ecd4c..f438790 100644 --- a/src/AutoPilotPlugins/PX4/Images/DatalinkLoss.svg +++ b/src/AutoPilotPlugins/PX4/Images/DatalinkLoss.svg @@ -1,26 +1,24 @@ + viewBox="194 896 97.2 97.4" style="enable-background:new 194 896 97.2 97.4;" xml:space="preserve"> + - - - - - + + - - + + diff --git a/src/AutoPilotPlugins/PX4/Images/DatalinkLossLight.svg b/src/AutoPilotPlugins/PX4/Images/DatalinkLossLight.svg index a24b235..4870a5c 100644 --- a/src/AutoPilotPlugins/PX4/Images/DatalinkLossLight.svg +++ b/src/AutoPilotPlugins/PX4/Images/DatalinkLossLight.svg @@ -1,23 +1,25 @@ + viewBox="194 896 97.2 97.4" style="enable-background:new 194 896 97.2 97.4;" xml:space="preserve"> - - - + + + + + - - + + diff --git a/src/AutoPilotPlugins/PX4/Images/RCLoss.svg b/src/AutoPilotPlugins/PX4/Images/RCLoss.svg index 03d38d5..bdf8225 100644 --- a/src/AutoPilotPlugins/PX4/Images/RCLoss.svg +++ b/src/AutoPilotPlugins/PX4/Images/RCLoss.svg @@ -2,8 +2,8 @@ + xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" x="0px" y="0px" viewBox="-250 452 97.2 97.2" + style="enable-background:new -250 452 97.2 97.2;" xml:space="preserve"> GPS @@ -68,15 +69,15 @@ -251.5,446.7 -264.6,446.7 "/> - - - - + + + + - - + + diff --git a/src/AutoPilotPlugins/PX4/Images/RCLossLight.svg b/src/AutoPilotPlugins/PX4/Images/RCLossLight.svg index b6f71d7..9fdae57 100644 --- a/src/AutoPilotPlugins/PX4/Images/RCLossLight.svg +++ b/src/AutoPilotPlugins/PX4/Images/RCLossLight.svg @@ -2,17 +2,18 @@ + xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" x="0px" y="0px" viewBox="-250 452 97.2 97.2" + style="enable-background:new -250 452 97.2 97.2;" xml:space="preserve"> GPS @@ -68,15 +69,15 @@ -251.5,446.7 -264.6,446.7 "/> - - - - + + + + - - + + diff --git a/src/AutoPilotPlugins/PX4/SafetyComponent.qml b/src/AutoPilotPlugins/PX4/SafetyComponent.qml index c519dff..1a3e675 100644 --- a/src/AutoPilotPlugins/PX4/SafetyComponent.qml +++ b/src/AutoPilotPlugins/PX4/SafetyComponent.qml @@ -128,7 +128,7 @@ QGCView { } Row { QGCLabel { - anchors.baseline: batLowLevelField.baseline + anchors.baseline: batCritLevelField.baseline width: _middleRowWidth text: qsTr("Battery Failsafe Level:") } diff --git a/src/FirmwarePlugin/APM/MavCmdInfoFixedWing.json b/src/FirmwarePlugin/APM/MavCmdInfoFixedWing.json index 77a8d80..c93a456 100644 --- a/src/FirmwarePlugin/APM/MavCmdInfoFixedWing.json +++ b/src/FirmwarePlugin/APM/MavCmdInfoFixedWing.json @@ -1,6 +1,167 @@ { "version": 1, - "mavCmdInfo": [ + { + "id": 16, + "rawName": "MAV_CMD_NAV_WAYPOINT", + "friendlyName": "Waypoint", + "description": "Travel to a position in 3D space.", + "specifiesCoordinate": true, + "friendlyEdit": true, + "category": "Basic", + "param1": { + "label": "Hold:", + "units": "seconds", + "default": 0, + "decimalPlaces": 0 + }, + "param7": { + "label": "Altitude:", + "units": "meters", + "default": 50, + "decimalPlaces": 0 + } + }, + { + "id": 17, + "rawName": "MAV_CMD_NAV_LOITER_UNLIM", + "friendlyName": "Loiter", + "description": "Travel to a position and Loiter around the specified radius indefinitely.", + "specifiesCoordinate": true, + "friendlyEdit": true, + "category": "Loiter", + "param3": { + "label": "Radius:", + "units": "meters", + "default": 100, + "decimalPlaces": 0 + }, + "param7": { + "label": "Altitude:", + "units": "meters", + "default": 50, + "decimalPlaces": 0 + } + }, + { + "id": 18, + "rawName": "MAV_CMD_NAV_LOITER_TURNS", + "friendlyName": "Loiter (turns)", + "description": "Travel to a position and Loiter around the specified radius for a number of turns.", + "specifiesCoordinate": true, + "friendlyEdit": true, + "category": "Loiter", + "param1": { + "label": "Turns:", + "default": 1, + "decimalPlaces": 0 + }, + "param3": { + "label": "Radius:", + "units": "meters", + "default": 100, + "decimalPlaces": 0 + }, + "param7": { + "label": "Altitude:", + "units": "meters", + "default": 50, + "decimalPlaces": 0 + } + }, + { + "id": 19, + "rawName": "MAV_CMD_NAV_LOITER_TIME", + "friendlyName": "Loiter (time)", + "description": "Travel to a position and Loiter around the specified radius for a number of seconds.", + "specifiesCoordinate": true, + "friendlyEdit": true, + "category": "Loiter", + "param1": { + "label": "Seconds:", + "units": "seconds", + "default": 30, + "decimalPlaces": 1 + }, + "param3": { + "label": "Radius:", + "units": "meters", + "default": 100, + "decimalPlaces": 0 + }, + "param7": { + "label": "Altitude:", + "units": "meters", + "default": 50, + "decimalPlaces": 0 + } + }, + { + "id": 21, + "rawName": "MAV_CMD_NAV_LAND", + "friendlyName": "Land", + "description": "Land vehicle at the specified location.", + "specifiesCoordinate": true, + "friendlyEdit": true, + "category": "Basic", + "param1": { + "label": "Abort Alt:", + "units": "meters", + "default": 25, + "decimalPlaces": 0 + }, + "param4": { + "label": "Heading:", + "units": "radians", + "default": 0, + "decimalPlaces": 2 + }, + "param7": { + "label": "Altitude:", + "units": "meters", + "default": 0, + "decimalPlaces": 1 + } + }, + { + "id": 22, + "rawName": "MAV_CMD_NAV_TAKEOFF", + "friendlyName": "Takeoff", + "description": "Take off from the ground and travel towards the specified position.", + "specifiesCoordinate": true, + "friendlyEdit": true, + "category": "Basic", + "param1": { + "label": "Pitch:", + "units": "degrees", + "default": 0, + "decimalPlaces": 0 + }, + "param4": { + "label": "Heading:", + "units": "radians", + "default": 0, + "decimalPlaces": 1 + }, + "param7": { + "label": "Altitude:", + "units": "meters", + "default": 25, + "decimalPlaces": 0 + } + }, + { + "id": 206, + "rawName": "MAV_CMD_DO_SET_CAM_TRIGG_DIST", + "friendlyName": "Camera trigger distance", + "description": "Set camera trigger distance.", + "category": "Camera", + "param1": { + "label": "Distance:", + "default": 25, + "units": "meters", + "decimalPlaces": 1 + } + } ] } diff --git a/src/FirmwarePlugin/PX4/MavCmdInfoFixedWing.json b/src/FirmwarePlugin/PX4/MavCmdInfoFixedWing.json index 77a8d80..c93a456 100644 --- a/src/FirmwarePlugin/PX4/MavCmdInfoFixedWing.json +++ b/src/FirmwarePlugin/PX4/MavCmdInfoFixedWing.json @@ -1,6 +1,167 @@ { "version": 1, - "mavCmdInfo": [ + { + "id": 16, + "rawName": "MAV_CMD_NAV_WAYPOINT", + "friendlyName": "Waypoint", + "description": "Travel to a position in 3D space.", + "specifiesCoordinate": true, + "friendlyEdit": true, + "category": "Basic", + "param1": { + "label": "Hold:", + "units": "seconds", + "default": 0, + "decimalPlaces": 0 + }, + "param7": { + "label": "Altitude:", + "units": "meters", + "default": 50, + "decimalPlaces": 0 + } + }, + { + "id": 17, + "rawName": "MAV_CMD_NAV_LOITER_UNLIM", + "friendlyName": "Loiter", + "description": "Travel to a position and Loiter around the specified radius indefinitely.", + "specifiesCoordinate": true, + "friendlyEdit": true, + "category": "Loiter", + "param3": { + "label": "Radius:", + "units": "meters", + "default": 100, + "decimalPlaces": 0 + }, + "param7": { + "label": "Altitude:", + "units": "meters", + "default": 50, + "decimalPlaces": 0 + } + }, + { + "id": 18, + "rawName": "MAV_CMD_NAV_LOITER_TURNS", + "friendlyName": "Loiter (turns)", + "description": "Travel to a position and Loiter around the specified radius for a number of turns.", + "specifiesCoordinate": true, + "friendlyEdit": true, + "category": "Loiter", + "param1": { + "label": "Turns:", + "default": 1, + "decimalPlaces": 0 + }, + "param3": { + "label": "Radius:", + "units": "meters", + "default": 100, + "decimalPlaces": 0 + }, + "param7": { + "label": "Altitude:", + "units": "meters", + "default": 50, + "decimalPlaces": 0 + } + }, + { + "id": 19, + "rawName": "MAV_CMD_NAV_LOITER_TIME", + "friendlyName": "Loiter (time)", + "description": "Travel to a position and Loiter around the specified radius for a number of seconds.", + "specifiesCoordinate": true, + "friendlyEdit": true, + "category": "Loiter", + "param1": { + "label": "Seconds:", + "units": "seconds", + "default": 30, + "decimalPlaces": 1 + }, + "param3": { + "label": "Radius:", + "units": "meters", + "default": 100, + "decimalPlaces": 0 + }, + "param7": { + "label": "Altitude:", + "units": "meters", + "default": 50, + "decimalPlaces": 0 + } + }, + { + "id": 21, + "rawName": "MAV_CMD_NAV_LAND", + "friendlyName": "Land", + "description": "Land vehicle at the specified location.", + "specifiesCoordinate": true, + "friendlyEdit": true, + "category": "Basic", + "param1": { + "label": "Abort Alt:", + "units": "meters", + "default": 25, + "decimalPlaces": 0 + }, + "param4": { + "label": "Heading:", + "units": "radians", + "default": 0, + "decimalPlaces": 2 + }, + "param7": { + "label": "Altitude:", + "units": "meters", + "default": 0, + "decimalPlaces": 1 + } + }, + { + "id": 22, + "rawName": "MAV_CMD_NAV_TAKEOFF", + "friendlyName": "Takeoff", + "description": "Take off from the ground and travel towards the specified position.", + "specifiesCoordinate": true, + "friendlyEdit": true, + "category": "Basic", + "param1": { + "label": "Pitch:", + "units": "degrees", + "default": 0, + "decimalPlaces": 0 + }, + "param4": { + "label": "Heading:", + "units": "radians", + "default": 0, + "decimalPlaces": 1 + }, + "param7": { + "label": "Altitude:", + "units": "meters", + "default": 25, + "decimalPlaces": 0 + } + }, + { + "id": 206, + "rawName": "MAV_CMD_DO_SET_CAM_TRIGG_DIST", + "friendlyName": "Camera trigger distance", + "description": "Set camera trigger distance.", + "category": "Camera", + "param1": { + "label": "Distance:", + "default": 25, + "units": "meters", + "decimalPlaces": 1 + } + } ] } diff --git a/src/MissionManager/MavCmdInfoCommon.json b/src/MissionManager/MavCmdInfoCommon.json index b5d9bf8..69bf14f 100644 --- a/src/MissionManager/MavCmdInfoCommon.json +++ b/src/MissionManager/MavCmdInfoCommon.json @@ -409,7 +409,7 @@ }, "param2": { "label": "Repeat:", - "default": 0, + "default": 10, "decimalPlaces": 0 } }, diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index 5938dfa..4c6001e 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -987,11 +987,18 @@ bool MissionController::_findLastAltitude(double* lastAltitude) // Don't use home position for (int i=1; i<_visualItems->count(); i++) { - VisualMissionItem* item = qobject_cast(_visualItems->get(i)); + VisualMissionItem* visualItem = qobject_cast(_visualItems->get(i)); - if (item->specifiesCoordinate() && !item->isStandaloneCoordinate()) { - foundAltitude = item->exitCoordinate().altitude(); + if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) { + foundAltitude = visualItem->exitCoordinate().altitude(); found = true; + + if (visualItem->isSimpleItem()) { + SimpleMissionItem* simpleItem = qobject_cast(visualItem); + if ((MAV_CMD)simpleItem->command() == MAV_CMD_NAV_TAKEOFF) { + found = false; + } + } } } diff --git a/src/QmlControls/ParameterEditorDialog.qml b/src/QmlControls/ParameterEditorDialog.qml index 12a00ff..0eec834 100644 --- a/src/QmlControls/ParameterEditorDialog.qml +++ b/src/QmlControls/ParameterEditorDialog.qml @@ -47,7 +47,18 @@ QGCViewDialog { QGCPalette { id: qgcPal; colorGroupEnabled: true } function accept() { - if (factCombo.visible) { + if (bitmaskEditor.visible) { + var value = 0; + for (var i = 0; i < fact.bitmaskValues.length; ++i) { + var checkbox = bitmaskEditor.itemAt(i) + if (checkbox.checked) { + value |= fact.bitmaskValues[i]; + } + } + fact.value = value; + fact.valueChanged(fact.value) + } + else if (factCombo.visible) { fact.enumIndex = factCombo.currentIndex hideDialog() } else { @@ -127,7 +138,7 @@ QGCViewDialog { visible: _showCombo model: fact.enumStrings - property bool _showCombo: fact.enumStrings.length != 0 && !validate + property bool _showCombo: fact.enumStrings.length != 0 && fact.bitmaskStrings.length == 0 && !validate Component.onCompleted: { // We can't bind directly to fact.enumIndex since that would add an unknown value @@ -138,6 +149,19 @@ QGCViewDialog { } } + Column { + spacing: ScreenTools.defaultFontPixelHeight / 2 + + Repeater { + id: bitmaskEditor + model: fact.bitmaskStrings + delegate : QGCCheckBox { + text : modelData + checked : fact.value & fact.bitmaskValues[index] + } + } + } + QGCLabel { text: fact.name } Row { diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 0c062ae..bf09100 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -1420,6 +1420,40 @@ void Vehicle::_setCoordinateValid(bool coordinateValid) } } +QString Vehicle::vehicleTypeName() const { + static QMap typeNames = { + { MAV_TYPE_GENERIC, tr("Generic micro air vehicle" )}, + { MAV_TYPE_FIXED_WING, tr("Fixed wing aircraft")}, + { MAV_TYPE_QUADROTOR, tr("Quadrotor")}, + { MAV_TYPE_COAXIAL, tr("Coaxial helicopter")}, + { MAV_TYPE_HELICOPTER, tr("Normal helicopter with tail rotor.")}, + { MAV_TYPE_ANTENNA_TRACKER, tr("Ground installation")}, + { MAV_TYPE_GCS, tr("Operator control unit / ground control station")}, + { MAV_TYPE_AIRSHIP, tr("Airship, controlled")}, + { MAV_TYPE_FREE_BALLOON, tr("Free balloon, uncontrolled")}, + { MAV_TYPE_ROCKET, tr("Rocket")}, + { MAV_TYPE_GROUND_ROVER, tr("Ground rover")}, + { MAV_TYPE_SURFACE_BOAT, tr("Surface vessel, boat, ship")}, + { MAV_TYPE_SUBMARINE, tr("Submarine")}, + { MAV_TYPE_HEXAROTOR, tr("Hexarotor")}, + { MAV_TYPE_OCTOROTOR, tr("Octorotor")}, + { MAV_TYPE_TRICOPTER, tr("Octorotor")}, + { MAV_TYPE_FLAPPING_WING, tr("Flapping wing")}, + { MAV_TYPE_KITE, tr("Flapping wing")}, + { MAV_TYPE_ONBOARD_CONTROLLER, tr("Onboard companion controller")}, + { MAV_TYPE_VTOL_DUOROTOR, tr("Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter")}, + { MAV_TYPE_VTOL_QUADROTOR, tr("Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter")}, + { MAV_TYPE_VTOL_TILTROTOR, tr("Tiltrotor VTOL")}, + { MAV_TYPE_VTOL_RESERVED2, tr("VTOL reserved 2")}, + { MAV_TYPE_VTOL_RESERVED3, tr("VTOL reserved 3")}, + { MAV_TYPE_VTOL_RESERVED4, tr("VTOL reserved 4")}, + { MAV_TYPE_VTOL_RESERVED5, tr("VTOL reserved 5")}, + { MAV_TYPE_GIMBAL, tr("Onboard gimbal")}, + { MAV_TYPE_ADSB, tr("Onboard ADSB peripheral")}, + }; + return typeNames[_vehicleType]; +} + /// Returns the string to speak to identify the vehicle QString Vehicle::_vehicleIdSpeech(void) { diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index 8880214..afcb078 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -395,6 +395,7 @@ public: int id(void) { return _id; } MAV_AUTOPILOT firmwareType(void) const { return _firmwareType; } MAV_TYPE vehicleType(void) const { return _vehicleType; } + Q_INVOKABLE QString vehicleTypeName(void) const; /// Returns the highest quality link available to the Vehicle LinkInterface* priorityLink(void); diff --git a/src/VehicleSetup/SetupView.qml b/src/VehicleSetup/SetupView.qml index 18e50da..35c85d9 100644 --- a/src/VehicleSetup/SetupView.qml +++ b/src/VehicleSetup/SetupView.qml @@ -36,6 +36,7 @@ import QGroundControl.ScreenTools 1.0 import QGroundControl.MultiVehicleManager 1.0 Rectangle { + id: setupView color: qgcPal.window z: QGroundControl.zOrderTopMost @@ -110,6 +111,13 @@ Rectangle { panelLoader.sourceComponent = messagePanelComponent } else { panelLoader.source = vehicleComponent.setupSource + for(var i = 0; i < componentRepeater.count; i++) { + var obj = componentRepeater.itemAt(i); + if (obj.text === vehicleComponent.name) { + obj.checked = true; + break; + } + } } } } @@ -296,7 +304,6 @@ Rectangle { text: modelData.name visible: modelData.setupSource.toString() != "" - onClicked: showVehicleComponentPanel(modelData) } } diff --git a/src/VehicleSetup/VehicleSummary.qml b/src/VehicleSetup/VehicleSummary.qml index 18bf39b..977370f 100644 --- a/src/VehicleSetup/VehicleSummary.qml +++ b/src/VehicleSetup/VehicleSummary.qml @@ -117,19 +117,11 @@ Rectangle { readonly property real titleHeight: ScreenTools.defaultFontPixelHeight * 2 // Title bar - Rectangle { + QGCButton { id: titleBar width: parent.width height: titleHeight - color: qgcPal.windowShade - - // Title text - QGCLabel { - anchors.fill: parent - verticalAlignment: TextEdit.AlignVCenter - horizontalAlignment: TextEdit.AlignHCenter - text: capitalizeWords(modelData.name) - } + text: capitalizeWords(modelData.name) // Setup indicator Rectangle { @@ -142,6 +134,10 @@ Rectangle { color: modelData.setupComplete ? "#00d932" : "red" visible: modelData.requiresSetup } + + onClicked : { + setupView.showVehicleComponentPanel(modelData) + } } // Summary Qml