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 "MAVLinkEnums.h"
6#include "VehicleTypes.h"
7
8class Vehicle;
9
10#include <functional>
11
32{
33 Q_OBJECT
34 Q_DISABLE_COPY(RetryableRequestMessageState)
35
36public:
37 using MessageHandler = std::function<void(Vehicle* vehicle, const mavlink_message_t& message)>;
38 using FailureHandler = std::function<void(VehicleTypes::RequestMessageResultHandlerFailureCode_t failureCode, MAV_RESULT result)>;
39 using SkipPredicate = std::function<bool()>;
40
50 QState* parent,
51 uint32_t messageId,
52 MessageHandler messageHandler = nullptr,
53 int maxRetries = 1,
54 int compId = MAV_COMP_ID_AUTOPILOT1,
55 int timeoutMsecs = 5000);
56
58 void setFailureHandler(FailureHandler handler) { _failureHandler = std::move(handler); }
59
62 void setSkipPredicate(SkipPredicate predicate) { _skipPredicate = std::move(predicate); }
63
65 void setFailOnMaxRetries(bool fail) { _failOnMaxRetries = fail; }
66
69
71 MAV_RESULT lastResult() const { return _lastResult; }
72
74 int retryCount() const { return _retryCount; }
75
77 int maxRetries() const { return _maxRetries; }
78
79signals:
81 void messageReceived(const mavlink_message_t& message);
82
85
86protected:
87 void connectWaitSignal() override {}
88 void disconnectWaitSignal() override {}
89 void onWaitEntered() override;
90 void onWaitExited() override;
91 void onWaitTimeout() override;
92
93private:
94 void _sendRequest();
95 void _queueRetry();
96 void _handleResult(MAV_RESULT result,
98 const mavlink_message_t& message);
99
100 uint32_t _messageId;
101 MessageHandler _messageHandler;
102 FailureHandler _failureHandler;
103 SkipPredicate _skipPredicate;
104 int _compId;
105 int _maxRetries;
106 int _retryCount = 0;
107 bool _failOnMaxRetries = false;
108
109 bool _requestActive = false;
110
112 MAV_RESULT _lastResult = MAV_RESULT_ACCEPTED;
113};
struct __mavlink_message mavlink_message_t
QString stateName() const
Vehicle * vehicle() const
Requests a MAVLink message with built-in retry logic.
int maxRetries() const
Get max retries setting.
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()
std::function< void(VehicleTypes::RequestMessageResultHandlerFailureCode_t failureCode, MAV_RESULT result)> FailureHandler
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.
VehicleTypes::RequestMessageResultHandlerFailureCode_t lastFailureCode() const
Get the failure code from the last attempt.
Base class for states that wait for something with optional timeout.
int timeoutMsecs() const
RequestMessageResultHandlerFailureCode_t
@ RequestMessageNoFailure