5 Action action,
int maxRetries,
int retryDelayMsecs,
8 , _action(std::move(action))
9 , _maxRetries(maxRetries)
10 , _retryDelayMsecs(retryDelayMsecs)
11 , _exhaustedBehavior(exhaustedBehavior)
13 _retryTimer.setSingleShot(
true);
14 connect(&_retryTimer, &QTimer::timeout,
this, &RetryState::_executeAction);
24void RetryState::_executeAction()
28 qCDebug(QGCStateMachineLog) <<
stateName() <<
"attempt" << _currentAttempt
37 qCDebug(QGCStateMachineLog) <<
stateName() <<
"succeeded on attempt" << _currentAttempt;
40 }
else if (_currentAttempt <= _maxRetries) {
41 qCDebug(QGCStateMachineLog) <<
stateName() <<
"failed, retrying in"
42 << _retryDelayMsecs <<
"ms";
44 _retryTimer.start(_retryDelayMsecs);
46 qCDebug(QGCStateMachineLog) <<
stateName() <<
"all retries exhausted";
QString stateName() const
void succeeded()
Emitted when the action eventually succeeds.
int totalAttempts() const
std::function< bool()> Action
void skipped()
Emitted when retries are exhausted and behavior is EmitAdvance.
void onEnter() override
Override to perform actions on state entry.
void exhausted()
Emitted when all retries are exhausted (both behaviors).
RetryState(const QString &stateName, QState *parent, Action action, int maxRetries=0, int retryDelayMsecs=1000, ExhaustedBehavior exhaustedBehavior=EmitError)
@ EmitAdvance
Emit advance() after retries exhausted (skip/continue).
void retrying(int attempt, int maxAttempts)
Emitted before each retry attempt.