4#include "MAVLinkEnums.h"
38 int compId = MAV_COMP_ID_AUTOPILOT1,
63 static void _resultHandler(
void* resultHandlerData,
78 MAV_RESULT _commandResult = MAV_RESULT_ACCEPTED;
struct __mavlink_message mavlink_message_t
Vehicle * vehicle() const
Requests a MAVLink message from the vehicle using MAV_CMD_REQUEST_MESSAGE.
void onWaitEntered() override
Called when the state is entered - subclasses should call base implementation.
void disconnectWaitSignal() override
Subclasses override to tear down their signal connections.
void connectWaitSignal() override
Subclasses override to set up their signal connections.
MAV_RESULT commandResult() const
VehicleTypes::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.
void messageReceived(const mavlink_message_t &message)
Emitted when the message is successfully received.
Base class for states that wait for something with optional timeout.
RequestMessageResultHandlerFailureCode_t
@ RequestMessageNoFailure