diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc index 17945e62efef6b733a5e30fc4e7f3118542908b2..36df1d2193acb75ea1abdeb5b04afc63cad728b3 100644 --- a/qgroundcontrol.qrc +++ b/qgroundcontrol.qrc @@ -70,6 +70,9 @@ src/FactSystem/FactControls/FactCheckBox.qml src/FactSystem/FactControls/FactComboBox.qml src/QmlControls/QGroundControl.Controls.qmldir + + + src/QmlControls/QGCButton.qml src/QmlControls/QGCRadioButton.qml src/QmlControls/QGCCheckBox.qml @@ -81,7 +84,6 @@ src/QmlControls/QGCMovableItem.qml src/QmlControls/QGroundControl.ScreenTools.qmldir src/QmlControls/ScreenTools.qml - src/QmlControls/ScreenToolsFontQuery.qml src/QmlControls/SubMenuButton.qml src/QmlControls/IndicatorButton.qml src/QmlControls/VehicleRotationCal.qml @@ -94,6 +96,10 @@ src/QmlControls/ParameterEditor.qml src/QmlControls/ParameterEditorDialog.qml src/QmlControls/ModeSwitchDisplay.qml + src/QmlControls/MissionItemIndexLabel.qml + src/QmlControls/MissionItemSummary.qml + + src/QmlControls/ScreenToolsFontQuery.qml src/ViewWidgets/ParameterEditorWidget.qml src/ViewWidgets/CustomCommandWidget.qml src/VehicleSetup/SetupView.qml @@ -125,6 +131,7 @@ src/FlightMap/FlightMap.qml src/FlightMap/QGCVideoBackground.qml + src/FlightMap/Widgets/QGCAltitudeWidget.qml src/FlightMap/Widgets/QGCArtificialHorizon.qml src/FlightMap/Widgets/QGCAttitudeWidget.qml @@ -138,8 +145,11 @@ src/FlightMap/Widgets/QGCSlider.qml src/FlightMap/Widgets/QGCSpeedWidget.qml src/FlightMap/Widgets/QGCWaypointEditor.qml - src/FlightMap/MapItems/QGCWaypoint.qml + + + src/FlightMap/MapItems/MissionMapItem.qml src/FlightMap/MapItems/VehicleMapItem.qml + resources/LeftArrow.svg diff --git a/src/FlightDisplay/FlightDisplayView.qml b/src/FlightDisplay/FlightDisplayView.qml index d6d35225338a943d9c947fb377e08fb0eb331c3b..519b957e9d43bd1db9641b12e3a618eb98226174 100644 --- a/src/FlightDisplay/FlightDisplayView.qml +++ b/src/FlightDisplay/FlightDisplayView.qml @@ -52,9 +52,11 @@ Item { property real _roll: _activeVehicle ? (isNaN(_activeVehicle.roll) ? _defaultRoll : _activeVehicle.roll) : _defaultRoll property real _pitch: _activeVehicle ? (isNaN(_activeVehicle.pitch) ? _defaultPitch : _activeVehicle.pitch) : _defaultPitch + property real _heading: _activeVehicle ? (isNaN(_activeVehicle.heading) ? _defaultHeading : _activeVehicle.heading) : _defaultHeading + property real _latitude: _activeVehicle ? ((_activeVehicle.latitude === 0) ? _defaultLatitude : _activeVehicle.latitude) : _defaultLatitude property real _longitude: _activeVehicle ? ((_activeVehicle.longitude === 0) ? _defaultLongitude : _activeVehicle.longitude) : _defaultLongitude - property real _heading: _activeVehicle ? (isNaN(_activeVehicle.heading) ? _defaultHeading : _activeVehicle.heading) : _defaultHeading + property real _altitudeWGS84: _activeVehicle ? _activeVehicle.altitudeWGS84 : _defaultAltitudeWGS84 property real _groundSpeed: _activeVehicle ? _activeVehicle.groundSpeed : _defaultGroundSpeed property real _airSpeed: _activeVehicle ? _activeVehicle.airSpeed : _defaultAirSpeed @@ -69,20 +71,21 @@ Item { } FlightMap { - id: flightMap - anchors.fill: parent - mapName: "FlightDisplayView" - latitude: _latitude - longitude: _longitude - z: 10 - showVehicles: true + id: flightMap + anchors.fill: parent + mapName: "FlightDisplayView" + latitude: parent._latitude + longitude: parent._longitude + z: 10 + showVehicles: true + showMissionItems: true } QGCCompassWidget { x: ScreenTools.defaultFontPixelSize * (7.1) y: ScreenTools.defaultFontPixelSize * (0.42) size: ScreenTools.defaultFontPixelSize * (13.3) - heading: _heading + heading: parent._heading active: multiVehicleManager.activeVehicleAvailable z: flightMap.z + 2 } @@ -92,8 +95,8 @@ Item { anchors.right: parent.right y: ScreenTools.defaultFontPixelSize * (0.42) size: ScreenTools.defaultFontPixelSize * (13.3) - rollAngle: _roll - pitchAngle: _pitch + rollAngle: parent._roll + pitchAngle: parent._pitch active: multiVehicleManager.activeVehicleAvailable z: flightMap.z + 2 } @@ -102,7 +105,7 @@ Item { anchors.right: parent.right height: parent.height * 0.65 > ScreenTools.defaultFontPixelSize * (23.4) ? ScreenTools.defaultFontPixelSize * (23.4) : parent.height * 0.65 width: ScreenTools.defaultFontPixelSize * (5) - altitude: _altitudeWGS84 + altitude: parent._altitudeWGS84 z: 30 } @@ -110,15 +113,15 @@ Item { anchors.left: parent.left width: ScreenTools.defaultFontPixelSize * (5) height: parent.height * 0.65 > ScreenTools.defaultFontPixelSize * (23.4) ? ScreenTools.defaultFontPixelSize * (23.4) : parent.height * 0.65 - speed: _groundSpeed + speed: parent._groundSpeed z: 40 } QGCCurrentSpeed { anchors.left: parent.left width: ScreenTools.defaultFontPixelSize * (6.25) - airspeed: _airSpeed - groundspeed: _groundSpeed + airspeed: parent._airSpeed + groundspeed: parent._groundSpeed active: multiVehicleManager.activeVehicleAvailable z: 50 } @@ -126,8 +129,8 @@ Item { QGCCurrentAltitude { anchors.right: parent.right width: ScreenTools.defaultFontPixelSize * (6.25) - altitude: _altitudeWGS84 - vertZ: _climbRate + altitude: parent._altitudeWGS84 + vertZ: parent._climbRate active: multiVehicleManager.activeVehicleAvailable z: 60 } diff --git a/src/FlightMap/FlightMap.qml b/src/FlightMap/FlightMap.qml index 891fd0e4ee8d1504881687cec1f8b6ee25feb3e9..202a8db97df7997ead749fef7dbc6dbe1eec3003 100644 --- a/src/FlightMap/FlightMap.qml +++ b/src/FlightMap/FlightMap.qml @@ -50,12 +50,15 @@ Item { property string mapName: 'defaultMap' property alias mapItem: map property alias mapMenu: mapTypeMenu - property bool showVehicles: false + property bool showVehicles: false + property bool showMissionItems: false Component.onCompleted: { map.zoomLevel = 18 mapTypeMenu.update(); addExistingVehicles() + updateMissionItemsConnections() + updateMissionItems() } //-- Menu to select supported map types @@ -143,7 +146,6 @@ Item { // we need to keep a separate array of Vehicles which must be at the top level of the object // hierarchy in order for the dynamically added object to see it. - property var _vehicles: [] ///< List of known vehicles property var _vehicleMapItems: [] ///< List of known vehicle map items @@ -155,6 +157,10 @@ Item { } function addVehicle(vehicle) { + if (!showVehicles) { + return + } + var qmlItemTemplate = "VehicleMapItem { " + "coordinate: _vehicles[%1].coordinate; " + "heading: _vehicles[%1].heading " + @@ -173,6 +179,10 @@ Item { } function removeVehicle(vehicle) { + if (!showVehicles) { + return + } + for (var i=0; i<_vehicles.length; i++) { if (_vehicles[i] == vehicle) { _vehicles[i] = undefined @@ -184,12 +194,103 @@ Item { } function addExistingVehicles() { + if (!showVehicles) { + return + } + for (var i=0; i map.maximumZoomLevel) { + endZoomLevel = map.maximumZoomLevel + } + animateZoom.startZoom = map.zoomLevel + animateZoom.endZoom = endZoomLevel + animateZoom.start() + } } + QGCButton { - width: parent.buttonWidth + width: parent._buttonWidth text: "-" - onClicked: map.zoomLevel = map.zoomLevel - parent.zoomIncrement + + onClicked: { + var endZoomLevel = map.zoomLevel - parent._zoomIncrement + if (endZoomLevel < map.minimumZoomLevel) { + endZoomLevel = map.minimumZoomLevel + } + animateZoom.startZoom = map.zoomLevel + animateZoom.endZoom = endZoomLevel + animateZoom.start() + } } } } diff --git a/src/FlightMap/MapItems/MissionMapItem.qml b/src/FlightMap/MapItems/MissionMapItem.qml new file mode 100644 index 0000000000000000000000000000000000000000..defffca5b566e8688f94f124ee5390ab2c57584a --- /dev/null +++ b/src/FlightMap/MapItems/MissionMapItem.qml @@ -0,0 +1,41 @@ +/*===================================================================== + +QGroundControl Open Source Ground Control Station + +(c) 2009, 2015 QGROUNDCONTROL PROJECT + +This file is part of the QGROUNDCONTROL project + + QGROUNDCONTROL is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + QGROUNDCONTROL is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with QGROUNDCONTROL. If not, see . + +======================================================================*/ + +import QtQuick 2.4 +import QtLocation 5.3 + +import QGroundControl.ScreenTools 1.0 +import QGroundControl.Controls 1.0 + +/// Marker for displaying a mission item on the map +MapQuickItem { + property int index + + anchorPoint.x: sourceItem.width / 2 + anchorPoint.y: sourceItem.height / 2 + + sourceItem: + MissionItemIndexLabel { + missionItemIndex: index + } +} diff --git a/src/FlightMap/MapItems/QGCWaypoint.qml b/src/FlightMap/MapItems/QGCWaypoint.qml deleted file mode 100644 index 47daa1806756ec1da379c4842e80775911ca576a..0000000000000000000000000000000000000000 --- a/src/FlightMap/MapItems/QGCWaypoint.qml +++ /dev/null @@ -1,81 +0,0 @@ -/*===================================================================== - -QGroundControl Open Source Ground Control Station - -(c) 2009, 2015 QGROUNDCONTROL PROJECT - -This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - -======================================================================*/ - -/** - * @file - * @brief QGC Waypoint Marker - * @author Gus Grubba - */ - -import QtQuick 2.4 -import QtLocation 5.3 - -MapQuickItem { - id: marker - property int waypointID: 0 - anchorPoint.x: markerIcon.width / 2 - anchorPoint.y: markerIcon.height / 2 - sourceItem: Rectangle { - id: markerIcon - width: 30 - height: 30 - color: markerMouseArea.containsMouse ? (markerMouseArea.pressed ? Qt.rgba(0.69,0.2,0.68,0.25) : Qt.rgba(0.69,0.2,0.68,0.75)) : Qt.rgba(0,0,0,0.5) - radius: 8 - border.color: Qt.rgba(0,0,0,0.75) - Text { - id: number - anchors.centerIn: parent - font.pixelSize: 11 - font.weight: Font.DemiBold - color: "white" - text: marker.waypointID - } - MouseArea { - id: markerMouseArea - enabled: !map.readOnly - anchors.fill: parent - hoverEnabled: true - drag.target: marker - preventStealing: true - property int pressX : -1 - property int pressY : -1 - property int jitterThreshold : 4 - onPressed : { - pressX = mouse.x; - pressY = mouse.y; - map.currentMarker = -1; - for (var i = 0; i < map.markers.length; i++) { - if (marker === map.markers[i]) { - map.currentMarker = i; - break; - } - } - } - onPositionChanged: { - if (Math.abs(pressX - mouse.x ) < jitterThreshold && Math.abs(pressY - mouse.y) < jitterThreshold) { - map.updateMarker(marker.coordinate, marker.waypointID) - } - } - } - } -} diff --git a/src/FlightMap/qmldir b/src/FlightMap/qmldir index 0f00c982ac409efa27a4c16c1e1627881578c990..06e5ae2a4517bd000a6a2e8e0d395c1e04444424 100644 --- a/src/FlightMap/qmldir +++ b/src/FlightMap/qmldir @@ -1,7 +1,7 @@ Module QGroundControl.FlightMap # Main view controls -FlightMap 1.0 FlightMap.qml +FlightMap 1.0 FlightMap.qml QGCVideoBackground 1.0 QGCVideoBackground.qml # Widgets @@ -21,4 +21,4 @@ QGCWaypointEditor 1.0 QGCWaypointEditor.qml # MapQuickItems VehicleMapItem 1.0 VehicleMapItem.qml -QGCWaypoint 1.0 QGCWaypoint.qml +MissioMapItem 1.0 MissionMapItem.qml diff --git a/src/QmlControls/MissionItemIndexLabel.qml b/src/QmlControls/MissionItemIndexLabel.qml new file mode 100644 index 0000000000000000000000000000000000000000..cf4f496e3132869945116889d9b36745ad25f0dd --- /dev/null +++ b/src/QmlControls/MissionItemIndexLabel.qml @@ -0,0 +1,24 @@ +import QtQuick 2.2 +import QtQuick.Controls 1.2 +import QtQuick.Controls.Styles 1.2 + +import QGroundControl.ScreenTools 1.0 + +Rectangle { + property int missionItemIndex ///< Index to show in label + + width: ScreenTools.defaultFontPixelHeight * 1.5 + height: width + radius: width / 2 + border.width: 2 + border.color: "white" + color: "orange" + + QGCLabel { + anchors.fill: parent + horizontalAlignment: Text.AlignHCenter + verticalAlignment: Text.AlignVCenter + color: "white" + text: missionItemIndex + } +} diff --git a/src/QmlControls/MissionItemSummary.qml b/src/QmlControls/MissionItemSummary.qml new file mode 100644 index 0000000000000000000000000000000000000000..860788443abe1b69a0a45184d575b6755eb94bc3 --- /dev/null +++ b/src/QmlControls/MissionItemSummary.qml @@ -0,0 +1,34 @@ +import QtQuick 2.2 +import QtQuick.Controls 1.2 +import QtQuick.Controls.Styles 1.2 + +import QGroundControl.ScreenTools 1.0 + +/// Mission item summary display control +Rectangle { + property var missionItem ///< Mission Item object + property int missionItemIndex ///< Index for this item + + width: ScreenTools.defaultFontPixelWidth * 15 + height: ScreenTools.defaultFontPixelWidth * 3 + border.width: 2 + border.color: "white" + color: "white" + opacity: 0.75 + radius: ScreenTools.defaultFontPixelWidth + + QGCLabel { + anchors.margins: parent.radius / 2 + anchors.left: parent.left + anchors.top: parent.top + color: "black" + horizontalAlignment: Text.AlignTop + text: missionItem.type + } + + MissionItemIndexLabel { + anchors.top: parent.top + anchors.right: parent.right + missionItemIndex: parent.missionItemIndex + 1 + } +} diff --git a/src/QmlControls/QGroundControl.Controls.qmldir b/src/QmlControls/QGroundControl.Controls.qmldir index 3b627337c5dbb9d6fb5fd8d70779df20ea086c84..511d4d9d4a32473d9c00f7e7936f85512acbad41 100644 --- a/src/QmlControls/QGroundControl.Controls.qmldir +++ b/src/QmlControls/QGroundControl.Controls.qmldir @@ -1,28 +1,31 @@ Module QGroundControl.Controls -QGCLabel 1.0 QGCLabel.qml -QGCButton 1.0 QGCButton.qml -QGCRadioButton 1.0 QGCRadioButton.qml -QGCCheckBox 1.0 QGCCheckBox.qml -QGCTextField 1.0 QGCTextField.qml -QGCComboBox 1.0 QGCComboBox.qml -QGCColoredImage 1.0 QGCColoredImage.qml -QGCToolBarButton 1.0 QGCToolBarButton.qml -QGCMovableItem 1.0 QGCMovableItem.qml +QGCLabel 1.0 QGCLabel.qml +QGCButton 1.0 QGCButton.qml +QGCRadioButton 1.0 QGCRadioButton.qml +QGCCheckBox 1.0 QGCCheckBox.qml +QGCTextField 1.0 QGCTextField.qml +QGCComboBox 1.0 QGCComboBox.qml +QGCColoredImage 1.0 QGCColoredImage.qml +QGCToolBarButton 1.0 QGCToolBarButton.qml +QGCMovableItem 1.0 QGCMovableItem.qml -SubMenuButton 1.0 SubMenuButton.qml -IndicatorButton 1.0 IndicatorButton.qml -VehicleRotationCal 1.0 VehicleRotationCal.qml -VehicleSummaryRow 1.0 VehicleSummaryRow.qml -ViewWidget 1.0 ViewWidget.qml +SubMenuButton 1.0 SubMenuButton.qml +IndicatorButton 1.0 IndicatorButton.qml +VehicleRotationCal 1.0 VehicleRotationCal.qml +VehicleSummaryRow 1.0 VehicleSummaryRow.qml +ViewWidget 1.0 ViewWidget.qml -ParameterEditor 1.0 ParameterEditor.qml -ParameterEditorDialog 1.0 ParameterEditorDialog.qml +ParameterEditor 1.0 ParameterEditor.qml +ParameterEditorDialog 1.0 ParameterEditorDialog.qml ModeSwitchDisplay 1.0 ModeSwitchDisplay.qml -QGCView 1.0 QGCView.qml -QGCViewPanel 1.0 QGCViewPanel.qml -QGCViewDialog 1.0 QGCViewDialog.qml -QGCViewMessage 1.0 QGCViewMessage.qml +QGCView 1.0 QGCView.qml +QGCViewPanel 1.0 QGCViewPanel.qml +QGCViewDialog 1.0 QGCViewDialog.qml +QGCViewMessage 1.0 QGCViewMessage.qml + +MissionItemIndexLabel 1.0 MissionItemIndexLabel.qml +MissionItemSummary 1.0 MissionItemSummary.qml diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 74612fc6b8f15778a9c811dbb26318a0c10f8cd0..8d3298dfa925b62350b0e86dadba1ac0758c8759 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -714,7 +714,7 @@ void Vehicle::_waypointViewOnlyListChanged() Waypoint* wp = waypoints[i]; _waypoints.append(new Waypoint(*wp)); } - emit waypointsChanged(); + emit missionItemsChanged(); /* if(_longitude == DEFAULT_LON && _latitude == DEFAULT_LAT && _waypoints.length()) { _longitude = _waypoints[0]->getLongitude(); diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index b38ac95c88d7e70245777af8ca4bcdf4d7552278..bd3615f853b6ad638c560549b786db27991a682e 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -87,8 +87,9 @@ public: Q_PROPERTY(double waypointDistance READ waypointDistance NOTIFY waypointDistanceChanged) Q_PROPERTY(uint16_t currentWaypoint READ currentWaypoint NOTIFY currentWaypointChanged) Q_PROPERTY(unsigned int heartbeatTimeout READ heartbeatTimeout NOTIFY heartbeatTimeoutChanged) + //-- Waypoint management - Q_PROPERTY(QQmlListProperty waypoints READ waypoints NOTIFY waypointsChanged) + Q_PROPERTY(QQmlListProperty missionItems READ missionItems NOTIFY missionItemsChanged) // Property accesors int id(void) { return _id; } @@ -161,7 +162,7 @@ public: uint16_t currentWaypoint () { return _currentWaypoint; } unsigned int heartbeatTimeout () { return _currentHeartbeatTimeout; } - QQmlListProperty waypoints() {return QQmlListProperty(this, _waypoints); } + QQmlListProperty missionItems() {return QQmlListProperty(this, _waypoints); } public slots: void setLatitude(double latitude); @@ -203,7 +204,7 @@ signals: void satelliteLockChanged (); void waypointDistanceChanged(); void currentWaypointChanged (); - void waypointsChanged (); + void missionItemsChanged (); private slots: void _mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message); diff --git a/src/Waypoint.cc b/src/Waypoint.cc index 6c3d2f8ef8fec02c436fdcb2c5537b120b32016b..eb6a44a462fcf885fa13da33a48a4135f7ce39ad 100644 --- a/src/Waypoint.cc +++ b/src/Waypoint.cc @@ -67,7 +67,8 @@ Waypoint::Waypoint( , _description(description) , _reachedTime(0) { - + connect(this, &Waypoint::latitudeChanged, this, &Waypoint::coordinateChanged); + connect(this, &Waypoint::longitudeChanged, this, &Waypoint::coordinateChanged); } Waypoint::Waypoint(const Waypoint& other) @@ -233,6 +234,7 @@ void Waypoint::setAction(int /*MAV_CMD*/ action) } emit changed(this); + emit typeChanged(type()); } } @@ -362,3 +364,112 @@ void Waypoint::setTurns(int turns) emit changed(this); } } + +QGeoCoordinate Waypoint::coordinate(void) +{ + return QGeoCoordinate(_x, _y); +} + +QString Waypoint::type(void) +{ + QString type; + + switch (_action) { + case MAV_CMD_NAV_WAYPOINT: + type = "Waypoint"; + break; + case MAV_CMD_NAV_LOITER_UNLIM: + case MAV_CMD_NAV_LOITER_TURNS: + case MAV_CMD_NAV_LOITER_TIME: + type = "Loiter"; + break; + case MAV_CMD_NAV_RETURN_TO_LAUNCH: + type = "Return To Launch"; + break; + case MAV_CMD_NAV_LAND: + type = "Land"; + break; + case MAV_CMD_NAV_TAKEOFF: + type = "Takeoff"; + break; + default: + type = QString("Unknown(%1)").arg(_action); + break; +#if 0 + // FIXME: NYI + MAV_CMD_NAV_LAND_LOCAL=23, /* Land at local position (local frame only) |Landing target number (if available)| Maximum accepted offset from desired landing position [m] - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land| Landing descend rate [ms^-1]| Desired yaw angle [rad]| Y-axis position [m]| X-axis position [m]| Z-axis / ground level position [m]| */ + MAV_CMD_NAV_TAKEOFF_LOCAL=24, /* Takeoff from local position (local frame only) |Minimum pitch (if airspeed sensor present), desired pitch without sensor [rad]| Empty| Takeoff ascend rate [ms^-1]| Yaw angle [rad] (if magnetometer or another yaw estimation source present), ignored without one of these| Y-axis position [m]| X-axis position [m]| Z-axis position [m]| */ + MAV_CMD_NAV_FOLLOW=25, /* Vehicle following, i.e. this waypoint represents the position of a moving vehicle |Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation| Ground speed of vehicle to be followed| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT=30, /* Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached. |Empty| Empty| Empty| Empty| Empty| Empty| Desired altitude in meters| */ + MAV_CMD_NAV_LOITER_TO_ALT=31, /* Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint. |Heading Required (0 = False)| Radius in meters. If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter.| Empty| Empty| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_ROI=80, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ + MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ + MAV_CMD_NAV_SPLINE_WAYPOINT=82, /* Navigate to MISSION using a spline path. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Empty| Empty| Empty| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ + MAV_CMD_NAV_ALTITUDE_WAIT=83, /* Mission command to wait for an altitude or downwards vertical speed. This is meant for high altitude balloon launches, allowing the aircraft to be idle until either an altitude is reached or a negative vertical speed is reached (indicating early balloon burst). The wiggle time is how often to wiggle the control surfaces to prevent them seizing up. |altitude (m)| descent speed (m/s)| Wiggle Time (s)| Empty| Empty| Empty| Empty| */ + MAV_CMD_NAV_GUIDED_ENABLE=92, /* hand control over to an external controller |On / Off (> 0.5f on)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */ + MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Custom mode - this is system specific, please refer to the individual autopilot specifications for details.| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */ + MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */ + MAV_CMD_DO_FLIGHTTERMINATION=185, /* Terminate flight immediately |Flight termination activated if > 0.5| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_LAND_START=189, /* Mission command to perform a landing. This is used as a marker in a mission to tell the autopilot where a sequence of mission items that represents a landing starts. It may also be sent via a COMMAND_LONG to trigger a landing, in which case the nearest (geographically) landing sequence in the mission will be used. The Latitude/Longitude is optional, and may be set to 0/0 if not needed. If specified then it will be used to help find the closest landing sequence. |Empty| Empty| Empty| Empty| Latitude| Longitude| Empty| */ + MAV_CMD_DO_RALLY_LAND=190, /* Mission command to perform a landing from a rally point. |Break altitude (meters)| Landing speed (m/s)| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_GO_AROUND=191, /* Mission command to safely abort an autonmous landing. |Altitude (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_ROI=201, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ + MAV_CMD_DO_DIGICAM_CONFIGURE=202, /* Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)| */ + MAV_CMD_DO_DIGICAM_CONTROL=203, /* Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty| */ + MAV_CMD_DO_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| */ + MAV_CMD_DO_MOUNT_CONTROL=205, /* Mission command to control a camera or antenna mount |pitch or lat in degrees, depending on mount mode.| roll or lon in degrees depending on mount mode| yaw or alt (in meters) depending on mount mode| reserved| reserved| reserved| MAV_MOUNT_MODE enum value| */ + MAV_CMD_DO_SET_CAM_TRIGG_DIST=206, /* Mission command to set CAM_TRIGG_DIST for this flight |Camera trigger distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_FENCE_ENABLE=207, /* Mission command to enable the geofence |enable? (0=disable, 1=enable, 2=disable_floor_only)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_PARACHUTE=208, /* Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_MOTOR_TEST=209, /* Mission command to perform motor test |motor sequence number (a number from 1 to max number of motors on the vehicle)| throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum)| throttle| timeout (in seconds)| Empty| Empty| Empty| */ + MAV_CMD_DO_INVERTED_FLIGHT=210, /* Change to/from inverted flight |inverted (0=normal, 1=inverted)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_GRIPPER=211, /* Mission command to operate EPM gripper |gripper number (a number from 1 to max number of grippers on the vehicle)| gripper action (0=release, 1=grab. See GRIPPER_ACTIONS enum)| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_AUTOTUNE_ENABLE=212, /* Enable/disable autotune |enable (1: enable, 0:disable)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_MOUNT_CONTROL_QUAT=220, /* Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1, w (1 in null-rotation)| q2 - quaternion param #2, x (0 in null-rotation)| q3 - quaternion param #3, y (0 in null-rotation)| q4 - quaternion param #4, z (0 in null-rotation)| Empty| Empty| Empty| */ + MAV_CMD_DO_GUIDED_MASTER=221, /* set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_GUIDED_LIMITS=222, /* set limits for external control |timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout| absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit| absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit| horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit| Empty| Empty| Empty| */ + MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Compass/Motor interference calibration: 0: no, 1: yes| Empty| */ + MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */ + MAV_CMD_PREFLIGHT_UAVCAN=243, /* Trigger UAVCAN config. This command will be only accepted if in pre-flight mode. |1: Trigger actuator ID assignment and direction mapping.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */ + MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM, 2: Reset to defaults| Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: start logging with rate of param 3 in Hz (e.g. set to 1000 for 1000 Hz logging)| Reserved| Empty| Empty| Empty| */ + MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */ + MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */ + MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */ + MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */ + MAV_CMD_GET_HOME_POSITION=410, /* Request the home position from the vehicle. |Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */ + MAV_CMD_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */ + MAV_CMD_GET_MESSAGE_INTERVAL=510, /* Request the interval between messages for a particular MAVLink message ID |The MAVLink message ID| */ + MAV_CMD_SET_MESSAGE_INTERVAL=511, /* Request the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM |The MAVLink message ID| The interval between two messages, in microseconds. Set to -1 to disable and 0 to request default rate.| */ + MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES=520, /* Request autopilot capabilities |1: Request autopilot version| Reserved (all remaining params)| */ + MAV_CMD_IMAGE_START_CAPTURE=2000, /* Start image capture sequence |Duration between two consecutive pictures (in seconds)| Number of images to capture total - 0 for unlimited capture| Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)| */ + MAV_CMD_IMAGE_STOP_CAPTURE=2001, /* Stop image capture sequence |Reserved| Reserved| */ + MAV_CMD_DO_TRIGGER_CONTROL=2003, /* Enable or disable on-board camera triggering system. |Trigger enable/disable (0 for disable, 1 for start)| Shutter integration time (in ms)| Reserved| */ + MAV_CMD_VIDEO_START_CAPTURE=2500, /* Starts video capture |Camera ID (0 for all cameras), 1 for first, 2 for second, etc.| Frames per second| Resolution in megapixels (0.3 for 640x480, 1.3 for 1280x720, etc)| */ + MAV_CMD_VIDEO_STOP_CAPTURE=2501, /* Stop the current video capture |Reserved| Reserved| */ + MAV_CMD_PANORAMA_CREATE=2800, /* Create a panorama at the current position |Viewing angle horizontal of the panorama (in degrees, +- 0.5 the total angle)| Viewing angle vertical of panorama (in degrees)| Speed of the horizontal rotation (in degrees per second)| Speed of the vertical rotation (in degrees per second)| */ + MAV_CMD_DO_VTOL_TRANSITION=3000, /* Request VTOL transition |The target VTOL state, as defined by ENUM MAV_VTOL_STATE. Only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used.| */ + MAV_CMD_PAYLOAD_PREPARE_DEPLOY=30001, /* Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity. |Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.| Desired approach vector in degrees compass heading (0..360). A negative value indicates the system can define the approach vector at will.| Desired ground speed at release time. This can be overriden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will.| Minimum altitude clearance to the release position in meters. A negative value indicates the system can define the clearance at will.| Latitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT| Longitude unscaled for MISSION_ITEM or in 1e7 degrees for MISSION_ITEM_INT| Altitude, in meters AMSL| */ + MAV_CMD_PAYLOAD_CONTROL_DEPLOY=30002, /* Control the payload deployment. |Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deploment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */ + MAV_CMD_DO_START_MAG_CAL=42424, /* Initiate a magnetometer calibration |uint8_t bitmask of magnetometers (0 means all)| Automatically retry on failure (0=no retry, 1=retry).| Save without user input (0=require input, 1=autosave).| Delay (seconds)| Empty| Empty| Empty| */ + MAV_CMD_DO_ACCEPT_MAG_CAL=42425, /* Initiate a magnetometer calibration |uint8_t bitmask of magnetometers (0 means all)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_CANCEL_MAG_CAL=42426, /* Cancel a running magnetometer calibration |uint8_t bitmask of magnetometers (0 means all)| Empty| Empty| Empty| Empty| Empty| Empty| */ +#endif + } + + return type; +} diff --git a/src/Waypoint.h b/src/Waypoint.h index c2618ff7c1f68a21e80a1d1502d916b84c2126dd..9683b0b22b4ea18d080bae4036baab916805ae83 100644 --- a/src/Waypoint.h +++ b/src/Waypoint.h @@ -37,6 +37,8 @@ This file is part of the PIXHAWK project #include #include #include +#include + #include "QGCMAVLink.h" #include "QGC.h" @@ -65,6 +67,9 @@ public: const Waypoint& operator=(const Waypoint& other); + Q_PROPERTY(QGeoCoordinate coordinate READ coordinate NOTIFY coordinateChanged) + Q_PROPERTY(QString type READ type NOTIFY typeChanged) + Q_PROPERTY(double longitude READ longitude NOTIFY longitudeChanged) Q_PROPERTY(double latitude READ latitude NOTIFY latitudeChanged) Q_PROPERTY(double altitude READ altitude NOTIFY altitudeChanged) @@ -161,7 +166,9 @@ public: void save(QTextStream &saveStream); bool load(QTextStream &loadStream); - + + QGeoCoordinate coordinate(void); + QString type(void); protected: quint16 _id; @@ -227,7 +234,8 @@ signals: void latitudeChanged (); void longitudeChanged (); void altitudeChanged (); - + void coordinateChanged(void); + void typeChanged(QString type); }; QML_DECLARE_TYPE(Waypoint)