Browse Source

Merge branch 'master' of https://github.com/mavlink/qgroundcontrol into Airmap

# Conflicts:
#	src/MissionManager/ComplexMissionItem.h
QGC4.4
Gus Grubba 7 years ago
parent
commit
ec51046694
  1. 14
      .travis.yml
  2. 9
      QGCInstaller.pri
  3. 2
      libs/mavlink/include/mavlink/v2.0
  4. 2
      src/AnalyzeView/ULogParser.cc
  5. 7
      src/AutoPilotPlugins/APM/APMPowerComponent.qml
  6. 138
      src/AutoPilotPlugins/PX4/PX4SimpleFlightModes.qml
  7. 6
      src/FirmwarePlugin/FirmwarePlugin.cc
  8. 4
      src/FirmwarePlugin/FirmwarePlugin.h
  9. 54
      src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
  10. 1
      src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
  11. 32
      src/FlightDisplay/FlightDisplayView.qml
  12. 105
      src/FlightDisplay/FlightDisplayViewMap.qml
  13. 5
      src/FlightDisplay/GuidedActionConfirm.qml
  14. 35
      src/FlightDisplay/GuidedActionsController.qml
  15. 3
      src/FlightDisplay/GuidedAltitudeSlider.qml
  16. 3
      src/FlightMap/MapItems/MissionItemIndicatorDrag.qml
  17. 8
      src/FollowMe/FollowMe.cc
  18. 8
      src/MissionManager/ComplexMissionItem.h
  19. 40
      src/MissionManager/MissionController.cc
  20. 2
      src/MissionManager/MissionController.h
  21. 107
      src/MissionManager/QGCMapCircleVisuals.qml
  22. 27
      src/MissionManager/SimpleMissionItem.cc
  23. 24
      src/MissionManager/SimpleMissionItem.h
  24. 22
      src/MissionManager/StructureScanComplexItem.cc
  25. 2
      src/MissionManager/StructureScanComplexItem.h
  26. 2
      src/MissionManager/StructureScanComplexItemTest.cc
  27. 102
      src/MissionManager/SurveyComplexItem.cc
  28. 4
      src/MissionManager/VisualMissionItem.h
  29. 2
      src/PlanView/MissionItemStatus.qml
  30. 2
      src/QGCApplication.cc
  31. 2
      src/QmlControls/DropPanel.qml
  32. 2
      src/QmlControls/MissionItemIndexLabel.qml
  33. 10
      src/QmlControls/QGCComboBox.qml
  34. 8
      src/QtLocationPlugin/QGCMapEngine.cpp
  35. 4
      src/QtLocationPlugin/QGCTileCacheWorker.cpp
  36. 2
      src/QtLocationPlugin/QGeoCodeReplyQGC.cpp
  37. 4
      src/QtLocationPlugin/QGeoCodingManagerEngineQGC.cpp
  38. 2
      src/QtLocationPlugin/QGeoMapReplyQGC.cpp
  39. 2
      src/QtLocationPlugin/QGeoTiledMappingManagerEngineQGC.cpp
  40. 120
      src/Vehicle/Vehicle.cc
  41. 18
      src/Vehicle/Vehicle.h
  42. 2
      src/VideoStreaming/VideoStreaming.cc
  43. 12
      src/VideoStreaming/gstqtvideosink/painters/openglsurfacepainter.cpp
  44. 4
      src/comm/QGCXPlaneLink.cc
  45. 2
      src/qgcunittest/TCPLinkTest.cc
  46. 4
      src/qgcunittest/TCPLoopBackServer.cc
  47. 2
      src/ui/MainWindow.cc

14
.travis.yml

@ -104,19 +104,7 @@ install: @@ -104,19 +104,7 @@ install:
;
fi
- if [[ "${SPEC}" = "macx-clang" && "${TRAVIS_PULL_REQUEST}" = "false" ]]; then
wget --quiet https://s3-us-west-2.amazonaws.com/qgroundcontrol/dependencies/gstreamer-1.0-1.5.2-x86_64.pkg &&
sudo installer -verboseR -pkg gstreamer-1.0-1.5.2-x86_64.pkg -target /
;
fi
- if [[ "${SPEC}" = "macx-clang" && "${TRAVIS_PULL_REQUEST}" = "false" ]]; then
wget --quiet https://s3-us-west-2.amazonaws.com/qgroundcontrol/dependencies/gstreamer-1.0-devel-1.5.2-x86_64.pkg &&
sudo installer -verboseR -pkg gstreamer-1.0-devel-1.5.2-x86_64.pkg -target /
;
fi
- if [[ "${SPEC}" = "macx-clang" && "${TRAVIS_PULL_REQUEST}" = "false" ]]; then
- if [[ "${SPEC}" = "macx-clang" ]]; then
wget --quiet https://s3-us-west-2.amazonaws.com/qgroundcontrol/dependencies/osx-gstreamer.tar.bz2 &&
sudo tar jxf osx-gstreamer.tar.bz2 -C /Library/Frameworks
;

9
QGCInstaller.pri

@ -23,12 +23,19 @@ installer { @@ -23,12 +23,19 @@ installer {
} else {
message("Skipping GStreamer Framework")
}
# We cd to release directory so we can run macdeployqt without a path to the
# qgroundcontrol.app file. If you specify a path to the .app file the symbolic
# links to plugins will not be created correctly.
QMAKE_POST_LINK += && cd $${DESTDIR} && $$dirname(QMAKE_QMAKE)/macdeployqt $${TARGET}.app -appstore-compliant -verbose=2 -qmldir=$${BASEDIR}/src
# macdeploy is missing some relocations once in a while. "Fix" it:
# macdeployqt does not deploy texttospeech plugin
QMAKE_POST_LINK += && mkdir $${TARGET}.app/Contents/PlugIns/texttospeech
QMAKE_POST_LINK += && cp $$[QT_INSTALL_PLUGINS]/texttospeech/libqtexttospeech_speechosx.dylib $${TARGET}.app/Contents/PlugIns/texttospeech
# macdeployqt is missing some relocations once in a while. "Fix" it:
QMAKE_POST_LINK += && python $$BASEDIR/tools/osxrelocator.py $${TARGET}.app/Contents @rpath @executable_path/../Frameworks -r > /dev/null 2>&1
# Create package
QMAKE_POST_LINK += && hdiutil create /tmp/tmp.dmg -ov -volname "$${TARGET}-$${MAC_VERSION}" -fs HFS+ -srcfolder "$${DESTDIR}/"
QMAKE_POST_LINK += && mkdir -p $${DESTDIR}/package

2
libs/mavlink/include/mavlink/v2.0

@ -1 +1 @@ @@ -1 +1 @@
Subproject commit 033fa8e7a4a75a0c3f17cea57e3be8966e05f770
Subproject commit f5c0ba684659fbc6c6c5f8777bd30e0b3c32fdef

2
src/AnalyzeView/ULogParser.cc

@ -57,7 +57,7 @@ QString ULogParser::extractArraySize(QString &typeNameFull, int &arraySize) @@ -57,7 +57,7 @@ QString ULogParser::extractArraySize(QString &typeNameFull, int &arraySize)
return typeNameFull;
}
arraySize = typeNameFull.mid(startPos + 1, endPos - startPos - 1).toInt();
arraySize = typeNameFull.midRef(startPos + 1, endPos - startPos - 1).toInt();
return typeNameFull.mid(0, startPos);
}

7
src/AutoPilotPlugins/APM/APMPowerComponent.qml

