Skip to content

Commit

Permalink
Comms: Update MAVLinkProtocol
Browse files Browse the repository at this point in the history
  • Loading branch information
HTRamsey committed Oct 7, 2024
1 parent 459fd03 commit ba11774
Show file tree
Hide file tree
Showing 38 changed files with 572 additions and 707 deletions.
3 changes: 1 addition & 2 deletions src/AirLink/AirlinkLink.cc
Original file line number Diff line number Diff line change
Expand Up @@ -130,9 +130,8 @@ bool AirlinkLink::_connect()
pendingTimer->deleteLater();
}
});
MAVLinkProtocol *mavlink = qgcApp()->toolbox()->mavlinkProtocol();
auto conn = std::make_shared<QMetaObject::Connection>();
*conn = connect(mavlink, &MAVLinkProtocol::messageReceived, [this, conn] (LinkInterface* linkSrc, mavlink_message_t message) {
*conn = connect(MAVLinkProtocol::instance(), &MAVLinkProtocol::messageReceived, [this, conn] (LinkInterface* linkSrc, mavlink_message_t message) {
if (this != linkSrc || message.msgid != MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE) {
return;
}
Expand Down
12 changes: 6 additions & 6 deletions src/AnalyzeView/LogDownloadController.cc
Original file line number Diff line number Diff line change
Expand Up @@ -394,8 +394,8 @@ LogDownloadController::_requestLogData(uint16_t id, uint32_t offset, uint32_t co
qCDebug(LogDownloadControllerLog) << "Request log data (id:" << id << "offset:" << offset << "size:" << count << "retryCount" << retryCount << ")";
mavlink_message_t msg;
mavlink_msg_log_request_data_pack_chan(
qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
MAVLinkProtocol::instance()->getSystemId(),
MAVLinkProtocol::instance()->getComponentId(),
sharedLink->mavlinkChannel(),
&msg,
_vehicle->id(), _vehicle->defaultComponentId(),
Expand Down Expand Up @@ -425,8 +425,8 @@ LogDownloadController::_requestLogList(uint32_t start, uint32_t end)
if (sharedLink) {
mavlink_message_t msg;
mavlink_msg_log_request_list_pack_chan(
qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
MAVLinkProtocol::instance()->getSystemId(),
MAVLinkProtocol::instance()->getComponentId(),
sharedLink->mavlinkChannel(),
&msg,
_vehicle->id(),
Expand Down Expand Up @@ -596,8 +596,8 @@ LogDownloadController::eraseAll(void)
if (sharedLink) {
mavlink_message_t msg;
mavlink_msg_log_erase_pack_chan(
qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
MAVLinkProtocol::instance()->getSystemId(),
MAVLinkProtocol::instance()->getComponentId(),
sharedLink->mavlinkChannel(),
&msg,
qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->id(), qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->defaultComponentId());
Expand Down
5 changes: 2 additions & 3 deletions src/AnalyzeView/MAVLinkConsoleController.cc
Original file line number Diff line number Diff line change
Expand Up @@ -155,12 +155,11 @@ MAVLinkConsoleController::_sendSerialData(QByteArray data, bool close)
chunk.append(MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN - chunk.size(), '\0');
uint8_t flags = SERIAL_CONTROL_FLAG_EXCLUSIVE | SERIAL_CONTROL_FLAG_RESPOND | SERIAL_CONTROL_FLAG_MULTI;
if (close) flags = 0;
auto protocol = qgcApp()->toolbox()->mavlinkProtocol();
auto link = _vehicle->vehicleLinkManager()->primaryLink();
mavlink_message_t msg;
mavlink_msg_serial_control_pack_chan(
protocol->getSystemId(),
protocol->getComponentId(),
MAVLinkProtocol::instance()->getSystemId(),
MAVLinkProtocol::instance()->getComponentId(),
sharedLink->mavlinkChannel(),
&msg,
SERIAL_CONTROL_DEV_SHELL,
Expand Down
3 changes: 1 addition & 2 deletions src/AnalyzeView/MAVLinkInspectorController.cc
Original file line number Diff line number Diff line change
Expand Up @@ -28,8 +28,7 @@ MAVLinkInspectorController::MAVLinkInspectorController()
connect(multiVehicleManager, &MultiVehicleManager::vehicleAdded, this, &MAVLinkInspectorController::_vehicleAdded);
connect(multiVehicleManager, &MultiVehicleManager::vehicleRemoved, this, &MAVLinkInspectorController::_vehicleRemoved);
connect(multiVehicleManager, &MultiVehicleManager::activeVehicleChanged, this, &MAVLinkInspectorController::_setActiveVehicle);
MAVLinkProtocol* mavlinkProtocol = qgcApp()->toolbox()->mavlinkProtocol();
connect(mavlinkProtocol, &MAVLinkProtocol::messageReceived, this, &MAVLinkInspectorController::_receiveMessage);
connect(MAVLinkProtocol::instance(), &MAVLinkProtocol::messageReceived, this, &MAVLinkInspectorController::_receiveMessage);
connect(&_updateFrequencyTimer, &QTimer::timeout, this, &MAVLinkInspectorController::_refreshFrequency);
_updateFrequencyTimer.start(1000);
_timeScaleSt.append(new TimeScale_st(this, tr("5 Sec"), 5 * 1000));
Expand Down
10 changes: 5 additions & 5 deletions src/AutoPilotPlugins/APM/APMSensorsComponentController.cc
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ void APMSensorsComponentController::_startLogCalibration(void)
}
_cancelButton->setEnabled(_calTypeInProgress == QGCMAVLink::CalibrationMag);

connect(qgcApp()->toolbox()->mavlinkProtocol(), &MAVLinkProtocol::messageReceived, this, &APMSensorsComponentController::_mavlinkMessageReceived);
connect(MAVLinkProtocol::instance(), &MAVLinkProtocol::messageReceived, this, &APMSensorsComponentController::_mavlinkMessageReceived);
}

void APMSensorsComponentController::_startVisualCalibration(void)
Expand All @@ -116,7 +116,7 @@ void APMSensorsComponentController::_startVisualCalibration(void)

_progressBar->setProperty("value", 0);

connect(qgcApp()->toolbox()->mavlinkProtocol(), &MAVLinkProtocol::messageReceived, this, &APMSensorsComponentController::_mavlinkMessageReceived);
connect(MAVLinkProtocol::instance(), &MAVLinkProtocol::messageReceived, this, &APMSensorsComponentController::_mavlinkMessageReceived);
}

void APMSensorsComponentController::_resetInternalState(void)
Expand Down Expand Up @@ -147,7 +147,7 @@ void APMSensorsComponentController::_resetInternalState(void)

void APMSensorsComponentController::_stopCalibration(APMSensorsComponentController::StopCalibrationCode code)
{
disconnect(qgcApp()->toolbox()->mavlinkProtocol(), &MAVLinkProtocol::messageReceived, this, &APMSensorsComponentController::_mavlinkMessageReceived);
disconnect(MAVLinkProtocol::instance(), &MAVLinkProtocol::messageReceived, this, &APMSensorsComponentController::_mavlinkMessageReceived);
_vehicle->vehicleLinkManager()->setCommunicationLostEnabled(true);

disconnect(_vehicle, &Vehicle::textMessageReceived, this, &APMSensorsComponentController::_handleUASTextMessage);
Expand Down Expand Up @@ -462,8 +462,8 @@ void APMSensorsComponentController::nextClicked(void)
if (sharedLink) {
mavlink_message_t msg;

mavlink_msg_command_ack_pack_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
mavlink_msg_command_ack_pack_chan(MAVLinkProtocol::instance()->getSystemId(),
MAVLinkProtocol::instance()->getComponentId(),
sharedLink->mavlinkChannel(),
&msg,
0, // command
Expand Down
11 changes: 4 additions & 7 deletions src/Camera/QGCCameraIO.cc
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,6 @@
#include "MavlinkCameraControl.h"
#include "QGCCameraIO.h"
#include "QGCLoggingCategory.h"
#include "QGCApplication.h"
#include "QGCToolbox.h"
#include "LinkInterface.h"
#include "MAVLinkProtocol.h"
#include "Vehicle.h"
Expand Down Expand Up @@ -47,7 +45,6 @@ QGCCameraParamIO::QGCCameraParamIO(MavlinkCameraControl *control, Fact* fact, Ve
connect(&_paramWriteTimer, &QTimer::timeout, this, &QGCCameraParamIO::_paramWriteTimeout);
connect(_fact, &Fact::rawValueChanged, this, &QGCCameraParamIO::_factChanged);
connect(_fact, &Fact::_containerRawValueChanged, this, &QGCCameraParamIO::_containerRawValueChanged);
_pMavlink = qgcApp()->toolbox()->mavlinkProtocol();
//-- TODO: Even though we don't use anything larger than 32-bit, this should
// probably be updated.
switch (_fact->type()) {
Expand Down Expand Up @@ -196,8 +193,8 @@ QGCCameraParamIO::_sendParameter()
p.target_component = static_cast<uint8_t>(_control->compID());
strncpy(p.param_id, _fact->name().toStdString().c_str(), MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_ID_LEN);
mavlink_msg_param_ext_set_encode_chan(
static_cast<uint8_t>(_pMavlink->getSystemId()),
static_cast<uint8_t>(_pMavlink->getComponentId()),
static_cast<uint8_t>(MAVLinkProtocol::instance()->getSystemId()),
static_cast<uint8_t>(MAVLinkProtocol::instance()->getComponentId()),
sharedLink->mavlinkChannel(),
&msg,
&p);
Expand Down Expand Up @@ -369,8 +366,8 @@ QGCCameraParamIO::paramRequest(bool reset)
strncpy(param_id, _fact->name().toStdString().c_str(), MAVLINK_MSG_PARAM_EXT_REQUEST_READ_FIELD_PARAM_ID_LEN);
mavlink_message_t msg;
mavlink_msg_param_ext_request_read_pack_chan(
static_cast<uint8_t>(_pMavlink->getSystemId()),
static_cast<uint8_t>(_pMavlink->getComponentId()),
static_cast<uint8_t>(MAVLinkProtocol::instance()->getSystemId()),
static_cast<uint8_t>(MAVLinkProtocol::instance()->getComponentId()),
sharedLink->mavlinkChannel(),
&msg,
static_cast<uint8_t>(_vehicle->id()),
Expand Down
2 changes: 0 additions & 2 deletions src/Camera/QGCCameraIO.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@
class MavlinkCameraControl;
class Fact;
class Vehicle;
class MAVLinkProtocol;

Q_DECLARE_LOGGING_CATEGORY(CameraIOLog)
Q_DECLARE_LOGGING_CATEGORY(CameraIOLogVerbose)
Expand Down Expand Up @@ -77,7 +76,6 @@ private slots:
bool _done;
bool _updateOnSet;
MAV_PARAM_EXT_TYPE _mavParamType;
MAVLinkProtocol* _pMavlink;
bool _forceUIUpdate;
};

5 changes: 2 additions & 3 deletions src/Camera/VehicleCameraControl.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1155,11 +1155,10 @@ VehicleCameraControl::_requestAllParameters()
}
SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock();
if (sharedLink) {
MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
mavlink_message_t msg;
mavlink_msg_param_ext_request_list_pack_chan(
static_cast<uint8_t>(mavlink->getSystemId()),
static_cast<uint8_t>(mavlink->getComponentId()),
static_cast<uint8_t>(MAVLinkProtocol::instance()->getSystemId()),
static_cast<uint8_t>(MAVLinkProtocol::instance()->getComponentId()),
sharedLink->mavlinkChannel(),
&msg,
static_cast<uint8_t>(_vehicle->id()),
Expand Down
13 changes: 6 additions & 7 deletions src/Comms/LinkManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,6 @@ void LinkManager::setToolbox(QGCToolbox *toolbox)
QGCTool::setToolbox(toolbox);

_autoConnectSettings = toolbox->settingsManager()->autoConnectSettings();
_mavlinkProtocol = _toolbox->mavlinkProtocol();

if (!qgcApp()->runningUnitTests()) {
(void) connect(_portListTimer, &QTimer::timeout, this, &LinkManager::_updateAutoConnectLinks);
Expand Down Expand Up @@ -161,12 +160,12 @@ bool LinkManager::createConnectedLink(SharedLinkConfigurationPtr &config)
config->setLink(link);

(void) connect(link.get(), &LinkInterface::communicationError, _app, &QGCApplication::criticalMessageBoxOnMainThread);
(void) connect(link.get(), &LinkInterface::bytesReceived, _mavlinkProtocol, &MAVLinkProtocol::receiveBytes);
(void) connect(link.get(), &LinkInterface::bytesSent, _mavlinkProtocol, &MAVLinkProtocol::logSentBytes);
(void) connect(link.get(), &LinkInterface::bytesReceived, MAVLinkProtocol::instance(), &MAVLinkProtocol::receiveBytes);
(void) connect(link.get(), &LinkInterface::bytesSent, MAVLinkProtocol::instance(), &MAVLinkProtocol::logSentBytes);
(void) connect(link.get(), &LinkInterface::disconnected, this, &LinkManager::_linkDisconnected);

_mavlinkProtocol->resetMetadataForLink(link.get());
_mavlinkProtocol->setVersion(_mavlinkProtocol->getCurrentVersion());
MAVLinkProtocol::instance()->resetMetadataForLink(link.get());
MAVLinkProtocol::instance()->setVersion(MAVLinkProtocol::instance()->getCurrentVersion());

if (!link->_connect()) {
link->_freeMavlinkChannel();
Expand Down Expand Up @@ -219,8 +218,8 @@ void LinkManager::_linkDisconnected()
}

(void) disconnect(link, &LinkInterface::communicationError, _app, &QGCApplication::criticalMessageBoxOnMainThread);
(void) disconnect(link, &LinkInterface::bytesReceived, _mavlinkProtocol, &MAVLinkProtocol::receiveBytes);
(void) disconnect(link, &LinkInterface::bytesSent, _mavlinkProtocol, &MAVLinkProtocol::logSentBytes);
(void) disconnect(link, &LinkInterface::bytesReceived, MAVLinkProtocol::instance(), &MAVLinkProtocol::receiveBytes);
(void) disconnect(link, &LinkInterface::bytesSent, MAVLinkProtocol::instance(), &MAVLinkProtocol::logSentBytes);
(void) disconnect(link, &LinkInterface::disconnected, this, &LinkManager::_linkDisconnected);

link->_freeMavlinkChannel();
Expand Down
1 change: 0 additions & 1 deletion src/Comms/LinkManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -149,7 +149,6 @@ private slots:
QString _connectionsSuspendedReason; ///< User visible reason for suspension

AutoConnectSettings *_autoConnectSettings = nullptr;
MAVLinkProtocol *_mavlinkProtocol = nullptr;
QTimer *_portListTimer = nullptr;
QmlObjectListModel *_qmlConfigurations = nullptr;

Expand Down
4 changes: 2 additions & 2 deletions src/Comms/LogReplayLink.cc
Original file line number Diff line number Diff line change
Expand Up @@ -360,7 +360,7 @@ void LogReplayLink::_play(void)
{
qgcApp()->toolbox()->linkManager()->setConnectionsSuspended(tr("Connect not allowed during Flight Data replay."));
#ifndef __mobile__
qgcApp()->toolbox()->mavlinkProtocol()->suspendLogForReplay(true);
MAVLinkProtocol::instance()->suspendLogForReplay(true);
#endif

// Make sure we aren't at the end of the file, if we are, reset to the beginning and play from there.
Expand All @@ -379,7 +379,7 @@ void LogReplayLink::_pause(void)
{
qgcApp()->toolbox()->linkManager()->setConnectionsAllowed();
#ifndef __mobile__
qgcApp()->toolbox()->mavlinkProtocol()->suspendLogForReplay(false);
MAVLinkProtocol::instance()->suspendLogForReplay(false);
#endif

_readTickTimer.stop();
Expand Down
Loading

0 comments on commit ba11774

Please sign in to comment.