PlanManager: use shorter timeout to download items

When downloading mission items from the autopilot we need to retry more
agressively, so use a shorter timeout. If we don't do this, we might not
re-request a mission item in time and the autopilot has already given up
the overall mission transfer.

This fixes the case where a mission request from QGC to autopilot or a
mission item from autopilot to QGC gets lost on the link and needs to be
requested again.
parent 1e856cc1
......@@ -36,7 +36,6 @@ PlanManager::PlanManager(Vehicle* vehicle, MAV_MISSION_TYPE planType)
{
_ackTimeoutTimer = new QTimer(this);
_ackTimeoutTimer->setSingleShot(true);
_ackTimeoutTimer->setInterval(_ackTimeoutMilliseconds);
connect(_ackTimeoutTimer, &QTimer::timeout, this, &PlanManager::_ackTimeout);
}
......@@ -245,6 +244,24 @@ void PlanManager::_ackTimeout(void)
void PlanManager::_startAckTimeout(AckType_t ack)
{
switch (ack) {
case AckMissionItem:
// We are actively trying to get the mission item, so we don't want to wait as long.
_ackTimeoutTimer->setInterval(_retryTimeoutMilliseconds);
break;
case AckNone:
// FALLTHROUGH
case AckMissionCount:
// FALLTHROUGH
case AckMissionRequest:
// FALLTHROUGH
case AckMissionClearAll:
// FALLTHROUGH
case AckGuidedItem:
_ackTimeoutTimer->setInterval(_ackTimeoutMilliseconds);
break;
}
_expectedAck = ack;
_ackTimeoutTimer->start();
}
......
......@@ -70,7 +70,10 @@ public:
} ErrorCode_t;
// These values are public so the unit test can set appropriate signal wait times
// When passively waiting for a mission process, use a longer timeout.
static const int _ackTimeoutMilliseconds = 1000;
// When actively retrying to request mission items, use a shorter timeout instead.
static const int _retryTimeoutMilliseconds = 250;
static const int _maxRetryCount = 5;
signals:
......
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