Unverified Commit d5044690 authored by Gus Grubba's avatar Gus Grubba Committed by GitHub

Merge pull request #7461 from patrickelectric/rc

Random corrections around the code
parents cfb50c6d 666be8a1
......@@ -782,7 +782,7 @@ void APMSensorsComponentController::_handleMagCalProgress(mavlink_message_t& mes
}
}
if (magCalProgress.compass_id < 3) {
if (magCalProgress.compass_id < 3 && compassCalCount != 0) {
// Each compass gets a portion of the overall progress
_rgCompassCalProgress[magCalProgress.compass_id] = magCalProgress.completion_pct / compassCalCount;
}
......
......@@ -33,7 +33,7 @@ void AutoPilotPlugin::_recalcSetupComplete(void)
{
bool newSetupComplete = true;
for(const QVariant componentVariant: vehicleComponents()) {
for(const QVariant& componentVariant: vehicleComponents()) {
VehicleComponent* component = qobject_cast<VehicleComponent*>(qvariant_cast<QObject *>(componentVariant));
if (component) {
if (!component->setupComplete()) {
......
......@@ -1153,7 +1153,7 @@ void
QGCCameraControl::_requestAllParameters()
{
//-- Reset receive list
for(QString paramName: _paramIO.keys()) {
for(const QString& paramName: _paramIO.keys()) {
if(_paramIO[paramName]) {
_paramIO[paramName]->setParamRequest();
} else {
......@@ -1391,7 +1391,7 @@ QGCCameraControl::_updateRanges(Fact* pFact)
}
//-- Parameter update requests
if(_requestUpdates.contains(pFact->name())) {
for(QString param: _requestUpdates[pFact->name()]) {
for(const QString& param: _requestUpdates[pFact->name()]) {
if(!_updatesToRequest.contains(param)) {
_updatesToRequest << param;
}
......@@ -1406,7 +1406,7 @@ QGCCameraControl::_updateRanges(Fact* pFact)
void
QGCCameraControl::_requestParamUpdates()
{
for(QString param: _updatesToRequest) {
for(const QString& param: _updatesToRequest) {
_paramIO[param]->paramRequest();
}
_updatesToRequest.clear();
......@@ -1831,7 +1831,6 @@ QGCCameraControl::_loadRanges(QDomNode option, const QString factName, QString p
for(int i = 0; i < parameterRanges.size(); i++) {
QString param;
QString condition;
QMap<QString, QVariant> rangeList;
QDomNode paramRange = parameterRanges.item(i);
if(!read_attribute(paramRange, kParameter, param)) {
qCritical() << QString("Malformed option range for parameter %1").arg(factName);
......@@ -2003,7 +2002,7 @@ QGCCameraControl::_dataReady(QByteArray data)
void
QGCCameraControl::_paramDone()
{
for(QString param: _paramIO.keys()) {
for(const QString& param: _paramIO.keys()) {
if(!_paramIO[param]->paramDone()) {
return;
}
......
......@@ -217,14 +217,14 @@ QGeoTiledMappingManagerEngineQGC::_setCache(const QVariantMap &parameters)
cacheDir = parameters.value(QStringLiteral("mapping.cache.directory")).toString();
else {
cacheDir = getQGCMapEngine()->getCachePath();
if(!QFileInfo(cacheDir).exists()) {
if(!QFileInfo::exists(cacheDir)) {
if(!QDir::root().mkpath(cacheDir)) {
qWarning() << "Could not create mapping disk cache directory: " << cacheDir;
cacheDir = QDir::homePath() + QStringLiteral("/.qgcmapscache/");
}
}
}
if(!QFileInfo(cacheDir).exists()) {
if(!QFileInfo::exists(cacheDir)) {
if(!QDir::root().mkpath(cacheDir)) {
qWarning() << "Could not create mapping disk cache directory: " << cacheDir;
cacheDir.clear();
......
......@@ -501,6 +501,7 @@ void TerrainTileManager::_terrainDone(QByteArray responseBytes, QNetworkReply::N
}
_tilesMutex.unlock();
} else {
delete terrainTile;
qCWarning(TerrainQueryLog) << "Received invalid tile";
}
reply->deleteLater();
......
......@@ -119,7 +119,7 @@ void PX4FirmwareUpgradeThreadWorker::_findBoardOnce(void)
bool PX4FirmwareUpgradeThreadWorker::_findBoardFromPorts(QGCSerialPortInfo& portInfo, QGCSerialPortInfo::BoardType_t& boardType, QString& boardName)
{
for (QGCSerialPortInfo info: QGCSerialPortInfo::availablePorts()) {
for (const QGCSerialPortInfo& info: QGCSerialPortInfo::availablePorts()) {
info.getBoardInfo(boardType, boardName);
qCDebug(FirmwareUpgradeVerboseLog) << "Serial Port --------------";
......
......@@ -518,7 +518,7 @@ void LinkManager::_updateAutoConnectLinks(void)
#endif
// Iterate Comm Ports
for (QGCSerialPortInfo portInfo: portList) {
for (const QGCSerialPortInfo& portInfo: portList) {
qCDebug(LinkManagerVerboseLog) << "-----------------------------------------------------";
qCDebug(LinkManagerVerboseLog) << "portName: " << portInfo.portName();
qCDebug(LinkManagerVerboseLog) << "systemLocation: " << portInfo.systemLocation();
......@@ -931,7 +931,7 @@ void LinkManager::_activeLinkCheck(void)
QSignalSpy spy(link, SIGNAL(bytesReceived(LinkInterface*, QByteArray)));
if (spy.wait(100)) {
QList<QVariant> arguments = spy.takeFirst();
if (arguments[1].value<QByteArray>().contains("nsh>")) {
if (arguments[1].toByteArray().contains("nsh>")) {
foundNSHPrompt = true;
}
}
......
......@@ -461,7 +461,7 @@ void MAVLinkProtocol::checkForLostLogFiles(void)
QFileInfoList fileInfoList = tempDir.entryInfoList(QStringList(filter), QDir::Files);
//qDebug() << "Orphaned log file count" << fileInfoList.count();
for(const QFileInfo fileInfo: fileInfoList) {
for(const QFileInfo& fileInfo: fileInfoList) {
//qDebug() << "Orphaned log file" << fileInfo.filePath();
if (fileInfo.size() == 0) {
// Delete all zero length files
......
......@@ -55,7 +55,6 @@ static QString get_ip_address(const QString& address)
if (info.error() == QHostInfo::NoError)
{
QList<QHostAddress> hostAddresses = info.addresses();
QHostAddress address;
for (int i = 0; i < hostAddresses.size(); i++)
{
// Exclude all IPv6 addresses
......
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