Commit a68e2f21 authored by Gus Grubba's avatar Gus Grubba

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

parents 72082c24 0e0d3073
......@@ -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
}
......
......@@ -150,7 +150,8 @@ LinuxBuild {
platforminputcontexts \
platforms \
position \
sqldrivers
sqldrivers \
texttospeech
!contains(DEFINES, __rasp_pi2__) {
QT_PLUGIN_LIST += xcbglintegrations
......
......@@ -34,10 +34,9 @@ mkdir -p ${APPDIR}
cd ${TMPDIR}
wget -c --quiet http://ftp.us.debian.org/debian/pool/main/u/udev/udev_175-7.2_amd64.deb
wget -c --quiet http://ftp.us.debian.org/debian/pool/main/e/espeak/espeak_1.46.02-2_amd64.deb
wget -c --quiet http://ftp.us.debian.org/debian/pool/main/s/speech-dispatcher/speech-dispatcher_0.8.8-1_amd64.deb
wget -c --quiet http://ftp.us.debian.org/debian/pool/main/libs/libsdl2/libsdl2-2.0-0_2.0.2%2bdfsg1-6_amd64.deb
cd ${APPDIR}
find ../ -name *.deb -exec dpkg -x {} . \;
......
......@@ -101,13 +101,15 @@ Item {
property bool showLand: _activeVehicle && _activeVehicle.guidedModeSupported && _vehicleArmed && !_activeVehicle.fixedWing && !_vehicleInLandMode
property bool showStartMission: _activeVehicle && _missionAvailable && !_missionActive && !_vehicleFlying
property bool showContinueMission: _activeVehicle && _missionAvailable && !_missionActive && _vehicleFlying && (_currentMissionIndex < missionController.visualItems.count - 1)
property bool showResumeMission: _activeVehicle && !_vehicleArmed && _vehicleWasFlying && _missionAvailable && _resumeMissionIndex > 0 && (_resumeMissionIndex < missionController.visualItems.count - 2)
property bool showPause: _activeVehicle && _vehicleArmed && _activeVehicle.pauseVehicleSupported && _vehicleFlying && !_vehiclePaused
property bool showChangeAlt: (_activeVehicle && _vehicleFlying) && _activeVehicle.guidedModeSupported && _vehicleArmed && !_missionActive
property bool showOrbit: !_hideOrbit && _activeVehicle && _vehicleFlying && _activeVehicle.orbitModeSupported && _vehicleArmed && !_missionActive
property bool showLandAbort: _activeVehicle && _vehicleFlying && _activeVehicle.fixedWing && _vehicleLanding
property bool showGotoLocation: _activeVehicle && _vehicleFlying
// Note: The 'missionController.visualItems.count - 3' is a hack to not trigger resume mission when a mission ends with an RTL item
property bool showResumeMission: _activeVehicle && !_vehicleArmed && _vehicleWasFlying && _missionAvailable && _resumeMissionIndex > 0 && (_resumeMissionIndex < missionController.visualItems.count - 3)
property bool guidedUIVisible: guidedActionConfirm.visible || guidedActionList.visible
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
......
......@@ -479,6 +479,7 @@ void MissionController::removeAll(void)
{
if (_visualItems) {
_deinitAllVisualItems();
_visualItems->clearAndDeleteContents();
_visualItems->deleteLater();
_settingsItem = NULL;
_visualItems = new QmlObjectListModel(this);
......
......@@ -242,7 +242,7 @@ void MissionManager::_handleMissionCurrent(const mavlink_message_t& message)
emit currentIndexChanged(_currentMissionIndex);
}
if (_currentMissionIndex != _lastCurrentIndex) {
if (_currentMissionIndex != _lastCurrentIndex && _cachedLastCurrentIndex != _currentMissionIndex) {
// We have to be careful of an RTL sequence causing a change of index to the DO_LAND_START sequence. This also triggers
// a flight mode change away from mission flight mode. So we only update _lastCurrentIndex when the flight mode is mission.
// But we can run into problems where we may get the MISSION_CURRENT message for the RTL/DO_LAND_START sequenc change prior
......
......@@ -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);
......@@ -132,9 +121,9 @@ 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
1; // Gimbal control command
((_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
}
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 = 1;
static const int _hoverAndCaptureDelaySeconds = 2;
};
#endif
......@@ -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")
......
......@@ -61,14 +61,14 @@ double limitAngleToPMPId(double angle)
{
while (angle < -M_PI)
{
angle += M_PI;
angle += 2.0f * M_PI;
}
}
else if (angle > M_PI)
{
while (angle > M_PI)
{
angle -= M_PI;
angle -= 2.0f * M_PI;
}
}
}
......
......@@ -33,6 +33,8 @@ TerrainBatchManager::TerrainBatchManager(void)
void TerrainBatchManager::addQuery(ElevationProvider* elevationProvider, const QList<QGeoCoordinate>& coordinates)
{
if (coordinates.length() > 0) {
qCDebug(ElevationProviderLog) << "addQuery: elevationProvider:coordinates.count" << elevationProvider << coordinates.count();
connect(elevationProvider, &ElevationProvider::destroyed, this, &TerrainBatchManager::_elevationProviderDestroyed);
QueuedRequestInfo_t queuedRequestInfo = { elevationProvider, coordinates };
_requestQueue.append(queuedRequestInfo);
if (!_batchTimer.isActive()) {
......@@ -43,7 +45,7 @@ void TerrainBatchManager::addQuery(ElevationProvider* elevationProvider, const Q
void TerrainBatchManager::_sendNextBatch(void)
{
qCDebug(ElevationProviderLog) << "_sendNextBatch _state:_requestQueue.count" << (int)_state << _requestQueue.count();
qCDebug(ElevationProviderLog) << "_sendNextBatch _state:_requestQueue.count:_sentRequests.count" << _stateToString(_state) << _requestQueue.count() << _sentRequests.count();
if (_state != State::Idle) {
// Waiting for last download the complete, wait some more
......@@ -60,7 +62,7 @@ void TerrainBatchManager::_sendNextBatch(void)
// Convert coordinates to point strings for json query
QString points;
foreach (const QueuedRequestInfo_t& requestInfo, _requestQueue) {
SentRequestInfo_t sentRequestInfo = { requestInfo.elevationProvider, requestInfo.coordinates.count() };
SentRequestInfo_t sentRequestInfo = { requestInfo.elevationProvider, false, requestInfo.coordinates.count() };
qCDebug(ElevationProviderLog) << "Building request: coordinate count" << requestInfo.coordinates.count();
_sentRequests.append(sentRequestInfo);
......@@ -100,20 +102,23 @@ void TerrainBatchManager::_batchFailed(void)
QList<float> noAltitudes;
foreach (const SentRequestInfo_t& sentRequestInfo, _sentRequests) {
sentRequestInfo.elevationProvider->_signalTerrainData(false, noAltitudes);
if (!sentRequestInfo.providerDestroyed) {
disconnect(sentRequestInfo.elevationProvider, &ElevationProvider::destroyed, this, &TerrainBatchManager::_elevationProviderDestroyed);
sentRequestInfo.elevationProvider->_signalTerrainData(false, noAltitudes);
}
}
_sentRequests.clear();
}
void TerrainBatchManager::_requestFinished()
{
qCDebug(ElevationProviderLog) << "_requestFinished";
QNetworkReply* reply = qobject_cast<QNetworkReply*>(QObject::sender());
_state = State::Idle;
// When an error occurs we still end up here
if (reply->error() != QNetworkReply::NoError) {
qCDebug(ElevationProviderLog) << "_requestFinished error:" << reply->error();
_batchFailed();
reply->deleteLater();
return;
......@@ -124,6 +129,7 @@ void TerrainBatchManager::_requestFinished()
QJsonParseError parseError;
QJsonDocument responseJson = QJsonDocument::fromJson(responseBytes, &parseError);
if (parseError.error != QJsonParseError::NoError) {
qCDebug(ElevationProviderLog) << "_requestFinished unable to parse json:" << parseError.errorString();
_batchFailed();
reply->deleteLater();
return;
......@@ -132,6 +138,7 @@ void TerrainBatchManager::_requestFinished()
QJsonObject rootObject = responseJson.object();
QString status = rootObject["status"].toString();
if (status != "success") {
qCDebug(ElevationProviderLog) << "_requestFinished status != success:" << status;
_batchFailed();
reply->deleteLater();
return;
......@@ -145,15 +152,56 @@ void TerrainBatchManager::_requestFinished()
int currentIndex = 0;
foreach (const SentRequestInfo_t& sentRequestInfo, _sentRequests) {
QList<float> requestAltitudes = altitudes.mid(currentIndex, sentRequestInfo.cCoord);
sentRequestInfo.elevationProvider->_signalTerrainData(true, requestAltitudes);
currentIndex += sentRequestInfo.cCoord;
if (!sentRequestInfo.providerDestroyed) {
disconnect(sentRequestInfo.elevationProvider, &ElevationProvider::destroyed, this, &TerrainBatchManager::_elevationProviderDestroyed);
QList<float> requestAltitudes = altitudes.mid(currentIndex, sentRequestInfo.cCoord);
sentRequestInfo.elevationProvider->_signalTerrainData(true, requestAltitudes);
currentIndex += sentRequestInfo.cCoord;
}
}
_sentRequests.clear();
reply->deleteLater();
}
void TerrainBatchManager::_elevationProviderDestroyed(QObject* elevationProvider)
{
// Remove/Mark deleted objects queries from queues
qCDebug(ElevationProviderLog) << "_elevationProviderDestroyed elevationProvider" << elevationProvider;
int i = 0;
while (i < _requestQueue.count()) {
const QueuedRequestInfo_t& requestInfo = _requestQueue[i];
if (requestInfo.elevationProvider == elevationProvider) {
qCDebug(ElevationProviderLog) << "Removing deleted provider from _requestQueue index:elevationProvider" << i << requestInfo.elevationProvider;
_requestQueue.removeAt(i);
} else {
i++;
}
}
for (int i=0; i<_sentRequests.count(); i++) {
SentRequestInfo_t& sentRequestInfo = _sentRequests[i];
if (sentRequestInfo.elevationProvider == elevationProvider) {
qCDebug(ElevationProviderLog) << "Zombieing deleted provider from _sentRequests index:elevatationProvider" << sentRequestInfo.elevationProvider;
sentRequestInfo.providerDestroyed = true;
}
}
}
QString TerrainBatchManager::_stateToString(State state)
{
switch (state) {
case State::Idle:
return QStringLiteral("Idle");
case State::Downloading:
return QStringLiteral("Downloading");
}
return QStringLiteral("State unknown");
}
ElevationProvider::ElevationProvider(QObject* parent)
: QObject(parent)
{
......@@ -161,7 +209,6 @@ ElevationProvider::ElevationProvider(QObject* parent)
}
void ElevationProvider::queryTerrainData(const QList<QGeoCoordinate>& coordinates)
{
qCDebug(ElevationProviderLog) << "queryTerrainData: coordinate count" << coordinates.count();
if (coordinates.length() == 0) {
return;
}
......
......@@ -30,8 +30,9 @@ public:
void addQuery(ElevationProvider* elevationProvider, const QList<QGeoCoordinate>& coordinates);
private slots:
void _sendNextBatch (void);
void _requestFinished (void);
void _sendNextBatch (void);
void _requestFinished (void);
void _elevationProviderDestroyed (QObject* elevationProvider);
private:
typedef struct {
......@@ -41,6 +42,7 @@ private:
typedef struct {
ElevationProvider* elevationProvider;
bool providerDestroyed;
int cCoord;
} SentRequestInfo_t;
......@@ -51,6 +53,7 @@ private:
};
void _batchFailed(void);
QString _stateToString(State state);
QList<QueuedRequestInfo_t> _requestQueue;
QList<SentRequestInfo_t> _sentRequests;
......
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