Commit 2d86dae5 authored by Gus Grubba's avatar Gus Grubba

Merge branches 'localizationUpdate' and 'master' of...

Merge branches 'localizationUpdate' and 'master' of https://github.com/mavlink/qgroundcontrol into localizationUpdate
parents d38fc4b6 0905b11b
......@@ -15,7 +15,7 @@ Vagrant.configure(2) do |config|
config.vm.provider "virtualbox"
config.vm.provider "vmware_fusion"
config.vm.box = "boxcutter/ubuntu1604"
config.vm.box = "ubuntu/xenial64"
config.vm.provider :docker do |docker, override|
override.vm.box = "tknerr/baseimage-ubuntu-16.04"
end
......
......@@ -3379,7 +3379,7 @@ by initializing the estimator to the LPE_LAT/LON parameters when global informat
<short_desc>Integer bitmask controlling data fusion</short_desc>
<long_desc>Set bits in the following positions to enable: 0 : Set to true to fuse GPS data if available, also requires GPS for altitude init 1 : Set to true to fuse optical flow data if available 2 : Set to true to fuse vision position 3 : Set to true to enable landing target 4 : Set to true to fuse land detector 5 : Set to true to publish AGL as local position down component 6 : Set to true to enable flow gyro compensation 7 : Set to true to enable baro fusion default (145 - GPS, baro, land detector)</long_desc>
<min>0</min>
<max>4294967295</max>
<max>255</max>
<scope>modules/local_position_estimator</scope>
<bitmask>
<bit index="0"> fuse GPS, requires GPS for alt. init</bit>
......@@ -5482,7 +5482,7 @@ the setpoint will be capped to MPC_XY_VEL_MAX</short_desc>
<parameter default="3" name="PLD_MAX_SRCH" type="INT32">
<short_desc>Maximum number of search attempts</short_desc>
<long_desc>Maximum number of times to seach for the landing target if it is lost during the precision landing.</long_desc>
<min>0.0</min>
<min>0</min>
<max>100</max>
<scope>modules/navigator</scope>
</parameter>
......
......@@ -1216,8 +1216,6 @@ void MissionController::_recalcMissionFlightStatus()
}
}
qDebug() << "Gimbal calc";
for (int i=0; i<_visualItems->count(); i++) {
VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(item);
......@@ -1247,7 +1245,6 @@ void MissionController::_recalcMissionFlightStatus()
// Look for gimbal change
double gimbalYaw = item->specifiedGimbalYaw();
if (!qIsNaN(gimbalYaw)) {
qDebug() << _editMode << gimbalYaw;
_missionFlightStatus.gimbalYaw = gimbalYaw;
}
double gimbalPitch = item->specifiedGimbalPitch();
......@@ -1353,7 +1350,6 @@ void MissionController::_recalcMissionFlightStatus()
_addTimeDistance(vtolInHover, hoverTime, cruiseTime, extraTime, distance, item->sequenceNumber());
}
qDebug() << "setMissionFlightStatus" << item->sequenceNumber() << _missionFlightStatus.gimbalYaw << item->commandName();
item->setMissionFlightStatus(_missionFlightStatus);
}
......
......@@ -297,6 +297,11 @@ void MissionSettingsItem::setMissionEndRTL(bool missionEndRTL)
void MissionSettingsItem::_setHomeAltFromTerrain(double terrainAltitude)
{
if (!_plannedHomePositionFromVehicle) {
// We need to stop this from signalling, Otherwise the dirty but get set on a delay
// which then marks the Plan view as incorrectly dirty
_plannedHomePositionAltitudeFact.setSendValueChangedSignals(false);
_plannedHomePositionAltitudeFact.setRawValue(terrainAltitude);
_plannedHomePositionAltitudeFact.clearDeferredValueChangeSignal();
_plannedHomePositionAltitudeFact.setSendValueChangedSignals(false);
}
}
......@@ -453,6 +453,7 @@ Item {
id: radiusField
text: _circleRadius.toFixed(2)
onEditingFinished: setRadiusFromDialog()
inputMethodHints: Qt.ImhFormattedNumbersOnly
}
}
......
......@@ -31,7 +31,7 @@ Rectangle {
readonly property real _margins: ScreenTools.defaultFontPixelWidth
onMaxWidthChanged: {
var calcLength = (statusListView.count + 1)*statusListView.contentItem.children[0].width
var calcLength = (statusListView.count + 1) * (statusListView.count ? statusListView.contentItem.children[0].width : 1)
root.width = root.maxWidth > calcLength ? calcLength : root.maxWidth
}
......@@ -63,7 +63,7 @@ Rectangle {
currentIndex: _missionController.currentPlanViewIndex
onCountChanged: {
var calcLength = (statusListView.count + 1)*statusListView.contentItem.children[0].width
var calcLength = (statusListView.count + 1) * (statusListView.count ? statusListView.contentItem.children[0].width : 1)
root.width = root.maxWidth > calcLength ? calcLength : root.maxWidth
}
......
This diff is collapsed.
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment