QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
RequestMessageState.cc
Go to the documentation of this file.
4
6 uint32_t messageId,
7 MessageHandler messageHandler,
8 int compId,
9 int timeoutMsecs,
10 float param1,
11 float param2,
12 float param3,
13 float param4,
14 float param5)
15 : WaitStateBase(QStringLiteral("RequestMessageState:%1").arg(messageId), parent, timeoutMsecs)
16 , _messageId(messageId)
17 , _messageHandler(std::move(messageHandler))
18 , _compId(compId)
19 , _param1(param1)
20 , _param2(param2)
21 , _param3(param3)
22 , _param4(param4)
23 , _param5(param5)
24{
25}
26
28{
30
32
33 if (!sharedLink) {
34 qCDebug(QGCStateMachineLog) << "Skipping request due to no primary link" << stateName();
36 waitFailed();
37 return;
38 }
39
40 if (sharedLink->linkConfiguration()->isHighLatency() || sharedLink->isLogReplay()) {
41 qCDebug(QGCStateMachineLog) << "Skipping request due to link type" << stateName();
42 // Not an error - just skip on high latency/replay links
44 return;
45 }
46
47 qCDebug(QGCStateMachineLog) << "Requesting message id" << _messageId << stateName();
48 vehicle()->requestMessage(_resultHandler, this, _compId, _messageId, _param1, _param2, _param3, _param4, _param5);
49}
50
52{
53 qCDebug(QGCStateMachineLog) << "Timeout waiting for message" << _messageId << stateName();
56}
57
58void RequestMessageState::_resultHandler(void* resultHandlerData,
59 MAV_RESULT commandResult,
61 const mavlink_message_t& message)
62{
63 auto* state = static_cast<RequestMessageState*>(resultHandlerData);
64 state->_failureCode = failureCode;
65 state->_commandResult = commandResult;
66
68 qCDebug(QGCStateMachineLog) << "Message received successfully" << state->stateName();
69
70 if (state->_messageHandler) {
71 state->_messageHandler(state->vehicle(), message);
72 }
73
74 emit state->messageReceived(message);
75 state->waitComplete();
76 } else {
77 switch (failureCode) {
79 qCDebug(QGCStateMachineLog) << "Command error" << commandResult << state->stateName();
80 break;
82 qCDebug(QGCStateMachineLog) << "Command not acked" << state->stateName();
83 break;
85 qCDebug(QGCStateMachineLog) << "Message not received" << state->stateName();
86 break;
88 qCDebug(QGCStateMachineLog) << "Duplicate command" << state->stateName();
89 break;
90 default:
91 qCDebug(QGCStateMachineLog) << "Unknown failure" << failureCode << state->stateName();
92 break;
93 }
94 state->waitFailed();
95 }
96}
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
struct __mavlink_message mavlink_message_t
QString stateName() const
Vehicle * vehicle() const
void onWaitEntered() override
Called when the state is entered - subclasses should call base implementation.
MAV_RESULT commandResult() const
Vehicle::RequestMessageResultHandlerFailureCode_t failureCode() const
std::function< void(Vehicle *vehicle, const mavlink_message_t &message)> MessageHandler
void onWaitTimeout() override
Called when the timeout expires - default emits timeout(), subclasses can override.
RequestMessageState(QState *parent, uint32_t messageId, MessageHandler messageHandler=MessageHandler(), int compId=MAV_COMP_ID_AUTOPILOT1, int timeoutMsecs=5000, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f)
WeakLinkInterfacePtr primaryLink() const
VehicleLinkManager * vehicleLinkManager()
Definition Vehicle.h:580
RequestMessageResultHandlerFailureCode_t
Definition Vehicle.h:668
@ RequestMessageFailureMessageNotReceived
Definition Vehicle.h:672
@ RequestMessageNoFailure
Definition Vehicle.h:669
@ RequestMessageFailureCommandNotAcked
Definition Vehicle.h:671
@ RequestMessageFailureCommandError
Definition Vehicle.h:670
@ RequestMessageFailureDuplicate
Exact duplicate request already active or queued for this component/message id.
Definition Vehicle.h:673
void requestMessage(RequestMessageResultHandler resultHandler, void *resultHandlerData, int compId, int messageId, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f)
Definition Vehicle.cc:3099
virtual void onWaitTimeout()
Called when the timeout expires - default emits timeout(), subclasses can override.
virtual void onWaitEntered()
Called when the state is entered - subclasses should call base implementation.