Browse Source

MAVFtp: Allow proper compId as default (#10488)

QGC4.4
olliw42 2 years ago committed by GitHub
parent
commit
55200937f6
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
  1. 2
      src/Camera/QGCCameraControl.cc
  2. 2
      src/FactSystem/ParameterManager.cc
  3. 2
      src/Vehicle/ComponentInformationManager.cc
  4. 13
      src/Vehicle/FTPManager.cc
  5. 23
      src/Vehicle/FTPManager.h
  6. 6
      src/Vehicle/FTPManagerTest.cc

2
src/Camera/QGCCameraControl.cc

@ -1970,7 +1970,7 @@ QGCCameraControl::_handleDefinitionFile(const QString &url) @@ -1970,7 +1970,7 @@ QGCCameraControl::_handleDefinitionFile(const QString &url)
ver,
ext.toStdString().c_str());
connect(_vehicle->ftpManager(), &FTPManager::downloadComplete, this, &QGCCameraControl::_ftpDownloadComplete);
_vehicle->ftpManager()->download(url,
_vehicle->ftpManager()->download(_compID, url,
qgcApp()->toolbox()->settingsManager()->appSettings()->parameterSavePath().toStdString().c_str(),
fileName);
return;

2
src/FactSystem/ParameterManager.cc

@ -531,7 +531,7 @@ void ParameterManager::refreshAllParameters(uint8_t componentId) @@ -531,7 +531,7 @@ void ParameterManager::refreshAllParameters(uint8_t componentId)
FTPManager* ftpManager = _vehicle->ftpManager();
connect(ftpManager, &FTPManager::downloadComplete, this, &ParameterManager::_ftpDownloadComplete);
_waitingParamTimeoutTimer.stop();
if (ftpManager->download("@PARAM/param.pck",
if (ftpManager->download(MAV_COMP_ID_AUTOPILOT1, "@PARAM/param.pck",
QStandardPaths::writableLocation(QStandardPaths::TempLocation),
"", false /* No filesize check */)) {
connect(ftpManager, &FTPManager::commandProgress, this, &ParameterManager::_ftpDownloadProgress);

2
src/Vehicle/ComponentInformationManager.cc

@ -420,7 +420,7 @@ void RequestMetaDataTypeStateMachine::_requestFile(const QString& cacheFileTag, @@ -420,7 +420,7 @@ void RequestMetaDataTypeStateMachine::_requestFile(const QString& cacheFileTag,
qCDebug(ComponentInformationManagerLog) << "Downloading json" << uri;
if (_uriIsMAVLinkFTP(uri)) {
connect(ftpManager, &FTPManager::downloadComplete, this, &RequestMetaDataTypeStateMachine::_ftpDownloadComplete);
if (ftpManager->download(uri, QStandardPaths::writableLocation(QStandardPaths::TempLocation))) {
if (ftpManager->download(MAV_COMP_ID_AUTOPILOT1, uri, QStandardPaths::writableLocation(QStandardPaths::TempLocation))) {
_downloadStartTime.start();
connect(ftpManager, &FTPManager::commandProgress, this, &RequestMetaDataTypeStateMachine::_ftpDownloadProgress);
} else {

13
src/Vehicle/FTPManager.cc

@ -34,9 +34,9 @@ FTPManager::FTPManager(Vehicle* vehicle) @@ -34,9 +34,9 @@ FTPManager::FTPManager(Vehicle* vehicle)
Q_ASSERT(sizeof(MavlinkFTP::RequestHeader) == 12);
}
bool FTPManager::download(const QString& fromURI, const QString& toDir, const QString& fileName, bool checksize)
bool FTPManager::download(uint8_t fromCompId, const QString& fromURI, const QString& toDir, const QString& fileName, bool checksize)
{
qCDebug(FTPManagerLog) << "download fromURI:" << fromURI << "to:" << toDir;
qCDebug(FTPManagerLog) << "download fromURI:" << fromURI << "to:" << toDir << "fromCompId:" << fromCompId;
if (!_rgStateMachine.isEmpty()) {
qCDebug(FTPManagerLog) << "Cannot download. Already in another operation";
@ -58,7 +58,7 @@ bool FTPManager::download(const QString& fromURI, const QString& toDir, const QS @@ -58,7 +58,7 @@ bool FTPManager::download(const QString& fromURI, const QString& toDir, const QS
_downloadState.toDir.setPath(toDir);
_downloadState.checksize = checksize;
if (!_parseURI(fromURI, _downloadState.fullPathOnVehicle, _ftpCompId)) {
if (!_parseURI(fromCompId, fromURI, _downloadState.fullPathOnVehicle, _ftpCompId)) {
qCWarning(FTPManagerLog) << "_parseURI failed";
return false;
}
@ -171,7 +171,8 @@ void FTPManager::_downloadComplete(const QString& errorMsg) @@ -171,7 +171,8 @@ void FTPManager::_downloadComplete(const QString& errorMsg)
void FTPManager::_mavlinkMessageReceived(const mavlink_message_t& message)
{
if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL || message.compid != _ftpCompId) {
if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL ||
message.sysid != _vehicle->id() || message.compid != _ftpCompId) {
return;
}
@ -626,10 +627,10 @@ void FTPManager::_sendRequestExpectAck(MavlinkFTP::Request* request) @@ -626,10 +627,10 @@ void FTPManager::_sendRequestExpectAck(MavlinkFTP::Request* request)
}
}
bool FTPManager::_parseURI(const QString& uri, QString& parsedURI, uint8_t& compId)
bool FTPManager::_parseURI(uint8_t fromCompId, const QString& uri, QString& parsedURI, uint8_t& compId)
{
parsedURI = uri;
compId = MAV_COMP_ID_AUTOPILOT1;
compId = (fromCompId == MAV_COMP_ID_ALL) ? (uint8_t)MAV_COMP_ID_AUTOPILOT1 : fromCompId;
// Pull scheme off the front if there
QString ftpPrefix(QStringLiteral("%1://").arg(mavlinkFTPScheme));

23
src/Vehicle/FTPManager.h

@ -32,18 +32,19 @@ public: @@ -32,18 +32,19 @@ public:
FTPManager(Vehicle* vehicle);
/// Downloads the specified file.
/// @param fromURI File to download from vehicle, fully qualified path. May be in the format "mftp://[;comp=<id>]..." where the component id is specified.
/// If component id is not specified MAV_COMP_ID_AUTOPILOT1 is used.
/// @param toDir Local directory to download file to
/// @param filename (optional)
/// @param checksize (optional, default true) If true compare the filesize indicated in the open
/// response with the transmitted filesize. If false the transmission is tftp style
/// and the indicated filesize from MAVFTP fileopen response is ignored.
/// This is used for the APM parameterdownload where the filesize is wrong due to
/// a dynamic file creation on the vehicle.
/// @param fromCompId Component id of the component to download from. If fromCompId is MAV_COMP_ID_ALL, then MAV_COMP_ID_AUTOPILOT1 is used.
/// @param fromURI File to download from component, fully qualified path. May be in the format "mftp://[;comp=<id>]..." where the component id
/// is specified. If component id is not specified, then the id set via fromCompId is used.
/// @param toDir Local directory to download file to
/// @param filename (optional)
/// @param checksize (optional, default true) If true compare the filesize indicated in the open
/// response with the transmitted filesize. If false the transmission is tftp style
/// and the indicated filesize from MAVFTP fileopen response is ignored.
/// This is used for the APM parameter download where the filesize is wrong due to
/// a dynamic file creation on the vehicle.
/// @return true: download has started, false: error, no download
/// Signals downloadComplete, commandError, commandProgress
bool download(const QString& fromURI, const QString& toDir, const QString& fileName="", bool checksize = true);
bool download(uint8_t fromCompId, const QString& fromURI, const QString& toDir, const QString& fileName="", bool checksize = true);
/// Cancel the current operation
/// This will emit downloadComplete() when done, and if there's currently a download in progress
@ -136,7 +137,7 @@ private: @@ -136,7 +137,7 @@ private:
void _fillRequestDataWithString(MavlinkFTP::Request* request, const QString& str);
void _fillMissingBlocksWorker (bool firstRequest);
void _burstReadFileWorker (bool firstRequest);
bool _parseURI (const QString& uri, QString& parsedURI, uint8_t& compId);
bool _parseURI (uint8_t fromCompId, const QString& uri, QString& parsedURI, uint8_t& compId);
void _terminateSessionBegin (void);
void _terminateSessionAckOrNak (const MavlinkFTP::Request* ackOrNak);

6
src/Vehicle/FTPManagerTest.cc

@ -33,7 +33,7 @@ void FTPManagerTest::_testCaseWorker(const TestCase_t& testCase) @@ -33,7 +33,7 @@ void FTPManagerTest::_testCaseWorker(const TestCase_t& testCase)
QSignalSpy spyDownloadComplete(ftpManager, &FTPManager::downloadComplete);
// void downloadComplete (const QString& file, const QString& errorMsg);
ftpManager->download(testCase.file, QStandardPaths::writableLocation(QStandardPaths::TempLocation));
ftpManager->download(MAV_COMP_ID_AUTOPILOT1, testCase.file, QStandardPaths::writableLocation(QStandardPaths::TempLocation));
QCOMPARE(spyDownloadComplete.wait(10000), true);
QCOMPARE(spyDownloadComplete.count(), 1);
@ -53,7 +53,7 @@ void FTPManagerTest::_sizeTestCaseWorker(int fileSize) @@ -53,7 +53,7 @@ void FTPManagerTest::_sizeTestCaseWorker(int fileSize)
QSignalSpy spyDownloadComplete(ftpManager, &FTPManager::downloadComplete);
ftpManager->download(filename, QStandardPaths::writableLocation(QStandardPaths::TempLocation));
ftpManager->download(MAV_COMP_ID_AUTOPILOT1, filename, QStandardPaths::writableLocation(QStandardPaths::TempLocation));
QCOMPARE(spyDownloadComplete.wait(10000), true);
QCOMPARE(spyDownloadComplete.count(), 1);
@ -106,7 +106,7 @@ void FTPManagerTest::_testLostPackets(void) @@ -106,7 +106,7 @@ void FTPManagerTest::_testLostPackets(void)
QSignalSpy spyDownloadComplete(ftpManager, &FTPManager::downloadComplete);
_mockLink->mockLinkFTP()->enableRandromDrops(true);
ftpManager->download(filename, QStandardPaths::writableLocation(QStandardPaths::TempLocation));
ftpManager->download(MAV_COMP_ID_AUTOPILOT1, filename, QStandardPaths::writableLocation(QStandardPaths::TempLocation));
QCOMPARE(spyDownloadComplete.wait(10000), true);
QCOMPARE(spyDownloadComplete.count(), 1);

Loading…
Cancel
Save