15 :
WaitStateBase(QStringLiteral(
"RequestMessageState:%1").arg(messageId), parent, timeoutMsecs)
16 , _messageId(messageId)
17 , _messageHandler(std::move(messageHandler))
34 qCDebug(QGCStateMachineLog) <<
"Skipping request due to no primary link" <<
stateName();
40 if (sharedLink->linkConfiguration()->isHighLatency() || sharedLink->isLogReplay()) {
41 qCDebug(QGCStateMachineLog) <<
"Skipping request due to link type" <<
stateName();
47 qCDebug(QGCStateMachineLog) <<
"Requesting message id" << _messageId <<
stateName();
48 vehicle()->
requestMessage(_resultHandler,
this, _compId, _messageId, _param1, _param2, _param3, _param4, _param5);
53 qCDebug(QGCStateMachineLog) <<
"Timeout waiting for message" << _messageId <<
stateName();
58void RequestMessageState::_resultHandler(
void* resultHandlerData,
59 MAV_RESULT commandResult,
68 qCDebug(QGCStateMachineLog) <<
"Message received successfully" << state->stateName();
70 if (state->_messageHandler) {
71 state->_messageHandler(state->vehicle(), message);
74 emit state->messageReceived(message);
75 state->waitComplete();
79 qCDebug(QGCStateMachineLog) <<
"Command error" <<
commandResult << state->stateName();
82 qCDebug(QGCStateMachineLog) <<
"Command not acked" << state->stateName();
85 qCDebug(QGCStateMachineLog) <<
"Message not received" << state->stateName();
88 qCDebug(QGCStateMachineLog) <<
"Duplicate command" << state->stateName();
91 qCDebug(QGCStateMachineLog) <<
"Unknown failure" <<
failureCode << state->stateName();
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()
RequestMessageResultHandlerFailureCode_t
@ RequestMessageFailureMessageNotReceived
@ RequestMessageNoFailure
@ RequestMessageFailureCommandNotAcked
@ RequestMessageFailureCommandError
@ RequestMessageFailureDuplicate
Exact duplicate request already active or queued for this component/message id.
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)
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.