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

#include <MessageIntervalManager.h>

+ Inheritance diagram for MessageIntervalManager:
+ Collaboration diagram for MessageIntervalManager:

Signals

void mavlinkMsgIntervalsChanged (uint8_t compid, uint16_t msgId, int32_t rate)
 

Public Member Functions

 MessageIntervalManager (Vehicle *vehicle, MavCommandQueue *commandQueue, RequestMessageCoordinator *reqMsgCoord)
 
int32_t getMessageRate (uint8_t compId, uint16_t msgId)
 
void setMessageRate (uint8_t compId, uint16_t msgId, int32_t rate)
 
void handleMessageInterval (const mavlink_message_t &message)
 

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

Tracks per-component MAVLink message intervals and mediates SET_MESSAGE_INTERVAL commands plus MESSAGE_INTERVAL request/response flows.

Layers on top of MavCommandQueue (for SET_MESSAGE_INTERVAL) and RequestMessageCoordinator (for MESSAGE_INTERVAL queries).

Definition at line 20 of file MessageIntervalManager.h.

Constructor & Destructor Documentation

◆ MessageIntervalManager()

MessageIntervalManager::MessageIntervalManager ( Vehicle vehicle,
MavCommandQueue commandQueue,
RequestMessageCoordinator reqMsgCoord 
)

Definition at line 32 of file MessageIntervalManager.cc.

Member Function Documentation

◆ getMessageRate()

int32_t MessageIntervalManager::getMessageRate ( uint8_t  compId,
uint16_t  msgId 
)

Returns the last-known rate (Hz) for (compId, msgId). If unknown, issues an asynchronous MESSAGE_INTERVAL request and returns 0.

Definition at line 82 of file MessageIntervalManager.cc.

Referenced by Vehicle::getMessageRate().

◆ handleMessageInterval()

void MessageIntervalManager::handleMessageInterval ( const mavlink_message_t message)

Decode a MESSAGE_INTERVAL message and update the cache, emitting a change signal if the rate changed.

Definition at line 40 of file MessageIntervalManager.cc.

References mavlinkMsgIntervalsChanged().

◆ mavlinkMsgIntervalsChanged

void MessageIntervalManager::mavlinkMsgIntervalsChanged ( uint8_t  compid,
uint16_t  msgId,
int32_t  rate 
)
signal

Referenced by handleMessageInterval().

◆ setMessageRate()

void MessageIntervalManager::setMessageRate ( uint8_t  compId,
uint16_t  msgId,
int32_t  rate 
)

Sends MAV_CMD_SET_MESSAGE_INTERVAL to update the rate for the given message id, then requests MESSAGE_INTERVAL on ack to confirm the new rate.

Definition at line 107 of file MessageIntervalManager.cc.

References MavCommandQueue::sendCommandWithHandler().

Referenced by Vehicle::setMessageRate().


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