Commit 8d7de40e authored by DonLakeFlyer's avatar DonLakeFlyer

Correctly handling of failed upload

parent 08f54ff7
...@@ -90,7 +90,7 @@ void APMGeoFenceManager::sendToVehicle(const QGeoCoordinate& breachReturn, QmlOb ...@@ -90,7 +90,7 @@ void APMGeoFenceManager::sendToVehicle(const QGeoCoordinate& breachReturn, QmlOb
_sendFencePoint(index); _sendFencePoint(index);
} }
emit sendComplete(); emit sendComplete(false /* error */);
} }
void APMGeoFenceManager::loadFromVehicle(void) void APMGeoFenceManager::loadFromVehicle(void)
...@@ -332,5 +332,5 @@ void APMGeoFenceManager::removeAll(void) ...@@ -332,5 +332,5 @@ void APMGeoFenceManager::removeAll(void)
QmlObjectListModel emptyPolygon; QmlObjectListModel emptyPolygon;
sendToVehicle(_breachReturnPoint, emptyPolygon); sendToVehicle(_breachReturnPoint, emptyPolygon);
emit removeAllComplete(); emit removeAllComplete(false /* error */);
} }
...@@ -48,7 +48,7 @@ void APMRallyPointManager::sendToVehicle(const QList<QGeoCoordinate>& rgPoints) ...@@ -48,7 +48,7 @@ void APMRallyPointManager::sendToVehicle(const QList<QGeoCoordinate>& rgPoints)
_sendRallyPoint(index); _sendRallyPoint(index);
} }
emit sendComplete(); emit sendComplete(false /* error */);
} }
void APMRallyPointManager::loadFromVehicle(void) void APMRallyPointManager::loadFromVehicle(void)
...@@ -157,5 +157,5 @@ void APMRallyPointManager::removeAll(void) ...@@ -157,5 +157,5 @@ void APMRallyPointManager::removeAll(void)
QList<QGeoCoordinate> noRallyPoints; QList<QGeoCoordinate> noRallyPoints;
sendToVehicle(noRallyPoints); sendToVehicle(noRallyPoints);
emit removeAllComplete(); emit removeAllComplete(false /* error */);
} }
...@@ -291,18 +291,20 @@ void GeoFenceController::_managerLoadComplete(const QGeoCoordinate& breachReturn ...@@ -291,18 +291,20 @@ void GeoFenceController::_managerLoadComplete(const QGeoCoordinate& breachReturn
_itemsRequested = false; _itemsRequested = false;
} }
void GeoFenceController::_managerSendComplete(void) void GeoFenceController::_managerSendComplete(bool error)
{ {
// Fly view always reloads on manager sendComplete // Fly view always reloads on manager sendComplete
if (!_editMode) { if (!error && !_editMode) {
showPlanFromManagerVehicle(); showPlanFromManagerVehicle();
} }
} }
void GeoFenceController::_managerRemoveAllComplete(void) void GeoFenceController::_managerRemoveAllComplete(bool error)
{ {
if (!error) {
// Remove all from vehicle so we always update // Remove all from vehicle so we always update
showPlanFromManagerVehicle(); showPlanFromManagerVehicle();
}
} }
bool GeoFenceController::containsItems(void) const bool GeoFenceController::containsItems(void) const
......
...@@ -90,8 +90,8 @@ private slots: ...@@ -90,8 +90,8 @@ private slots:
void _setReturnPointFromManager(QGeoCoordinate breachReturnPoint); void _setReturnPointFromManager(QGeoCoordinate breachReturnPoint);
void _managerLoadComplete(const QGeoCoordinate& breachReturn, const QList<QGeoCoordinate>& polygon); void _managerLoadComplete(const QGeoCoordinate& breachReturn, const QList<QGeoCoordinate>& polygon);
void _updateContainsItems(void); void _updateContainsItems(void);
void _managerSendComplete(void); void _managerSendComplete(bool error);
void _managerRemoveAllComplete(void); void _managerRemoveAllComplete(bool error);
private: private:
void _init(void); void _init(void);
......
...@@ -43,12 +43,12 @@ void GeoFenceManager::sendToVehicle(const QGeoCoordinate& breachReturn, QmlObjec ...@@ -43,12 +43,12 @@ void GeoFenceManager::sendToVehicle(const QGeoCoordinate& breachReturn, QmlObjec
// No geofence support in unknown vehicle // No geofence support in unknown vehicle
Q_UNUSED(breachReturn); Q_UNUSED(breachReturn);
Q_UNUSED(polygon); Q_UNUSED(polygon);
emit sendComplete(); emit sendComplete(false /* error */);
} }
void GeoFenceManager::removeAll(void) void GeoFenceManager::removeAll(void)
{ {
// No geofence support in unknown vehicle // No geofence support in unknown vehicle
emit removeAllComplete(); emit removeAllComplete(false /* error */);
} }
...@@ -96,8 +96,8 @@ signals: ...@@ -96,8 +96,8 @@ signals:
void polygonSupportedChanged (bool polygonSupported); void polygonSupportedChanged (bool polygonSupported);
void polygonEnabledChanged (bool polygonEnabled); void polygonEnabledChanged (bool polygonEnabled);
void breachReturnSupportedChanged (bool breachReturnSupported); void breachReturnSupportedChanged (bool breachReturnSupported);
void removeAllComplete (void); void removeAllComplete (bool error);
void sendComplete (void); void sendComplete (bool error);
protected: protected:
void _sendError(ErrorCode_t errorCode, const QString& errorMsg); void _sendError(ErrorCode_t errorCode, const QString& errorMsg);
......
...@@ -1716,16 +1716,18 @@ bool MissionController::showPlanFromManagerVehicle (void) ...@@ -1716,16 +1716,18 @@ bool MissionController::showPlanFromManagerVehicle (void)
} }
} }
void MissionController::_managerSendComplete(void) void MissionController::_managerSendComplete(bool error)
{ {
// FLy view always reloads on send complete // Fly view always reloads on send complete
if (!_editMode) { if (!error && !_editMode) {
showPlanFromManagerVehicle(); showPlanFromManagerVehicle();
} }
} }
void MissionController::_managerRemoveAllComplete(void) void MissionController::_managerRemoveAllComplete(bool error)
{ {
if (!error) {
// Remove all from vehicle so we always update // Remove all from vehicle so we always update
showPlanFromManagerVehicle(); showPlanFromManagerVehicle();
}
} }
...@@ -181,8 +181,8 @@ private slots: ...@@ -181,8 +181,8 @@ private slots:
void _cameraFeedback(QGeoCoordinate imageCoordinate, int index); void _cameraFeedback(QGeoCoordinate imageCoordinate, int index);
void _progressPctChanged(double progressPct); void _progressPctChanged(double progressPct);
void _visualItemsDirtyChanged(bool dirty); void _visualItemsDirtyChanged(bool dirty);
void _managerSendComplete(void); void _managerSendComplete(bool error);
void _managerRemoveAllComplete(void); void _managerRemoveAllComplete(bool error);
private: private:
void _init(void); void _init(void);
......
...@@ -50,10 +50,10 @@ void MissionManager::_writeMissionItemsWorker(void) ...@@ -50,10 +50,10 @@ void MissionManager::_writeMissionItemsWorker(void)
emit progressPct(0); emit progressPct(0);
qCDebug(MissionManagerLog) << "writeMissionItems count:" << _missionItems.count(); qCDebug(MissionManagerLog) << "writeMissionItems count:" << _writeMissionItems.count();
// Prime write list // Prime write list
for (int i=0; i<_missionItems.count(); i++) { for (int i=0; i<_writeMissionItems.count(); i++) {
_itemIndicesToWrite << i; _itemIndicesToWrite << i;
} }
...@@ -80,15 +80,15 @@ void MissionManager::writeMissionItems(const QList<MissionItem*>& missionItems) ...@@ -80,15 +80,15 @@ void MissionManager::writeMissionItems(const QList<MissionItem*>& missionItems)
return; return;
} }
bool skipFirstItem = !_vehicle->firmwarePlugin()->sendHomePositionToVehicle(); _clearAndDeleteWriteMissionItems();
_clearAndDeleteMissionItems(); bool skipFirstItem = !_vehicle->firmwarePlugin()->sendHomePositionToVehicle();
int firstIndex = skipFirstItem ? 1 : 0; int firstIndex = skipFirstItem ? 1 : 0;
for (int i=firstIndex; i<missionItems.count(); i++) { for (int i=firstIndex; i<missionItems.count(); i++) {
MissionItem* item = new MissionItem(*missionItems[i]); MissionItem* item = new MissionItem(*missionItems[i]);
_missionItems.append(item); _writeMissionItems.append(item);
item->setIsCurrentItem(i == firstIndex); item->setIsCurrentItem(i == firstIndex);
...@@ -107,7 +107,7 @@ void MissionManager::writeMissionItems(const QList<MissionItem*>& missionItems) ...@@ -107,7 +107,7 @@ void MissionManager::writeMissionItems(const QList<MissionItem*>& missionItems)
/// This begins the write sequence with the vehicle. This may be called during a retry. /// This begins the write sequence with the vehicle. This may be called during a retry.
void MissionManager::_writeMissionCount(void) void MissionManager::_writeMissionCount(void)
{ {
qCDebug(MissionManagerLog) << "_writeMissionCount count:_retryCount" << _missionItems.count() << _retryCount; qCDebug(MissionManagerLog) << "_writeMissionCount count:_retryCount" << _writeMissionItems.count() << _retryCount;
mavlink_message_t message; mavlink_message_t message;
mavlink_mission_count_t missionCount; mavlink_mission_count_t missionCount;
...@@ -115,7 +115,7 @@ void MissionManager::_writeMissionCount(void) ...@@ -115,7 +115,7 @@ void MissionManager::_writeMissionCount(void)
memset(&missionCount, 0, sizeof(missionCount)); memset(&missionCount, 0, sizeof(missionCount));
missionCount.target_system = _vehicle->id(); missionCount.target_system = _vehicle->id();
missionCount.target_component = MAV_COMP_ID_MISSIONPLANNER; missionCount.target_component = MAV_COMP_ID_MISSIONPLANNER;
missionCount.count = _missionItems.count(); missionCount.count = _writeMissionItems.count();
_dedicatedLink = _vehicle->priorityLink(); _dedicatedLink = _vehicle->priorityLink();
mavlink_msg_mission_count_encode_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), mavlink_msg_mission_count_encode_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
...@@ -539,13 +539,13 @@ void MissionManager::_handleMissionRequest(const mavlink_message_t& message, boo ...@@ -539,13 +539,13 @@ void MissionManager::_handleMissionRequest(const mavlink_message_t& message, boo
mavlink_msg_mission_request_decode(&message, &missionRequest); mavlink_msg_mission_request_decode(&message, &missionRequest);
qCDebug(MissionManagerLog) << "_handleMissionRequest sequenceNumber" << missionRequest.seq; qCDebug(MissionManagerLog) << "_handleMissionRequest sequenceNumber" << missionRequest.seq;
if (missionRequest.seq > _missionItems.count() - 1) { if (missionRequest.seq > _writeMissionItems.count() - 1) {
_sendError(RequestRangeError, QString("Vehicle requested item outside range, count:request %1:%2. Send to Vehicle failed.").arg(_missionItems.count()).arg(missionRequest.seq)); _sendError(RequestRangeError, QString("Vehicle requested item outside range, count:request %1:%2. Send to Vehicle failed.").arg(_writeMissionItems.count()).arg(missionRequest.seq));
_finishTransaction(false); _finishTransaction(false);
return; return;
} }
emit progressPct((double)missionRequest.seq / (double)_missionItems.count()); emit progressPct((double)missionRequest.seq / (double)_writeMissionItems.count());
_lastMissionRequest = missionRequest.seq; _lastMissionRequest = missionRequest.seq;
if (!_itemIndicesToWrite.contains(missionRequest.seq)) { if (!_itemIndicesToWrite.contains(missionRequest.seq)) {
...@@ -554,7 +554,7 @@ void MissionManager::_handleMissionRequest(const mavlink_message_t& message, boo ...@@ -554,7 +554,7 @@ void MissionManager::_handleMissionRequest(const mavlink_message_t& message, boo
_itemIndicesToWrite.removeOne(missionRequest.seq); _itemIndicesToWrite.removeOne(missionRequest.seq);
} }
MissionItem* item = _missionItems[missionRequest.seq]; MissionItem* item = _writeMissionItems[missionRequest.seq];
qCDebug(MissionManagerLog) << "_handleMissionRequest sequenceNumber:command" << missionRequest.seq << item->command(); qCDebug(MissionManagerLog) << "_handleMissionRequest sequenceNumber:command" << missionRequest.seq << item->command();
mavlink_message_t messageOut; mavlink_message_t messageOut;
...@@ -653,11 +653,11 @@ void MissionManager::_handleMissionAck(const mavlink_message_t& message) ...@@ -653,11 +653,11 @@ void MissionManager::_handleMissionAck(const mavlink_message_t& message)
qCDebug(MissionManagerLog) << "_handleMissionAck write sequence complete"; qCDebug(MissionManagerLog) << "_handleMissionAck write sequence complete";
_finishTransaction(true); _finishTransaction(true);
} else { } else {
_sendError(MissingRequestsError, QString("Vehicle did not request all items during write sequence, missed count %1. Vehicle only has partial list of mission items.").arg(_itemIndicesToWrite.count())); _sendError(MissingRequestsError, QString("Vehicle did not request all items during write sequence, missed count %1.").arg(_itemIndicesToWrite.count()));
_finishTransaction(false); _finishTransaction(false);
} }
} else { } else {
_sendError(VehicleError, QString("Vehicle returned error: %1. Vehicle only has partial list of mission items.").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type))); _sendError(VehicleError, QString("Vehicle returned error: %1.").arg(_missionResultToString((MAV_MISSION_RESULT)missionAck.type)));
_finishTransaction(false); _finishTransaction(false);
} }
break; break;
...@@ -779,8 +779,8 @@ QString MissionManager::_ackTypeToString(AckType_t ackType) ...@@ -779,8 +779,8 @@ QString MissionManager::_ackTypeToString(AckType_t ackType)
QString MissionManager::_lastMissionReqestString(MAV_MISSION_RESULT result) QString MissionManager::_lastMissionReqestString(MAV_MISSION_RESULT result)
{ {
if (_lastMissionRequest != -1 && _lastMissionRequest >= 0 && _lastMissionRequest < _missionItems.count()) { if (_lastMissionRequest != -1 && _lastMissionRequest >= 0 && _lastMissionRequest < _writeMissionItems.count()) {
MissionItem* item = _missionItems[_lastMissionRequest]; MissionItem* item = _writeMissionItems[_lastMissionRequest];
switch (result) { switch (result) {
case MAV_MISSION_UNSUPPORTED_FRAME: case MAV_MISSION_UNSUPPORTED_FRAME:
...@@ -895,10 +895,21 @@ void MissionManager::_finishTransaction(bool success) ...@@ -895,10 +895,21 @@ void MissionManager::_finishTransaction(bool success)
emit newMissionItemsAvailable(false); emit newMissionItemsAvailable(false);
break; break;
case TransactionWrite: case TransactionWrite:
emit sendComplete(); if (success) {
// Write succeeded, update internal list to be current
_clearAndDeleteMissionItems();
for (int i=0; i<_writeMissionItems.count(); i++) {
_missionItems.append(_writeMissionItems[i]);
}
_writeMissionItems.clear();
} else {
// Write failed, throw out the write list
_clearAndDeleteWriteMissionItems();
}
emit sendComplete(!success /* error */);
break; break;
case TransactionRemoveAll: case TransactionRemoveAll:
emit removeAllComplete(); emit removeAllComplete(!success /* error */);
break; break;
default: default:
break; break;
...@@ -1123,9 +1134,9 @@ void MissionManager::generateResumeMission(int resumeIndex) ...@@ -1123,9 +1134,9 @@ void MissionManager::generateResumeMission(int resumeIndex)
} }
// Send to vehicle // Send to vehicle
_clearAndDeleteMissionItems(); _clearAndDeleteWriteMissionItems();
for (int i=0; i<resumeMission.count(); i++) { for (int i=0; i<resumeMission.count(); i++) {
_missionItems.append(new MissionItem(*resumeMission[i], this)); _writeMissionItems.append(new MissionItem(*resumeMission[i], this));
} }
_resumeMission = true; _resumeMission = true;
_writeMissionItemsWorker(); _writeMissionItemsWorker();
...@@ -1143,3 +1154,12 @@ void MissionManager::_clearAndDeleteMissionItems(void) ...@@ -1143,3 +1154,12 @@ void MissionManager::_clearAndDeleteMissionItems(void)
} }
_missionItems.clear(); _missionItems.clear();
} }
void MissionManager::_clearAndDeleteWriteMissionItems(void)
{
for (int i=0; i<_writeMissionItems.count(); i++) {
_writeMissionItems[i]->deleteLater();
}
_writeMissionItems.clear();
}
...@@ -90,8 +90,8 @@ signals: ...@@ -90,8 +90,8 @@ signals:
void resumeMissionReady(void); void resumeMissionReady(void);
void cameraFeedback(QGeoCoordinate imageCoordinate, int index); void cameraFeedback(QGeoCoordinate imageCoordinate, int index);
void progressPct(double progressPercentPct); void progressPct(double progressPercentPct);
void removeAllComplete (void); void removeAllComplete (bool error);
void sendComplete (void); void sendComplete (bool error);
private slots: private slots:
void _mavlinkMessageReceived(const mavlink_message_t& message); void _mavlinkMessageReceived(const mavlink_message_t& message);
...@@ -134,6 +134,7 @@ private: ...@@ -134,6 +134,7 @@ private:
void _writeMissionCount(void); void _writeMissionCount(void);
void _writeMissionItemsWorker(void); void _writeMissionItemsWorker(void);
void _clearAndDeleteMissionItems(void); void _clearAndDeleteMissionItems(void);
void _clearAndDeleteWriteMissionItems(void);
QString _lastMissionReqestString(MAV_MISSION_RESULT result); QString _lastMissionReqestString(MAV_MISSION_RESULT result);
void _removeAllWorker(void); void _removeAllWorker(void);
...@@ -153,7 +154,8 @@ private: ...@@ -153,7 +154,8 @@ private:
QMutex _dataMutex; QMutex _dataMutex;
QList<MissionItem*> _missionItems; QList<MissionItem*> _missionItems; ///< Set of mission items on vehicle
QList<MissionItem*> _writeMissionItems; ///< Set of mission items currently being written to vehicle
int _currentMissionIndex; int _currentMissionIndex;
int _lastCurrentIndex; int _lastCurrentIndex;
}; };
......
...@@ -203,18 +203,20 @@ void RallyPointController::_managerLoadComplete(const QList<QGeoCoordinate> rgPo ...@@ -203,18 +203,20 @@ void RallyPointController::_managerLoadComplete(const QList<QGeoCoordinate> rgPo
_itemsRequested = false; _itemsRequested = false;
} }
void RallyPointController::_managerSendComplete(void) void RallyPointController::_managerSendComplete(bool error)
{ {
// Fly view always reloads after send // Fly view always reloads after send
if (_editMode) { if (!error && _editMode) {
showPlanFromManagerVehicle(); showPlanFromManagerVehicle();
} }
} }
void RallyPointController::_managerRemoveAllComplete(void) void RallyPointController::_managerRemoveAllComplete(bool error)
{ {
if (!error) {
// Remove all from vehicle so we always update // Remove all from vehicle so we always update
showPlanFromManagerVehicle(); showPlanFromManagerVehicle();
}
} }
void RallyPointController::addPoint(QGeoCoordinate point) void RallyPointController::addPoint(QGeoCoordinate point)
......
...@@ -64,8 +64,8 @@ signals: ...@@ -64,8 +64,8 @@ signals:
private slots: private slots:
void _managerLoadComplete(const QList<QGeoCoordinate> rgPoints); void _managerLoadComplete(const QList<QGeoCoordinate> rgPoints);
void _managerSendComplete(void); void _managerSendComplete(bool error);
void _managerRemoveAllComplete(void); void _managerRemoveAllComplete(bool error);
void _setFirstPointCurrent(void); void _setFirstPointCurrent(void);
void _updateContainsItems(void); void _updateContainsItems(void);
......
...@@ -41,11 +41,11 @@ void RallyPointManager::sendToVehicle(const QList<QGeoCoordinate>& rgPoints) ...@@ -41,11 +41,11 @@ void RallyPointManager::sendToVehicle(const QList<QGeoCoordinate>& rgPoints)
{ {
// No support in generic vehicle // No support in generic vehicle
Q_UNUSED(rgPoints); Q_UNUSED(rgPoints);
emit sendComplete(); emit sendComplete(false /* error */);
} }
void RallyPointManager::removeAll(void) void RallyPointManager::removeAll(void)
{ {
// No support in generic vehicle // No support in generic vehicle
emit removeAllComplete(); emit removeAllComplete(false /* error */);
} }
...@@ -62,8 +62,8 @@ signals: ...@@ -62,8 +62,8 @@ signals:
void loadComplete (const QList<QGeoCoordinate> rgPoints); void loadComplete (const QList<QGeoCoordinate> rgPoints);
void inProgressChanged (bool inProgress); void inProgressChanged (bool inProgress);
void error (int errorCode, const QString& errorMsg); void error (int errorCode, const QString& errorMsg);
void removeAllComplete (void); void removeAllComplete (bool error);
void sendComplete (void); void sendComplete (bool error);
protected: protected:
void _sendError(ErrorCode_t errorCode, const QString& errorMsg); void _sendError(ErrorCode_t errorCode, const QString& errorMsg);
......
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