@ -214,10 +214,9 @@ SetupPage { @@ -214,10 +214,9 @@ SetupPage {
QGCLabel { text: qsTr("Battery monitor:") }
FactComboBox {
id: monitorCombo
Layout.minimumWidth: _fieldWidth
fact: battMonitor
indexModel: false
id: monitorCombo
fact: battMonitor
indexModel: false
}
QGCLabel {

138
src/AutoPilotPlugins/PX4/PX4SimpleFlightModes.qml

@ -7,9 +7,9 @@ @@ -7,9 +7,9 @@
*
****************************************************************************/
import QtQuick 2.3
import QtQuick.Controls 1.2
import QtQuick 2.3
import QtQuick.Controls 1.2
import QtQuick.Layouts 1.2
import QGroundControl.FactSystem 1.0
import QGroundControl.FactControls 1.0
@ -65,49 +65,48 @@ Item { @@ -65,49 +65,48 @@ Item {
height: flightModeColumn.height + ScreenTools.defaultFontPixelHeight
color: qgcPal.windowShade
Column {
ColumnLayout {
id: flightModeColumn
anchors.margins: ScreenTools.defaultFontPixelWidth
anchors.left: parent.left
anchors.top: parent.top
spacing: ScreenTools.defaultFontPixelHeight
Row {
spacing: _margins
RowLayout {
Layout.fillWidth: true
spacing: _margins
QGCLabel {
id: modeChannelLabel
anchors.baseline: modeChannelCombo.baseline
Layout.fillWidth: true
text: qsTr("Mode channel:")
}
FactComboBox {
id: modeChannelCombo
width: _channelComboWidth
fact: controller.getParameterFact(-1, "RC_MAP_FLTMODE")
indexModel: false
Layout.preferredWidth: _channelComboWidth
fact: controller.getParameterFact(-1, "RC_MAP_FLTMODE")
indexModel: false
}
}
Repeater {
model: 6
Row {
spacing: ScreenTools.defaultFontPixelWidth
RowLayout {
Layout.fillWidth: true
spacing: ScreenTools.defaultFontPixelWidth
property int index: modelData + 1
QGCLabel {
anchors.baseline: modeCombo.baseline
Layout.fillWidth: true
text: qsTr("Flight Mode %1").arg(index)
color: controller.activeFlightMode == index ? "yellow" : qgcPal.text
}
FactComboBox {
id: modeCombo
width: _flightModeComboWidth
fact: controller.getParameterFact(-1, "COM_FLTMODE" + index)
indexModel: false
Layout.preferredWidth: _channelComboWidth
fact: controller.getParameterFact(-1, "COM_FLTMODE" + index)
indexModel: false
}
}
} // Repeater - Flight Modes
@ -126,74 +125,87 @@ Item { @@ -126,74 +125,87 @@ Item {
Rectangle {
id: switchSettingsRect
width: switchSettingsColumn.width + (_margins * 2)
height: switchSettingsColumn.height + ScreenTools.defaultFontPixelHeight
width: switchSettingsGrid.width + (_margins * 2)
height: switchSettingsGrid.height + ScreenTools.defaultFontPixelHeight
color: qgcPal.windowShade
Column {
id: switchSettingsColumn
GridLayout {
id: switchSettingsGrid
anchors.margins: ScreenTools.defaultFontPixelWidth
anchors.left: parent.left
anchors.top: parent.top
spacing: ScreenTools.defaultFontPixelHeight
columns: 2
columnSpacing: ScreenTools.defaultFontPixelWidth
Row {
spacing: ScreenTools.defaultFontPixelWidth
Repeater {
model: [ "RC_MAP_ACRO_SW", "RC_MAP_ARM_SW", "RC_MAP_GEAR_SW", "RC_MAP_KILL_SW", "RC_MAP_LOITER_SW", "RC_MAP_OFFB_SW", "RC_MAP_POSCTL_SW", "RC_MAP_RATT_SW", "RC_MAP_RETURN_SW", "RC_MAP_STAB_SW" ]
property Fact fact: controller.getParameterFact(-1, "RC_MAP_RETURN_SW")
RowLayout {
spacing: ScreenTools.defaultFontPixelWidth
Layout.fillWidth: true
QGCLabel {
anchors.baseline: returnCombo.baseline
text: qsTr("Return switch:")
color: parent.fact.value === 0 ? qgcPal.text : (controller.rcChannelValues[parent.fact.value - 1] >= 1500 ? "yellow" : qgcPal.text)
}
property Fact fact: controller.getParameterFact(-1, modelData)
FactComboBox {
id: returnCombo
width: _channelComboWidth
fact: parent.fact
indexModel: false
QGCLabel {
text: fact.shortDescription
Layout.fillWidth: true
}
FactComboBox {
Layout.preferredWidth: _channelComboWidth
fact: parent.fact
indexModel: false
}
}
}
Row {
spacing: ScreenTools.defaultFontPixelWidth
Repeater {
model: [ "RC_MAP_FLAPS", "RC_MAP_MAN_SW" ]
property Fact fact: controller.getParameterFact(-1, "RC_MAP_KILL_SW")
RowLayout {
spacing: ScreenTools.defaultFontPixelWidth
visible: controller.vehicle.fixedWing
Layout.fillWidth: true
QGCLabel {
anchors.baseline: killCombo.baseline
text: qsTr("Kill switch:")
color: parent.fact.value === 0 ? qgcPal.text : (controller.rcChannelValues[parent.fact.value - 1] >= 1500 ? "yellow" : qgcPal.text)
}
property Fact fact: controller.getParameterFact(-1, modelData)
FactComboBox {
id: killCombo
width: _channelComboWidth
fact: parent.fact
indexModel: false
QGCLabel {
text: fact.shortDescription
Layout.fillWidth: true
}
FactComboBox {
Layout.preferredWidth: _channelComboWidth
fact: parent.fact
indexModel: false
}
}
}
Row {
spacing: ScreenTools.defaultFontPixelWidth
Repeater {
model: [ "RC_MAP_TRANS_SW" ]
property Fact fact: controller.getParameterFact(-1, "RC_MAP_OFFB_SW")
RowLayout {
spacing: ScreenTools.defaultFontPixelWidth
Layout.fillWidth: true
visible: controller.vehicle.vtol
QGCLabel {
anchors.baseline: offboardCombo.baseline
text: qsTr("Offboard switch:")
color: parent.fact.value === 0 ? qgcPal.text : (controller.rcChannelValues[parent.fact.value - 1] >= 1500 ? "yellow" : qgcPal.text)
}
property Fact fact: controller.getParameterFact(-1, modelData)
FactComboBox {
id: offboardCombo
width: _channelComboWidth
fact: parent.fact
indexModel: false
QGCLabel {
text: fact.shortDescription
Layout.fillWidth: true
}
FactComboBox {
Layout.preferredWidth: _channelComboWidth
fact: parent.fact
indexModel: false
}
}
}
Row {
spacing: ScreenTools.defaultFontPixelWidth

6
src/FirmwarePlugin/FirmwarePlugin.cc

@ -270,12 +270,6 @@ void FirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle, double takeoffAltRel) @@ -270,12 +270,6 @@ void FirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle, double takeoffAltRel)
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
}
void FirmwarePlugin::guidedModeOrbit(Vehicle* /*vehicle*/, const QGeoCoordinate& /*centerCoord*/, double /*radius*/, double /*velocity*/, double /*altitude*/)
{
// Not supported by generic vehicle
qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
}
void FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord)
{
// Not supported by generic vehicle

4
src/FirmwarePlugin/FirmwarePlugin.h

@ -136,10 +136,6 @@ public: @@ -136,10 +136,6 @@ public:
/// Command the vehicle to start the mission
virtual void startMission(Vehicle* vehicle);
/// Command vehicle to orbit given center point
/// @param centerCoord Center Coordinates
virtual void guidedModeOrbit(Vehicle* vehicle, const QGeoCoordinate& centerCoord, double radius, double velocity, double altitude);
/// Command vehicle to move to specified location (altitude is included and relative)
virtual void guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord);

54
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc

@ -232,7 +232,7 @@ bool PX4FirmwarePlugin::isCapable(const Vehicle *vehicle, FirmwareCapabilities c @@ -232,7 +232,7 @@ bool PX4FirmwarePlugin::isCapable(const Vehicle *vehicle, FirmwareCapabilities c
{
int available = SetFlightModeCapability | PauseVehicleCapability | GuidedModeCapability;
if (vehicle->multiRotor() || vehicle->vtol()) {
available |= TakeoffVehicleCapability;
available |= TakeoffVehicleCapability | OrbitModeCapability;
}
return (capabilities & available) == capabilities;
@ -364,24 +364,6 @@ void PX4FirmwarePlugin::guidedModeLand(Vehicle* vehicle) @@ -364,24 +364,6 @@ void PX4FirmwarePlugin::guidedModeLand(Vehicle* vehicle)
_setFlightModeAndValidate(vehicle, _landingFlightMode);
}
void PX4FirmwarePlugin::guidedModeOrbit(Vehicle* vehicle, const QGeoCoordinate& centerCoord, double radius, double velocity, double altitude)
{
if (!isGuidedMode(vehicle)) {
setGuidedMode(vehicle, true);
}
vehicle->sendMavCommand(vehicle->defaultComponentId(),
MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE,
true, // show error if fails
radius,
velocity,
altitude,
NAN,
centerCoord.isValid() ? centerCoord.latitude() : NAN,
centerCoord.isValid() ? centerCoord.longitude() : NAN,
centerCoord.isValid() ? centerCoord.altitude() : NAN);
}
void PX4FirmwarePlugin::_mavCommandResult(int vehicleId, int component, int command, int result, bool noReponseFromVehicle)
{
Q_UNUSED(vehicleId);
@ -446,16 +428,30 @@ void PX4FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoord @@ -446,16 +428,30 @@ void PX4FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoord
return;
}
vehicle->sendMavCommand(vehicle->defaultComponentId(),
MAV_CMD_DO_REPOSITION,
true, // show error is fails
-1.0f,
MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
0.0f,
NAN,
gotoCoord.latitude(),
gotoCoord.longitude(),
vehicle->altitudeAMSL()->rawValue().toFloat());
if (vehicle->capabilityBits() && MAV_PROTOCOL_CAPABILITY_COMMAND_INT) {
vehicle->sendMavCommandInt(vehicle->defaultComponentId(),
MAV_CMD_DO_REPOSITION,
MAV_FRAME_GLOBAL,
true, // show error is fails
-1.0f,
MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
0.0f,
NAN,
gotoCoord.latitude(),
gotoCoord.longitude(),
vehicle->altitudeAMSL()->rawValue().toFloat());
} else {
vehicle->sendMavCommand(vehicle->defaultComponentId(),
MAV_CMD_DO_REPOSITION,
true, // show error is fails
-1.0f,
MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
0.0f,
NAN,
gotoCoord.latitude(),
gotoCoord.longitude(),
vehicle->altitudeAMSL()->rawValue().toFloat());
}
}
void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitudeChange)

1
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h

@ -46,7 +46,6 @@ public: @@ -46,7 +46,6 @@ public:
void guidedModeRTL (Vehicle* vehicle) override;
void guidedModeLand (Vehicle* vehicle) override;
void guidedModeTakeoff (Vehicle* vehicle, double takeoffAltRel) override;
void guidedModeOrbit (Vehicle* vehicle, const QGeoCoordinate& centerCoord = QGeoCoordinate(), double radius = NAN, double velocity = NAN, double altitude = NAN) override;
void guidedModeGotoLocation (Vehicle* vehicle, const QGeoCoordinate& gotoCoord) override;
void guidedModeChangeAltitude (Vehicle* vehicle, double altitudeRel) override;
double minimumTakeoffAltitude (Vehicle* vehicle) override;

32
src/FlightDisplay/FlightDisplayView.qml

@ -509,11 +509,10 @@ QGCView { @@ -509,11 +509,10 @@ QGCView {
z: _panel.z + 4
title: qsTr("Fly")
maxHeight: (_flightVideo.visible ? _flightVideo.y : parent.height) - toolStrip.y
buttonVisible: [ _useChecklist, _guidedController.showTakeoff || !_guidedController.showLand, _guidedController.showLand && !_guidedController.showTakeoff, true, true, true, _guidedController.smartShotsAvailable ]
buttonEnabled: [ _useChecklist && _activeVehicle, _guidedController.showTakeoff, _guidedController.showLand, _guidedController.showRTL, _guidedController.showPause, _anyActionAvailable, _anySmartShotAvailable ]
buttonVisible: [ _useChecklist, _guidedController.showTakeoff || !_guidedController.showLand, _guidedController.showLand && !_guidedController.showTakeoff, true, true, true ]
buttonEnabled: [ _useChecklist && _activeVehicle, _guidedController.showTakeoff, _guidedController.showLand, _guidedController.showRTL, _guidedController.showPause, _anyActionAvailable ]
property bool _anyActionAvailable: _guidedController.showStartMission || _guidedController.showResumeMission || _guidedController.showChangeAlt || _guidedController.showLandAbort
property bool _anySmartShotAvailable: _guidedController.showOrbit
property var _actionModel: [
{
title: _guidedController.startMissionTitle,
@ -546,14 +545,6 @@ QGCView { @@ -546,14 +545,6 @@ QGCView {
visible: _guidedController.showLandAbort
}
]
property var _smartShotModel: [
{
title: _guidedController.orbitTitle,
text: _guidedController.orbitMessage,
action: _guidedController.actionOrbit,
visible: _guidedController.showOrbit
}
]
model: [
{
@ -585,28 +576,15 @@ QGCView { @@ -585,28 +576,15 @@ QGCView {
name: qsTr("Action"),
iconSource: "/res/action.svg",
action: -1
},
/*
No firmware support any smart shots yet
{
name: qsTr("Smart"),
iconSource: "/qmlimages/MapCenter.svg",
action: -1
},
*/
}
]
onClicked: {
guidedActionsController.closeAll()
var action = model[index].action
if (action === -1) {
if (index == 5) {
guidedActionList.model = _actionModel
guidedActionList.visible = true
} else if (index == 6) {
guidedActionList.model = _smartShotModel
guidedActionList.visible = true
}
guidedActionList.model = _actionModel
guidedActionList.visible = true
} else {
_guidedController.confirmAction(action)
}

105
src/FlightDisplay/FlightDisplayViewMap.qml

@ -50,7 +50,6 @@ FlightMap { @@ -50,7 +50,6 @@ FlightMap {
property var _rallyPointController: _planMasterController.rallyPointController
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property var _activeVehicleCoordinate: _activeVehicle ? _activeVehicle.coordinate : QtPositioning.coordinate()
property var _gotoHereCoordinate: QtPositioning.coordinate()
property real _toolButtonTopMargin: parent.height - ScreenTools.availableHeight + (ScreenTools.defaultFontPixelHeight / 2)
property bool _airspaceEnabled: QGroundControl.airmapSupported ? QGroundControl.settingsManager.airMapSettings.enableAirMap.rawValue : false
@ -282,10 +281,19 @@ FlightMap { @@ -282,10 +281,19 @@ FlightMap {
}
}
// GoTo here waypoint
// Camera trigger points
MapItemView {
model: _activeVehicle ? _activeVehicle.cameraTriggerPoints : 0
delegate: CameraTriggerIndicator {
coordinate: object.coordinate
z: QGroundControl.zOrderTopMost
}
}
MapQuickItem {
coordinate: _gotoHereCoordinate
visible: _activeVehicle && _activeVehicle.guidedModeSupported && _gotoHereCoordinate.isValid
id: gotoLocationItem
visible: false
z: QGroundControl.zOrderMapItems
anchorPoint.x: sourceItem.anchorPointX
anchorPoint.y: sourceItem.anchorPointY
@ -295,15 +303,44 @@ FlightMap { @@ -295,15 +303,44 @@ FlightMap {
index: -1
label: qsTr("Goto here", "Goto here waypoint")
}
}
// Camera trigger points
MapItemView {
model: _activeVehicle ? _activeVehicle.cameraTriggerPoints : 0
function show(coord) {
gotoLocationItem.coordinate = coord
gotoLocationItem.visible = true
}
delegate: CameraTriggerIndicator {
coordinate: object.coordinate
z: QGroundControl.zOrderTopMost
function hide() {
gotoLocationItem.visible = false
}
}
QGCMapCircleVisuals {
id: orbitMapCircle
mapControl: parent
mapCircle: _mapCircle
visible: false
property alias center: _mapCircle.center
property real radius: defaultRadius
readonly property real defaultRadius: 30
function show(coord) {
orbitMapCircle.radius = defaultRadius
orbitMapCircle.center = coord
orbitMapCircle.visible = true
}
function hide() {
orbitMapCircle.visible = false
}
Component.onCompleted: guidedActionsController.orbitMapCircle = orbitMapCircle
QGCMapCircle {
id: _mapCircle
interactive: true
radius.rawValue: orbitMapCircle.radius
}
}
@ -311,10 +348,50 @@ FlightMap { @@ -311,10 +348,50 @@ FlightMap {
MouseArea {
anchors.fill: parent
Menu {
id: clickMenu
property var coord
MenuItem {
text: qsTr("Go to location")
visible: guidedActionsController.showGotoLocation
onTriggered: {
gotoLocationItem.show(clickMenu.coord)
orbitMapCircle.hide()
guidedActionsController.confirmAction(guidedActionsController.actionGoto, clickMenu.coord)
}
}
MenuItem {
text: qsTr("Orbit at location")
visible: guidedActionsController.showOrbit
onTriggered: {
orbitMapCircle.show(clickMenu.coord)
gotoLocationItem.hide()
guidedActionsController.confirmAction(guidedActionsController.actionOrbit, clickMenu.coord)
}
}
}
onClicked: {
if (guidedActionsController.showGotoLocation && !guidedActionsController.guidedUIVisible) {
_gotoHereCoordinate = flightMap.toCoordinate(Qt.point(mouse.x, mouse.y), false /* clipToViewPort */)
guidedActionsController.confirmAction(guidedActionsController.actionGoto, _gotoHereCoordinate)
if (guidedActionsController.guidedUIVisible || (!guidedActionsController.showGotoLocation && !guidedActionsController.showOrbit)) {
return
}
orbitMapCircle.hide()
gotoLocationItem.hide()
var clickCoord = flightMap.toCoordinate(Qt.point(mouse.x, mouse.y), false /* clipToViewPort */)
if (guidedActionsController.showGotoLocation && guidedActionsController.showOrbit) {
clickMenu.coord = clickCoord
clickMenu.popup()
} else if (guidedActionsController.showGotoLocation) {
_guidedLocationCoordinate = clickCoord
guidedActionsController.confirmAction(guidedActionsController.actionGoto, clickCoord)
} else if (guidedActionsController.showOrbit) {
orbitMapCircle.show(clickCoord)
guidedActionsController.confirmAction(guidedActionsController.actionOrbit, clickCoord)
}
}
}

5
src/FlightDisplay/GuidedActionConfirm.qml

@ -100,12 +100,13 @@ Rectangle { @@ -100,12 +100,13 @@ Rectangle {
onAccept: {
_root.visible = false
var altitudeChange = 0
if (altitudeSlider.visible) {
_root.actionData = altitudeSlider.getValue()
altitudeChange = altitudeSlider.getAltitudeChangeValue()
altitudeSlider.visible = false
}
hideTrigger = false
guidedController.executeAction(_root.action, _root.actionData)
guidedController.executeAction(_root.action, _root.actionData, altitudeChange)
}
onReject: {

35
src/FlightDisplay/GuidedActionsController.qml

@ -31,6 +31,7 @@ Item { @@ -31,6 +31,7 @@ Item {
property var confirmDialog
property var actionList
property var altitudeSlider
property var orbitMapCircle
readonly property string emergencyStopTitle: qsTr("EMERGENCY STOP")
readonly property string armTitle: qsTr("Arm")
@ -62,9 +63,9 @@ Item { @@ -62,9 +63,9 @@ Item {
readonly property string landMessage: qsTr("Land the vehicle at the current position.")
readonly property string rtlMessage: qsTr("Return to the home position of the vehicle.")
readonly property string changeAltMessage: qsTr("Change the altitude of the vehicle up or down.")
readonly property string gotoMessage: qsTr("Move the vehicle to the location clicked on the map.")
readonly property string gotoMessage: qsTr("Move the vehicle to the specified location.")
property string setWaypointMessage: qsTr("Adjust current waypoint to %1.").arg(_actionData)
readonly property string orbitMessage: qsTr("Orbit the vehicle around the current location.")
readonly property string orbitMessage: qsTr("Orbit the vehicle around the specified location. Warning: WORK IN PROGRESS!")
readonly property string landAbortMessage: qsTr("Abort the landing sequence.")
readonly property string pauseMessage: qsTr("Pause the vehicle at it's current position, adjusting altitude up or down as needed.")
readonly property string mvPauseMessage: qsTr("Pause all vehicles at their current position.")
@ -103,7 +104,7 @@ Item { @@ -103,7 +104,7 @@ Item {
property bool showContinueMission: _guidedActionsEnabled && _missionAvailable && !_missionActive && _vehicleFlying && (_currentMissionIndex < missionController.visualItems.count - 1)
property bool showPause: _guidedActionsEnabled && _vehicleArmed && _activeVehicle.pauseVehicleSupported && _vehicleFlying && !_vehiclePaused
property bool showChangeAlt: _guidedActionsEnabled && _vehicleFlying && _activeVehicle.guidedModeSupported && _vehicleArmed && !_missionActive
property bool showOrbit: _guidedActionsEnabled && !_hideOrbit && _vehicleFlying && _activeVehicle.orbitModeSupported && _vehicleArmed && !_missionActive
property bool showOrbit: _guidedActionsEnabled && !_hideOrbit && _vehicleFlying && _activeVehicle.orbitModeSupported && !_missionActive
property bool showLandAbort: _guidedActionsEnabled && _vehicleFlying && _activeVehicle.fixedWing && _vehicleLanding
property bool showGotoLocation: _guidedActionsEnabled && _vehicleFlying
@ -152,8 +153,16 @@ Item { @@ -152,8 +153,16 @@ Item {
on__GuidedModeSupportedChanged: _outputState()
on__PauseVehicleSupportedChanged: _outputState()
on_CurrentMissionIndexChanged: console.log("_currentMissionIndex", _currentMissionIndex)
on_ResumeMissionIndexChanged: console.log("_resumeMissionIndex", _resumeMissionIndex)
on_CurrentMissionIndexChanged: {
if (__debugGuidedStates) {
console.log("_currentMissionIndex", _currentMissionIndex)
}
}
on_ResumeMissionIndexChanged: {
if (__debugGuidedStates) {
console.log("_resumeMissionIndex", _resumeMissionIndex)
}
}
onShowResumeMissionChanged: {
if (__debugGuidedStates) {
console.log("showResumeMission", showResumeMission)
@ -182,7 +191,8 @@ Item { @@ -182,7 +191,8 @@ Item {
_vehicleWasFlying = true
}
}
property var _actionData
property var _actionData
on_FlightModeChanged: {
_vehiclePaused = _activeVehicle ? _flightMode === _activeVehicle.pauseFlightMode : false
@ -291,6 +301,8 @@ Item { @@ -291,6 +301,8 @@ Item {
confirmDialog.title = orbitTitle
confirmDialog.message = orbitMessage
confirmDialog.hideTrigger = Qt.binding(function() { return !showOrbit })
altitudeSlider.reset()
altitudeSlider.visible = true
break;
case actionLandAbort:
confirmDialog.title = landAbortTitle
@ -327,7 +339,7 @@ Item { @@ -327,7 +339,7 @@ Item {
}
// Executes the specified action
function executeAction(actionCode, actionData) {
function executeAction(actionCode, actionData, actionAltitudeChange) {
var i;
var rgVehicle;
switch (actionCode) {
@ -338,7 +350,7 @@ Item { @@ -338,7 +350,7 @@ Item {
_activeVehicle.guidedModeLand()
break
case actionTakeoff:
_activeVehicle.guidedModeTakeoff(actionData)
_activeVehicle.guidedModeTakeoff(actionAltitudeChange)
break
case actionResumeMission:
case actionResumeMissionUploadFail:
@ -368,7 +380,7 @@ Item { @@ -368,7 +380,7 @@ Item {
_activeVehicle.emergencyStop()
break
case actionChangeAlt:
_activeVehicle.guidedModeChangeAltitude(actionData)
_activeVehicle.guidedModeChangeAltitude(actionAltitudeChange)
break
case actionGoto:
_activeVehicle.guidedModeGotoLocation(actionData)
@ -377,14 +389,15 @@ Item { @@ -377,14 +389,15 @@ Item {
_activeVehicle.setCurrentMissionSequence(actionData)
break
case actionOrbit:
_activeVehicle.guidedModeOrbit()
_activeVehicle.guidedModeOrbit(orbitMapCircle.center, orbitMapCircle.radius, _activeVehicle.altitudeAMSL + actionAltitudeChange)
orbitMapCircle.hide()
break
case actionLandAbort:
_activeVehicle.abortLanding(50) // hardcoded value for climbOutAltitude that is currently ignored
break
case actionPause:
_activeVehicle.pauseVehicle()
_activeVehicle.guidedModeChangeAltitude(actionData)
_activeVehicle.guidedModeChangeAltitude(actionAltitudeChange)
break
case actionMVPause:
rgVehicle = QGroundControl.multiVehicleManager.vehicles

3
src/FlightDisplay/GuidedAltitudeSlider.qml

@ -36,7 +36,8 @@ Rectangle { @@ -36,7 +36,8 @@ Rectangle {
altField.setToMinimumTakeoff()
}
function getValue() {
/// Returns the user specified change in altitude from the current vehicle altitude
function getAltitudeChangeValue() {
return altField.newAltitudeMeters - _vehicleAltitude
}

3
src/FlightMap/MapItems/MissionItemIndicatorDrag.qml

@ -25,6 +25,7 @@ Rectangle { @@ -25,6 +25,7 @@ Rectangle {
z: QGroundControl.zOrderMapItems + 1 // Above item icons
// Properties which must be specific by consumer
property var mapControl ///< Map control which contains this item
property var itemIndicator ///< The mission item indicator to drag around
property var itemCoordinate ///< Coordinate we are updating during drag
@ -51,7 +52,7 @@ Rectangle { @@ -51,7 +52,7 @@ Rectangle {
function liveDrag() {
if (!itemDragger._preventCoordinateBindingLoop && itemDrag.drag.active) {
var point = Qt.point(itemDragger.x + _touchMarginHorizontal + itemIndicator.anchorPoint.x, itemDragger.y + _touchMarginVertical + itemIndicator.anchorPoint.y)
var coordinate = map.toCoordinate(point, false /* clipToViewPort */)
var coordinate = mapControl.toCoordinate(point, false /* clipToViewPort */)
itemDragger._preventCoordinateBindingLoop = true
coordinate.altitude = itemCoordinate.altitude
itemCoordinate = coordinate

8
src/FollowMe/FollowMe.cc

@ -84,9 +84,9 @@ void FollowMe::_settingsChanged() @@ -84,9 +84,9 @@ void FollowMe::_settingsChanged()
void FollowMe::_enable()
{
connect(_toolbox->qgcPositionManager(),
SIGNAL(positionInfoUpdated(QGeoPositionInfo)),
&QGCPositionManager::positionInfoUpdated,
this,
SLOT(_setGPSLocation(QGeoPositionInfo)));
&FollowMe::_setGPSLocation);
_gcsMotionReportTimer.setInterval(_toolbox->qgcPositionManager()->updateInterval());
_gcsMotionReportTimer.start();
}
@ -94,9 +94,9 @@ void FollowMe::_enable() @@ -94,9 +94,9 @@ void FollowMe::_enable()
void FollowMe::_disable()
{
disconnect(_toolbox->qgcPositionManager(),
SIGNAL(positionInfoUpdated(QGeoPositionInfo)),
&QGCPositionManager::positionInfoUpdated,
this,
SLOT(_setGPSLocation(QGeoPositionInfo)));
&FollowMe::_setGPSLocation);
_gcsMotionReportTimer.stop();
}

8
src/MissionManager/ComplexMissionItem.h

@ -32,9 +32,6 @@ public: @@ -32,9 +32,6 @@ public:
/// Signals boundingCubeChanged
virtual QGCGeoBoundingCube boundingCube(void) const { return QGCGeoBoundingCube(); }
/// @return Amount of additional time delay in seconds needed to fly the complex item
virtual double additionalTimeDelay(void) const { return 0; }
/// Load the complex mission item from Json
/// @param complexObject Complex mission item json object
/// @param sequenceNumber Sequence number for first MISSION_ITEM in survey
@ -51,11 +48,14 @@ public: @@ -51,11 +48,14 @@ public:
/// This mission item attribute specifies the type of the complex item.
static const char* jsonComplexItemTypeKey;
// Overrides from VisualMissionItem
double additionalTimeDelay(void) const final { return 0; }
signals:
void complexDistanceChanged (void);
void boundingCubeChanged (void);
void greatestDistanceToChanged (void);
void additionalTimeDelayChanged (void);
};
#endif

40
src/MissionManager/MissionController.cc

@ -216,6 +216,17 @@ void MissionController::loadFromVehicle(void) @@ -216,6 +216,17 @@ void MissionController::loadFromVehicle(void)
}
}
void MissionController::_warnIfTerrainFrameUsed(void)
{
for (int i=1; i<_visualItems->count(); i++) {
SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(_visualItems->get(i));
if (simpleItem && simpleItem->altitudeMode() == SimpleMissionItem::AltitudeTerrainFrame) {
qgcApp()->showMessage(tr("Warning: You are using MAV_FRAME_GLOBAL_TERRAIN_ALT in a mission. %1 does not support sending terrain tiles to vehicle.").arg(qgcApp()->applicationName()));
break;
}
}
}
void MissionController::sendToVehicle(void)
{
if (_masterController->offline()) {
@ -224,6 +235,7 @@ void MissionController::sendToVehicle(void) @@ -224,6 +235,7 @@ void MissionController::sendToVehicle(void)
qCWarning(MissionControllerLog) << "MissionControllerLog::sendToVehicle called while syncInProgress";
} else {
qCDebug(MissionControllerLog) << "MissionControllerLog::sendToVehicle";
_warnIfTerrainFrameUsed();
if (_visualItems->count() == 1) {
// This prevents us from sending a possibly bogus home position to the vehicle
QmlObjectListModel emptyModel;
@ -1200,26 +1212,6 @@ void MissionController::_addCruiseTime(double cruiseTime, double cruiseDistance, @@ -1200,26 +1212,6 @@ void MissionController::_addCruiseTime(double cruiseTime, double cruiseDistance,
_updateBatteryInfo(waypointIndex);
}
/// Adds additional time to a mission as specified by the command
void MissionController::_addCommandTimeDelay(SimpleMissionItem* simpleItem, bool vtolInHover)
{
double seconds = 0;
if (!simpleItem) {
return;
}
// This routine is currently quite minimal and only handles the simple cases.
switch ((int)simpleItem->command()) {
case MAV_CMD_NAV_WAYPOINT:
case MAV_CMD_CONDITION_DELAY:
seconds = simpleItem->missionItem().param1();
break;
}
_addTimeDistance(vtolInHover, 0, 0, seconds, 0, -1);
}
/// Adds the specified time to the appropriate hover or cruise time values.
/// @param vtolInHover true: vtol is currrent in hover mode
/// @param hoverTime Amount of time tp add to hover
@ -1374,8 +1366,7 @@ void MissionController::_recalcMissionFlightStatus() @@ -1374,8 +1366,7 @@ void MissionController::_recalcMissionFlightStatus()
}
}
// Check for command specific time delays
_addCommandTimeDelay(simpleItem, vtolInHover);
_addTimeDistance(vtolInHover, 0, 0, item->additionalTimeDelay(), 0, -1);
if (item->specifiesCoordinate()) {
// Keep track of the min/max altitude for all waypoints so we can show altitudes as a percentage
@ -1426,8 +1417,7 @@ void MissionController::_recalcMissionFlightStatus() @@ -1426,8 +1417,7 @@ void MissionController::_recalcMissionFlightStatus()
double hoverTime = distance / _missionFlightStatus.hoverSpeed;
double cruiseTime = distance / _missionFlightStatus.cruiseSpeed;
double extraTime = complexItem->additionalTimeDelay();
_addTimeDistance(vtolInHover, hoverTime, cruiseTime, extraTime, distance, item->sequenceNumber());
_addTimeDistance(vtolInHover, hoverTime, cruiseTime, 0, distance, item->sequenceNumber());
}
item->setMissionFlightStatus(_missionFlightStatus);
@ -1619,6 +1609,7 @@ void MissionController::_initVisualItem(VisualMissionItem* visualItem) @@ -1619,6 +1609,7 @@ void MissionController::_initVisualItem(VisualMissionItem* visualItem)
connect(visualItem, &VisualMissionItem::specifiedGimbalYawChanged, this, &MissionController::_recalcMissionFlightStatus);
connect(visualItem, &VisualMissionItem::specifiedGimbalPitchChanged, this, &MissionController::_recalcMissionFlightStatus);
connect(visualItem, &VisualMissionItem::terrainAltitudeChanged, this, &MissionController::_recalcMissionFlightStatus);
connect(visualItem, &VisualMissionItem::additionalTimeDelayChanged, this, &MissionController::_recalcMissionFlightStatus);
connect(visualItem, &VisualMissionItem::lastSequenceNumberChanged, this, &MissionController::_recalcSequence);
if (visualItem->isSimpleItem()) {
@ -1634,7 +1625,6 @@ void MissionController::_initVisualItem(VisualMissionItem* visualItem) @@ -1634,7 +1625,6 @@ void MissionController::_initVisualItem(VisualMissionItem* visualItem)
if (complexItem) {
connect(complexItem, &ComplexMissionItem::complexDistanceChanged, this, &MissionController::_recalcMissionFlightStatus);
connect(complexItem, &ComplexMissionItem::greatestDistanceToChanged, this, &MissionController::_recalcMissionFlightStatus);
connect(complexItem, &ComplexMissionItem::additionalTimeDelayChanged, this, &MissionController::_recalcMissionFlightStatus);
} else {
qWarning() << "ComplexMissionItem not found";
}

2
src/MissionManager/MissionController.h

@ -263,9 +263,9 @@ private: @@ -263,9 +263,9 @@ private:
bool _loadItemsFromJson(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString);
void _initLoadedVisualItems(QmlObjectListModel* loadedVisualItems);
void _addWaypointLineSegment(CoordVectHashTable& prevItemPairHashTable, VisualItemPair& pair);
void _addCommandTimeDelay(SimpleMissionItem* simpleItem, bool vtolInHover);
void _addTimeDistance(bool vtolInHover, double hoverTime, double cruiseTime, double extraTime, double distance, int seqNum);
int _insertComplexMissionItemWorker(ComplexMissionItem* complexItem, int i);
void _warnIfTerrainFrameUsed(void);
private:
MissionManager* _missionManager;

107
src/MissionManager/QGCMapCircleVisuals.qml

@ -27,52 +27,60 @@ Item { @@ -27,52 +27,60 @@ Item {
property bool interactive: mapCircle.interactive /// true: user can manipulate polygon
property color interiorColor: "transparent"
property real interiorOpacity: 1
property int borderWidth: 0
property color borderColor: "black"
property int borderWidth: 2
property color borderColor: "orange"
property var _circleComponent
property var _centerDragHandleComponent
property var _dragHandlesComponent
function addVisuals() {
_circleComponent = circleComponent.createObject(mapControl)
mapControl.addMapItem(_circleComponent)
if (!_circleComponent) {
_circleComponent = circleComponent.createObject(mapControl)
mapControl.addMapItem(_circleComponent)
}
}
function removeVisuals() {
_circleComponent.destroy()
if (_circleComponent) {
_circleComponent.destroy()
_circleComponent = undefined
}
}
function addHandles() {
if (!_centerDragHandleComponent) {
_centerDragHandleComponent = centerDragHandleComponent.createObject(mapControl)
function addDragHandles() {
if (!_dragHandlesComponent) {
_dragHandlesComponent = dragHandlesComponent.createObject(mapControl)
}
}
function removeHandles() {
if (_centerDragHandleComponent) {
_centerDragHandleComponent.destroy()
_centerDragHandleComponent = undefined
function removeDragHandles() {
if (_dragHandlesComponent) {
_dragHandlesComponent.destroy()
_dragHandlesComponent = undefined
}
}
onInteractiveChanged: {
if (interactive) {
addHandles()
function updateInternalComponents() {
if (visible) {
addVisuals()
if (interactive) {
addDragHandles()
} else {
removeDragHandles()
}
} else {
removeHandles()
removeVisuals()
removeDragHandles()
}
}
Component.onCompleted: {
addVisuals()
if (interactive) {
addHandles()
}
}
Component.onCompleted: updateInternalComponents()
onInteractiveChanged: updateInternalComponents()
onVisibleChanged: updateInternalComponents()
Component.onDestruction: {
removeVisuals()
removeHandles()
removeDragHandles()
}
Component {
@ -112,27 +120,58 @@ Item { @@ -112,27 +120,58 @@ Item {
id: centerDragAreaComponent
MissionItemIndicatorDrag {
onItemCoordinateChanged: mapCircle.center = itemCoordinate
mapControl: _root.mapControl
onItemCoordinateChanged: mapCircle.center = itemCoordinate
}
}
Component {
id: centerDragHandleComponent
id: radiusDragAreaComponent
MissionItemIndicatorDrag {
mapControl: _root.mapControl
onItemCoordinateChanged: mapCircle.radius.rawValue = mapCircle.center.distanceTo(itemCoordinate)
}
}
Component {
id: dragHandlesComponent
Item {
property var dragHandle
property var dragArea
property var centerDragHandle
property var centerDragArea
property var radiusDragHandle
property var radiusDragArea
property var radiusDragCoord: QtPositioning.coordinate()
property var circleCenterCoord: mapCircle.center
property real circleRadius: mapCircle.radius.rawValue
function calcRadiusDragCoord() {
radiusDragCoord = mapCircle.center.atDistanceAndAzimuth(circleRadius, 90)
}
onCircleCenterCoordChanged: calcRadiusDragCoord()
onCircleRadiusChanged: calcRadiusDragCoord()
Component.onCompleted: {
dragHandle = dragHandleComponent.createObject(mapControl)
dragHandle.coordinate = Qt.binding(function() { return mapCircle.center })
mapControl.addMapItem(dragHandle)
dragArea = centerDragAreaComponent.createObject(mapControl, { "itemIndicator": dragHandle, "itemCoordinate": mapCircle.center })
calcRadiusDragCoord()
radiusDragHandle = dragHandleComponent.createObject(mapControl)
radiusDragHandle.coordinate = Qt.binding(function() { return radiusDragCoord })
mapControl.addMapItem(radiusDragHandle)
radiusDragArea = radiusDragAreaComponent.createObject(mapControl, { "itemIndicator": radiusDragHandle, "itemCoordinate": radiusDragCoord })
centerDragHandle = dragHandleComponent.createObject(mapControl)
centerDragHandle.coordinate = Qt.binding(function() { return circleCenterCoord })
mapControl.addMapItem(centerDragHandle)
centerDragArea = centerDragAreaComponent.createObject(mapControl, { "itemIndicator": centerDragHandle, "itemCoordinate": circleCenterCoord })
}
Component.onDestruction: {
dragHandle.destroy()
dragArea.destroy()
centerDragHandle.destroy()
centerDragArea.destroy()
radiusDragHandle.destroy()
radiusDragArea.destroy()
}
}
}

27
src/MissionManager/SimpleMissionItem.cc

@ -205,6 +205,8 @@ void SimpleMissionItem::_connectSignals(void) @@ -205,6 +205,8 @@ void SimpleMissionItem::_connectSignals(void)
connect(&_missionItem._param6Fact, &Fact::valueChanged, this, &SimpleMissionItem::_sendCoordinateChanged);
connect(&_missionItem._param7Fact, &Fact::valueChanged, this, &SimpleMissionItem::_sendCoordinateChanged);
connect(&_missionItem._param1Fact, &Fact::valueChanged, this, &SimpleMissionItem::_possibleAdditionalTimeDelayChanged);
// The following changes may also change friendlyEditAllowed
connect(&_missionItem._autoContinueFact, &Fact::valueChanged, this, &SimpleMissionItem::_sendFriendlyEditAllowedChanged);
connect(&_missionItem._commandFact, &Fact::valueChanged, this, &SimpleMissionItem::_sendFriendlyEditAllowedChanged);
@ -951,3 +953,28 @@ void SimpleMissionItem::setAltitudeMode(AltitudeMode altitudeMode) @@ -951,3 +953,28 @@ void SimpleMissionItem::setAltitudeMode(AltitudeMode altitudeMode)
emit altitudeModeChanged();
}
}
double SimpleMissionItem::additionalTimeDelay(void) const
{
switch (command()) {
case MAV_CMD_NAV_WAYPOINT:
case MAV_CMD_CONDITION_DELAY:
case MAV_CMD_NAV_DELAY:
return missionItem().param1();
default:
return 0;
}
}
void SimpleMissionItem::_possibleAdditionalTimeDelayChanged(void)
{
switch (command()) {
case MAV_CMD_NAV_WAYPOINT:
case MAV_CMD_CONDITION_DELAY:
case MAV_CMD_NAV_DELAY:
emit additionalTimeDelayChanged();
break;
}
return;
}

24
src/MissionManager/SimpleMissionItem.h

@ -122,6 +122,7 @@ public: @@ -122,6 +122,7 @@ public:
void applyNewAltitude (double newAltitude) final;
void setMissionFlightStatus (MissionController::MissionFlightStatus_t& missionFlightStatus) final;
bool readyForSave (void) const final;
double additionalTimeDelay (void) const final;
bool coordinateHasRelativeAltitude (void) const final { return _missionItem.relativeAltitude(); }
bool exitCoordinateHasRelativeAltitude (void) const final { return coordinateHasRelativeAltitude(); }
@ -147,17 +148,18 @@ signals: @@ -147,17 +148,18 @@ signals:
void supportsTerrainFrameChanged(void);
private slots:
void _setDirty (void);
void _sectionDirtyChanged (bool dirty);
void _sendCommandChanged (void);
void _sendCoordinateChanged (void);
void _sendFriendlyEditAllowedChanged(void);
void _altitudeChanged (void);
void _altitudeModeChanged (void);
void _terrainAltChanged (void);
void _updateLastSequenceNumber (void);
void _rebuildFacts (void);
void _rebuildTextFieldFacts (void);
void _setDirty (void);
void _sectionDirtyChanged (bool dirty);
void _sendCommandChanged (void);
void _sendCoordinateChanged (void);
void _sendFriendlyEditAllowedChanged (void);
void _altitudeChanged (void);
void _altitudeModeChanged (void);
void _terrainAltChanged (void);
void _updateLastSequenceNumber (void);
void _rebuildFacts (void);
void _rebuildTextFieldFacts (void);
void _possibleAdditionalTimeDelayChanged(void);
private:
void _connectSignals (void);

22
src/MissionManager/StructureScanComplexItem.cc

@ -63,9 +63,11 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, bool flyVie @@ -63,9 +63,11 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, bool flyVie
connect(&_altitudeFact, &Fact::valueChanged, this, &StructureScanComplexItem::_updateCoordinateAltitudes);
connect(&_structurePolygon, &QGCMapPolygon::dirtyChanged, this, &StructureScanComplexItem::_polygonDirtyChanged);
connect(&_structurePolygon, &QGCMapPolygon::countChanged, this, &StructureScanComplexItem::_polygonCountChanged);
connect(&_structurePolygon, &QGCMapPolygon::pathChanged, this, &StructureScanComplexItem::_rebuildFlightPolygon);
connect(&_structurePolygon, &QGCMapPolygon::countChanged, this, &StructureScanComplexItem::_updateLastSequenceNumber);
connect(&_layersFact, &Fact::valueChanged, this, &StructureScanComplexItem::_updateLastSequenceNumber);
connect(&_flightPolygon, &QGCMapPolygon::pathChanged, this, &StructureScanComplexItem::_flightPathChanged);
connect(_cameraCalc.distanceToSurface(), &Fact::valueChanged, this, &StructureScanComplexItem::_rebuildFlightPolygon);
@ -108,19 +110,23 @@ void StructureScanComplexItem::_clearInternal(void) @@ -108,19 +110,23 @@ void StructureScanComplexItem::_clearInternal(void)
emit lastSequenceNumberChanged(lastSequenceNumber());
}
void StructureScanComplexItem::_polygonCountChanged(int count)
void StructureScanComplexItem::_updateLastSequenceNumber(void)
{
Q_UNUSED(count);
emit lastSequenceNumberChanged(lastSequenceNumber());
}
int StructureScanComplexItem::lastSequenceNumber(void) const
{
return _sequenceNumber +
(_layersFact.rawValue().toInt() *
((_flightPolygon.count() + 1) + // 1 waypoint for each polygon vertex + 1 to go back to first polygon vertex for each layer
2)) + // Camera trigger start/stop for each layer
2; // ROI_WPNEXT_OFFSET and ROI_NONE commands
// Each structure layer contains:
// 1 waypoint for each polygon vertex + 1 to go back to first polygon vertex for each layer
// Two commands for camera trigger start/stop
int layerItemCount = _flightPolygon.count() + 1 + 2;
int multiLayerItemCount = layerItemCount * _layersFact.rawValue().toInt();
int itemCount = multiLayerItemCount + 2; // +2 for ROI_WPNEXT_OFFSET and ROI_NONE commands
return _sequenceNumber + itemCount - 1;
}
void StructureScanComplexItem::setDirty(bool dirty)

2
src/MissionManager/StructureScanComplexItem.h

@ -107,13 +107,13 @@ signals: @@ -107,13 +107,13 @@ signals:
private slots:
void _setDirty(void);
void _polygonDirtyChanged (bool dirty);
void _polygonCountChanged (int count);
void _flightPathChanged (void);
void _clearInternal (void);
void _updateCoordinateAltitudes (void);
void _rebuildFlightPolygon (void);
void _recalcCameraShots (void);
void _recalcLayerInfo (void);
void _updateLastSequenceNumber (void);
private:
void _setExitCoordinate(const QGeoCoordinate& coordinate);

2
src/MissionManager/StructureScanComplexItemTest.cc

@ -134,6 +134,6 @@ void StructureScanComplexItemTest::_testItemCount(void) @@ -134,6 +134,6 @@ void StructureScanComplexItemTest::_testItemCount(void)
_initItem();
_structureScanItem->appendMissionItems(items, this);
QCOMPARE(items.count(), _structureScanItem->lastSequenceNumber());
QCOMPARE(items.count() - 1, _structureScanItem->lastSequenceNumber());
}

102
src/MissionManager/SurveyComplexItem.cc

@ -442,108 +442,6 @@ void SurveyComplexItem::_adjustTransectsToEntryPointLocation(QList<QList<QGeoCoo @@ -442,108 +442,6 @@ void SurveyComplexItem::_adjustTransectsToEntryPointLocation(QList<QList<QGeoCoo
qCDebug(SurveyComplexItemLog) << "_adjustTransectsToEntryPointLocation Modified entry point:entryLocation" << transects.first().first() << _entryPoint;
}
#if 0
void SurveyComplexItem::_generateGrid(void)
{
if (_ignoreRecalc) {
return;
}
if (_mapPolygon.count() < 3 || _gridSpacingFact.rawValue().toDouble() <= 0) {
_clearInternal();
return;
}
_simpleGridPoints.clear();
_transectSegments.clear();
_reflyTransectSegments.clear();
_additionalFlightDelaySeconds = 0;
QList<QPointF> polygonPoints;
QList<QList<QPointF>> transectSegments;
// Convert polygon to NED
QGeoCoordinate tangentOrigin = _mapPolygon.pathModel().value<QGCQGeoCoordinate*>(0)->coordinate();
qCDebug(SurveyComplexItemLog) << "Convert polygon to NED - tangentOrigin" << tangentOrigin;
for (int i=0; i<_mapPolygon.count(); i++) {
double y, x, down;
QGeoCoordinate vertex = _mapPolygon.pathModel().value<QGCQGeoCoordinate*>(i)->coordinate();
if (i == 0) {
// This avoids a nan calculation that comes out of convertGeoToNed
x = y = 0;
} else {
convertGeoToNed(vertex, tangentOrigin, &y, &x, &down);
}
polygonPoints += QPointF(x, y);
qCDebug(SurveyComplexItemLog) << "vertex:x:y" << vertex << polygonPoints.last().x() << polygonPoints.last().y();
}
double coveredArea = 0.0;
for (int i=0; i<polygonPoints.count(); i++) {
if (i != 0) {
coveredArea += polygonPoints[i - 1].x() * polygonPoints[i].y() - polygonPoints[i].x() * polygonPoints[i -1].y();
} else {
coveredArea += polygonPoints.last().x() * polygonPoints[i].y() - polygonPoints[i].x() * polygonPoints.last().y();
}
}
_setCoveredArea(0.5 * fabs(coveredArea));
// Generate grid
int cameraShots = 0;
cameraShots += _gridGenerator(polygonPoints, transectSegments, false /* refly */);
_convertTransectToGeo(transectSegments, tangentOrigin, _transectSegments);
_adjustTransectsToEntryPointLocation(_transectSegments);
_appendGridPointsFromTransects(_transectSegments);
if (_refly90Degrees) {
transectSegments.clear();
cameraShots += _gridGenerator(polygonPoints, transectSegments, true /* refly */);
_convertTransectToGeo(transectSegments, tangentOrigin, _reflyTransectSegments);
_optimizeTransectsForShortestDistance(_transectSegments.last().last(), _reflyTransectSegments);
_appendGridPointsFromTransects(_reflyTransectSegments);
}
// Calc survey distance
double surveyDistance = 0.0;
for (int i=1; i<_simpleGridPoints.count(); i++) {
QGeoCoordinate coord1 = _simpleGridPoints[i-1].value<QGeoCoordinate>();
QGeoCoordinate coord2 = _simpleGridPoints[i].value<QGeoCoordinate>();
surveyDistance += coord1.distanceTo(coord2);
}
_setSurveyDistance(surveyDistance);
if (cameraShots == 0 && _triggerCamera()) {
cameraShots = (int)floor(surveyDistance / _triggerDistance());
// Take into account immediate camera trigger at waypoint entry
cameraShots++;
}
_setCameraShots(cameraShots);
if (_hoverAndCaptureEnabled()) {
_additionalFlightDelaySeconds = cameraShots * _hoverAndCaptureDelaySeconds;
}
emit additionalTimeDelayChanged();
emit gridPointsChanged();
// Determine command count for lastSequenceNumber
_missionCommandCount = _calcMissionCommandCount(_transectSegments);
_missionCommandCount += _calcMissionCommandCount(_reflyTransectSegments);
emit lastSequenceNumberChanged(lastSequenceNumber());
// Set exit coordinate
if (_simpleGridPoints.count()) {
QGeoCoordinate coordinate = _simpleGridPoints.first().value<QGeoCoordinate>();
coordinate.setAltitude(_gridAltitudeFact.rawValue().toDouble());
setCoordinate(coordinate);
QGeoCoordinate exitCoordinate = _simpleGridPoints.last().value<QGeoCoordinate>();
exitCoordinate.setAltitude(_gridAltitudeFact.rawValue().toDouble());
_setExitCoordinate(exitCoordinate);
}
setDirty(true);
}
#endif
QPointF SurveyComplexItem::_rotatePoint(const QPointF& point, const QPointF& origin, double angle)
{
QPointF rotated;

4
src/MissionManager/VisualMissionItem.h

@ -151,6 +151,9 @@ public: @@ -151,6 +151,9 @@ public:
/// Adjust the altitude of the item if appropriate to the new altitude.
virtual void applyNewAltitude(double newAltitude) = 0;
/// @return Amount of additional time delay in seconds needed to fly this item
virtual double additionalTimeDelay(void) const = 0;
double missionGimbalYaw (void) const { return _missionGimbalYaw; }
double missionVehicleYaw (void) const { return _missionVehicleYaw; }
void setMissionVehicleYaw(double vehicleYaw);
@ -184,6 +187,7 @@ signals: @@ -184,6 +187,7 @@ signals:
void missionGimbalYawChanged (double missionGimbalYaw);
void missionVehicleYawChanged (double missionVehicleYaw);
void terrainAltitudeChanged (double terrainAltitude);
void additionalTimeDelayChanged (void);
void coordinateHasRelativeAltitudeChanged (bool coordinateHasRelativeAltitude);
void exitCoordinateHasRelativeAltitudeChanged (bool exitCoordinateHasRelativeAltitude);

2
src/PlanView/MissionItemStatus.qml

@ -73,6 +73,7 @@ Rectangle { @@ -73,6 +73,7 @@ Rectangle {
visible: display
property real availableHeight: height - indicator.height
property bool _coordValid: object.coordinate.isValid
property bool _terrainAvailable: !isNaN(object.terrainPercent)
property real _terrainPercent: _terrainAvailable ? object.terrainPercent : 1
@ -85,6 +86,7 @@ Rectangle { @@ -85,6 +86,7 @@ Rectangle {
width: indicator.width
height: _terrainAvailable ? Math.max(availableHeight * _terrainPercent, 1) : parent.height
color: _terrainAvailable ? (_terrainPercent > object.altPercent ? "red": qgcPal.text) : "yellow"
visible: _coordValid
}
MissionItemIndexLabel {

2
src/QGCApplication.cc

@ -77,6 +77,7 @@ @@ -77,6 +77,7 @@
#include "FollowMe.h"
#include "MissionCommandTree.h"
#include "QGCMapPolygon.h"
#include "QGCMapCircle.h"
#include "ParameterManager.h"
#include "SettingsManager.h"
#include "QGCCorePlugin.h"
@ -392,6 +393,7 @@ void QGCApplication::_initCommon(void) @@ -392,6 +393,7 @@ void QGCApplication::_initCommon(void)
qmlRegisterType<LogDownloadController> ("QGroundControl.Controllers", 1, 0, "LogDownloadController");
qmlRegisterType<SyslinkComponentController> ("QGroundControl.Controllers", 1, 0, "SyslinkComponentController");
qmlRegisterType<EditPositionDialogController> ("QGroundControl.Controllers", 1, 0, "EditPositionDialogController");
qmlRegisterType<QGCMapCircle> ("QGroundControl.FlightMap", 1, 0, "QGCMapCircle");
#ifndef __mobile__
qmlRegisterType<ViewWidgetController> ("QGroundControl.Controllers", 1, 0, "ViewWidgetController");
qmlRegisterType<CustomCommandWidgetController> ("QGroundControl.Controllers", 1, 0, "CustomCommandWidgetController");

2
src/QmlControls/DropPanel.qml

@ -162,8 +162,6 @@ Item { @@ -162,8 +162,6 @@ Item {
Loader {
id: panelLoader
x: _dropMargin
y: _dropMargin
onHeightChanged: _calcPositions()
onWidthChanged: _calcPositions()

2
src/QmlControls/MissionItemIndexLabel.qml

@ -109,7 +109,7 @@ Canvas { @@ -109,7 +109,7 @@ Canvas {
verticalAlignment: Text.AlignVCenter
color: "white"
font.pointSize: ScreenTools.defaultFontPointSize
fontSizeMode: Text.HorizontalFit
fontSizeMode: Text.Fit
text: _index
}
}

10
src/QmlControls/QGCComboBox.qml

@ -21,6 +21,8 @@ Button { @@ -21,6 +21,8 @@ Button {
property var _qgcPal: QGCPalette { colorGroupEnabled: enabled }
property int _horizontalPadding: ScreenTools.defaultFontPixelWidth
property int _verticalPadding: Math.round(ScreenTools.defaultFontPixelHeight / 2)
property real _dropImageWidth: ScreenTools.defaultFontPixelHeight / 2
property real _dropImageMargin: _dropImageWidth / 2
property var __popup: popup
signal activated(int index)
@ -44,10 +46,10 @@ Button { @@ -44,10 +46,10 @@ Button {
QGCColoredImage {
id: image
width: ScreenTools.defaultFontPixelHeight / 2
height: width
width: _dropImageWidth
height: _dropImageWidth
anchors.verticalCenter: parent.verticalCenter
anchors.rightMargin: width / 2
anchors.rightMargin: _dropImageMargin
anchors.right: parent.right
source: "/qmlimages/arrow-down.png"
color: control._qgcPal.buttonText
@ -56,7 +58,7 @@ Button { @@ -56,7 +58,7 @@ Button {
/*! This defines the label of the button. */
label: Item {
implicitWidth: text.implicitWidth
implicitWidth: text.implicitWidth + _dropImageWidth
implicitHeight: text.implicitHeight
baselineOffset: text.y + text.baselineOffset

8
src/QtLocationPlugin/QGCMapEngine.cpp

@ -187,13 +187,13 @@ QGCMapEngine::_wipeOldCaches() @@ -187,13 +187,13 @@ QGCMapEngine::_wipeOldCaches()
#ifdef __mobile__
oldCacheDir = QStandardPaths::writableLocation(QStandardPaths::AppDataLocation) + QLatin1String("/QGCMapCache55");
#else
oldCacheDir = QStandardPaths::writableLocation(QStandardPaths::GenericCacheLocation) + QLatin1String("/QGCMapCache55");
oldCacheDir = QStandardPaths::writableLocation(QStandardPaths::GenericCacheLocation) + QStringLiteral("/QGCMapCache55");
#endif
_checkWipeDirectory(oldCacheDir);
#ifdef __mobile__
oldCacheDir = QStandardPaths::writableLocation(QStandardPaths::AppDataLocation) + QLatin1String("/QGCMapCache100");
#else
oldCacheDir = QStandardPaths::writableLocation(QStandardPaths::GenericCacheLocation) + QLatin1String("/QGCMapCache100");
oldCacheDir = QStandardPaths::writableLocation(QStandardPaths::GenericCacheLocation) + QStringLiteral("/QGCMapCache100");
#endif
_checkWipeDirectory(oldCacheDir);
}
@ -208,11 +208,11 @@ QGCMapEngine::init() @@ -208,11 +208,11 @@ QGCMapEngine::init()
#ifdef __mobile__
QString cacheDir = QStandardPaths::writableLocation(QStandardPaths::AppDataLocation) + QLatin1String("/QGCMapCache" CACHE_PATH_VERSION);
#else
QString cacheDir = QStandardPaths::writableLocation(QStandardPaths::GenericCacheLocation) + QLatin1String("/QGCMapCache" CACHE_PATH_VERSION);
QString cacheDir = QStandardPaths::writableLocation(QStandardPaths::GenericCacheLocation) + QStringLiteral("/QGCMapCache" CACHE_PATH_VERSION);
#endif
if(!QDir::root().mkpath(cacheDir)) {
qWarning() << "Could not create mapping disk cache directory: " << cacheDir;
cacheDir = QDir::homePath() + QLatin1String("/.qgcmapscache/");
cacheDir = QDir::homePath() + QStringLiteral("/.qgcmapscache/");
if(!QDir::root().mkpath(cacheDir)) {
qWarning() << "Could not create mapping disk cache directory: " << cacheDir;
cacheDir.clear();

4
src/QtLocationPlugin/QGCTileCacheWorker.cpp

@ -30,8 +30,8 @@ @@ -30,8 +30,8 @@
#include "time.h"
const char* kDefaultSet = "Default Tile Set";
const QString kSession = QLatin1String("QGeoTileWorkerSession");
const QString kExportSession = QLatin1String("QGeoTileExportSession");
const QString kSession = QStringLiteral("QGeoTileWorkerSession");
const QString kExportSession = QStringLiteral("QGeoTileExportSession");
QGC_LOGGING_CATEGORY(QGCTileCacheLog, "QGCTileCacheLog")

2
src/QtLocationPlugin/QGeoCodeReplyQGC.cpp

@ -158,7 +158,7 @@ JasonMonger kMonger; @@ -158,7 +158,7 @@ JasonMonger kMonger;
QGeoCodeReplyQGC::QGeoCodeReplyQGC(QNetworkReply *reply, QObject *parent)
: QGeoCodeReply(parent), m_reply(reply)
{
connect(m_reply, SIGNAL(finished()), this, SLOT(networkReplyFinished()));
connect(m_reply, &QNetworkReply::finished, this, &QGeoCodeReplyQGC::networkReplyFinished);
connect(m_reply, SIGNAL(error(QNetworkReply::NetworkError)),
this, SLOT(networkReplyError(QNetworkReply::NetworkError)));

4
src/QtLocationPlugin/QGeoCodingManagerEngineQGC.cpp

@ -125,7 +125,7 @@ QGeoCodeReply *QGeoCodingManagerEngineQGC::geocode(const QString &address, int l @@ -125,7 +125,7 @@ QGeoCodeReply *QGeoCodingManagerEngineQGC::geocode(const QString &address, int l
QGeoCodeReplyQGC *geocodeReply = new QGeoCodeReplyQGC(reply);
connect(geocodeReply, SIGNAL(finished()), this, SLOT(replyFinished()));
connect(geocodeReply, &QGeoCodeReply::finished, this, &QGeoCodingManagerEngineQGC::replyFinished);
connect(geocodeReply, SIGNAL(error(QGeoCodeReply::Error,QString)),
this, SLOT(replyError(QGeoCodeReply::Error,QString)));
@ -156,7 +156,7 @@ QGeoCodeReply *QGeoCodingManagerEngineQGC::reverseGeocode(const QGeoCoordinate & @@ -156,7 +156,7 @@ QGeoCodeReply *QGeoCodingManagerEngineQGC::reverseGeocode(const QGeoCoordinate &
QGeoCodeReplyQGC *geocodeReply = new QGeoCodeReplyQGC(reply);
connect(geocodeReply, SIGNAL(finished()), this, SLOT(replyFinished()));
connect(geocodeReply, &QGeoCodeReply::finished, this, &QGeoCodingManagerEngineQGC::replyFinished);
connect(geocodeReply, SIGNAL(error(QGeoCodeReply::Error,QString)),
this, SLOT(replyError(QGeoCodeReply::Error,QString)));

2
src/QtLocationPlugin/QGeoMapReplyQGC.cpp

@ -189,7 +189,7 @@ QGeoTiledMapReplyQGC::cacheError(QGCMapTask::TaskType type, QString /*errorStrin @@ -189,7 +189,7 @@ QGeoTiledMapReplyQGC::cacheError(QGCMapTask::TaskType type, QString /*errorStrin
#endif
_reply = _networkManager->get(_request);
_reply->setParent(0);
connect(_reply, SIGNAL(finished()), this, SLOT(networkReplyFinished()));
connect(_reply, &QNetworkReply::finished, this, &QGeoTiledMapReplyQGC::networkReplyFinished);
connect(_reply, SIGNAL(error(QNetworkReply::NetworkError)), this, SLOT(networkReplyError(QNetworkReply::NetworkError)));
#if !defined(__mobile__)
_networkManager->setProxy(proxy);

2
src/QtLocationPlugin/QGeoTiledMappingManagerEngineQGC.cpp

@ -216,7 +216,7 @@ QGeoTiledMappingManagerEngineQGC::_setCache(const QVariantMap &parameters) @@ -216,7 +216,7 @@ QGeoTiledMappingManagerEngineQGC::_setCache(const QVariantMap &parameters)
if(!QFileInfo(cacheDir).exists()) {
if(!QDir::root().mkpath(cacheDir)) {
qWarning() << "Could not create mapping disk cache directory: " << cacheDir;
cacheDir = QDir::homePath() + QLatin1String("/.qgcmapscache/");
cacheDir = QDir::homePath() + QStringLiteral("/.qgcmapscache/");
}
}
}

120
src/Vehicle/Vehicle.cc

@ -1091,6 +1091,7 @@ void Vehicle::_setCapabilities(uint64_t capabilityBits) @@ -1091,6 +1091,7 @@ void Vehicle::_setCapabilities(uint64_t capabilityBits)
qCDebug(VehicleLog) << QString("Vehicle %1 Mavlink 2.0").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_MAVLINK2 ? supports : doesNotSupport);
qCDebug(VehicleLog) << QString("Vehicle %1 MISSION_ITEM_INT").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_MISSION_INT ? supports : doesNotSupport);
qCDebug(VehicleLog) << QString("Vehicle %1 MISSION_COMMAND_INT").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_COMMAND_INT ? supports : doesNotSupport);
qCDebug(VehicleLog) << QString("Vehicle %1 GeoFence").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_MISSION_FENCE ? supports : doesNotSupport);
qCDebug(VehicleLog) << QString("Vehicle %1 RallyPoints").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_MISSION_RALLY ? supports : doesNotSupport);
}
@ -2780,13 +2781,42 @@ void Vehicle::guidedModeChangeAltitude(double altitudeChange) @@ -2780,13 +2781,42 @@ void Vehicle::guidedModeChangeAltitude(double altitudeChange)
_firmwarePlugin->guidedModeChangeAltitude(this, altitudeChange);
}
void Vehicle::guidedModeOrbit(const QGeoCoordinate& centerCoord, double radius, double velocity, double altitude)
void Vehicle::guidedModeOrbit(const QGeoCoordinate& centerCoord, double radius, double amslAltitude)
{
if (!orbitModeSupported()) {
qgcApp()->showMessage(QStringLiteral("Orbit mode not supported by Vehicle."));
return;
}
_firmwarePlugin->guidedModeOrbit(this, centerCoord, radius, velocity, altitude);
double lat, lon, alt;
if (centerCoord.isValid()) {
lat = lon = alt = qQNaN();
} else {
lat = centerCoord.latitude();
lon = centerCoord.longitude();
alt = amslAltitude;
}
if (capabilityBits() && MAV_PROTOCOL_CAPABILITY_COMMAND_INT) {
sendMavCommandInt(defaultComponentId(),
MAV_CMD_DO_ORBIT,
MAV_FRAME_GLOBAL,
true, // show error if fails
radius,
qQNaN(), // Use default velocity
0, // Vehicle points to center
qQNaN(), // reserved
lat, lon, alt);
} else {
sendMavCommand(defaultComponentId(),
MAV_CMD_DO_ORBIT,
true, // show error if fails
radius,
qQNaN(), // Use default velocity
0, // Vehicle points to center
qQNaN(), // reserved
lat, lon, alt);
}
}
void Vehicle::pauseVehicle(void)
@ -2845,8 +2875,34 @@ void Vehicle::sendMavCommand(int component, MAV_CMD command, bool showError, flo @@ -2845,8 +2875,34 @@ void Vehicle::sendMavCommand(int component, MAV_CMD command, bool showError, flo
{
MavCommandQueueEntry_t entry;
entry.commandInt = false;
entry.component = component;
entry.command = command;
entry.showError = showError;
entry.rgParam[0] = param1;
entry.rgParam[1] = param2;
entry.rgParam[2] = param3;
entry.rgParam[3] = param4;
entry.rgParam[4] = param5;
entry.rgParam[5] = param6;
entry.rgParam[6] = param7;
_mavCommandQueue.append(entry);
if (_mavCommandQueue.count() == 1) {
_mavCommandRetryCount = 0;
_sendMavCommandAgain();
}
}
void Vehicle::sendMavCommandInt(int component, MAV_CMD command, MAV_FRAME frame, bool showError, float param1, float param2, float param3, float param4, double param5, double param6, float param7)
{
MavCommandQueueEntry_t entry;
entry.commandInt = true;
entry.component = component;
entry.command = command;
entry.frame = frame;
entry.showError = showError;
entry.rgParam[0] = param1;
entry.rgParam[1] = param2;
@ -2930,25 +2986,47 @@ void Vehicle::_sendMavCommandAgain(void) @@ -2930,25 +2986,47 @@ void Vehicle::_sendMavCommandAgain(void)
_mavCommandAckTimer.start();
mavlink_message_t msg;
mavlink_command_long_t cmd;
memset(&cmd, 0, sizeof(cmd));
cmd.command = queuedCommand.command;
cmd.confirmation = 0;
cmd.param1 = queuedCommand.rgParam[0];
cmd.param2 = queuedCommand.rgParam[1];
cmd.param3 = queuedCommand.rgParam[2];
cmd.param4 = queuedCommand.rgParam[3];
cmd.param5 = queuedCommand.rgParam[4];
cmd.param6 = queuedCommand.rgParam[5];
cmd.param7 = queuedCommand.rgParam[6];
cmd.target_system = _id;
cmd.target_component = queuedCommand.component;
mavlink_msg_command_long_encode_chan(_mavlink->getSystemId(),
_mavlink->getComponentId(),
priorityLink()->mavlinkChannel(),
&msg,
&cmd);
if (queuedCommand.commandInt) {
mavlink_command_int_t cmd;
memset(&cmd, 0, sizeof(cmd));
cmd.target_system = _id;
cmd.target_component = queuedCommand.component;
cmd.command = queuedCommand.command;
cmd.frame = queuedCommand.frame;
cmd.param1 = queuedCommand.rgParam[0];
cmd.param2 = queuedCommand.rgParam[1];
cmd.param3 = queuedCommand.rgParam[2];
cmd.param4 = queuedCommand.rgParam[3];
cmd.x = queuedCommand.rgParam[4] * qPow(10.0, 7.0);
cmd.y = queuedCommand.rgParam[5] * qPow(10.0, 7.0);
cmd.z = queuedCommand.rgParam[6];
mavlink_msg_command_int_encode_chan(_mavlink->getSystemId(),
_mavlink->getComponentId(),
priorityLink()->mavlinkChannel(),
&msg,
&cmd);
} else {
mavlink_command_long_t cmd;
memset(&cmd, 0, sizeof(cmd));
cmd.target_system = _id;
cmd.target_component = queuedCommand.component;
cmd.command = queuedCommand.command;
cmd.confirmation = 0;
cmd.param1 = queuedCommand.rgParam[0];
cmd.param2 = queuedCommand.rgParam[1];
cmd.param3 = queuedCommand.rgParam[2];
cmd.param4 = queuedCommand.rgParam[3];
cmd.param5 = queuedCommand.rgParam[4];
cmd.param6 = queuedCommand.rgParam[5];
cmd.param7 = queuedCommand.rgParam[6];
mavlink_msg_command_long_encode_chan(_mavlink->getSystemId(),
_mavlink->getComponentId(),
priorityLink()->mavlinkChannel(),
&msg,
&cmd);
}
sendMessageOnLink(priorityLink(), msg);
}

18
src/Vehicle/Vehicle.h

@ -585,11 +585,10 @@ public: @@ -585,11 +585,10 @@ public:
Q_INVOKABLE void guidedModeChangeAltitude(double altitudeChange);
/// Command vehicle to orbit given center point
/// @param centerCoord Center Coordinates
/// @param centerCoord Orit around this point
/// @param radius Distance from vehicle to centerCoord
/// @param velocity Orbit velocity (positive CW, negative CCW)
/// @param altitude Desired Vehicle Altitude
Q_INVOKABLE void guidedModeOrbit(const QGeoCoordinate& centerCoord = QGeoCoordinate(), double radius = NAN, double velocity = NAN, double altitude = NAN);
/// @param amslAltitude Desired vehicle altitude
Q_INVOKABLE void guidedModeOrbit(const QGeoCoordinate& centerCoord, double radius, double amslAltitude);
/// Command vehicle to pause at current location. If vehicle supports guide mode, vehicle will be left
/// in guided mode after pause.
@ -844,6 +843,7 @@ public: @@ -844,6 +843,7 @@ public:
/// @param showError true: Display error to user if command failed, false: no error shown
/// Signals: mavCommandResult on success or failure
void sendMavCommand(int component, MAV_CMD command, bool showError, float param1 = 0.0f, float param2 = 0.0f, float param3 = 0.0f, float param4 = 0.0f, float param5 = 0.0f, float param6 = 0.0f, float param7 = 0.0f);
void sendMavCommandInt(int component, MAV_CMD command, MAV_FRAME frame, bool showError, float param1, float param2, float param3, float param4, double param5, double param6, float param7);
/// Same as sendMavCommand but available from Qml.
Q_INVOKABLE void sendCommand(int component, int command, bool showError, double param1 = 0.0f, double param2 = 0.0f, double param3 = 0.0f, double param4 = 0.0f, double param5 = 0.0f, double param6 = 0.0f, double param7 = 0.0f)
@ -1186,10 +1186,12 @@ private: @@ -1186,10 +1186,12 @@ private:
QGCCameraManager* _cameras;
typedef struct {
int component;
MAV_CMD command;
float rgParam[7];
bool showError;
int component;
bool commandInt; // true: use COMMAND_INT, false: use COMMAND_LONG
MAV_CMD command;
MAV_FRAME frame;
double rgParam[7];
bool showError;
} MavCommandQueueEntry_t;
QList<MavCommandQueueEntry_t> _mavCommandQueue;

2
src/VideoStreaming/VideoStreaming.cc

@ -159,7 +159,7 @@ void initializeVideoStreaming(int &argc, char* argv[], char* logpath, char* debu @@ -159,7 +159,7 @@ void initializeVideoStreaming(int &argc, char* argv[], char* logpath, char* debu
Q_UNUSED(debuglevel);
#endif
qmlRegisterType<VideoItem> ("QGroundControl.QgcQtGStreamer", 1, 0, "VideoItem");
qmlRegisterUncreatableType<VideoSurface>("QGroundControl.QgcQtGStreamer", 1, 0, "VideoSurface", QLatin1String("VideoSurface from QML is not supported"));
qmlRegisterUncreatableType<VideoSurface>("QGroundControl.QgcQtGStreamer", 1, 0, "VideoSurface", QStringLiteral("VideoSurface from QML is not supported"));
}
void shutdownVideoStreaming()

12
src/VideoStreaming/gstqtvideosink/painters/openglsurfacepainter.cpp

@ -60,7 +60,7 @@ OpenGLSurfacePainter::OpenGLSurfacePainter() @@ -60,7 +60,7 @@ OpenGLSurfacePainter::OpenGLSurfacePainter()
, m_videoColorMatrix(GST_VIDEO_COLOR_MATRIX_UNKNOWN)
{
#ifndef QT_OPENGL_ES
glActiveTexture = (_glActiveTexture) QGLContext::currentContext()->getProcAddress(QLatin1String("glActiveTexture"));
glActiveTexture = (_glActiveTexture) QGLContext::currentContext()->getProcAddress(QStringLiteral("glActiveTexture"));
#endif
}
@ -397,11 +397,11 @@ ArbFpSurfacePainter::ArbFpSurfacePainter() @@ -397,11 +397,11 @@ ArbFpSurfacePainter::ArbFpSurfacePainter()
, m_programId(0)
{
const QGLContext *context = QGLContext::currentContext();
glProgramStringARB = (_glProgramStringARB) context->getProcAddress(QLatin1String("glProgramStringARB"));
glBindProgramARB = (_glBindProgramARB) context->getProcAddress(QLatin1String("glBindProgramARB"));
glDeleteProgramsARB = (_glDeleteProgramsARB) context->getProcAddress(QLatin1String("glDeleteProgramsARB"));
glGenProgramsARB = (_glGenProgramsARB) context->getProcAddress(QLatin1String("glGenProgramsARB"));
glProgramLocalParameter4fARB = (_glProgramLocalParameter4fARB) context->getProcAddress(QLatin1String("glProgramLocalParameter4fARB"));
glProgramStringARB = (_glProgramStringARB) context->getProcAddress(QStringLiteral("glProgramStringARB"));
glBindProgramARB = (_glBindProgramARB) context->getProcAddress(QStringLiteral("glBindProgramARB"));
glDeleteProgramsARB = (_glDeleteProgramsARB) context->getProcAddress(QStringLiteral("glDeleteProgramsARB"));
glGenProgramsARB = (_glGenProgramsARB) context->getProcAddress(QStringLiteral("glGenProgramsARB"));
glProgramLocalParameter4fARB = (_glProgramLocalParameter4fARB) context->getProcAddress(QStringLiteral("glProgramLocalParameter4fARB"));
}
void ArbFpSurfacePainter::init(const BufferFormat &format)

4
src/comm/QGCXPlaneLink.cc

@ -532,6 +532,10 @@ void QGCXPlaneLink::updateActuatorControls(quint64 time, quint64 flags, float ct @@ -532,6 +532,10 @@ void QGCXPlaneLink::updateActuatorControls(quint64 time, quint64 flags, float ct
p.f[6] = ctl_3;
p.f[7] = ctl_3;
writeBytesSafe((const char*)&p, sizeof(p));
/* Send flap signals, assuming that they are mapped to channel 5 (ctl_4) */
sendDataRef("sim/flightmodel/controls/flaprqst", ctl_4);
sendDataRef("sim/flightmodel/controls/flap2rqst", ctl_4);
break;
}

2
src/qgcunittest/TCPLinkTest.cc

@ -130,7 +130,7 @@ void TCPLinkTest::_connectSucceed_test(void) @@ -130,7 +130,7 @@ void TCPLinkTest::_connectSucceed_test(void)
// We emit this signal such that it will be queued and run on the TCPLink thread. This in turn
// allows the TCPLink object to pump the bytes through.
connect(this, SIGNAL(waitForBytesWritten(int)), _link, SLOT(waitForBytesWritten(int)));
connect(this, &TCPLinkTest::waitForBytesWritten, _link, &TCPLink::waitForBytesWritten);
emit waitForBytesWritten(1000);
// Check for loopback, both from signal received and actual bytes returned

4
src/qgcunittest/TCPLoopBackServer.cc

@ -30,7 +30,7 @@ void TCPLoopBackServer::run(void) @@ -30,7 +30,7 @@ void TCPLoopBackServer::run(void)
_tcpServer = new QTcpServer(this);
Q_CHECK_PTR(_tcpServer);
bool connected = QObject::connect(_tcpServer, SIGNAL(newConnection()), this, SLOT(_newConnection()));
bool connected = QObject::connect(_tcpServer, &QTcpServer::newConnection, this, &TCPLoopBackServer::_newConnection);
Q_ASSERT(connected);
Q_UNUSED(connected); // Fix initialized-but-not-referenced warning on release builds
@ -45,7 +45,7 @@ void TCPLoopBackServer::_newConnection(void) @@ -45,7 +45,7 @@ void TCPLoopBackServer::_newConnection(void)
Q_ASSERT(_tcpServer);
_tcpSocket = _tcpServer->nextPendingConnection();
Q_ASSERT(_tcpSocket);
bool connected = QObject::connect(_tcpSocket, SIGNAL(readyRead()), this, SLOT(_readBytes()));
bool connected = QObject::connect(_tcpSocket, &QIODevice::readyRead, this, &TCPLoopBackServer::_readBytes);
Q_ASSERT(connected);
Q_UNUSED(connected); // Fix initialized-but-not-referenced warning on release builds
}

2
src/ui/MainWindow.cc

@ -152,7 +152,7 @@ MainWindow::MainWindow() @@ -152,7 +152,7 @@ MainWindow::MainWindow()
// Image provider
QQuickImageProvider* pImgProvider = dynamic_cast<QQuickImageProvider*>(qgcApp()->toolbox()->imageProvider());
_mainQmlWidgetHolder->getEngine()->addImageProvider(QLatin1String("QGCImages"), pImgProvider);
_mainQmlWidgetHolder->getEngine()->addImageProvider(QStringLiteral("QGCImages"), pImgProvider);
// Set dock options
setDockOptions(0);

Loading…
Cancel
Save