QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
RetryableRequestMessageState.h
Go to the documentation of this file.
1#pragma once
2
3#include "WaitStateBase.h"
4#include "Vehicle.h"
5
6#include <functional>
7
26{
27 Q_OBJECT
28 Q_DISABLE_COPY(RetryableRequestMessageState)
29
30public:
31 using MessageHandler = std::function<void(Vehicle* vehicle, const mavlink_message_t& message)>;
32 using FailureHandler = std::function<void(Vehicle::RequestMessageResultHandlerFailureCode_t failureCode, MAV_RESULT result)>;
33 using SkipPredicate = std::function<bool()>;
34
44 QState* parent,
45 uint32_t messageId,
46 MessageHandler messageHandler = nullptr,
47 int maxRetries = 1,
48 int compId = MAV_COMP_ID_AUTOPILOT1,
49 int timeoutMsecs = 5000);
50
52 void setFailureHandler(FailureHandler handler) { _failureHandler = std::move(handler); }
53
56 void setSkipPredicate(SkipPredicate predicate) { _skipPredicate = std::move(predicate); }
57
59 void setFailOnMaxRetries(bool fail) { _failOnMaxRetries = fail; }
60
63
65 MAV_RESULT lastResult() const { return _lastResult; }
66
68 int retryCount() const { return _retryCount; }
69
71 int maxRetries() const { return _maxRetries; }
72
73signals:
75 void messageReceived(const mavlink_message_t& message);
76
79
80protected:
81 void connectWaitSignal() override {}
82 void disconnectWaitSignal() override {}
83 void onWaitEntered() override;
84 void onWaitExited() override;
85 void onWaitTimeout() override;
86
87private:
88 void _sendRequest();
89 void _queueRetry();
90 void _handleResult(MAV_RESULT result,
92 const mavlink_message_t& message);
93
94 uint32_t _messageId;
95 MessageHandler _messageHandler;
96 FailureHandler _failureHandler;
97 SkipPredicate _skipPredicate;
98 int _compId;
99 int _maxRetries;
100 int _retryCount = 0;
101 bool _failOnMaxRetries = false;
102
103 bool _requestActive = false;
104
106 MAV_RESULT _lastResult = MAV_RESULT_ACCEPTED;
107};
struct __mavlink_message mavlink_message_t
QString stateName() const
Vehicle * vehicle() const
int maxRetries() const
Get max retries setting.
std::function< void(Vehicle::RequestMessageResultHandlerFailureCode_t failureCode, MAV_RESULT result)> FailureHandler
void onWaitExited() override
Called when the state is exited - subclasses should call base implementation.
int retryCount() const
Get current retry count.
void messageReceived(const mavlink_message_t &message)
Emitted when message is successfully received.
void setFailOnMaxRetries(bool fail)
If true, emit error() after max retries instead of advance()
Vehicle::RequestMessageResultHandlerFailureCode_t lastFailureCode() const
Get the failure code from the last attempt.
void disconnectWaitSignal() override
Subclasses override to tear down their signal connections.
void onWaitTimeout() override
Called when the timeout expires - default emits timeout(), subclasses can override.
void setSkipPredicate(SkipPredicate predicate)
void onWaitEntered() override
Called when the state is entered - subclasses should call base implementation.
void retriesExhausted()
Emitted when all retries are exhausted.
std::function< void(Vehicle *vehicle, const mavlink_message_t &message)> MessageHandler
void connectWaitSignal() override
Subclasses override to set up their signal connections.
MAV_RESULT lastResult() const
Get the MAV_RESULT from the last attempt.
void setFailureHandler(FailureHandler handler)
Set handler called when all retries fail.
RequestMessageResultHandlerFailureCode_t
Definition Vehicle.h:668
@ RequestMessageNoFailure
Definition Vehicle.h:669
int timeoutMsecs() const