QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
RequestMessageCoordinator Class Reference

#include <RequestMessageCoordinator.h>

+ Inheritance diagram for RequestMessageCoordinator:
+ Collaboration diagram for RequestMessageCoordinator:

Public Member Functions

 RequestMessageCoordinator (Vehicle *vehicle, MavCommandQueue *commandQueue)
 
 ~RequestMessageCoordinator ()
 
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)
 
void handleReceivedMessage (const mavlink_message_t &message)
 
void stop ()
 Clear pending state without firing callbacks (used during vehicle shutdown).
 

Static Public Member Functions

static QString failureCodeToString (RequestMessageResultHandlerFailureCode_t failureCode)
 

Additional Inherited Members

- Public Types inherited from VehicleTypes
enum  MavCmdResultFailureCode_t { MavCmdResultCommandResultOnly , MavCmdResultFailureNoResponseToCommand , MavCmdResultFailureDuplicateCommand }
 
enum  RequestMessageResultHandlerFailureCode_t {
  RequestMessageNoFailure , RequestMessageFailureCommandError , RequestMessageFailureCommandNotAcked , RequestMessageFailureMessageNotReceived ,
  RequestMessageFailureDuplicate
}
 
typedef void(* MavCmdProgressHandler) (void *progressHandlerData, int compId, const mavlink_command_ack_t &ack)
 Callback for sendMavCommandWithHandler which handles MAV_RESULT_IN_PROGRESS acks.
 
typedef void(* MavCmdResultHandler) (void *resultHandlerData, int compId, const mavlink_command_ack_t &ack, MavCmdResultFailureCode_t failureCode)
 Callback for sendMavCommandWithHandler which handles all non-IN_PROGRESS acks.
 
typedef struct VehicleTypes::MavCmdAckHandlerInfo_s MavCmdAckHandlerInfo_t
 Callback info bundle for sendMavCommandWithHandler.
 
typedef void(* RequestMessageResultHandler) (void *resultHandlerData, MAV_RESULT commandResult, RequestMessageResultHandlerFailureCode_t failureCode, const mavlink_message_t &message)
 Callback for requestMessage — delivered when the ack/message pair resolves or a failure occurs.
 
- Static Public Attributes inherited from VehicleTypes
static const int versionNotSetValue = -1
 

Detailed Description

Coordinates MAV_CMD_REQUEST_MESSAGE workflows: per-component queueing, ack/message correlation, duplicate suppression, and timeout handling for the requested message.

Layers on top of MavCommandQueue for the actual command send + ack callback.

Definition at line 18 of file RequestMessageCoordinator.h.

Constructor & Destructor Documentation

◆ RequestMessageCoordinator()

RequestMessageCoordinator::RequestMessageCoordinator ( Vehicle vehicle,
MavCommandQueue commandQueue 
)

Definition at line 11 of file RequestMessageCoordinator.cc.

◆ ~RequestMessageCoordinator()

RequestMessageCoordinator::~RequestMessageCoordinator ( )

Definition at line 18 of file RequestMessageCoordinator.cc.

References stop().

Member Function Documentation

◆ failureCodeToString()

◆ handleReceivedMessage()

void RequestMessageCoordinator::handleReceivedMessage ( const mavlink_message_t message)

Called for every inbound mavlink message so the coordinator can correlate arrivals with outstanding requests and enforce per-request timeouts.

Definition at line 150 of file RequestMessageCoordinator.cc.

References VehicleTypes::RequestMessageFailureMessageNotReceived, VehicleTypes::RequestMessageNoFailure, and QGC::runningUnitTests().

◆ requestMessage()

void RequestMessageCoordinator::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 
)

Requests the vehicle to send the specified message. Will retry a number of times.

Parameters
resultHandlerCallback for result
resultHandlerDataOpaque data passed back to resultHandler

Definition at line 281 of file RequestMessageCoordinator.cc.

References Vehicle::compId(), and VehicleTypes::RequestMessageFailureDuplicate.

Referenced by Vehicle::requestMessage().

◆ stop()

void RequestMessageCoordinator::stop ( )

Clear pending state without firing callbacks (used during vehicle shutdown).

Definition at line 23 of file RequestMessageCoordinator.cc.

Referenced by ~RequestMessageCoordinator().


The documentation for this class was generated from the following files: