QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
WaitForParamResponseState.cc
Go to the documentation of this file.
2#include "Vehicle.h"
4
5#include <utility>
6
8 Predicate paramValuePredicate,
9 Predicate paramErrorPredicate)
10 : WaitStateBase(QStringLiteral("WaitForParamResponseState"), parent, timeoutMsecs)
11 , _paramValuePredicate(std::move(paramValuePredicate))
12 , _paramErrorPredicate(std::move(paramErrorPredicate))
13{
14}
15
17{
18 connect(vehicle(), &Vehicle::mavlinkMessageReceived, this, &WaitForParamResponseState::_messageReceived, Qt::UniqueConnection);
19}
20
22{
23 if (vehicle()) {
24 disconnect(vehicle(), &Vehicle::mavlinkMessageReceived, this, &WaitForParamResponseState::_messageReceived);
25 }
26}
27
28void WaitForParamResponseState::_messageReceived(const mavlink_message_t &message)
29{
30 if (message.msgid == MAVLINK_MSG_ID_PARAM_VALUE) {
31 if (_paramValuePredicate && !_paramValuePredicate(message)) {
32 return;
33 }
34
35 qCDebug(QGCStateMachineLog) << "Received PARAM_VALUE" << stateName();
37 return;
38 }
39
40 if (message.msgid == MAVLINK_MSG_ID_PARAM_ERROR) {
41 if (_paramErrorPredicate && !_paramErrorPredicate(message)) {
42 return;
43 }
44
45 mavlink_param_error_t paramError{};
46 mavlink_msg_param_error_decode(&message, &paramError);
47
48 _lastParamError = paramError.error;
49 _lastParamErrorString = _paramErrorToString(paramError.error);
50
51 char paramId[MAVLINK_MSG_PARAM_ERROR_FIELD_PARAM_ID_LEN + 1] = {};
52 (void) strncpy(paramId, paramError.param_id, MAVLINK_MSG_PARAM_ERROR_FIELD_PARAM_ID_LEN);
53
54 qCDebug(QGCStateMachineLog) << "Received PARAM_ERROR for" << paramId
55 << "error:" << _lastParamErrorString << stateName();
56 waitFailed();
57 return;
58 }
59}
60
61QString WaitForParamResponseState::_paramErrorToString(uint8_t errorCode)
62{
63 switch (errorCode) {
64 case MAV_PARAM_ERROR_NO_ERROR:
65 return QStringLiteral("No error");
66 case MAV_PARAM_ERROR_DOES_NOT_EXIST:
67 return QStringLiteral("Parameter does not exist");
68 case MAV_PARAM_ERROR_VALUE_OUT_OF_RANGE:
69 return QStringLiteral("Value out of range");
70 case MAV_PARAM_ERROR_PERMISSION_DENIED:
71 return QStringLiteral("Permission denied");
72 case MAV_PARAM_ERROR_COMPONENT_NOT_FOUND:
73 return QStringLiteral("Component not found");
74 case MAV_PARAM_ERROR_READ_ONLY:
75 return QStringLiteral("Parameter is read-only");
76 case MAV_PARAM_ERROR_TYPE_UNSUPPORTED:
77 return QStringLiteral("Parameter type unsupported");
78 case MAV_PARAM_ERROR_TYPE_MISMATCH:
79 return QStringLiteral("Parameter type mismatch");
80 case MAV_PARAM_ERROR_READ_FAIL:
81 return QStringLiteral("Parameter read failed");
82 default:
83 return QStringLiteral("Unknown error (%1)").arg(errorCode);
84 }
85}
struct __mavlink_message mavlink_message_t
QString stateName() const
Vehicle * vehicle() const
void mavlinkMessageReceived(const mavlink_message_t &message)
void disconnectWaitSignal() override
Subclasses override to tear down their signal connections.
WaitForParamResponseState(QState *parent, int timeoutMsecs, Predicate paramValuePredicate, Predicate paramErrorPredicate)
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.