diff --git a/src/MissionManager/Survey.SettingsGroup.json b/src/MissionManager/Survey.SettingsGroup.json index e28cb354aa95538a24f45eaf593279e020e1e29f..b11c5e461e63c143b203be930d5a708cb262659c 100644 --- a/src/MissionManager/Survey.SettingsGroup.json +++ b/src/MissionManager/Survey.SettingsGroup.json @@ -64,7 +64,7 @@ "min": 0, "max": 85, "units": "%", - "defaultValue": 10 + "defaultValue": 70 }, { "name": "SideOverlap", @@ -74,7 +74,7 @@ "min": 0, "max": 85, "units": "%", - "defaultValue": 10 + "defaultValue": 70 }, { "name": "CameraSensorWidth", diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index d72e20438a8ab717b2f479bcab6933f71de5995c..19c006ea3faed58641d5d03481f029bdd01f5eb5 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -296,7 +296,7 @@ QString MainWindow::_getWindowGeometryKey() #ifndef __mobile__ MAVLinkDecoder* MainWindow::_mavLinkDecoderInstance(void) { - if (_mavlinkDecoder) { + if (!_mavlinkDecoder) { _mavlinkDecoder = new MAVLinkDecoder(qgcApp()->toolbox()->mavlinkProtocol()); connect(_mavlinkDecoder, &MAVLinkDecoder::valueChanged, this, &MainWindow::valueChanged); }