Browse Source

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

QGC4.4
Gus Grubba 6 years ago
parent
commit
1ae69b3b05
  1. 13
      src/FlightDisplay/GuidedActionList.qml
  2. 10
      src/Vehicle/Vehicle.cc

13
src/FlightDisplay/GuidedActionList.qml

@ -32,6 +32,9 @@ Rectangle { @@ -32,6 +32,9 @@ Rectangle {
property alias model: actionRepeater.model
property real _margins: Math.round(ScreenTools.defaultFontPixelHeight * 0.66)
property real _actionWidth: ScreenTools.defaultFontPixelWidth * 25
property real _actionHorizSpacing: ScreenTools.defaultFontPixelHeight * 2
QGCPalette { id: qgcPal }
@ -58,11 +61,11 @@ Rectangle { @@ -58,11 +61,11 @@ Rectangle {
Layout.minimumWidth: _width
Layout.maximumWidth: _width
property real _width: Math.min(_root.width * 0.8, actionRow.width)
property real _width: Math.min((_actionWidth * 2) + _actionHorizSpacing, actionRow.width)
RowLayout {
id: actionRow
spacing: ScreenTools.defaultFontPixelHeight * 2
spacing: _actionHorizSpacing
Repeater {
id: actionRepeater
@ -74,11 +77,11 @@ Rectangle { @@ -74,11 +77,11 @@ Rectangle {
QGCLabel {
id: actionMessage
text: modelData.text ? modelData.text : ""
text: modelData.text
horizontalAlignment: Text.AlignHCenter
wrapMode: Text.WordWrap
Layout.minimumWidth: _width
Layout.maximumWidth: _width
Layout.minimumWidth: _actionWidth
Layout.maximumWidth: _actionWidth
Layout.fillHeight: true
property real _width: ScreenTools.defaultFontPixelWidth * 25

10
src/Vehicle/Vehicle.cc

@ -348,8 +348,10 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType, @@ -348,8 +348,10 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
, _globalPositionIntMessageAvailable(false)
, _defaultCruiseSpeed(_settingsManager->appSettings()->offlineEditingCruiseSpeed()->rawValue().toDouble())
, _defaultHoverSpeed(_settingsManager->appSettings()->offlineEditingHoverSpeed()->rawValue().toDouble())
, _mavlinkProtocolRequestComplete(true)
, _maxProtoVersion(200)
, _vehicleCapabilitiesKnown(true)
, _capabilityBits(_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA ? 0 : MAV_PROTOCOL_CAPABILITY_MISSION_FENCE | MAV_PROTOCOL_CAPABILITY_MISSION_RALLY)
, _capabilityBits(MAV_PROTOCOL_CAPABILITY_MISSION_FENCE | MAV_PROTOCOL_CAPABILITY_MISSION_RALLY)
, _highLatencyLink(false)
, _receivingAttitudeQuaternion(false)
, _cameras(nullptr)
@ -574,12 +576,6 @@ void Vehicle::_offlineFirmwareTypeSettingChanged(QVariant value) @@ -574,12 +576,6 @@ void Vehicle::_offlineFirmwareTypeSettingChanged(QVariant value)
_firmwareType = static_cast<MAV_AUTOPILOT>(value.toInt());
_firmwarePlugin = _firmwarePluginManager->firmwarePluginForAutopilot(_firmwareType, _vehicleType);
emit firmwareTypeChanged();
if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
_capabilityBits = 0;
} else {
_capabilityBits = MAV_PROTOCOL_CAPABILITY_MISSION_FENCE | MAV_PROTOCOL_CAPABILITY_MISSION_RALLY;
}
emit capabilityBitsChanged(_capabilityBits);
}
void Vehicle::_offlineVehicleTypeSettingChanged(QVariant value)

Loading…
Cancel
Save