QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
WaitForParamResponseState.h
Go to the documentation of this file.
1#pragma once
2
3#include "WaitStateBase.h"
4#include "QGCMAVLink.h"
5
6#include <cstdint>
7#include <functional>
8
9class Vehicle;
10
18{
19 Q_OBJECT
20 Q_DISABLE_COPY(WaitForParamResponseState)
21
22public:
23 using Predicate = std::function<bool(const mavlink_message_t &message)>;
24
29 WaitForParamResponseState(QState *parent, int timeoutMsecs,
30 Predicate paramValuePredicate,
31 Predicate paramErrorPredicate);
32
34 uint8_t lastParamError() const { return _lastParamError; }
35
37 QString lastParamErrorString() const { return _lastParamErrorString; }
38
39protected:
40 void connectWaitSignal() override;
41 void disconnectWaitSignal() override;
42
43private slots:
44 void _messageReceived(const mavlink_message_t &message);
45
46private:
47 static QString _paramErrorToString(uint8_t errorCode);
48
49 Predicate _paramValuePredicate;
50 Predicate _paramErrorPredicate;
51 uint8_t _lastParamError = 0;
52 QString _lastParamErrorString;
53};
struct __mavlink_message mavlink_message_t
Waits for either PARAM_VALUE (success) or PARAM_ERROR (rejection) from the vehicle.
void disconnectWaitSignal() override
Subclasses override to tear down their signal connections.
std::function< bool(const mavlink_message_t &message)> Predicate
void connectWaitSignal() override
Subclasses override to set up their signal connections.
Base class for states that wait for something with optional timeout.
int timeoutMsecs() const