Commit 2b0fff52 authored by Don Gagne's avatar Don Gagne

Mini-protocols must only communicate over single link

parent 01f26954
...@@ -45,15 +45,15 @@ QGC_LOGGING_CATEGORY(ParameterLoaderVerboseLog, "ParameterLoaderVerboseLog") ...@@ -45,15 +45,15 @@ QGC_LOGGING_CATEGORY(ParameterLoaderVerboseLog, "ParameterLoaderVerboseLog")
Fact ParameterLoader::_defaultFact; Fact ParameterLoader::_defaultFact;
ParameterLoader::ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent) : ParameterLoader::ParameterLoader(AutoPilotPlugin* autopilot, Vehicle* vehicle, QObject* parent)
QObject(parent), : QObject(parent)
_autopilot(autopilot), , _autopilot(autopilot)
_vehicle(vehicle), , _vehicle(vehicle)
_mavlink(qgcApp()->toolbox()->mavlinkProtocol()), , _mavlink(qgcApp()->toolbox()->mavlinkProtocol())
_parametersReady(false), , _parametersReady(false)
_initialLoadComplete(false), , _initialLoadComplete(false)
_defaultComponentId(FactSystem::defaultComponentId), , _defaultComponentId(FactSystem::defaultComponentId)
_totalParamCount(0) , _totalParamCount(0)
{ {
Q_ASSERT(_autopilot); Q_ASSERT(_autopilot);
Q_ASSERT(_vehicle); Q_ASSERT(_vehicle);
...@@ -321,7 +321,7 @@ void ParameterLoader::refreshAllParameters(void) ...@@ -321,7 +321,7 @@ void ParameterLoader::refreshAllParameters(void)
mavlink_message_t msg; mavlink_message_t msg;
mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, _vehicle->id(), MAV_COMP_ID_ALL); mavlink_msg_param_request_list_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, _vehicle->id(), MAV_COMP_ID_ALL);
_vehicle->sendMessage(msg); _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
qCDebug(ParameterLoaderLog) << "Request to refresh all parameters"; qCDebug(ParameterLoaderLog) << "Request to refresh all parameters";
} }
...@@ -522,7 +522,7 @@ void ParameterLoader::_tryCacheLookup() ...@@ -522,7 +522,7 @@ void ParameterLoader::_tryCacheLookup()
mavlink_message_t msg; mavlink_message_t msg;
mavlink_msg_param_request_read_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, _vehicle->id(), MAV_COMP_ID_ALL, "_HASH_CHECK", -1); mavlink_msg_param_request_read_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, _vehicle->id(), MAV_COMP_ID_ALL, "_HASH_CHECK", -1);
_vehicle->sendMessage(msg); _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
} }
void ParameterLoader::_readParameterRaw(int componentId, const QString& paramName, int paramIndex) void ParameterLoader::_readParameterRaw(int componentId, const QString& paramName, int paramIndex)
...@@ -538,7 +538,7 @@ void ParameterLoader::_readParameterRaw(int componentId, const QString& paramNam ...@@ -538,7 +538,7 @@ void ParameterLoader::_readParameterRaw(int componentId, const QString& paramNam
componentId, // Target component id componentId, // Target component id
fixedParamName, // Named parameter being requested fixedParamName, // Named parameter being requested
paramIndex); // Parameter index being requested, -1 for named paramIndex); // Parameter index being requested, -1 for named
_vehicle->sendMessage(msg); _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
} }
void ParameterLoader::_writeParameterRaw(int componentId, const QString& paramName, const QVariant& value) void ParameterLoader::_writeParameterRaw(int componentId, const QString& paramName, const QVariant& value)
...@@ -591,7 +591,7 @@ void ParameterLoader::_writeParameterRaw(int componentId, const QString& paramNa ...@@ -591,7 +591,7 @@ void ParameterLoader::_writeParameterRaw(int componentId, const QString& paramNa
mavlink_message_t msg; mavlink_message_t msg;
mavlink_msg_param_set_encode(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, &p); mavlink_msg_param_set_encode(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, &p);
_vehicle->sendMessage(msg); _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
} }
void ParameterLoader::_writeLocalParamCache() void ParameterLoader::_writeLocalParamCache()
...@@ -663,7 +663,7 @@ void ParameterLoader::_saveToEEPROM(void) ...@@ -663,7 +663,7 @@ void ParameterLoader::_saveToEEPROM(void)
if (_vehicle->firmwarePlugin()->isCapable(FirmwarePlugin::MavCmdPreflightStorageCapability)) { if (_vehicle->firmwarePlugin()->isCapable(FirmwarePlugin::MavCmdPreflightStorageCapability)) {
mavlink_message_t msg; mavlink_message_t msg;
mavlink_msg_command_long_pack(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, _vehicle->id(), 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 1, -1, -1, -1, 0, 0, 0); mavlink_msg_command_long_pack(_mavlink->getSystemId(), _mavlink->getComponentId(), &msg, _vehicle->id(), 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 1, -1, -1, -1, 0, 0, 0);
_vehicle->sendMessage(msg); _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
qCDebug(ParameterLoaderLog) << "_saveToEEPROM"; qCDebug(ParameterLoaderLog) << "_saveToEEPROM";
} else { } else {
qCDebug(ParameterLoaderLog) << "_saveToEEPROM skipped due to FirmwarePlugin::isCapable"; qCDebug(ParameterLoaderLog) << "_saveToEEPROM skipped due to FirmwarePlugin::isCapable";
......
...@@ -34,6 +34,7 @@ QGC_LOGGING_CATEGORY(MissionManagerLog, "MissionManagerLog") ...@@ -34,6 +34,7 @@ QGC_LOGGING_CATEGORY(MissionManagerLog, "MissionManagerLog")
MissionManager::MissionManager(Vehicle* vehicle) MissionManager::MissionManager(Vehicle* vehicle)
: _vehicle(vehicle) : _vehicle(vehicle)
, _dedicatedLink(NULL)
, _ackTimeoutTimer(NULL) , _ackTimeoutTimer(NULL)
, _retryAck(AckNone) , _retryAck(AckNone)
, _readTransactionInProgress(false) , _readTransactionInProgress(false)
...@@ -98,7 +99,8 @@ void MissionManager::writeMissionItems(const QmlObjectListModel& missionItems) ...@@ -98,7 +99,8 @@ void MissionManager::writeMissionItems(const QmlObjectListModel& missionItems)
mavlink_msg_mission_count_encode(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), &message, &missionCount); mavlink_msg_mission_count_encode(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), &message, &missionCount);
_vehicle->sendMessage(message); _dedicatedLink = _vehicle->priorityLink();
_vehicle->sendMessageOnLink(_dedicatedLink, message);
_startAckTimeout(AckMissionRequest); _startAckTimeout(AckMissionRequest);
emit inProgressChanged(true); emit inProgressChanged(true);
} }
...@@ -120,7 +122,8 @@ void MissionManager::requestMissionItems(void) ...@@ -120,7 +122,8 @@ void MissionManager::requestMissionItems(void)
mavlink_msg_mission_request_list_encode(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), &message, &request); mavlink_msg_mission_request_list_encode(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), &message, &request);
_vehicle->sendMessage(message); _dedicatedLink = _vehicle->priorityLink();
_vehicle->sendMessageOnLink(_dedicatedLink, message);
_startAckTimeout(AckMissionCount); _startAckTimeout(AckMissionCount);
emit inProgressChanged(true); emit inProgressChanged(true);
} }
...@@ -180,10 +183,11 @@ void MissionManager::_readTransactionComplete(void) ...@@ -180,10 +183,11 @@ void MissionManager::_readTransactionComplete(void)
mavlink_msg_mission_ack_encode(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), &message, &missionAck); mavlink_msg_mission_ack_encode(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), &message, &missionAck);
_vehicle->sendMessage(message); _vehicle->sendMessageOnLink(_dedicatedLink, message);
emit newMissionItemsAvailable(); // FIXME: Hack to get master changed, remove before push
_finishTransaction(true); _finishTransaction(true);
emit newMissionItemsAvailable();
} }
void MissionManager::_handleMissionCount(const mavlink_message_t& message) void MissionManager::_handleMissionCount(const mavlink_message_t& message)
...@@ -228,7 +232,7 @@ void MissionManager::_requestNextMissionItem(void) ...@@ -228,7 +232,7 @@ void MissionManager::_requestNextMissionItem(void)
mavlink_msg_mission_request_encode(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), &message, &missionRequest); mavlink_msg_mission_request_encode(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), &message, &missionRequest);
_vehicle->sendMessage(message); _vehicle->sendMessageOnLink(_dedicatedLink, message);
_startAckTimeout(AckMissionItem); _startAckTimeout(AckMissionItem);
} }
...@@ -330,7 +334,7 @@ void MissionManager::_handleMissionRequest(const mavlink_message_t& message) ...@@ -330,7 +334,7 @@ void MissionManager::_handleMissionRequest(const mavlink_message_t& message)
mavlink_msg_mission_item_encode(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), &messageOut, &missionItem); mavlink_msg_mission_item_encode(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), &messageOut, &missionItem);
_vehicle->sendMessage(messageOut); _vehicle->sendMessageOnLink(_dedicatedLink, messageOut);
_startAckTimeout(AckMissionRequest); _startAckTimeout(AckMissionRequest);
} }
......
...@@ -33,6 +33,7 @@ ...@@ -33,6 +33,7 @@
#include "QmlObjectListModel.h" #include "QmlObjectListModel.h"
#include "QGCMAVLink.h" #include "QGCMAVLink.h"
#include "QGCLoggingCategory.h" #include "QGCLoggingCategory.h"
#include "LinkInterface.h"
class Vehicle; class Vehicle;
...@@ -116,6 +117,7 @@ private: ...@@ -116,6 +117,7 @@ private:
private: private:
Vehicle* _vehicle; Vehicle* _vehicle;
LinkInterface* _dedicatedLink;
QTimer* _ackTimeoutTimer; QTimer* _ackTimeoutTimer;
AckType_t _retryAck; AckType_t _retryAck;
......
...@@ -390,7 +390,7 @@ LogDownloadController::_requestLogData(uint8_t id, uint32_t offset, uint32_t cou ...@@ -390,7 +390,7 @@ LogDownloadController::_requestLogData(uint8_t id, uint32_t offset, uint32_t cou
&msg, &msg,
qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->id(), MAV_COMP_ID_ALL, qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->id(), MAV_COMP_ID_ALL,
id, offset, count); id, offset, count);
_vehicle->sendMessage(msg); _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
} }
} }
...@@ -419,7 +419,7 @@ LogDownloadController::_requestLogList(uint32_t start, uint32_t end) ...@@ -419,7 +419,7 @@ LogDownloadController::_requestLogList(uint32_t start, uint32_t end)
MAV_COMP_ID_ALL, MAV_COMP_ID_ALL,
start, start,
end); end);
_vehicle->sendMessage(msg); _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
//-- Wait 2 seconds before bitching about not getting anything //-- Wait 2 seconds before bitching about not getting anything
_timer.start(2000); _timer.start(2000);
} }
...@@ -556,7 +556,7 @@ LogDownloadController::eraseAll(void) ...@@ -556,7 +556,7 @@ LogDownloadController::eraseAll(void)
qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
&msg, &msg,
qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->id(), MAV_COMP_ID_ALL); qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->id(), MAV_COMP_ID_ALL);
_vehicle->sendMessage(msg); _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
refresh(); refresh();
} }
} }
......
...@@ -34,13 +34,14 @@ ...@@ -34,13 +34,14 @@
QGC_LOGGING_CATEGORY(FileManagerLog, "FileManagerLog") QGC_LOGGING_CATEGORY(FileManagerLog, "FileManagerLog")
FileManager::FileManager(QObject* parent, Vehicle* vehicle) : FileManager::FileManager(QObject* parent, Vehicle* vehicle)
QObject(parent), : QObject(parent)
_currentOperation(kCOIdle), , _currentOperation(kCOIdle)
_vehicle(vehicle), , _vehicle(vehicle)
_lastOutgoingSeqNumber(0), , _dedicatedLink(NULL)
_activeSession(0), , _lastOutgoingSeqNumber(0)
_systemIdQGC(0) , _activeSession(0)
, _systemIdQGC(0)
{ {
connect(&_ackTimer, &QTimer::timeout, this, &FileManager::_ackTimeout); connect(&_ackTimer, &QTimer::timeout, this, &FileManager::_ackTimeout);
...@@ -308,10 +309,8 @@ void FileManager::_writeFileDatablock(void) ...@@ -308,10 +309,8 @@ void FileManager::_writeFileDatablock(void)
_sendRequest(&request); _sendRequest(&request);
} }
void FileManager::receiveMessage(LinkInterface* link, mavlink_message_t message) void FileManager::receiveMessage(mavlink_message_t message)
{ {
Q_UNUSED(link);
// receiveMessage is signalled will all mavlink messages so we need to filter everything else out but ours. // receiveMessage is signalled will all mavlink messages so we need to filter everything else out but ours.
if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) { if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) {
return; return;
...@@ -444,6 +443,12 @@ void FileManager::listDirectory(const QString& dirPath) ...@@ -444,6 +443,12 @@ void FileManager::listDirectory(const QString& dirPath)
return; return;
} }
_dedicatedLink = _vehicle->priorityLink();
if (!_dedicatedLink) {
_emitErrorMessage(tr("Command not sent. No Vehicle links."));
return;
}
// initialise the lister // initialise the lister
_listPath = dirPath; _listPath = dirPath;
_listOffset = 0; _listOffset = 0;
...@@ -481,6 +486,12 @@ void FileManager::downloadPath(const QString& from, const QDir& downloadDir) ...@@ -481,6 +486,12 @@ void FileManager::downloadPath(const QString& from, const QDir& downloadDir)
_emitErrorMessage(tr("Command not sent. Waiting for previous command to complete.")); _emitErrorMessage(tr("Command not sent. Waiting for previous command to complete."));
return; return;
} }
_dedicatedLink = _vehicle->priorityLink();
if (!_dedicatedLink) {
_emitErrorMessage(tr("Command not sent. No Vehicle links."));
return;
}
qCDebug(FileManagerLog) << "downloadPath from:" << from << "to:" << downloadDir; qCDebug(FileManagerLog) << "downloadPath from:" << from << "to:" << downloadDir;
_downloadWorker(from, downloadDir, true /* read file */); _downloadWorker(from, downloadDir, true /* read file */);
...@@ -492,6 +503,12 @@ void FileManager::streamPath(const QString& from, const QDir& downloadDir) ...@@ -492,6 +503,12 @@ void FileManager::streamPath(const QString& from, const QDir& downloadDir)
_emitErrorMessage(tr("Command not sent. Waiting for previous command to complete.")); _emitErrorMessage(tr("Command not sent. Waiting for previous command to complete."));
return; return;
} }
_dedicatedLink = _vehicle->priorityLink();
if (!_dedicatedLink) {
_emitErrorMessage(tr("Command not sent. No Vehicle links."));
return;
}
qCDebug(FileManagerLog) << "streamPath from:" << from << "to:" << downloadDir; qCDebug(FileManagerLog) << "streamPath from:" << from << "to:" << downloadDir;
_downloadWorker(from, downloadDir, false /* stream file */); _downloadWorker(from, downloadDir, false /* stream file */);
...@@ -537,6 +554,12 @@ void FileManager::uploadPath(const QString& toPath, const QFileInfo& uploadFile) ...@@ -537,6 +554,12 @@ void FileManager::uploadPath(const QString& toPath, const QFileInfo& uploadFile)
return; return;
} }
_dedicatedLink = _vehicle->priorityLink();
if (!_dedicatedLink) {
_emitErrorMessage(tr("Command not sent. No Vehicle links."));
return;
}
if (toPath.isEmpty()) { if (toPath.isEmpty()) {
return; return;
} }
...@@ -731,5 +754,5 @@ void FileManager::_sendRequest(Request* request) ...@@ -731,5 +754,5 @@ void FileManager::_sendRequest(Request* request)
0, // Target component 0, // Target component
(uint8_t*)request); // Payload (uint8_t*)request); // Payload
_vehicle->sendMessage(message); _vehicle->sendMessageOnLink(_dedicatedLink, message);
} }
...@@ -87,7 +87,7 @@ signals: ...@@ -87,7 +87,7 @@ signals:
void commandProgress(int value); void commandProgress(int value);
public slots: public slots:
void receiveMessage(LinkInterface* link, mavlink_message_t message); void receiveMessage(mavlink_message_t message);
private slots: private slots:
void _ackTimeout(void); void _ackTimeout(void);
...@@ -203,7 +203,8 @@ private: ...@@ -203,7 +203,8 @@ private:
OperationState _currentOperation; ///< Current operation of state machine OperationState _currentOperation; ///< Current operation of state machine
QTimer _ackTimer; ///< Used to signal a timeout waiting for an ack QTimer _ackTimer; ///< Used to signal a timeout waiting for an ack
Vehicle* _vehicle; Vehicle* _vehicle;
LinkInterface* _dedicatedLink; ///< Link to use for communication
uint16_t _lastOutgoingSeqNumber; ///< Sequence number sent in last outgoing packet uint16_t _lastOutgoingSeqNumber; ///< Sequence number sent in last outgoing packet
......
...@@ -185,7 +185,7 @@ UAS::UAS(MAVLinkProtocol* protocol, Vehicle* vehicle, FirmwarePluginManager * fi ...@@ -185,7 +185,7 @@ UAS::UAS(MAVLinkProtocol* protocol, Vehicle* vehicle, FirmwarePluginManager * fi
} }
#ifndef __mobile__ #ifndef __mobile__
connect(mavlink, &MAVLinkProtocol::messageReceived, &fileManager, &FileManager::receiveMessage); connect(_vehicle, &Vehicle::mavlinkMessageReceived, &fileManager, &FileManager::receiveMessage);
#endif #endif
color = UASInterface::getNextColor(); color = UASInterface::getNextColor();
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment