Unverified Commit 2a4261eb authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #6195 from DonLakeFlyer/StableMerge

Stable merge
parents 05992691 7737cee8
......@@ -26,12 +26,12 @@ installer {
# 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 += && mkdir -p $${DESTDIR}/package
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:
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
QMAKE_POST_LINK += && hdiutil convert /tmp/tmp.dmg -format UDBZ -o $${DESTDIR}/package/$${TARGET}.dmg
QMAKE_POST_LINK += && rm /tmp/tmp.dmg
}
......
......@@ -22,12 +22,9 @@
#include <QVariantAnimation>
#include <QJsonArray>
/* types for local parameter cache */
typedef QPair<int /* FactMetaData::ValueType_t */, QVariant /* Fact::rawValue */> ParamTypeVal;
typedef QMap<QString /* parameter name */, ParamTypeVal> CacheMapName2ParamTypeVal;
QGC_LOGGING_CATEGORY(ParameterManagerVerbose1Log, "ParameterManagerVerbose1Log")
QGC_LOGGING_CATEGORY(ParameterManagerVerbose2Log, "ParameterManagerVerbose2Log")
QGC_LOGGING_CATEGORY(ParameterManagerDebugCacheFailureLog, "ParameterManagerDebugCacheFailureLog") // Turn on to debug parameter cache crc misses
Fact ParameterManager::_defaultFact;
......@@ -151,6 +148,24 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
return;
}
// Used to debug cache crc misses (turn on ParameterManagerDebugCacheFailureLog)
if (!_initialLoadComplete && !_logReplay && _debugCacheCRC.contains(componentId) && _debugCacheCRC[componentId]) {
if (_debugCacheMap[componentId].contains(parameterName)) {
const ParamTypeVal& cacheParamTypeVal = _debugCacheMap[componentId][parameterName];
size_t dataSize = FactMetaData::typeToSize(static_cast<FactMetaData::ValueType_t>(cacheParamTypeVal.first));
const void *cacheData = cacheParamTypeVal.second.constData();
const void *vehicleData = value.constData();
if (memcmp(cacheData, vehicleData, dataSize)) {
qDebug() << "Cache/Vehicle values differ for name:cache:actual" << parameterName << value << cacheParamTypeVal.second;
}
_debugCacheParamSeen[componentId][parameterName] = true;
} else {
qDebug() << "Parameter missing from cache" << parameterName;
}
}
_initialRequestTimeoutTimer.stop();
_waitingParamTimeoutTimer.stop();
......@@ -340,11 +355,6 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
_setupCategoryMap();
}
if (_prevWaitingWriteParamNameCount != 0 && waitingWriteParamNameCount == 0) {
// If all the writes just finished the vehicle is up to date, so persist.
_saveToEEPROM();
}
// Update param cache. The param cache is only used on PX4 Firmware since ArduPilot and Solo have volatile params
// which invalidate the cache. The Solo also streams param updates in flight for things like gimbal values
// which in turn causes a perf problem with all the param cache updates.
......@@ -875,22 +885,13 @@ void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVarian
_parameterSetMajorVersion = -1;
_clearMetaData();
qCInfo(ParameterManagerLog) << "Parameters cache match failed" << qPrintable(QFileInfo(cacheFile).absoluteFilePath());
if (ParameterManagerDebugCacheFailureLog().isDebugEnabled()) {
_debugCacheCRC[componentId] = true;
_debugCacheMap[componentId] = cacheMap;
foreach (const QString& name, cacheMap.keys()) {
_debugCacheParamSeen[componentId][name] = false;
}
}
void ParameterManager::_saveToEEPROM(void)
{
if (_saveRequired) {
_saveRequired = false;
if (_vehicle->firmwarePlugin()->isCapable(_vehicle, FirmwarePlugin::MavCmdPreflightStorageCapability)) {
_vehicle->sendMavCommand(MAV_COMP_ID_ALL,
MAV_CMD_PREFLIGHT_STORAGE,
true, // showError
1, // Write parameters to EEPROM
-1); // Don't do anything with mission storage
qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "_saveToEEPROM";
} else {
qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "_saveToEEPROM skipped due to FirmwarePlugin::isCapable";
qgcApp()->showMessage(tr("Parameter cache CRC match failed"));
}
}
}
......@@ -1110,6 +1111,18 @@ void ParameterManager::_checkInitialLoadComplete(void)
// We aren't waiting for any more initial parameter updates, initial parameter loading is complete
_initialLoadComplete = true;
// Parameter cache crc failure debugging
foreach (int componentId, _debugCacheParamSeen.keys()) {
if (!_logReplay && _debugCacheCRC.contains(componentId) && _debugCacheCRC[componentId]) {
foreach (const QString& paramName, _debugCacheParamSeen[componentId].keys()) {
if (!_debugCacheParamSeen[componentId][paramName]) {
qDebug() << "Parameter in cache but not on vehicle componentId:Name" << componentId << paramName;
}
}
}
}
_debugCacheCRC.clear();
qCDebug(ParameterManagerLog) << _logVehiclePrefix() << "Initial load complete";
// Check for index based load failures
......@@ -1423,6 +1436,7 @@ void ParameterManager::_loadOfflineEditingParams(void)
_setupCategoryMap();
_parametersReady = true;
_initialLoadComplete = true;
_debugCacheCRC.clear();
}
void ParameterManager::saveToJson(int componentId, const QStringList& paramsToSave, QJsonObject& saveObject)
......
......@@ -30,6 +30,7 @@
Q_DECLARE_LOGGING_CATEGORY(ParameterManagerVerbose1Log)
Q_DECLARE_LOGGING_CATEGORY(ParameterManagerVerbose2Log)
Q_DECLARE_LOGGING_CATEGORY(ParameterManagerDebugCacheFailureLog)
/// Connects to Parameter Manager to load/update Facts
class ParameterManager : public QObject
......@@ -153,7 +154,6 @@ private:
MAV_PARAM_TYPE _factTypeToMavType(FactMetaData::ValueType_t factType);
FactMetaData::ValueType_t _mavTypeToFactType(MAV_PARAM_TYPE mavType);
void _saveToEEPROM(void);
void _checkInitialLoadComplete(void);
/// First mapping is by component id
......@@ -175,6 +175,13 @@ private:
int _parameterSetMajorVersion; ///< Version for parameter set, -1 if not known
QObject* _parameterMetaData; ///< Opaque data from FirmwarePlugin::loadParameterMetaDataCall
typedef QPair<int /* FactMetaData::ValueType_t */, QVariant /* Fact::rawValue */> ParamTypeVal;
typedef QMap<QString /* parameter name */, ParamTypeVal> CacheMapName2ParamTypeVal;
QMap<int /* component id */, bool> _debugCacheCRC; ///< true: debug cache crc failure
QMap<int /* component id */, CacheMapName2ParamTypeVal> _debugCacheMap;
QMap<int /* component id */, QMap<QString /* param name */, bool /* seen */>> _debugCacheParamSeen;
// Wait counts from previous parameter update cycle
int _prevWaitingReadParamIndexCount;
int _prevWaitingReadParamNameCount;
......
......@@ -43,11 +43,10 @@ public:
/// Set of optional capabilites which firmware may support
typedef enum {
SetFlightModeCapability = 1 << 0, ///< FirmwarePlugin::setFlightMode method is supported
MavCmdPreflightStorageCapability = 1 << 1, ///< MAV_CMD_PREFLIGHT_STORAGE is supported
PauseVehicleCapability = 1 << 2, ///< Vehicle supports pausing at current location
GuidedModeCapability = 1 << 3, ///< Vehicle supports guided mode commands
OrbitModeCapability = 1 << 4, ///< Vehicle supports orbit mode
TakeoffVehicleCapability = 1 << 5, ///< Vehicle supports guided takeoff
PauseVehicleCapability = 1 << 1, ///< Vehicle supports pausing at current location
GuidedModeCapability = 1 << 2, ///< Vehicle supports guided mode commands
OrbitModeCapability = 1 << 3, ///< Vehicle supports orbit mode
TakeoffVehicleCapability = 1 << 4, ///< Vehicle supports guided takeoff
} FirmwareCapabilities;
/// Maps from on parameter name to another
......
......@@ -227,7 +227,7 @@ int PX4FirmwarePlugin::manualControlReservedButtonCount(void)
bool PX4FirmwarePlugin::isCapable(const Vehicle *vehicle, FirmwareCapabilities capabilities)
{
int available = MavCmdPreflightStorageCapability | SetFlightModeCapability | PauseVehicleCapability | GuidedModeCapability;
int available = SetFlightModeCapability | PauseVehicleCapability | GuidedModeCapability;
if (vehicle->multiRotor() || vehicle->vtol()) {
available |= TakeoffVehicleCapability;
}
......
......@@ -42,10 +42,28 @@ Rectangle {
if (hideTrigger) {
hideTrigger = false
altitudeSlider.visible = false
visibleTimer.stop()
visible = false
}
}
function show(immediate) {
if (immediate) {
visible = true
} else {
// We delay showing the confirmation for a small amount in order to any other state
// changes to propogate through the system. This way only the final state shows up.
visibleTimer.restart()
}
}
Timer {
id: visibleTimer
interval: 1000
repeat: false
onTriggered: visible = true
}
QGCPalette { id: qgcPal }
DeadMouseArea {
......
......@@ -185,9 +185,11 @@ Item {
// Called when an action is about to be executed in order to confirm
function confirmAction(actionCode, actionData) {
var showImmediate = true
closeAll()
confirmDialog.action = actionCode
confirmDialog.actionData = actionData
confirmDialog.hideTrigger = true
_actionData = actionData
switch (actionCode) {
case actionArm:
......@@ -219,6 +221,7 @@ Item {
altitudeSlider.visible = true
break;
case actionStartMission:
showImmediate = false
confirmDialog.title = startMissionTitle
confirmDialog.message = startMissionMessage
confirmDialog.hideTrigger = Qt.binding(function() { return !showStartMission })
......@@ -229,11 +232,13 @@ Item {
confirmDialog.hideTrigger = true
break;
case actionContinueMission:
showImmediate = false
confirmDialog.title = continueMissionTitle
confirmDialog.message = continueMissionMessage
confirmDialog.hideTrigger = Qt.binding(function() { return !showContinueMission })
break;
case actionResumeMission:
showImmediate = false
confirmDialog.title = resumeMissionTitle
confirmDialog.message = resumeMissionMessage
confirmDialog.hideTrigger = Qt.binding(function() { return !showResumeMission })
......@@ -308,7 +313,7 @@ Item {
console.warn("Unknown actionCode", actionCode)
return
}
confirmDialog.visible = true
confirmDialog.show(showImmediate)
}
// Executes the specified action
......
<?xml version="1.0" encoding="utf-8"?>
<!-- Generator: Adobe Illustrator 18.1.1, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
<svg version="1.1" id="Layer_2" xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" x="0px" y="0px"
viewBox="0 0 288 288" enable-background="new 0 0 288 288" xml:space="preserve">
<line fill="none" stroke="#FFFFFF" stroke-width="4" x1="143.999" y1="36.793" x2="143.999" y2="18.793"/>
<line fill="none" stroke="#FFFFFF" stroke-width="4" x1="171.739" y1="40.458" x2="176.398" y2="23.072"/>
<line fill="none" stroke="#FFFFFF" stroke-width="4" x1="197.586" y1="51.179" x2="206.586" y2="35.591"/>
<line fill="none" stroke="#FFFFFF" stroke-width="4" x1="219.777" y1="68.224" x2="232.505" y2="55.496"/>
<line fill="none" stroke="#FFFFFF" stroke-width="4" x1="236.801" y1="90.432" x2="252.389" y2="81.432"/>
<line fill="none" stroke="#FFFFFF" stroke-width="4" x1="116.254" y1="40.431" x2="111.596" y2="23.045"/>
<line fill="none" stroke="#FFFFFF" stroke-width="4" x1="90.397" y1="51.127" x2="81.397" y2="35.539"/>
<line fill="none" stroke="#FFFFFF" stroke-width="4" x1="68.189" y1="68.151" x2="55.461" y2="55.423"/>
<line fill="none" stroke="#FFFFFF" stroke-width="4" x1="51.144" y1="90.342" x2="35.556" y2="81.342"/>
<rect x="135" y="270" fill="none" width="18" height="18"/>
<!-- Generator: Adobe Illustrator 21.0.0, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
<svg version="1.1" xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" x="0px" y="0px"
viewBox="0 0 288 288" style="enable-background:new 0 0 288 288;" xml:space="preserve">
<style type="text/css">
.st0{fill:none;stroke:#FFFFFF;stroke-width:4;}
.st1{fill:none;stroke:#FFFFFF;stroke-miterlimit:10;}
</style>
<g id="Layer_2">
<line class="st0" x1="144" y1="45.8" x2="144" y2="18.8"/>
<line class="st0" x1="171.7" y1="40.5" x2="176.4" y2="23.1"/>
<line class="st0" x1="197.6" y1="51.2" x2="206.6" y2="35.6"/>
<line class="st0" x1="219.8" y1="68.2" x2="232.5" y2="55.5"/>
<line class="st0" x1="236.8" y1="90.4" x2="252.4" y2="81.4"/>
<line class="st0" x1="116.3" y1="40.4" x2="111.6" y2="23"/>
<line class="st0" x1="90.4" y1="51.1" x2="81.4" y2="35.5"/>
<line class="st0" x1="68.2" y1="68.2" x2="55.5" y2="55.4"/>
<line class="st0" x1="51.1" y1="90.3" x2="35.6" y2="81.3"/>
<rect x="135" y="270" class="st1" width="18" height="18"/>
</g>
<g id="Layer_3">
</g>
</svg>
......@@ -24,8 +24,6 @@ QGC_LOGGING_CATEGORY(StructureScanComplexItemLog, "StructureScanComplexItemLog")
const char* StructureScanComplexItem::_altitudeFactName = "Altitude";
const char* StructureScanComplexItem::_structureHeightFactName = "StructureHeight";
const char* StructureScanComplexItem::_layersFactName = "Layers";
const char* StructureScanComplexItem::_gimbalPitchFactName = "GimbalPitch";
const char* StructureScanComplexItem::_gimbalYawFactName = "GimbalYaw";
const char* StructureScanComplexItem::jsonComplexItemTypeValue = "StructureScan";
const char* StructureScanComplexItem::_jsonCameraCalcKey = "CameraCalc";
......@@ -46,8 +44,6 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, QObject* pa
, _cameraCalc (vehicle)
, _altitudeFact (0, _altitudeFactName, FactMetaData::valueTypeDouble)
, _layersFact (0, _layersFactName, FactMetaData::valueTypeUint32)
, _gimbalPitchFact (0, _gimbalPitchFactName, FactMetaData::valueTypeDouble)
, _gimbalYawFact (0, _gimbalYawFactName, FactMetaData::valueTypeDouble)
{
_editorQml = "qrc:/qml/StructureScanEditor.qml";
......@@ -57,20 +53,14 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, QObject* pa
_altitudeFact.setMetaData (_metaDataMap[_altitudeFactName]);
_layersFact.setMetaData (_metaDataMap[_layersFactName]);
_gimbalPitchFact.setMetaData(_metaDataMap[_gimbalPitchFactName]);
_gimbalYawFact.setMetaData (_metaDataMap[_gimbalYawFactName]);
_altitudeFact.setRawValue (_altitudeFact.rawDefaultValue());
_layersFact.setRawValue (_layersFact.rawDefaultValue());
_gimbalPitchFact.setRawValue(_gimbalPitchFact.rawDefaultValue());
_gimbalYawFact.setRawValue (_gimbalYawFact.rawDefaultValue());
_altitudeFact.setRawValue(qgcApp()->toolbox()->settingsManager()->appSettings()->defaultMissionItemAltitude()->rawValue());
connect(&_altitudeFact, &Fact::valueChanged, this, &StructureScanComplexItem::_setDirty);
connect(&_layersFact, &Fact::valueChanged, this, &StructureScanComplexItem::_setDirty);
connect(&_gimbalPitchFact, &Fact::valueChanged, this, &StructureScanComplexItem::_setDirty);
connect(&_gimbalYawFact, &Fact::valueChanged, this, &StructureScanComplexItem::_setDirty);
connect(&_layersFact, &Fact::valueChanged, this, &StructureScanComplexItem::_recalcLayerInfo);
connect(&_structureHeightFact, &Fact::valueChanged, this, &StructureScanComplexItem::_recalcLayerInfo);
......@@ -89,7 +79,6 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, QObject* pa
connect(&_flightPolygon, &QGCMapPolygon::pathChanged, this, &StructureScanComplexItem::_flightPathChanged);
connect(_cameraCalc.distanceToSurface(), &Fact::valueChanged, this, &StructureScanComplexItem::_rebuildFlightPolygon);
connect(&_cameraCalc, &CameraCalc::cameraNameChanged, this, &StructureScanComplexItem::_resetGimbal);
connect(&_flightPolygon, &QGCMapPolygon::pathChanged, this, &StructureScanComplexItem::_recalcCameraShots);
connect(_cameraCalc.adjustedFootprintSide(), &Fact::valueChanged, this, &StructureScanComplexItem::_recalcCameraShots);
......@@ -134,7 +123,7 @@ int StructureScanComplexItem::lastSequenceNumber(void) const
(_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
1; // Gimbal control command
2; // ROI_WPNEXT_OFFSET and ROI_NONE commands
}
void StructureScanComplexItem::setDirty(bool dirty)
......@@ -154,8 +143,6 @@ void StructureScanComplexItem::save(QJsonArray& missionItems)
saveObject[VisualMissionItem::jsonTypeKey] = VisualMissionItem::jsonTypeComplexItemValue;
saveObject[ComplexMissionItem::jsonComplexItemTypeKey] = jsonComplexItemTypeValue;
saveObject[_gimbalPitchFactName] = _gimbalPitchFact.rawValue().toDouble();
saveObject[_gimbalYawFactName] = _gimbalYawFact.rawValue().toDouble();
saveObject[_altitudeFactName] = _altitudeFact.rawValue().toDouble();
saveObject[_structureHeightFactName] = _structureHeightFact.rawValue().toDouble();
saveObject[_jsonAltitudeRelativeKey] = _altitudeRelative;
......@@ -186,8 +173,6 @@ bool StructureScanComplexItem::load(const QJsonObject& complexObject, int sequen
{ VisualMissionItem::jsonTypeKey, QJsonValue::String, true },
{ ComplexMissionItem::jsonComplexItemTypeKey, QJsonValue::String, true },
{ QGCMapPolygon::jsonPolygonKey, QJsonValue::Array, true },
{ _gimbalPitchFactName, QJsonValue::Double, true },
{ _gimbalYawFactName, QJsonValue::Double, true },
{ _altitudeFactName, QJsonValue::Double, true },
{ _structureHeightFactName, QJsonValue::Double, true },
{ _jsonAltitudeRelativeKey, QJsonValue::Bool, true },
......@@ -220,8 +205,6 @@ bool StructureScanComplexItem::load(const QJsonObject& complexObject, int sequen
return false;
}
_gimbalPitchFact.setRawValue(complexObject[_gimbalPitchFactName].toDouble());
_gimbalYawFact.setRawValue (complexObject[_gimbalYawFactName].toDouble());
_altitudeFact.setRawValue (complexObject[_altitudeFactName].toDouble());
_layersFact.setRawValue (complexObject[_layersFactName].toDouble());
_altitudeRelative = complexObject[_jsonAltitudeRelativeKey].toBool(true);
......@@ -268,13 +251,11 @@ void StructureScanComplexItem::appendMissionItems(QList<MissionItem*>& items, QO
double baseAltitude = _altitudeFact.rawValue().toDouble();
MissionItem* item = new MissionItem(seqNum++,
MAV_CMD_DO_MOUNT_CONTROL,
MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET,
MAV_FRAME_MISSION,
_gimbalPitchFact.rawValue().toDouble(),
0, // Gimbal roll
_gimbalYawFact.rawValue().toDouble(),
0, 0, 0, // param 4-6 not used
MAV_MOUNT_MODE_MAVLINK_TARGETING,
0, 0, 0, 0, // param 1-4 not used
0, 0, // Pitch and Roll stay in standard orientation
90, // 90 degreee yaw offset to point to structure
true, // autoContinue
false, // isCurrentItem
missionItemParent);
......@@ -349,6 +330,15 @@ void StructureScanComplexItem::appendMissionItems(QList<MissionItem*>& items, QO
missionItemParent);
items.append(item);
}
item = new MissionItem(seqNum++,
MAV_CMD_DO_SET_ROI_NONE,
MAV_FRAME_MISSION,
0, 0, 0,0, 0, 0, 0, // param 1-7 not used
true, // autoContinue
false, // isCurrentItem
missionItemParent);
items.append(item);
}
int StructureScanComplexItem::cameraShots(void) const
......@@ -447,12 +437,6 @@ void StructureScanComplexItem::_recalcCameraShots(void)
_setCameraShots(cameraShots * _layersFact.rawValue().toInt());
}
void StructureScanComplexItem::_resetGimbal(void)
{
_gimbalPitchFact.setCookedValue(0);
_gimbalYawFact.setCookedValue(90);
}
void StructureScanComplexItem::setAltitudeRelative(bool altitudeRelative)
{
if (altitudeRelative != _altitudeRelative) {
......
......@@ -28,8 +28,6 @@ public:
StructureScanComplexItem(Vehicle* vehicle, QObject* parent = NULL);
Q_PROPERTY(CameraCalc* cameraCalc READ cameraCalc CONSTANT)
Q_PROPERTY(Fact* gimbalPitch READ gimbalPitch CONSTANT)
Q_PROPERTY(Fact* gimbalYaw READ gimbalYaw CONSTANT)
Q_PROPERTY(Fact* altitude READ altitude CONSTANT)
Q_PROPERTY(Fact* structureHeight READ structureHeight CONSTANT)
Q_PROPERTY(Fact* layers READ layers CONSTANT)
......@@ -47,8 +45,6 @@ public:
bool altitudeRelative (void) const { return _altitudeRelative; }
int cameraShots (void) const;
Fact* gimbalPitch (void) { return &_gimbalPitchFact; }
Fact* gimbalYaw (void) { return &_gimbalYawFact; }
double timeBetweenShots (void);
QGCMapPolygon* structurePolygon (void) { return &_structurePolygon; }
QGCMapPolygon* flightPolygon (void) { return &_flightPolygon; }
......@@ -111,7 +107,6 @@ private slots:
void _updateCoordinateAltitudes (void);
void _rebuildFlightPolygon (void);
void _recalcCameraShots (void);
void _resetGimbal (void);
void _recalcLayerInfo (void);
private:
......@@ -140,14 +135,10 @@ private:
Fact _altitudeFact;
Fact _structureHeightFact;
Fact _layersFact;
Fact _gimbalPitchFact;
Fact _gimbalYawFact;
static const char* _altitudeFactName;
static const char* _structureHeightFactName;
static const char* _layersFactName;
static const char* _gimbalPitchFactName;
static const char* _gimbalYawFactName;
static const char* _jsonCameraCalcKey;
static const char* _jsonAltitudeRelativeKey;
......
......@@ -59,7 +59,7 @@ void StructureScanComplexItemTest::_testDirty(void)
// These facts should set dirty when changed
QList<Fact*> rgFacts;
rgFacts << _structureScanItem->gimbalPitch() << _structureScanItem->gimbalYaw() << _structureScanItem->altitude() << _structureScanItem->layers();
rgFacts << _structureScanItem->altitude() << _structureScanItem->layers();
foreach(Fact* fact, rgFacts) {
qDebug() << fact->name();
QVERIFY(!_structureScanItem->dirty());
......@@ -93,8 +93,6 @@ void StructureScanComplexItemTest::_initItem(void)
}
_structureScanItem->cameraCalc()->setCameraName(CameraCalc::manualCameraName());
_structureScanItem->gimbalPitch()->setCookedValue(45);
_structureScanItem->gimbalYaw()->setCookedValue(45);
_structureScanItem->layers()->setCookedValue(2);
_structureScanItem->setDirty(false);
......@@ -112,8 +110,6 @@ void StructureScanComplexItemTest::_validateItem(StructureScanComplexItem* item)
}
QCOMPARE(_structureScanItem->cameraCalc()->cameraName() , CameraCalc::manualCameraName());
QCOMPARE(item->gimbalPitch()->cookedValue().toDouble(), 45.0);
QCOMPARE(item->gimbalYaw()->cookedValue().toDouble(), 45.0);
QCOMPARE(item->layers()->cookedValue().toInt(), 2);
}
......@@ -132,17 +128,6 @@ void StructureScanComplexItemTest::_testSaveLoad(void)
newItem->deleteLater();
}
void StructureScanComplexItemTest::_testGimbalAngleUpdate(void)
{
// This sets the item to CameraCalc::CameraSpecNone and non-standard gimbal angles
_initItem();
// Switching to a camera specific setup should set gimbal angles to defaults
_structureScanItem->cameraCalc()->setCameraName(CameraCalc::customCameraName());
QCOMPARE(_structureScanItem->gimbalPitch()->cookedValue().toDouble(), 0.0);
QCOMPARE(_structureScanItem->gimbalYaw()->cookedValue().toDouble(), 90.0);
}
void StructureScanComplexItemTest::_testItemCount(void)
{
QList<MissionItem*> items;
......
......@@ -27,7 +27,6 @@ protected:
private slots:
void _testDirty(void);
void _testSaveLoad(void);
void _testGimbalAngleUpdate(void);
void _testItemCount(void);
private:
......
......@@ -296,7 +296,7 @@ private:
static const char* _jsonFixedValueIsAltitudeKey;
static const char* _jsonRefly90DegreesKey;
static const int _hoverAndCaptureDelaySeconds = 2;
static const int _hoverAndCaptureDelaySeconds = 4;
};
#endif
......@@ -36,6 +36,7 @@ Rectangle {
property var _fileExtension: QGroundControl.settingsManager.appSettings.missionFileExtension
property var _appSettings: QGroundControl.settingsManager.appSettings
property bool _waypointsOnlyMode: QGroundControl.corePlugin.options.missionWaypointsOnly
property bool _showCameraSection: !_waypointsOnlyMode || QGroundControl.corePlugin.showAdvancedUI
readonly property string _firmwareLabel: qsTr("Firmware")
readonly property string _vehicleLabel: qsTr("Vehicle")
......@@ -91,6 +92,7 @@ Rectangle {
CameraSection {
id: cameraSection
checked: missionItem.cameraSection.settingsSpecified
visible: _showCameraSection
}
QGCLabel {
......@@ -100,7 +102,7 @@ Rectangle {
wrapMode: Text.WordWrap
horizontalAlignment: Text.AlignHCenter
font.pointSize: ScreenTools.smallFontPointSize
visible: cameraSection.checked
visible: _showCameraSection && cameraSection.checked
}
SectionHeader {
......
......@@ -81,33 +81,6 @@ Rectangle {
sideDistanceLabel: qsTr("Trigger Distance")
}
GridLayout {
anchors.left: parent.left
anchors.right: parent.right
columnSpacing: ScreenTools.defaultFontPixelWidth / 2
rowSpacing: 0
columns: 3
visible: missionItem.cameraCalc.isManualCamera
Item { width: 1; height: 1 }
QGCLabel { text: qsTr("Pitch") }
QGCLabel { text: qsTr("Yaw") }
QGCLabel {
text: qsTr("Gimbal")
Layout.fillWidth: true
}
FactTextField {
fact: missionItem.gimbalPitch
implicitWidth: ScreenTools.defaultFontPixelWidth * 9
}
FactTextField {
fact: missionItem.gimbalYaw
implicitWidth: ScreenTools.defaultFontPixelWidth * 9
}
}
SectionHeader {
id: scanHeader
text: qsTr("Scan")
......
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