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

#include <MavCommandQueue.h>

+ Inheritance diagram for MavCommandQueue:
+ Collaboration diagram for MavCommandQueue:

Signals

void commandResult (int vehicleId, int targetComponent, int command, int ackResult, int failureCode)
 Emitted for every terminal ack that has no user-provided resultHandler.
 

Public Member Functions

 MavCommandQueue (Vehicle *vehicle)
 
 ~MavCommandQueue ()
 
void sendCommand (int compId, MAV_CMD command, bool showError, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
 
void sendCommandDelayed (int compId, MAV_CMD command, bool showError, int milliseconds, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
 
void sendCommandInt (int compId, MAV_CMD command, MAV_FRAME frame, bool showError, float param1, float param2, float param3, float param4, double param5, double param6, float param7)
 
void sendCommandWithHandler (const MavCmdAckHandlerInfo_t *ackHandlerInfo, int compId, MAV_CMD command, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
 
void sendCommandIntWithHandler (const MavCmdAckHandlerInfo_t *ackHandlerInfo, int compId, MAV_CMD command, MAV_FRAME frame, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, double param5=0.0, double param6=0.0, float param7=0.0f)
 
void sendCommandWithLambdaFallback (std::function< void()> lambda, int compId, MAV_CMD command, bool showError, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
 
void sendWorker (bool commandInt, bool showError, const MavCmdAckHandlerInfo_t *ackHandlerInfo, int compId, MAV_CMD command, MAV_FRAME frame, float param1, float param2, float param3, float param4, double param5, double param6, float param7)
 
bool isPending (int targetCompId, MAV_CMD command) const
 True if a matching (targetCompId, command) is already queued or awaiting ack.
 
int findEntryIndex (int targetCompId, MAV_CMD command) const
 Index of a matching entry in the pending queue, or -1. Exposed for test use.
 
void handleCommandAck (const mavlink_message_t &message, const mavlink_command_ack_t &ack)
 Process a COMMAND_ACK — match it to a pending entry and fire callbacks.
 
void stop ()
 

Static Public Member Functions

static QString failureCodeToString (MavCmdResultFailureCode_t failureCode)
 
static void showCommandAckError (const mavlink_command_ack_t &ack)
 

Static Public Attributes

static constexpr int kTestAckTimeoutMs = 500
 
static constexpr int kMaxRetryCount = 3
 
static constexpr int kTestMaxWaitMs = kTestAckTimeoutMs * kMaxRetryCount * 2
 
- Static Public Attributes inherited from VehicleTypes
static const int versionNotSetValue = -1
 

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.
 

Detailed Description

Owns the COMMAND_LONG / COMMAND_INT send/retry/ack pipeline for a single Vehicle.

Each outbound command is appended to a per-vehicle queue with its retry policy and ack timeout. A periodic timer resends entries whose ack window has expired; incoming COMMAND_ACK messages are matched by (compId, command) and either complete the entry or refresh its timer on MAV_RESULT_IN_PROGRESS.

Definition at line 20 of file MavCommandQueue.h.

Constructor & Destructor Documentation

◆ MavCommandQueue()

MavCommandQueue::MavCommandQueue ( Vehicle vehicle)
explicit

Definition at line 20 of file MavCommandQueue.cc.

◆ ~MavCommandQueue()

MavCommandQueue::~MavCommandQueue ( )

Definition at line 30 of file MavCommandQueue.cc.

Member Function Documentation

◆ commandResult

void MavCommandQueue::commandResult ( int  vehicleId,
int  targetComponent,
int  command,
int  ackResult,
int  failureCode 
)
signal

Emitted for every terminal ack that has no user-provided resultHandler.

Referenced by handleCommandAck(), and sendWorker().

◆ failureCodeToString()

◆ findEntryIndex()

int MavCommandQueue::findEntryIndex ( int  targetCompId,
MAV_CMD  command 
) const

Index of a matching entry in the pending queue, or -1. Exposed for test use.

Definition at line 159 of file MavCommandQueue.cc.

Referenced by Vehicle::_findMavCommandListEntryIndex(), handleCommandAck(), and isPending().

◆ handleCommandAck()

void MavCommandQueue::handleCommandAck ( const mavlink_message_t message,
const mavlink_command_ack_t ack 
)

◆ isPending()

bool MavCommandQueue::isPending ( int  targetCompId,
MAV_CMD  command 
) const

True if a matching (targetCompId, command) is already queued or awaiting ack.

Definition at line 154 of file MavCommandQueue.cc.

References findEntryIndex().

Referenced by Vehicle::isMavCommandPending(), and sendWorker().

◆ sendCommand()

void MavCommandQueue::sendCommand ( int  compId,
MAV_CMD  command,
bool  showError,
float  param1 = 0.0f,
float  param2 = 0.0f,
float  param3 = 0.0f,
float  param4 = 0.0f,
float  param5 = 0.0f,
float  param6 = 0.0f,
float  param7 = 0.0f 
)

◆ sendCommandDelayed()

void MavCommandQueue::sendCommandDelayed ( int  compId,
MAV_CMD  command,
bool  showError,
int  milliseconds,
float  param1 = 0.0f,
float  param2 = 0.0f,
float  param3 = 0.0f,
float  param4 = 0.0f,
float  param5 = 0.0f,
float  param6 = 0.0f,
float  param7 = 0.0f 
)

Definition at line 56 of file MavCommandQueue.cc.

References sendCommand().

Referenced by Vehicle::sendMavCommandDelayed().

◆ sendCommandInt()

void MavCommandQueue::sendCommandInt ( int  compId,
MAV_CMD  command,
MAV_FRAME  frame,
bool  showError,
float  param1,
float  param2,
float  param3,
float  param4,
double  param5,
double  param6,
float  param7 
)

Definition at line 63 of file MavCommandQueue.cc.

References sendWorker().

Referenced by Vehicle::sendMavCommandInt().

◆ sendCommandIntWithHandler()

void MavCommandQueue::sendCommandIntWithHandler ( const MavCmdAckHandlerInfo_t ackHandlerInfo,
int  compId,
MAV_CMD  command,
MAV_FRAME  frame,
float  param1 = 0.0f,
float  param2 = 0.0f,
float  param3 = 0.0f,
float  param4 = 0.0f,
double  param5 = 0.0,
double  param6 = 0.0,
float  param7 = 0.0f 
)

Definition at line 85 of file MavCommandQueue.cc.

References sendWorker().

Referenced by Vehicle::sendMavCommandIntWithHandler().

◆ sendCommandWithHandler()

void MavCommandQueue::sendCommandWithHandler ( const MavCmdAckHandlerInfo_t ackHandlerInfo,
int  compId,
MAV_CMD  command,
float  param1 = 0.0f,
float  param2 = 0.0f,
float  param3 = 0.0f,
float  param4 = 0.0f,
float  param5 = 0.0f,
float  param6 = 0.0f,
float  param7 = 0.0f 
)

◆ sendCommandWithLambdaFallback()

void MavCommandQueue::sendCommandWithLambdaFallback ( std::function< void()>  lambda,
int  compId,
MAV_CMD  command,
bool  showError,
float  param1 = 0.0f,
float  param2 = 0.0f,
float  param3 = 0.0f,
float  param4 = 0.0f,
float  param5 = 0.0f,
float  param6 = 0.0f,
float  param7 = 0.0f 
)

◆ sendWorker()

void MavCommandQueue::sendWorker ( bool  commandInt,
bool  showError,
const MavCmdAckHandlerInfo_t ackHandlerInfo,
int  compId,
MAV_CMD  command,
MAV_FRAME  frame,
float  param1,
float  param2,
float  param3,
float  param4,
double  param5,
double  param6,
float  param7 
)

◆ showCommandAckError()

void MavCommandQueue::showCommandAckError ( const mavlink_command_ack_t ack)
static

◆ stop()

void MavCommandQueue::stop ( )

Stop the response timer and clear pending entries without firing callbacks. Used during vehicle shutdown to prevent post-destruction callbacks.

Definition at line 36 of file MavCommandQueue.cc.

Referenced by Vehicle::~Vehicle().

Member Data Documentation

◆ kMaxRetryCount

constexpr int MavCommandQueue::kMaxRetryCount = 3
staticconstexpr

Definition at line 63 of file MavCommandQueue.h.

Referenced by sendWorker().

◆ kTestAckTimeoutMs

constexpr int MavCommandQueue::kTestAckTimeoutMs = 500
staticconstexpr

Definition at line 62 of file MavCommandQueue.h.

◆ kTestMaxWaitMs

constexpr int MavCommandQueue::kTestMaxWaitMs = kTestAckTimeoutMs * kMaxRetryCount * 2
staticconstexpr

Definition at line 64 of file MavCommandQueue.h.


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