Commit 629e8c01 authored by Gus Grubba's avatar Gus Grubba

Merge branch 'master' of https://github.com/mavlink/qgroundcontrol into localizationWork

# Conflicts:
#	ChangeLog.md
parents 4e340de2 9dae33ae
......@@ -9,6 +9,8 @@ Note: This file only contains high level features or important fixes.
* Added Airmap integration to QGC
* Added ESTIMATOR_STATUS values to new estimatorStatus Vehicle FactGroup. These are now available to display in instrument panel.
* Added Chinese and Turkish localization and partial German localization.
* Make Distance to GCS available for display from instrument panel.
* Make Heading to Home available for display from instrument panel.
## 3.4
......
......@@ -114,7 +114,7 @@ void GeoTagController::startTagging(void)
_setErrorMessage(tr("Save folder not empty"));
return;
}
foreach(QString dirFile, imageList)
for(QString dirFile: imageList)
{
if(!saveDirectory.remove(dirFile)) {
_setErrorMessage(tr("Couldn't replace the existing images"));
......
......@@ -198,8 +198,17 @@ SetupPage {
property var file: _oldFW ? "Sub/bluerov2-3_5.params" : "Sub/bluerov2-3_5_2.params"
onClicked : {
console.log(_oldFW)
console.log(_activeVehicle.firmwarePatchVersion)
controller.loadParameters(file)
hideDialog()
}
}
QGCButton {
width: parent.width
text: "Blue Robotics BlueROV2 Heavy"
property var file: "Sub/bluerov2-heavy-3_5_2.params"
onClicked : {
controller.loadParameters(file)
hideDialog()
}
......
......@@ -33,7 +33,7 @@ void AutoPilotPlugin::_recalcSetupComplete(void)
{
bool newSetupComplete = true;
foreach(const QVariant componentVariant, vehicleComponents()) {
for(const QVariant componentVariant: vehicleComponents()) {
VehicleComponent* component = qobject_cast<VehicleComponent*>(qvariant_cast<QObject *>(componentVariant));
if (component) {
if (!component->setupComplete()) {
......@@ -61,7 +61,7 @@ void AutoPilotPlugin::parametersReadyPreChecks(void)
_recalcSetupComplete();
// Connect signals in order to keep setupComplete up to date
foreach(const QVariant componentVariant, vehicleComponents()) {
for(const QVariant componentVariant: vehicleComponents()) {
VehicleComponent* component = qobject_cast<VehicleComponent*>(qvariant_cast<QObject *>(componentVariant));
if (component) {
connect(component, &VehicleComponent::setupCompleteChanged, this, &AutoPilotPlugin::_recalcSetupComplete);
......
......@@ -68,14 +68,14 @@ public:
Q_PROPERTY(int transmitterMode READ transmitterMode WRITE setTransmitterMode NOTIFY transmitterModeChanged)
Q_PROPERTY(QString imageHelp MEMBER _imageHelp NOTIFY imageHelpChanged)
Q_ENUMS(BindModes)
enum BindModes {
DSM2,
DSMX7,
DSMX8
};
Q_ENUM(BindModes)
Q_INVOKABLE void spektrumBindMode(int mode);
Q_INVOKABLE void cancelButtonClicked(void);
Q_INVOKABLE void skipButtonClicked(void);
......
......@@ -56,9 +56,7 @@ void PX4AdvancedFlightModesController::_init(void)
rcMinParam = QString("RC%1_MIN").arg(channel+1);
rcMaxParam = QString("RC%1_MAX").arg(channel+1);
rcRevParam = QString("RC%1_REV").arg(channel+1);
QVariant value;
_rgRCMin[channel] = getParameterFact(FactSystem::defaultComponentId, rcMinParam)->rawValue().toInt();
_rgRCMax[channel] = getParameterFact(FactSystem::defaultComponentId, rcMaxParam)->rawValue().toInt();
......@@ -170,7 +168,7 @@ void PX4AdvancedFlightModesController::_validateConfiguration(void)
for (int j=0; j<switchParams.count(); j++) {
if (map != 0 && map == switchMappings[j]) {
_validConfiguration = false;
_configurationErrors += tr("%1 is set to same channel as %2.\n").arg(switchParams[j]).arg(attitudeParams[i]);
_configurationErrors += tr("%1 is set to same channel as %2.\n").arg(switchParams[j], attitudeParams[i]);
}
}
}
......@@ -220,8 +218,6 @@ void PX4AdvancedFlightModesController::_rcChannelsChanged(int channelCount, int
double PX4AdvancedFlightModesController::_switchLiveRange(const QString& param)
{
QVariant value;
int channel = getParameterFact(-1, param)->rawValue().toInt();
if (channel == 0) {
return 0.0;
......
......@@ -90,7 +90,6 @@ void PX4AirframeLoader::loadAirframeMetaData(void)
QString airframeGroup;
QString image;
QString errorString;
int xmlState = XmlStateNone;
while (!xml.atEnd()) {
......
......@@ -43,7 +43,6 @@ bool PowerComponent::requiresSetup(void) const
bool PowerComponent::setupComplete(void) const
{
QVariant cvalue, evalue, nvalue;
return _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, "BAT_V_CHARGED")->rawValue().toFloat() != 0.0f &&
_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, "BAT_V_EMPTY")->rawValue().toFloat() != 0.0f &&
_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, "BAT_N_CELLS")->rawValue().toInt() != 0;
......
......@@ -140,7 +140,6 @@ void PowerComponentController::_handleUASTextMessage(int uasId, int compId, int
return;
}
QString busCompletePrefix("bus conf done:");
if (text.startsWith(calCompletePrefix)) {
_stopBusConfig();
emit calibrationSuccess(_warningMessages);
......
......@@ -917,7 +917,7 @@ void
QGCCameraControl::_requestAllParameters()
{
//-- Reset receive list
foreach(QString paramName, _paramIO.keys()) {
for(QString paramName: _paramIO.keys()) {
if(_paramIO[paramName]) {
_paramIO[paramName]->setParamRequest();
} else {
......@@ -984,7 +984,7 @@ QGCCameraControl::_updateActiveList()
{
//-- Clear out excluded parameters based on exclusion rules
QStringList exclusionList;
foreach(QGCCameraOptionExclusion* param, _valueExclusions) {
for(QGCCameraOptionExclusion* param: _valueExclusions) {
Fact* pFact = getFact(param->param);
if(pFact) {
QString option = pFact->rawValueString();
......@@ -994,7 +994,7 @@ QGCCameraControl::_updateActiveList()
}
}
QStringList active;
foreach(QString key, _settings) {
for(QString key: _settings) {
if(!exclusionList.contains(key)) {
active.append(key);
}
......@@ -1094,7 +1094,7 @@ QGCCameraControl::_updateRanges(Fact* pFact)
QStringList resetList;
QStringList updates;
//-- Iterate range sets looking for limited ranges
foreach(QGCCameraOptionRange* pRange, _optionRanges) {
for(QGCCameraOptionRange* pRange: _optionRanges) {
//-- If this fact or one of its conditions is part of this range set
if(!changedList.contains(pRange->targetParam) && (pRange->param == pFact->name() || pRange->condition.contains(pFact->name()))) {
Fact* pRFact = getFact(pRange->param); //-- This parameter
......@@ -1115,7 +1115,7 @@ QGCCameraControl::_updateRanges(Fact* pFact)
}
}
//-- Iterate range sets again looking for resets
foreach(QGCCameraOptionRange* pRange, _optionRanges) {
for(QGCCameraOptionRange* pRange: _optionRanges) {
if(!changedList.contains(pRange->targetParam) && (pRange->param == pFact->name() || pRange->condition.contains(pFact->name()))) {
Fact* pTFact = getFact(pRange->targetParam); //-- The target parameter (the one its range is to change)
if(!resetList.contains(pRange->targetParam)) {
......@@ -1128,7 +1128,7 @@ QGCCameraControl::_updateRanges(Fact* pFact)
}
}
//-- Update limited range set
foreach (Fact* f, rangesSet.keys()) {
for (Fact* f: rangesSet.keys()) {
f->setEnumInfo(rangesSet[f]->optNames, rangesSet[f]->optVariants);
if(!updates.contains(f->name())) {
_paramIO[f->name()]->optNames = rangesSet[f]->optNames;
......@@ -1139,7 +1139,7 @@ QGCCameraControl::_updateRanges(Fact* pFact)
}
}
//-- Restore full range set
foreach (Fact* f, rangesReset.keys()) {
for (Fact* f: rangesReset.keys()) {
f->setEnumInfo(_originalOptNames[rangesReset[f]], _originalOptValues[rangesReset[f]]);
if(!updates.contains(f->name())) {
_paramIO[f->name()]->optNames = _originalOptNames[rangesReset[f]];
......@@ -1151,7 +1151,7 @@ QGCCameraControl::_updateRanges(Fact* pFact)
}
//-- Parameter update requests
if(_requestUpdates.contains(pFact->name())) {
foreach(QString param, _requestUpdates[pFact->name()]) {
for(QString param: _requestUpdates[pFact->name()]) {
if(!_updatesToRequest.contains(param)) {
_updatesToRequest << param;
}
......@@ -1166,7 +1166,7 @@ QGCCameraControl::_updateRanges(Fact* pFact)
void
QGCCameraControl::_requestParamUpdates()
{
foreach(QString param, _updatesToRequest) {
for(QString param: _updatesToRequest) {
_paramIO[param]->paramRequest();
}
_updatesToRequest.clear();
......@@ -1358,7 +1358,7 @@ void
QGCCameraControl::_processRanges()
{
//-- After all parameter are loaded, process parameter ranges
foreach(QGCCameraOptionRange* pRange, _optionRanges) {
for(QGCCameraOptionRange* pRange: _optionRanges) {
Fact* pRFact = getFact(pRange->targetParam);
if(pRFact) {
for(int i = 0; i < pRange->optNames.size(); i++) {
......@@ -1488,7 +1488,7 @@ QGCCameraControl::_dataReady(QByteArray data)
void
QGCCameraControl::_paramDone()
{
foreach(QString param, _paramIO.keys()) {
for(QString param: _paramIO.keys()) {
if(!_paramIO[param]->paramDone()) {
return;
}
......
......@@ -97,10 +97,10 @@ public:
PHOTO_CAPTURE_TIMELAPSE,
};
Q_ENUMS(CameraMode)
Q_ENUMS(VideoStatus)
Q_ENUMS(PhotoStatus)
Q_ENUMS(PhotoMode)
Q_ENUM(CameraMode)
Q_ENUM(VideoStatus)
Q_ENUM(PhotoStatus)
Q_ENUM(PhotoMode)
Q_PROPERTY(int version READ version NOTIFY infoChanged)
Q_PROPERTY(QString modelName READ modelName NOTIFY infoChanged)
......
......@@ -221,7 +221,7 @@ int Fact::enumIndex(void)
//-- Only enums have an index
if(_metaData->enumValues().count()) {
int index = 0;
foreach (QVariant enumValue, _metaData->enumValues()) {
for (QVariant enumValue: _metaData->enumValues()) {
if (enumValue == rawValue()) {
return index;
}
......
......@@ -120,7 +120,7 @@ void FactGroup::_addFactGroup(FactGroup* factGroup, const QString& name)
void FactGroup::_updateAllValues(void)
{
foreach(Fact* fact, _nameToFactMap) {
for(Fact* fact: _nameToFactMap) {
fact->sendDeferredValueChangedSignal();
}
}
This diff is collapsed.
......@@ -154,7 +154,6 @@ void APMParameterMetaData::loadParameterFactMetaDataFile(const QString& metaData
return;
}
QString errorString;
bool badMetaData = true;
QStack<int> xmlState;
APMFactMetaDataRaw* rawMetaData = NULL;
......
......@@ -7587,16 +7587,24 @@ to takeoff is reached</short_desc>
<group name="SD Logging">
<parameter default="0" name="SDLOG_DIRS_MAX" type="INT32">
<short_desc>Maximum number of log directories to keep</short_desc>
<long_desc>If there are more log directories than this value, the system will delete the oldest directories during startup. In addition, the system will delete old logs if there is not enough free space left. The minimum amount is 300 MB. If this is set to 0, old directories will only be removed if the free space falls below the minimum.</long_desc>
<long_desc>If there are more log directories than this value, the system will delete the oldest directories during startup. In addition, the system will delete old logs if there is not enough free space left. The minimum amount is 300 MB. If this is set to 0, old directories will only be removed if the free space falls below the minimum. Note: this does not apply to mission log files.</long_desc>
<min>0</min>
<max>1000</max>
<reboot_required>true</reboot_required>
</parameter>
<parameter default="1" name="SDLOG_MISSION" type="INT32">
<short_desc>Mission Log</short_desc>
<long_desc>If enabled, a small additional "mission" log file will be written to the SD card. The log contains just those messages that are useful for tasks like generating flight statistics and geotagging. The different modes can be used to further reduce the logged data (and thus the log file size). For example, choose geotagging mode to only log data required for geotagging. Note that the normal/full log is still created, and contains all the data in the mission log (and more).</long_desc>
<reboot_required>true</reboot_required>
<values>
<value code="0">Disabled</value>
<value code="1">All mission messages</value>
<value code="2">Geotagging messages</value>
</values>
</parameter>
<parameter default="0" name="SDLOG_MODE" type="INT32">
<short_desc>Logging Mode</short_desc>
<long_desc>Determines when to start and stop logging. By default, logging is started when arming the system, and stopped when disarming.</long_desc>
<min>0</min>
<max>2</max>
<reboot_required>true</reboot_required>
<values>
<value code="0">when armed until disarm (default)</value>
......
......@@ -66,7 +66,7 @@ VideoManager::setToolbox(QGCToolbox *toolbox)
#ifndef QGC_DISABLE_UVC
// If we are using a UVC camera setup the device name
QList<QCameraInfo> cameras = QCameraInfo::availableCameras();
foreach (const QCameraInfo &cameraInfo, cameras) {
for (const QCameraInfo &cameraInfo: cameras) {
if(cameraInfo.description() == videoSource) {
_videoSourceID = cameraInfo.deviceName();
emit videoSourceIDChanged();
......
......@@ -34,7 +34,7 @@ Map {
property string mapName: 'defaultMap'
property bool isSatelliteMap: activeMapType.name.indexOf("Satellite") > -1 || activeMapType.name.indexOf("Hybrid") > -1
property var gcsPosition: QtPositioning.coordinate()
property var gcsPosition: QGroundControl.qgcPositionManger.gcsPosition
property bool userPanned: false ///< true: the user has manually panned the map
property bool allowGCSLocationCenter: false ///< true: map will center/zoom to gcs location one time
property bool allowVehicleLocationCenter: false ///< true: map will center/zoom to vehicle location one time
......@@ -80,19 +80,12 @@ Map {
ExclusiveGroup { id: mapTypeGroup }
// Update ground station position
Connections {
target: QGroundControl.qgcPositionManger
onLastPositionUpdated: {
if (valid && lastPosition.latitude && Math.abs(lastPosition.latitude) > 0.001 && lastPosition.longitude && Math.abs(lastPosition.longitude) > 0.001) {
gcsPosition = QtPositioning.coordinate(lastPosition.latitude,lastPosition.longitude)
if (!firstGCSPositionReceived && !firstVehiclePositionReceived && allowGCSLocationCenter) {
firstGCSPositionReceived = true
center = gcsPosition
zoomLevel = QGroundControl.flightMapInitialZoom
}
}
// Center map to gcs location
onGcsPositionChanged: {
if (gcsPosition.isValid && allowGCSLocationCenter && !firstGCSPositionReceived && !firstVehiclePositionReceived) {
firstGCSPositionReceived = true
center = gcsPosition
zoomLevel = QGroundControl.flightMapInitialZoom
}
}
......
......@@ -153,7 +153,7 @@ QVariantList JoystickManager::joysticks(void)
{
QVariantList list;
foreach (const QString &name, _name2JoystickMap.keys()) {
for (const QString &name: _name2JoystickMap.keys()) {
list += QVariant::fromValue(_name2JoystickMap[name]);
}
......
......@@ -68,7 +68,7 @@ void CameraCalcTest::_testDirty(void)
<< _cameraCalc->sideOverlap ()
<< _cameraCalc->adjustedFootprintSide()
<< _cameraCalc->adjustedFootprintFrontal();
foreach(Fact* fact, rgFacts) {
for(Fact* fact: rgFacts) {
qDebug() << fact->name();
QVERIFY(!_cameraCalc->dirty());
if (fact->typeIsBool()) {
......
......@@ -33,8 +33,8 @@ public:
TakeVideo,
StopTakingVideo,
TakePhoto
};
Q_ENUMS(CameraAction)
};
Q_ENUM(CameraAction)
Q_PROPERTY(bool specifyGimbal READ specifyGimbal WRITE setSpecifyGimbal NOTIFY specifyGimbalChanged)
Q_PROPERTY(Fact* gimbalPitch READ gimbalPitch CONSTANT)
......
......@@ -421,7 +421,7 @@ void CameraSectionTest::_testItemCount(void)
QList<int> rgCameraActions;
rgCameraActions << CameraSection::TakePhotosIntervalTime << CameraSection::TakePhotoIntervalDistance << CameraSection::StopTakingPhotos << CameraSection::TakeVideo << CameraSection::StopTakingVideo << CameraSection::TakePhoto;
foreach(int cameraAction, rgCameraActions) {
for(int cameraAction: rgCameraActions) {
qDebug() << "camera action" << cameraAction;
// Reset
......@@ -1063,8 +1063,8 @@ void CameraSectionTest::_testScanForMultipleItems(void)
rgActionItems << _validDistanceItem << _validTimeItem << _validStartVideoItem << _validStopVideoItem << _validTakePhotoItem;
// Camera action followed by gimbal/mode
foreach (SimpleMissionItem* actionItem, rgActionItems) {
foreach (SimpleMissionItem* cameraItem, rgCameraItems) {
for (SimpleMissionItem* actionItem: rgActionItems) {
for (SimpleMissionItem* cameraItem: rgCameraItems) {
SimpleMissionItem* item1 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this);
item1->missionItem() = actionItem->missionItem();
SimpleMissionItem* item2 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this);
......@@ -1084,8 +1084,8 @@ void CameraSectionTest::_testScanForMultipleItems(void)
}
// Gimbal/Mode followed by camera action
foreach (SimpleMissionItem* actionItem, rgCameraItems) {
foreach (SimpleMissionItem* cameraItem, rgActionItems) {
for (SimpleMissionItem* actionItem: rgCameraItems) {
for (SimpleMissionItem* cameraItem: rgActionItems) {
SimpleMissionItem* item1 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this);
item1->missionItem() = actionItem->missionItem();
SimpleMissionItem* item2 = new SimpleMissionItem(_offlineVehicle, false /* flyView */, this);
......
......@@ -149,7 +149,7 @@ void CorridorScanComplexItem::_appendLoadedMissionItems(QList<MissionItem*>& ite
int seqNum = _sequenceNumber;
foreach (const MissionItem* loadedMissionItem, _loadedMissionItems) {
for (const MissionItem* loadedMissionItem: _loadedMissionItems) {
MissionItem* item = new MissionItem(*loadedMissionItem, missionItemParent);
item->setSequenceNumber(seqNum++);
items.append(item);
......@@ -171,11 +171,11 @@ void CorridorScanComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& i
MAV_FRAME mavFrame = followTerrain() || !_cameraCalc.distanceToSurfaceRelative() ? MAV_FRAME_GLOBAL : MAV_FRAME_GLOBAL_RELATIVE_ALT;
//qDebug() << "_buildAndAppendMissionItems";
foreach (const QList<TransectStyleComplexItem::CoordInfo_t>& transect, _transects) {
for (const QList<TransectStyleComplexItem::CoordInfo_t>& transect: _transects) {
bool entryPoint = true;
//qDebug() << "start transect";
foreach (const CoordInfo_t& transectCoordInfo, transect) {
for (const CoordInfo_t& transectCoordInfo: transect) {
//qDebug() << transectCoordInfo.coordType;
item = new MissionItem(seqNum++,
......@@ -309,7 +309,7 @@ void CorridorScanComplexItem::_rebuildCorridorPolygon(void)
_surveyAreaPolygon.clear();
QList<QGeoCoordinate> rgCoord;
foreach (const QGeoCoordinate& vertex, firstSideVertices) {
for (const QGeoCoordinate& vertex: firstSideVertices) {
rgCoord.append(vertex);
}
for (int i=secondSideVertices.count() - 1; i >= 0; i--) {
......@@ -386,7 +386,7 @@ void CorridorScanComplexItem::_rebuildTransectsPhase1(void)
#if 0
qDebug() << "transect debug";
foreach (const TransectStyleComplexItem::CoordInfo_t& coordInfo, transect) {
for (const TransectStyleComplexItem::CoordInfo_t& coordInfo: transect) {
qDebug() << coordInfo.coordType;
}
#endif
......@@ -423,7 +423,7 @@ void CorridorScanComplexItem::_rebuildTransectsPhase1(void)
}
if (reverseTransects) {
QList<QList<TransectStyleComplexItem::CoordInfo_t>> reversedTransects;
foreach (const QList<TransectStyleComplexItem::CoordInfo_t>& transect, _transects) {
for (const QList<TransectStyleComplexItem::CoordInfo_t>& transect: _transects) {
reversedTransects.prepend(transect);
}
_transects = reversedTransects;
......@@ -431,7 +431,7 @@ void CorridorScanComplexItem::_rebuildTransectsPhase1(void)
if (reverseVertices) {
for (int i=0; i<_transects.count(); i++) {
QList<TransectStyleComplexItem::CoordInfo_t> reversedVertices;
foreach (const TransectStyleComplexItem::CoordInfo_t& vertex, _transects[i]) {
for (const TransectStyleComplexItem::CoordInfo_t& vertex: _transects[i]) {
reversedVertices.prepend(vertex);
}
_transects[i] = reversedVertices;
......@@ -466,11 +466,16 @@ void CorridorScanComplexItem::_rebuildTransectsPhase2(void)
_complexDistance += _visualTransectPoints[i].value<QGeoCoordinate>().distanceTo(_visualTransectPoints[i+1].value<QGeoCoordinate>());
}
if (_cameraTriggerInTurnAroundFact.rawValue().toBool()) {
_cameraShots = qCeil(_complexDistance / _cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble());
double triggerDistance = _cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble();
if (triggerDistance == 0) {
_cameraShots = 0;
} else {
int singleTransectImageCount = qCeil(_corridorPolyline.length() / _cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble());
_cameraShots = singleTransectImageCount * _transectCount();
if (_cameraTriggerInTurnAroundFact.rawValue().toBool()) {
_cameraShots = qCeil(_complexDistance / triggerDistance);
} else {
int singleTransectImageCount = qCeil(_corridorPolyline.length() / triggerDistance);
_cameraShots = singleTransectImageCount * _transectCount();
}
}
_coordinate = _visualTransectPoints.count() ? _visualTransectPoints.first().value<QGeoCoordinate>() : QGeoCoordinate();
......
......@@ -143,7 +143,7 @@ bool GeoFenceController::load(const QJsonObject& json, QString& errorString)
}
QJsonArray jsonPolygonArray = json[_jsonPolygonsKey].toArray();
foreach (const QJsonValue& jsonPolygonValue, jsonPolygonArray) {
for (const QJsonValue& jsonPolygonValue: jsonPolygonArray) {
if (jsonPolygonValue.type() != QJsonValue::Object) {
errorString = tr("GeoFence polygon not stored as object");
return false;
......@@ -157,7 +157,7 @@ bool GeoFenceController::load(const QJsonObject& json, QString& errorString)
}
QJsonArray jsonCircleArray = json[_jsonCirclesKey].toArray();
foreach (const QJsonValue& jsonCircleValue, jsonCircleArray) {
for (const QJsonValue& jsonCircleValue: jsonCircleArray) {
if (jsonCircleValue.type() != QJsonValue::Object) {
errorString = tr("GeoFence circle not stored as object");
return false;
......
......@@ -71,7 +71,7 @@ void MissionCommandList::_loadMavCmdInfoJson(const QString& jsonFilename, bool b
// Iterate over MissionCommandUIInfo objects
QJsonArray jsonArray = jsonValue.toArray();
foreach(QJsonValue info, jsonArray) {
for(QJsonValue info: jsonArray) {
if (!info.isObject()) {
qWarning() << jsonFilename << "mavCmdArray should contain objects";
return;
......@@ -96,7 +96,7 @@ void MissionCommandList::_loadMavCmdInfoJson(const QString& jsonFilename, bool b
}
// Build id list
foreach (MAV_CMD id, _infoMap.keys()) {
for (MAV_CMD id: _infoMap.keys()) {
_ids << id;
}
}
......
......@@ -47,13 +47,13 @@ void MissionCommandTree::setToolbox(QGCToolbox* toolbox)
} else {
#endif
// Load all levels of hierarchy
foreach (MAV_AUTOPILOT firmwareType, _toolbox->firmwarePluginManager()->supportedFirmwareTypes()) {
for (MAV_AUTOPILOT firmwareType: _toolbox->firmwarePluginManager()->supportedFirmwareTypes()) {
FirmwarePlugin* plugin = _toolbox->firmwarePluginManager()->firmwarePluginForAutopilot(firmwareType, MAV_TYPE_QUADROTOR);
QList<MAV_TYPE> vehicleTypes;
vehicleTypes << MAV_TYPE_GENERIC << MAV_TYPE_FIXED_WING << MAV_TYPE_QUADROTOR << MAV_TYPE_VTOL_QUADROTOR << MAV_TYPE_GROUND_ROVER << MAV_TYPE_SUBMARINE;
foreach(MAV_TYPE vehicleType, vehicleTypes) {
for(MAV_TYPE vehicleType: vehicleTypes) {
QString overrideFile = plugin->missionCommandOverrides(vehicleType);
if (!overrideFile.isEmpty()) {
_staticCommandTree[firmwareType][vehicleType] = new MissionCommandList(overrideFile, firmwareType == MAV_AUTOPILOT_GENERIC && vehicleType == MAV_TYPE_GENERIC /* baseCommandList */, this);
......@@ -105,7 +105,7 @@ void MissionCommandTree::_collapseHierarchy(Vehicle*
_baseVehicleInfo(vehicle, baseFirmwareType, baseVehicleType);
foreach (MAV_CMD command, cmdList->commandIds()) {
for (MAV_CMD command: cmdList->commandIds()) {
// Only add supported command to tree (MAV_CMD_NAV_LAST is used for planned home position)
if (!qgcApp()->runningUnitTests()
&& !vehicle->firmwarePlugin()->supportedMissionCommands().isEmpty()
......@@ -238,7 +238,7 @@ QVariantList MissionCommandTree::getCommandsForCategory(Vehicle* vehicle, const
QVariantList list;
QMap<MAV_CMD, MissionCommandUIInfo*> commandMap = _availableCommands[baseFirmwareType][baseVehicleType];
foreach (MAV_CMD command, commandMap.keys()) {
for (MAV_CMD command: commandMap.keys()) {
if (command == MAV_CMD_NAV_LAST) {
// MAV_CMD_NAV_LAST is used for Mission Settings item. Although we want to be able to get command info for it.
// The user should not be able to use it as a command.
......
......@@ -206,8 +206,8 @@ void MissionCommandTreeTest::testAllTrees(void)
vehicleList << MAV_TYPE_GENERIC << MAV_TYPE_QUADROTOR << MAV_TYPE_FIXED_WING << MAV_TYPE_GROUND_ROVER << MAV_TYPE_SUBMARINE << MAV_TYPE_VTOL_QUADROTOR;
// This will cause all of the variants of collapsed trees to be built
foreach(MAV_AUTOPILOT firmwareType, firmwareList) {
foreach (MAV_TYPE vehicleType, vehicleList) {
for(MAV_AUTOPILOT firmwareType: firmwareList) {
for (MAV_TYPE vehicleType: vehicleList) {
if (firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA && vehicleType == MAV_TYPE_VTOL_QUADROTOR) {
// VTOL in ArduPilot shows up as plane so we can test this pair
continue;
......
......@@ -85,7 +85,7 @@ const MissionCommandUIInfo& MissionCommandUIInfo::operator=(const MissionCommand
_infoMap = other._infoMap;
_paramRemoveList = other._paramRemoveList;
foreach (int index, other._paramInfoMap.keys()) {
for (int index: other._paramInfoMap.keys()) {
_paramInfoMap[index] = new MissionCmdParamInfo(*other._paramInfoMap[index], this);
}
......@@ -167,19 +167,19 @@ bool MissionCommandUIInfo::specifiesAltitudeOnly(void) const
void MissionCommandUIInfo::_overrideInfo(MissionCommandUIInfo* uiInfo)
{
// Override info values
foreach (const QString& valueKey, uiInfo->_infoMap.keys()) {
for (const QString& valueKey: uiInfo->_infoMap.keys()) {
_setInfoValue(valueKey, uiInfo->_infoMap[valueKey]);
}
// Add to the remove params list
foreach (int removeIndex, uiInfo->_paramRemoveList) {
for (int removeIndex: uiInfo->_paramRemoveList) {
if (!_paramRemoveList.contains(removeIndex)) {
_paramRemoveList.append(removeIndex);
}
}
// Override param info
foreach (const int paramIndex, uiInfo->_paramInfoMap.keys()) {
for (const int paramIndex: uiInfo->_paramInfoMap.keys()) {
_paramRemoveList.removeOne(paramIndex);
// MissionCmdParamInfo objects are owned by MissionCommandTree are are in existence for the entire run so
// we can just use the same pointer reference.
......@@ -202,7 +202,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ
<< _paramRemoveJsonKey << _categoryJsonKey << _specifiesAltitudeOnlyJsonKey;
// Look for unknown keys in top level object
foreach (const QString& key, jsonObject.keys()) {
for (const QString& key: jsonObject.keys()) {
if (!allKeys.contains(key) && key != _commentJsonKey) {
errorString = _loadErrorString(QString("Unknown key: %1").arg(key));
return false;
......@@ -267,7 +267,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ
}
if (jsonObject.contains(_paramRemoveJsonKey)) {
QStringList indexList = jsonObject.value(_paramRemoveJsonKey).toString().split(QStringLiteral(","));
foreach (const QString& indexString, indexList) {
for (const QString& indexString: indexList) {
_paramRemoveList.append(indexString.toInt());
}
}
......@@ -308,7 +308,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ
}
QString debugOutput;
foreach (const QString& infoKey, _infoMap.keys()) {
for (const QString& infoKey: _infoMap.keys()) {
debugOutput.append(QString("MavCmdInfo %1: %2 ").arg(infoKey).arg(_infoMap[infoKey].toString()));
}
qCDebug(MissionCommandsLog) << debugOutput;
......@@ -325,7 +325,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ
allParamKeys << _defaultJsonKey << _decimalPlacesJsonKey << _enumStringsJsonKey << _enumValuesJsonKey << _labelJsonKey << _unitsJsonKey << _nanUnchangedJsonKey;
// Look for unknown keys in param object
foreach (const QString& key, paramObject.keys()) {
for (const QString& key: paramObject.keys()) {
if (!allParamKeys.contains(key) && key != _commentJsonKey) {
errorString = _loadErrorString(QString("Unknown param key: %1").arg(key));
return false;
......@@ -372,7 +372,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ
}
QStringList enumValues = paramObject.value(_enumValuesJsonKey).toString().split(",", QString::SkipEmptyParts);
foreach (const QString &enumValue, enumValues) {
for (const QString &enumValue: enumValues) {
bool convertOk;
double value = enumValue.toDouble(&convertOk);
......
......@@ -1156,7 +1156,7 @@ void MissionController::_recalcWaypointLines(void)
// Create a temporary QObjectList and replace the model data
QObjectList objs;
objs.reserve(_linesTable.count());
foreach(CoordinateVector *vect, _linesTable.values()) {
for(CoordinateVector *vect: _linesTable.values()) {
objs.append(vect);
}
......
......@@ -301,7 +301,7 @@ void MissionItemTest::_testLoadFromJsonV1(void)
QStringList removeKeys;
removeKeys << MissionItem::_jsonParam1Key << MissionItem::_jsonParam2Key << MissionItem::_jsonParam3Key << MissionItem::_jsonParam4Key;
foreach (const QString& removeKey, removeKeys) {
for (const QString& removeKey: removeKeys) {
QJsonObject badObject = jsonObject;
badObject.remove(removeKey);
QCOMPARE(missionItem.load(badObject, _seq, errorString), false);
......@@ -329,7 +329,7 @@ void MissionItemTest::_testLoadFromJsonV2(void)
QStringList removeKeys;
removeKeys << MissionItem::_jsonCoordinateKey;
foreach(const QString& removeKey, removeKeys) {
for(const QString& removeKey: removeKeys) {
QJsonObject badObject = jsonObject;
badObject.remove(removeKey);
QCOMPARE(missionItem.load(badObject, _seq, errorString), false);
......@@ -399,7 +399,7 @@ void MissionItemTest::_testLoadFromJsonV3(void)
MissionItem::_jsonFrameKey <<
MissionItem::_jsonParamsKey <<
VisualMissionItem::jsonTypeKey;
foreach(const QString& removeKey, removeKeys) {
for(const QString& removeKey: removeKeys) {
QJsonObject badObject = jsonObject;
badObject.remove(removeKey);
QCOMPARE(missionItem.load(badObject, _seq, errorString), false);
......
......@@ -114,7 +114,7 @@ void PlanManager::_writeMissionCount(void)
_dedicatedLink->mavlinkChannel(),
&message,
_vehicle->id(),
MAV_COMP_ID_MISSIONPLANNER,
MAV_COMP_ID_AUTOPILOT1,
_writeMissionItems.count(),
_planType);
......@@ -157,7 +157,7 @@ void PlanManager::_requestList(void)
_dedicatedLink->mavlinkChannel(),
&message,
_vehicle->id(),
MAV_COMP_ID_MISSIONPLANNER,
MAV_COMP_ID_AUTOPILOT1,
_planType);
_vehicle->sendMessageOnLink(_dedicatedLink, message);
......@@ -296,7 +296,7 @@ void PlanManager::_readTransactionComplete(void)
_dedicatedLink->mavlinkChannel(),
&message,
_vehicle->id(),
MAV_COMP_ID_MISSIONPLANNER,
MAV_COMP_ID_AUTOPILOT1,
MAV_MISSION_ACCEPTED,
_planType);
......@@ -354,7 +354,7 @@ void PlanManager::_requestNextMissionItem(void)
_dedicatedLink->mavlinkChannel(),
&message,
_vehicle->id(),
MAV_COMP_ID_MISSIONPLANNER,
MAV_COMP_ID_AUTOPILOT1,
_itemIndicesToRead[0],
_planType);
} else {
......@@ -363,7 +363,7 @@ void PlanManager::_requestNextMissionItem(void)
_dedicatedLink->mavlinkChannel(),
&message,
_vehicle->id(),
MAV_COMP_ID_MISSIONPLANNER,
MAV_COMP_ID_AUTOPILOT1,
_itemIndicesToRead[0],
_planType);
}
......@@ -536,7 +536,7 @@ void PlanManager::_handleMissionRequest(const mavlink_message_t& message, bool m
_dedicatedLink->mavlinkChannel(),
&messageOut,
_vehicle->id(),
MAV_COMP_ID_MISSIONPLANNER,
MAV_COMP_ID_AUTOPILOT1,
missionRequest.seq,
item->frame(),
item->command(),
......@@ -556,7 +556,7 @@ void PlanManager::_handleMissionRequest(const mavlink_message_t& message, bool m
_dedicatedLink->mavlinkChannel(),
&messageOut,
_vehicle->id(),
MAV_COMP_ID_MISSIONPLANNER,
MAV_COMP_ID_AUTOPILOT1,
missionRequest.seq,
item->frame(),
item->command(),
......@@ -897,7 +897,7 @@ void PlanManager::_removeAllWorker(void)
_dedicatedLink->mavlinkChannel(),
&message,
_vehicle->id(),
MAV_COMP_ID_MISSIONPLANNER,
MAV_COMP_ID_AUTOPILOT1,
_planType);
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), message);
_startAckTimeout(AckMissionClearAll);
......
......@@ -58,7 +58,7 @@ const QGCMapPolygon& QGCMapPolygon::operator=(const QGCMapPolygon& other)
QVariantList vertices = other.path();
QList<QGeoCoordinate> rgCoord;
foreach (const QVariant& vertexVar, vertices) {
for (const QVariant& vertexVar: vertices) {
rgCoord.append(vertexVar.value<QGeoCoordinate>());
}
appendVertices(rgCoord);
......@@ -162,7 +162,7 @@ void QGCMapPolygon::setPath(const QList<QGeoCoordinate>& path)
{
_polygonPath.clear();
_polygonModel.clearAndDeleteContents();
foreach(const QGeoCoordinate& coord, path) {
for(const QGeoCoordinate& coord: path) {
_polygonPath.append(QVariant::fromValue(coord));
_polygonModel.append(new QGCQGeoCoordinate(coord, this));
}
......@@ -265,7 +265,7 @@ void QGCMapPolygon::appendVertices(const QList<QGeoCoordinate>& coordinates)
{
QList<QObject*> objects;
foreach (const QGeoCoordinate& coordinate, coordinates) {
for (const QGeoCoordinate& coordinate: coordinates) {
objects.append(new QGCQGeoCoordinate(coordinate, this));
_polygonPath.append(QVariant::fromValue(coordinate));
}
......
......@@ -120,7 +120,7 @@ void QGCMapPolyline::setPath(const QList<QGeoCoordinate>& path)
{
_polylinePath.clear();
_polylineModel.clearAndDeleteContents();
foreach (const QGeoCoordinate& coord, path) {
for (const QGeoCoordinate& coord: path) {
_polylinePath.append(QVariant::fromValue(coord));
_polylineModel.append(new QGCQGeoCoordinate(coord, this));
}
......@@ -382,7 +382,7 @@ void QGCMapPolyline::appendVertices(const QList<QGeoCoordinate>& coordinates)
{
QList<QObject*> objects;
foreach (const QGeoCoordinate& coordinate, coordinates) {
for (const QGeoCoordinate& coordinate: coordinates) {
objects.append(new QGCQGeoCoordinate(coordinate, this));
_polylinePath.append(QVariant::fromValue(coordinate));
}
......
......@@ -250,7 +250,7 @@ void SimpleMissionItem::_setupMetaData(void)
enumStrings.clear();
enumValues.clear();
MissionCommandTree* commandTree = qgcApp()->toolbox()->missionCommandTree();
foreach (const MAV_CMD command, commandTree->allCommandIds()) {
for (const MAV_CMD command: commandTree->allCommandIds()) {
enumStrings.append(commandTree->rawName(command));
enumValues.append(QVariant((int)command));
}
......
......@@ -433,6 +433,12 @@ void StructureScanComplexItem::_rebuildFlightPolygon(void)
void StructureScanComplexItem::_recalcCameraShots(void)
{
double triggerDistance = _cameraCalc.adjustedFootprintSide()->rawValue().toDouble();
if (triggerDistance == 0) {
_setCameraShots(0);
return;
}
if (_flightPolygon.count() < 3) {
_setCameraShots(0);
return;
......@@ -450,7 +456,7 @@ void StructureScanComplexItem::_recalcCameraShots(void)
return;
}
int cameraShots = distance / _cameraCalc.adjustedFootprintSide()->rawValue().toDouble();
int cameraShots = distance / triggerDistance;
_setCameraShots(cameraShots * _layersFact.rawValue().toInt());
}
......
......@@ -60,7 +60,7 @@ void StructureScanComplexItemTest::_testDirty(void)
// These facts should set dirty when changed
QList<Fact*> rgFacts;
rgFacts << _structureScanItem->altitude() << _structureScanItem->layers();
foreach(Fact* fact, rgFacts) {
for(Fact* fact: rgFacts) {
qDebug() << fact->name();
QVERIFY(!_structureScanItem->dirty());
if (fact->typeIsBool()) {
......
......@@ -819,10 +819,10 @@ void SurveyComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& items,
MAV_FRAME mavFrame = followTerrain() || !_cameraCalc.distanceToSurfaceRelative() ? MAV_FRAME_GLOBAL : MAV_FRAME_GLOBAL_RELATIVE_ALT;
foreach (const QList<TransectStyleComplexItem::CoordInfo_t>& transect, _transects) {
for (const QList<TransectStyleComplexItem::CoordInfo_t>& transect: _transects) {
bool entryPoint = true;
foreach (const CoordInfo_t& transectCoordInfo, transect) {
for (const CoordInfo_t& transectCoordInfo: transect) {
item = new MissionItem(seqNum++,
MAV_CMD_NAV_WAYPOINT,
mavFrame,
......@@ -940,7 +940,7 @@ bool SurveyComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& items,
firstWaypointTrigger = true;
}
foreach (const QList<TransectStyleComplexItem::CoordInfo_t>& transect, _transects) {
for (const QList<TransectStyleComplexItem::CoordInfo_t>& transect: _transects) {
int pointIndex = 0;
QGeoCoordinate coord;
CameraTriggerCode cameraTrigger;
......@@ -1182,7 +1182,7 @@ void SurveyComplexItem::_rebuildTransectsPhase1Worker(bool refly)
// Convert from NED to Geo
QList<QList<QGeoCoordinate>> transects;
foreach (const QLineF& line, resultLines) {
for (const QLineF& line: resultLines) {
QGeoCoordinate coord;
QList<QGeoCoordinate> transect;
......@@ -1234,7 +1234,7 @@ void SurveyComplexItem::_rebuildTransectsPhase1Worker(bool refly)
}
// Convert to CoordInfo transects and append to _transects
foreach (const QList<QGeoCoordinate>& transect, transects) {
for (const QList<QGeoCoordinate>& transect: transects) {
QGeoCoordinate coord;
QList<TransectStyleComplexItem::CoordInfo_t> coordInfoTransect;
TransectStyleComplexItem::CoordInfo_t coordInfo;
......@@ -1289,20 +1289,24 @@ void SurveyComplexItem::_rebuildTransectsPhase2(void)
_complexDistance += _visualTransectPoints[i].value<QGeoCoordinate>().distanceTo(_visualTransectPoints[i+1].value<QGeoCoordinate>());
}
if (_cameraTriggerInTurnAroundFact.rawValue().toBool()) {
_cameraShots = qCeil(_complexDistance / triggerDistance());
} else {
if (triggerDistance() == 0) {
_cameraShots = 0;
foreach (const QList<TransectStyleComplexItem::CoordInfo_t>& transect, _transects) {
QGeoCoordinate firstCameraCoord, lastCameraCoord;
if (_hasTurnaround()) {
firstCameraCoord = transect[1].coord;
lastCameraCoord = transect[transect.count() - 2].coord;
} else {
firstCameraCoord = transect.first().coord;
lastCameraCoord = transect.last().coord;
} else {
if (_cameraTriggerInTurnAroundFact.rawValue().toBool()) {
_cameraShots = qCeil(_complexDistance / triggerDistance());
} else {
_cameraShots = 0;
for (const QList<TransectStyleComplexItem::CoordInfo_t>& transect: _transects) {
QGeoCoordinate firstCameraCoord, lastCameraCoord;
if (_hasTurnaround()) {
firstCameraCoord = transect[1].coord;
lastCameraCoord = transect[transect.count() - 2].coord;
} else {
firstCameraCoord = transect.first().coord;
lastCameraCoord = transect.last().coord;
}
_cameraShots += qCeil(firstCameraCoord.distanceTo(lastCameraCoord) / triggerDistance());
}
_cameraShots += qCeil(firstCameraCoord.distanceTo(lastCameraCoord) / triggerDistance());
}
}
......@@ -1345,7 +1349,7 @@ void SurveyComplexItem::_appendLoadedMissionItems(QList<MissionItem*>& items, QO
int seqNum = _sequenceNumber;
foreach (const MissionItem* loadedMissionItem, _loadedMissionItems) {
for (const MissionItem* loadedMissionItem: _loadedMissionItems) {
MissionItem* item = new MissionItem(*loadedMissionItem, missionItemParent);
item->setSequenceNumber(seqNum++);
items.append(item);
......
......@@ -71,7 +71,7 @@ void SurveyComplexItemTest::_testDirty(void)
// These facts should set dirty when changed
QList<Fact*> rgFacts;
rgFacts << _surveyItem->gridAngle() << _surveyItem->flyAlternateTransects();
foreach(Fact* fact, rgFacts) {
for(Fact* fact: rgFacts) {
qDebug() << fact->name();
QVERIFY(!_surveyItem->dirty());
if (fact->typeIsBool()) {
......
......@@ -162,7 +162,7 @@ void TransectStyleComplexItem::_save(QJsonObject& complexObject)
QObject* missionItemParent = new QObject();
QList<MissionItem*> missionItems;
appendMissionItems(missionItems, missionItemParent);
foreach (const MissionItem* missionItem, missionItems) {
for (const MissionItem* missionItem: missionItems) {
QJsonObject missionItemJsonObject;
missionItem->save(missionItemJsonObject);
missionItemsJsonArray.append(missionItemJsonObject);
......@@ -228,7 +228,7 @@ bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, QString&
// Load generated mission items
_loadedMissionItemsParent = new QObject(this);
QJsonArray missionItemsJsonArray = innerObject[_jsonItemsKey].toArray();
foreach (const QJsonValue& missionItemJson, missionItemsJsonArray) {
for (const QJsonValue& missionItemJson: missionItemsJsonArray) {
MissionItem* missionItem = new MissionItem(_loadedMissionItemsParent);
if (!missionItem->load(missionItemJson.toObject(), 0 /* sequenceNumber */, errorString)) {
_loadedMissionItemsParent->deleteLater();
......@@ -371,8 +371,8 @@ void TransectStyleComplexItem::_rebuildTransects(void)
double top = 0.;
// Generate the visuals transect representation
_visualTransectPoints.clear();
foreach (const QList<CoordInfo_t>& transect, _transects) {
foreach (const CoordInfo_t& coordInfo, transect) {
for (const QList<CoordInfo_t>& transect: _transects) {
for (const CoordInfo_t& coordInfo: transect) {
_visualTransectPoints.append(QVariant::fromValue(coordInfo.coord));
double lat = coordInfo.coord.latitude() + 90.0;
double lon = coordInfo.coord.longitude() + 180.0;
......@@ -440,8 +440,8 @@ void TransectStyleComplexItem::_reallyQueryTransectsPathHeightInfo(void)
QList<QGeoCoordinate> transectPoints;
foreach (const QList<CoordInfo_t>& transect, _transects) {
foreach (const CoordInfo_t& coordInfo, transect) {
for (const QList<CoordInfo_t>& transect: _transects) {
for (const CoordInfo_t& coordInfo: transect) {
transectPoints.append(coordInfo.coord);
}
}
......@@ -645,7 +645,7 @@ void TransectStyleComplexItem::_adjustForTolerance(QList<CoordInfo_t>& transect)
#if 0
qDebug() << "_adjustForTolerance";
foreach (const TransectStyleComplexItem::CoordInfo_t& coordInfo, adjustedPoints) {
for (const TransectStyleComplexItem::CoordInfo_t& coordInfo: adjustedPoints) {
qDebug() << coordInfo.coordType;
}
#endif
......@@ -698,7 +698,7 @@ void TransectStyleComplexItem::_addInterstitialTerrainPoints(QList<CoordInfo_t>&
#if 0
qDebug() << "_addInterstitialTerrainPoints";
foreach (const TransectStyleComplexItem::CoordInfo_t& coordInfo, adjustedTransect) {
for (const TransectStyleComplexItem::CoordInfo_t& coordInfo: adjustedTransect) {
qDebug() << coordInfo.coordType;
}
#endif
......@@ -723,7 +723,7 @@ int TransectStyleComplexItem::lastSequenceNumber(void) const
// We have to determine from transects
int itemCount = 0;
foreach (const QList<CoordInfo_t>& rgCoordInfo, _transects) {
for (const QList<CoordInfo_t>& rgCoordInfo: _transects) {
itemCount += rgCoordInfo.count() * (hoverAndCaptureEnabled() ? 2 : 1);
}
......
......@@ -77,7 +77,7 @@ void TransectStyleComplexItemTest::_testDirty(void)
<< _transectStyleItem->cameraTriggerInTurnAround()
<< _transectStyleItem->hoverAndCapture()
<< _transectStyleItem->refly90Degrees();
foreach(Fact* fact, rgFacts) {
for(Fact* fact: rgFacts) {
qDebug() << fact->name();
QVERIFY(!_transectStyleItem->dirty());
changeFactValue(fact);
......@@ -102,7 +102,7 @@ void TransectStyleComplexItemTest::_testDirty(void)
void TransectStyleComplexItemTest::_setSurveyAreaPolygon(void)
{
foreach (const QGeoCoordinate vertex, _polygonVertices) {
for (const QGeoCoordinate vertex: _polygonVertices) {
_transectStyleItem->surveyAreaPolygon()->appendVertex(vertex);
}
}
......@@ -132,7 +132,7 @@ void TransectStyleComplexItemTest::_testRebuildTransects(void)
<< _transectStyleItem->refly90Degrees()
<< _transectStyleItem->cameraCalc()->frontalOverlap()
<< _transectStyleItem->cameraCalc()->sideOverlap();
foreach(Fact* fact, rgFacts) {
for(Fact* fact: rgFacts) {
qDebug() << fact->name();
changeFactValue(fact);
QVERIFY(_transectStyleItem->rebuildTransectsPhase1Called);
......@@ -175,7 +175,7 @@ void TransectStyleComplexItemTest::_testDistanceSignalling(void)
rgFacts << _transectStyleItem->turnAroundDistance()
<< _transectStyleItem->hoverAndCapture()
<< _transectStyleItem->refly90Degrees();
foreach(Fact* fact, rgFacts) {
for(Fact* fact: rgFacts) {
qDebug() << fact->name();
changeFactValue(fact);
QVERIFY(_multiSpy->checkSignalsByMask(complexDistanceChangedMask | greatestDistanceToChangedMask));
......
......@@ -37,6 +37,9 @@ QGCView {
property bool planControlColapsed: false
///< This property is used to determine dirty state for prompting on QGC shutdown
readonly property bool dirty: _planMasterController.dirty
readonly property int _decimalPlaces: 8
readonly property real _horizontalMargin: ScreenTools.defaultFontPixelWidth * 0.5
readonly property real _margin: ScreenTools.defaultFontPixelHeight * 0.5
......
......@@ -60,7 +60,19 @@ void QGCPositionManager::setNmeaSourceDevice(QIODevice* device)
void QGCPositionManager::_positionUpdated(const QGeoPositionInfo &update)
{
emit lastPositionUpdated(update.isValid(), QVariant::fromValue(update.coordinate()));
QGeoCoordinate newGCSPosition = QGeoCoordinate();
if (update.isValid()) {
// Note that gcsPosition filters out possible crap values
if (qAbs(update.coordinate().latitude()) > 0.001 && qAbs(update.coordinate().longitude()) > 0.001) {
newGCSPosition = update.coordinate();
}
}
if (newGCSPosition != _gcsPosition) {
_gcsPosition = newGCSPosition;
emit gcsPositionChanged(_gcsPosition);
}
emit positionInfoUpdated(update);
}
......
......@@ -25,6 +25,8 @@ public:
QGCPositionManager(QGCApplication* app, QGCToolbox* toolbox);
~QGCPositionManager();
Q_PROPERTY(QGeoCoordinate gcsPosition READ gcsPosition NOTIFY gcsPositionChanged)
enum QGCPositionSource {
Simulated,
InternalGPS,
......@@ -32,6 +34,8 @@ public:
NmeaGPS
};
QGeoCoordinate gcsPosition(void) { return _gcsPosition; }
void setPositionSource(QGCPositionSource source);
int updateInterval() const;
......@@ -45,13 +49,15 @@ private slots:
void _error(QGeoPositionInfoSource::Error positioningError);
signals:
void lastPositionUpdated(bool valid, QVariant lastPosition);
void gcsPositionChanged(QGeoCoordinate gcsPosition);
void positionInfoUpdated(QGeoPositionInfo update);
private:
int _updateInterval;
QGeoPositionInfoSource * _currentSource;
QGeoPositionInfoSource * _defaultSource;
QNmeaPositionInfoSource * _nmeaSource;
QGeoPositionInfoSource * _simulatedSource;
int _updateInterval;
QGeoCoordinate _gcsPosition;
QGeoPositionInfoSource* _currentSource;
QGeoPositionInfoSource* _defaultSource;
QNmeaPositionInfoSource* _nmeaSource;
QGeoPositionInfoSource* _simulatedSource;
};
......@@ -54,8 +54,6 @@ class QGCPalette : public QObject
{
Q_OBJECT
Q_ENUMS(Theme)
public:
enum ColorGroup {
ColorGroupDisabled = 0,
......@@ -68,6 +66,7 @@ public:
Dark,
cMaxTheme
};
Q_ENUM(Theme)
typedef QColor PaletteColorInfo_t[cMaxTheme][cMaxColorGroup];
......
......@@ -159,7 +159,7 @@ QString QGCQFileDialog::getSaveFileName(
}
break;
}
return QString("");
return {};
}
}
......@@ -190,7 +190,7 @@ QString QGCQFileDialog::_getFirstExtensionInFilter(const QString& filter) {
return match.captured(0).mid(2);
}
}
return QString("");
return {};
}
/// @brief Validates and updates the parameters for the file dialog calls
......
......@@ -70,7 +70,7 @@ QStringList ParameterEditorController::searchParameters(const QString& searchTex
{
QStringList list;
foreach(const QString &paramName, _vehicle->parameterManager()->parameterNames(_vehicle->defaultComponentId())) {
for(const QString &paramName: _vehicle->parameterManager()->parameterNames(_vehicle->defaultComponentId())) {
if (searchText.isEmpty()) {
list += paramName;
} else {
......@@ -168,11 +168,11 @@ void ParameterEditorController::_updateParameters(void)
if (searchItems.isEmpty()) {
const QMap<QString, QMap<QString, QStringList> >& categoryMap = _vehicle->parameterManager()->getCategoryMap();
foreach (const QString& parameter, categoryMap[_currentCategory][_currentGroup]) {
for (const QString& parameter: categoryMap[_currentCategory][_currentGroup]) {
newParameterList.append(_vehicle->parameterManager()->getParameter(_vehicle->defaultComponentId(), parameter));
}
} else {
foreach(const QString &parameter, _vehicle->parameterManager()->parameterNames(_vehicle->defaultComponentId())) {
for(const QString &parameter: _vehicle->parameterManager()->parameterNames(_vehicle->defaultComponentId())) {
Fact* fact = _vehicle->parameterManager()->getParameter(_vehicle->defaultComponentId(), parameter);
bool matched = true;
......
......@@ -24,13 +24,13 @@ QStringList QGCFileDialogController::getFiles(const QString& directoryPath, cons
QDir fileDir(directoryPath);
QStringList infoListExtensions;
foreach (const QString& extension, fileExtensions) {
for (const QString& extension: fileExtensions) {
infoListExtensions.append(QStringLiteral("*.%1").arg(extension));
}
QFileInfoList fileInfoList = fileDir.entryInfoList(infoListExtensions, QDir::Files, QDir::Name);
foreach (const QFileInfo& fileInfo, fileInfoList) {
for (const QFileInfo& fileInfo: fileInfoList) {
qCDebug(QGCFileDialogControllerLog) << "getFiles found" << fileInfo.fileName();
files << fileInfo.fileName();
}
......
......@@ -183,7 +183,7 @@ void QmlObjectListModel::insert(int i, QList<QObject*> objects)
}
int j = i;
foreach (QObject* object, objects) {
for (QObject* object: objects) {
QQmlEngine::setObjectOwnership(object, QQmlEngine::CppOwnership);
// Look for a dirtyChanged signal on the object
......@@ -233,7 +233,7 @@ void QmlObjectListModel::setDirty(bool dirty)
_dirty = dirty;
if (!dirty) {
// Need to clear dirty from all children
foreach(QObject* object, _objectList) {
for(QObject* object: _objectList) {
if (object->property("dirty").isValid()) {
object->setProperty("dirty", false);
}
......
......@@ -435,7 +435,7 @@ UrlFactory::_getURL(MapType type, int x, int y, int zoom, QNetworkAccessManager*
int y_max = 26 * pow(2, gap) + (2*gap - 1);
if ( zoom > 19 ) {
return QString("");
return {};
}
else if ( zoom > 5 && x >= x_min && x <= x_max && y >= y_min && y <= y_max ) {
return QString("http://xdworld.vworld.kr:8080/2d/Base/service/%1/%2/%3.png").arg(zoom).arg(x).arg(y);
......@@ -458,7 +458,7 @@ UrlFactory::_getURL(MapType type, int x, int y, int zoom, QNetworkAccessManager*
int y_max = 26 * pow(2, gap) + (2*gap - 1);
if ( zoom > 19 ) {
return QString("");
return {};
}
else if ( zoom > 5 && x >= x_min && x <= x_max && y >= y_min && y <= y_max ) {
return QString("http://xdworld.vworld.kr:8080/2d/Satellite/service/%1/%2/%3.jpeg").arg(zoom).arg(x).arg(y);
......
......@@ -35,7 +35,7 @@ public:
ActionExporting,
ActionDone,
};
Q_ENUMS(ImportAction)
Q_ENUM(ImportAction)
Q_PROPERTY(int tileX0 READ tileX0 NOTIFY tileX0Changed)
Q_PROPERTY(int tileX1 READ tileX1 NOTIFY tileX1Changed)
......
......@@ -59,7 +59,7 @@ class QGeoServiceProviderPrivate;
class Q_LOCATION_EXPORT QGeoServiceProvider : public QObject
{
Q_OBJECT
Q_ENUMS(Error)
Q_ENUM(Error)
public:
enum Error {
NoError,
......
......@@ -55,7 +55,7 @@ public:
UnknownSourceError = 2,
NoError = 3
};
Q_ENUMS(Error)
Q_ENUM(Error)
enum AreaMonitorFeature {
PersistentAreaMonitorFeature = 0x00000001,
......
......@@ -54,7 +54,7 @@ public:
UnknownSourceError = 2,
NoError = 3
};
Q_ENUMS(Error)
Q_ENUM(Error)
enum PositioningMethod {
NoPositioningMethods = 0x00000000,
......
......@@ -54,7 +54,7 @@ public:
NoError = 2,
UnknownSourceError = -1
};
Q_ENUMS(Error)
Q_ENUM(Error)
explicit QGeoSatelliteInfoSource(QObject *parent);
virtual ~QGeoSatelliteInfoSource();
......
......@@ -48,7 +48,7 @@ class Q_POSITIONING_EXPORT QGeoShape
Q_PROPERTY(ShapeType type READ type)
Q_PROPERTY(bool isValid READ isValid)
Q_PROPERTY(bool isEmpty READ isEmpty)
Q_ENUMS(ShapeType)
Q_ENUM(ShapeType)
public:
QGeoShape();
......
......@@ -46,10 +46,10 @@ public:
TemperatureUnitsFarenheit,
};
Q_ENUMS(DistanceUnits)
Q_ENUMS(AreaUnits)
Q_ENUMS(SpeedUnits)
Q_ENUMS(TemperatureUnits)
Q_ENUM(DistanceUnits)
Q_ENUM(AreaUnits)
Q_ENUM(SpeedUnits)
Q_ENUM(TemperatureUnits)
Q_PROPERTY(Fact* distanceUnits READ distanceUnits CONSTANT)
Q_PROPERTY(Fact* areaUnits READ areaUnits CONSTANT)
......
......@@ -71,7 +71,7 @@ VideoSettings::VideoSettings(QObject* parent)
#endif
#ifndef QGC_DISABLE_UVC
QList<QCameraInfo> cameras = QCameraInfo::availableCameras();
foreach (const QCameraInfo &cameraInfo, cameras) {
for (const QCameraInfo &cameraInfo: cameras) {
videoSourceList.append(cameraInfo.description());
}
#endif
......@@ -82,7 +82,7 @@ VideoSettings::VideoSettings(QObject* parent)
videoSourceList.insert(0, videoDisabled);
}
QVariantList videoSourceVarList;
foreach (const QString& videoSource, videoSourceList) {
for (const QString& videoSource: videoSourceList) {
videoSourceVarList.append(QVariant::fromValue(videoSource));
}
_nameToMetaDataMap[videoSourceName]->setEnumInfo(videoSourceList, videoSourceVarList);
......
......@@ -46,7 +46,7 @@ void TerrainAirMapQuery::requestCoordinateHeights(const QList<QGeoCoordinate>& c
}
QString points;
foreach (const QGeoCoordinate& coord, coordinates) {
for (const QGeoCoordinate& coord: coordinates) {
points += QString::number(coord.latitude(), 'f', 10) + ","
+ QString::number(coord.longitude(), 'f', 10) + ",";
}
......@@ -236,7 +236,7 @@ void TerrainAirMapQuery::_parsePathData(const QJsonValue& pathJson)
double lonStep = stepArray[1].toDouble();
QList<double> heights;
foreach (const QJsonValue& profileValue, profileArray) {
for (const QJsonValue& profileValue: profileArray) {
heights.append(profileValue.toDouble());
}
......@@ -404,7 +404,7 @@ bool TerrainTileManager::_getAltitudesForCoordinates(const QList<QGeoCoordinate>
{
error = false;
foreach (const QGeoCoordinate& coordinate, coordinates) {
for (const QGeoCoordinate& coordinate: coordinates) {
QString tileHash = _getTileHash(coordinate);
qCDebug(TerrainQueryLog) << "TerrainTileManager::_getAltitudesForCoordinates hash:coordinate" << tileHash << coordinate;
......@@ -451,7 +451,7 @@ void TerrainTileManager::_tileFailed(void)
{
QList<double> noAltitudes;
foreach (const QueuedRequestInfo_t& requestInfo, _requestQueue) {
for (const QueuedRequestInfo_t& requestInfo: _requestQueue) {
if (requestInfo.queryMode == QueryMode::QueryModeCoordinates) {
requestInfo.terrainQueryInterface->_signalCoordinateHeights(false, noAltitudes);
} else if (requestInfo.queryMode == QueryMode::QueryModePath) {
......@@ -584,7 +584,7 @@ void TerrainAtCoordinateBatchManager::_sendNextBatch(void)
// Convert coordinates to point strings for json query
QList<QGeoCoordinate> coords;
int requestQueueAdded = 0;
foreach (const QueuedRequestInfo_t& requestInfo, _requestQueue) {
for (const QueuedRequestInfo_t& requestInfo: _requestQueue) {
SentRequestInfo_t sentRequestInfo = { requestInfo.terrainAtCoordinateQuery, false, requestInfo.coordinates.count() };
_sentRequests.append(sentRequestInfo);
coords += requestInfo.coordinates;
......@@ -604,7 +604,7 @@ void TerrainAtCoordinateBatchManager::_batchFailed(void)
{
QList<double> noHeights;
foreach (const SentRequestInfo_t& sentRequestInfo, _sentRequests) {
for (const SentRequestInfo_t& sentRequestInfo: _sentRequests) {
if (!sentRequestInfo.queryObjectDestroyed) {
disconnect(sentRequestInfo.terrainAtCoordinateQuery, &TerrainAtCoordinateQuery::destroyed, this, &TerrainAtCoordinateBatchManager::_queryObjectDestroyed);
sentRequestInfo.terrainAtCoordinateQuery->_signalTerrainData(false, noHeights);
......@@ -663,7 +663,7 @@ void TerrainAtCoordinateBatchManager::_coordinateHeights(bool success, QList<dou
}
int currentIndex = 0;
foreach (const SentRequestInfo_t& sentRequestInfo, _sentRequests) {
for (const SentRequestInfo_t& sentRequestInfo: _sentRequests) {
if (!sentRequestInfo.queryObjectDestroyed) {
qCDebug(TerrainQueryVerboseLog) << "TerrainAtCoordinateBatchManager::_coordinateHeights returned TerrainCoordinateQuery:count" << sentRequestInfo.terrainAtCoordinateQuery << sentRequestInfo.cCoord;
disconnect(sentRequestInfo.terrainAtCoordinateQuery, &TerrainAtCoordinateQuery::destroyed, this, &TerrainAtCoordinateBatchManager::_queryObjectDestroyed);
......@@ -730,7 +730,7 @@ void TerrainPolyPathQuery::requestData(const QVariantList& polyPath)
{
QList<QGeoCoordinate> path;
foreach (const QVariant& geoVar, polyPath) {
for (const QVariant& geoVar: polyPath) {
path.append(geoVar.value<QGeoCoordinate>());
}
......
......@@ -39,6 +39,7 @@
#include "QGCCameraManager.h"
#include "VideoReceiver.h"
#include "VideoManager.h"
#include "PositionManager.h"
#if defined(QGC_AIRMAP_ENABLED)
#include "AirspaceVehicleManager.h"
#endif
......@@ -69,6 +70,8 @@ const char* Vehicle::_altitudeAMSLFactName = "altitudeAMSL";
const char* Vehicle::_flightDistanceFactName = "flightDistance";
const char* Vehicle::_flightTimeFactName = "flightTime";
const char* Vehicle::_distanceToHomeFactName = "distanceToHome";
const char* Vehicle::_headingToHomeFactName = "headingToHome";
const char* Vehicle::_distanceToGCSFactName = "distanceToGCS";
const char* Vehicle::_hobbsFactName = "hobbs";
const char* Vehicle::_gpsFactGroupName = "gps";
......@@ -192,6 +195,8 @@ Vehicle::Vehicle(LinkInterface* link,
, _flightDistanceFact (0, _flightDistanceFactName, FactMetaData::valueTypeDouble)
, _flightTimeFact (0, _flightTimeFactName, FactMetaData::valueTypeElapsedTimeInSeconds)
, _distanceToHomeFact (0, _distanceToHomeFactName, FactMetaData::valueTypeDouble)
, _headingToHomeFact (0, _headingToHomeFactName, FactMetaData::valueTypeDouble)
, _distanceToGCSFact (0, _distanceToGCSFactName, FactMetaData::valueTypeDouble)
, _hobbsFact (0, _hobbsFactName, FactMetaData::valueTypeString)
, _gpsFactGroup(this)
, _battery1FactGroup(this)
......@@ -385,6 +390,8 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
, _flightDistanceFact (0, _flightDistanceFactName, FactMetaData::valueTypeDouble)
, _flightTimeFact (0, _flightTimeFactName, FactMetaData::valueTypeElapsedTimeInSeconds)
, _distanceToHomeFact (0, _distanceToHomeFactName, FactMetaData::valueTypeDouble)
, _headingToHomeFact (0, _headingToHomeFactName, FactMetaData::valueTypeDouble)
, _distanceToGCSFact (0, _distanceToGCSFactName, FactMetaData::valueTypeDouble)
, _hobbsFact (0, _hobbsFactName, FactMetaData::valueTypeString)
, _gpsFactGroup(this)
, _battery1FactGroup(this)
......@@ -404,10 +411,13 @@ void Vehicle::_commonInit(void)
connect(_firmwarePlugin, &FirmwarePlugin::toolbarIndicatorsChanged, this, &Vehicle::toolBarIndicatorsChanged);
connect(this, &Vehicle::coordinateChanged, this, &Vehicle::_updateDistanceToHome);
connect(this, &Vehicle::homePositionChanged, this, &Vehicle::_updateDistanceToHome);
connect(this, &Vehicle::coordinateChanged, this, &Vehicle::_updateDistanceHeadingToHome);
connect(this, &Vehicle::coordinateChanged, this, &Vehicle::_updateDistanceToGCS);
connect(this, &Vehicle::homePositionChanged, this, &Vehicle::_updateDistanceHeadingToHome);
connect(this, &Vehicle::hobbsMeterChanged, this, &Vehicle::_updateHobbsMeter);
connect(_toolbox->qgcPositionManager(), &QGCPositionManager::gcsPositionChanged, this, &Vehicle::_updateDistanceToGCS);
_missionManager = new MissionManager(this);
connect(_missionManager, &MissionManager::error, this, &Vehicle::_missionManagerError);
connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_missionLoadComplete);
......@@ -453,6 +463,8 @@ void Vehicle::_commonInit(void)
_addFact(&_flightDistanceFact, _flightDistanceFactName);
_addFact(&_flightTimeFact, _flightTimeFactName);
_addFact(&_distanceToHomeFact, _distanceToHomeFactName);
_addFact(&_headingToHomeFact, _headingToHomeFactName);
_addFact(&_distanceToGCSFact, _distanceToGCSFactName);
_hobbsFact.setRawValue(QVariant(QString("0000:00:00")));
_addFact(&_hobbsFact, _hobbsFactName);
......@@ -2004,7 +2016,7 @@ bool Vehicle::xConfigMotors(void)
QString Vehicle::formatedMessages()
{
QString messages;
foreach(UASMessage* message, _toolbox->uasMessageHandler()->messages()) {
for(UASMessage* message: _toolbox->uasMessageHandler()->messages()) {
messages += message->getFormatedText();
}
return messages;
......@@ -2281,7 +2293,7 @@ QString Vehicle::priorityLinkName(void) const
QVariantList Vehicle::links(void) const {
QVariantList ret;
foreach( const auto &item, _links )
for( const auto &item: _links )
ret << QVariant::fromValue(item);
return ret;
......@@ -3589,12 +3601,28 @@ void Vehicle::_handleADSBVehicle(const mavlink_message_t& message)
}
}
void Vehicle::_updateDistanceToHome(void)
void Vehicle::_updateDistanceHeadingToHome(void)
{
if (coordinate().isValid() && homePosition().isValid()) {
_distanceToHomeFact.setRawValue(coordinate().distanceTo(homePosition()));
if (_distanceToHomeFact.rawValue().toDouble() > 1.0) {
_headingToHomeFact.setRawValue(coordinate().azimuthTo(homePosition()));
} else {
_headingToHomeFact.setRawValue(qQNaN());
}
} else {
_distanceToHomeFact.setRawValue(qQNaN());
_headingToHomeFact.setRawValue(qQNaN());
}
}
void Vehicle::_updateDistanceToGCS(void)
{
QGeoCoordinate gcsPosition = _toolbox->qgcPositionManager()->gcsPosition();
if (coordinate().isValid() && gcsPosition.isValid()) {
_distanceToGCSFact.setRawValue(coordinate().distanceTo(gcsPosition));
} else {
_distanceToGCSFact.setRawValue(qQNaN());
}
}
......
......@@ -656,6 +656,8 @@ public:
Q_PROPERTY(Fact* altitudeAMSL READ altitudeAMSL CONSTANT)
Q_PROPERTY(Fact* flightDistance READ flightDistance CONSTANT)
Q_PROPERTY(Fact* distanceToHome READ distanceToHome CONSTANT)
Q_PROPERTY(Fact* headingToHome READ headingToHome CONSTANT)
Q_PROPERTY(Fact* distanceToGCS READ distanceToGCS CONSTANT)
Q_PROPERTY(Fact* hobbs READ hobbs CONSTANT)
Q_PROPERTY(FactGroup* gps READ gpsFactGroup CONSTANT)
......@@ -945,6 +947,8 @@ public:
Fact* altitudeAMSL (void) { return &_altitudeAMSLFact; }
Fact* flightDistance (void) { return &_flightDistanceFact; }
Fact* distanceToHome (void) { return &_distanceToHomeFact; }
Fact* headingToHome (void) { return &_headingToHomeFact; }
Fact* distanceToGCS (void) { return &_distanceToGCSFact; }
Fact* hobbs (void) { return &_hobbsFact; }
FactGroup* gpsFactGroup (void) { return &_gpsFactGroup; }
......@@ -1189,7 +1193,8 @@ private slots:
void _sendMavCommandAgain(void);
void _clearTrajectoryPoints(void);
void _clearCameraTriggerPoints(void);
void _updateDistanceToHome(void);
void _updateDistanceHeadingToHome(void);
void _updateDistanceToGCS(void);
void _updateHobbsMeter(void);
void _vehicleParamLoaded(bool ready);
void _sendQGCTimeToVehicle(void);
......@@ -1453,6 +1458,8 @@ private:
Fact _flightDistanceFact;
Fact _flightTimeFact;
Fact _distanceToHomeFact;
Fact _headingToHomeFact;
Fact _distanceToGCSFact;
Fact _hobbsFact;
VehicleGPSFactGroup _gpsFactGroup;
......@@ -1480,6 +1487,8 @@ private:
static const char* _flightDistanceFactName;
static const char* _flightTimeFactName;
static const char* _distanceToHomeFactName;
static const char* _headingToHomeFactName;
static const char* _distanceToGCSFactName;
static const char* _hobbsFactName;
static const char* _gpsFactGroupName;
......
......@@ -90,6 +90,20 @@
"decimalPlaces": 1,
"units": "m"
},
{
"name": "headingToHome",
"shortDescription": "Heading to Home",
"type": "double",
"decimalPlaces": 0,
"units": "deg"
},
{
"name": "distanceToGCS",
"shortDescription": "Distance to GCS",
"type": "double",
"decimalPlaces": 1,
"units": "m"
},
{
"name": "flightTime",
"shortDescription": "Flight Time",
......
......@@ -184,7 +184,7 @@ bool Bootloader::_binProgram(QSerialPort* port, const FirmwareImage* image)
{
QFile firmwareFile(image->binFilename());
if (!firmwareFile.open(QIODevice::ReadOnly)) {
_errorString = tr("Unable to open firmware file %1: %2").arg(image->binFilename()).arg(firmwareFile.errorString());
_errorString = tr("Unable to open firmware file %1: %2").arg(image->binFilename(), firmwareFile.errorString());
return false;
}
uint32_t imageSize = (uint32_t)firmwareFile.size();
......@@ -354,7 +354,7 @@ bool Bootloader::_binVerifyBytes(QSerialPort* port, const FirmwareImage* image)
QFile firmwareFile(image->binFilename());
if (!firmwareFile.open(QIODevice::ReadOnly)) {
_errorString = tr("Unable to open firmware file %1: %2").arg(image->binFilename()).arg(firmwareFile.errorString());
_errorString = tr("Unable to open firmware file %1: %2").arg(image->binFilename(), firmwareFile.errorString());
return false;
}
uint32_t imageSize = (uint32_t)firmwareFile.size();
......@@ -545,7 +545,7 @@ bool Bootloader::open(QSerialPort* port, const QString portName)
port->setFlowControl(QSerialPort::NoFlowControl);
if (!port->open(QIODevice::ReadWrite)) {
_errorString = tr("Open failed on port %1: %2").arg(portName).arg(port->errorString());
_errorString = tr("Open failed on port %1: %2").arg(portName, port->errorString());
return false;
}
......
......@@ -122,7 +122,7 @@ bool FirmwareImage::_ihxLoad(const QString& ihxFilename)
QFile ihxFile(ihxFilename);
if (!ihxFile.open(QIODevice::ReadOnly | QIODevice::Text)) {
emit statusMessage(QString("Unable to open firmware file %1, error: %2").arg(ihxFilename).arg(ihxFile.errorString()));
emit statusMessage(QString("Unable to open firmware file %1, error: %2").arg(ihxFilename, ihxFile.errorString()));
return false;
}
......@@ -223,7 +223,7 @@ bool FirmwareImage::_px4Load(const QString& imageFilename)
QFile px4File(imageFilename);
if (!px4File.open(QIODevice::ReadOnly | QIODevice::Text)) {
emit statusMessage(tr("Unable to open firmware file %1, error: %2").arg(imageFilename).arg(px4File.errorString()));
emit statusMessage(tr("Unable to open firmware file %1, error: %2").arg(imageFilename, px4File.errorString()));
return false;
}
......@@ -292,7 +292,7 @@ bool FirmwareImage::_px4Load(const QString& imageFilename)
parameterFile.close();
}
} else {
emit statusMessage(tr("Unable to open parameter meta data file %1 for writing, error: %2").arg(parameterFilename).arg(parameterFile.errorString()));
emit statusMessage(tr("Unable to open parameter meta data file %1 for writing, error: %2").arg(parameterFilename, parameterFile.errorString()));
}
// Cache this file with the system
......@@ -324,7 +324,7 @@ bool FirmwareImage::_px4Load(const QString& imageFilename)
airframeFile.close();
}
} else {
emit statusMessage(tr("Unable to open airframe meta data file %1 for writing, error: %2").arg(airframeFilename).arg(airframeFile.errorString()));
emit statusMessage(tr("Unable to open airframe meta data file %1 for writing, error: %2").arg(airframeFilename, airframeFile.errorString()));
}
}
......@@ -350,7 +350,7 @@ bool FirmwareImage::_px4Load(const QString& imageFilename)
QFile decompressFile(decompressFilename);
if (!decompressFile.open(QIODevice::WriteOnly | QIODevice::Truncate)) {
emit statusMessage(tr("Unable to open decompressed file %1 for writing, error: %2").arg(decompressFilename).arg(decompressFile.errorString()));
emit statusMessage(tr("Unable to open decompressed file %1 for writing, error: %2").arg(decompressFilename, decompressFile.errorString()));
return false;
}
......@@ -449,7 +449,7 @@ bool FirmwareImage::_binLoad(const QString& imageFilename)
{
QFile binFile(imageFilename);
if (!binFile.open(QIODevice::ReadOnly)) {
emit statusMessage(tr("Unabled to open firmware file %1, %2").arg(imageFilename).arg(binFile.errorString()));
emit statusMessage(tr("Unabled to open firmware file %1, %2").arg(imageFilename, binFile.errorString()));
return false;
}
......
......@@ -354,7 +354,7 @@ void FirmwareUpgradeController::_initFirmwareHash()
#endif
// PX4 Firmwares
foreach (const FirmwareType_t& firmwareType, px4MapFirmwareTypeToDir.keys()) {
for (const FirmwareType_t& firmwareType: px4MapFirmwareTypeToDir.keys()) {
QString dir = px4MapFirmwareTypeToDir[firmwareType];
_rgPX4FMUV5Firmware.insert (FirmwareIdentifier(AutoPilotStackPX4, firmwareType, DefaultVehicleFirmware), px4Url.arg(dir).arg("v5"));
_rgPX4FMUV4PROFirmware.insert (FirmwareIdentifier(AutoPilotStackPX4, firmwareType, DefaultVehicleFirmware), px4Url.arg(dir).arg("v4pro"));
......@@ -365,9 +365,9 @@ void FirmwareUpgradeController::_initFirmwareHash()
#if !defined(NO_ARDUPILOT_DIALECT)
// ArduPilot Firmwares
foreach (const FirmwareType_t& firmwareType, apmMapFirmwareTypeToDir.keys()) {
for (const FirmwareType_t& firmwareType: apmMapFirmwareTypeToDir.keys()) {
QString firmwareTypeDir = apmMapFirmwareTypeToDir[firmwareType];
foreach (const FirmwareVehicleType_t& vehicleType, apmMapVehicleTypeToDir.keys()) {
for (const FirmwareVehicleType_t& vehicleType: apmMapVehicleTypeToDir.keys()) {
QString vehicleTypeDir = apmMapVehicleTypeToDir[vehicleType];
QString px4Dir = apmMapVehicleTypeToPX4Dir[vehicleType];
QString filename = apmMapVehicleTypeToFilename[vehicleType];
......@@ -382,9 +382,9 @@ void FirmwareUpgradeController::_initFirmwareHash()
#if !defined(NO_ARDUPILOT_DIALECT)
// ArduPilot ChibiOS Firmwares
foreach (const FirmwareType_t& firmwareType, apmMapFirmwareTypeToDir.keys()) {
for (const FirmwareType_t& firmwareType: apmMapFirmwareTypeToDir.keys()) {
QString firmwareTypeDir = apmMapFirmwareTypeToDir[firmwareType];
foreach (const FirmwareVehicleType_t& vehicleType, apmChibiOSMapVehicleTypeToDir.keys()) {
for (const FirmwareVehicleType_t& vehicleType: apmChibiOSMapVehicleTypeToDir.keys()) {
QString vehicleTypeDir = apmChibiOSMapVehicleTypeToDir[vehicleType];
QString fmuDir = apmChibiOSMapVehicleTypeToFmuDir[vehicleType];
QString filename = apmChibiOSMapVehicleTypeToFilename[vehicleType];
......@@ -692,7 +692,7 @@ void FirmwareUpgradeController::_loadAPMVersions(uint32_t bootloaderBoardID)
QHash<FirmwareIdentifier, QString>* prgFirmware = _firmwareHashForBoardId(static_cast<int>(bootloaderBoardID));
foreach (FirmwareIdentifier firmwareId, prgFirmware->keys()) {
for (FirmwareIdentifier firmwareId: prgFirmware->keys()) {
if (firmwareId.autopilotStackType == AutoPilotStackAPM) {
QString versionFile = QFileInfo(prgFirmware->value(firmwareId)).path() + "/git-version.txt";
......@@ -733,7 +733,7 @@ void FirmwareUpgradeController::_apmVersionDownloadFinished(QString remoteFile,
QHash<FirmwareIdentifier, QString>* prgFirmware = _firmwareHashForBoardId(static_cast<int>(_bootloaderBoardID));
QString remotePath = QFileInfo(remoteFile).path();
foreach (FirmwareIdentifier firmwareId, prgFirmware->keys()) {
for (FirmwareIdentifier firmwareId: prgFirmware->keys()) {
if (remotePath == QFileInfo((*prgFirmware)[firmwareId]).path()) {
qCDebug(FirmwareUpgradeLog) << "Adding version to map, version:firwmareType:vehicleType" << version << firmwareId.firmwareType << firmwareId.firmwareVehicleType;
_apmVersionMap[firmwareId.firmwareType][firmwareId.firmwareVehicleType] = version;
......@@ -761,7 +761,7 @@ QStringList FirmwareUpgradeController::apmAvailableVersions(void)
_apmVehicleTypeFromCurrentVersionList.clear();
foreach (FirmwareVehicleType_t vehicleType, vehicleTypes) {
for (FirmwareVehicleType_t vehicleType: vehicleTypes) {
if (_apmVersionMap[_selectedFirmwareType].contains(vehicleType)) {
QString version;
......
......@@ -67,9 +67,9 @@ public:
DefaultVehicleFirmware
} FirmwareVehicleType_t;
Q_ENUMS(AutoPilotStackType_t)
Q_ENUMS(FirmwareType_t)
Q_ENUMS(FirmwareVehicleType_t)
Q_ENUM(AutoPilotStackType_t)
Q_ENUM(FirmwareType_t)
Q_ENUM(FirmwareVehicleType_t)
class FirmwareIdentifier
{
......
......@@ -119,7 +119,7 @@ void PX4FirmwareUpgradeThreadWorker::_findBoardOnce(void)
bool PX4FirmwareUpgradeThreadWorker::_findBoardFromPorts(QGCSerialPortInfo& portInfo, QGCSerialPortInfo::BoardType_t& boardType, QString& boardName)
{
foreach (QGCSerialPortInfo info, QGCSerialPortInfo::availablePorts()) {
for (QGCSerialPortInfo info: QGCSerialPortInfo::availablePorts()) {
info.getBoardInfo(boardType, boardName);
qCDebug(FirmwareUpgradeVerboseLog) << "Serial Port --------------";
......
......@@ -54,7 +54,7 @@ void VehicleComponent::addSummaryQmlComponent(QQmlContext* context, QQuickItem*
void VehicleComponent::setupTriggerSignals(void)
{
// Watch for changed on trigger list params
foreach (const QString &paramName, setupCompleteChangedTriggerList()) {
for (const QString &paramName: setupCompleteChangedTriggerList()) {
if (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, paramName)) {
Fact* fact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, paramName);
connect(fact, &Fact::valueChanged, this, &VehicleComponent::_triggerUpdated);
......
......@@ -146,7 +146,7 @@ public:
POS_CENTER_LEFT,
POS_BOTTOM_LEFT
};
Q_ENUMS(Pos)
Q_ENUM(Pos)
CustomInstrumentWidget(QObject* parent = NULL);
Q_PROPERTY(QUrl source READ source CONSTANT)
Q_PROPERTY(Pos widgetPosition READ widgetPosition NOTIFY widgetPositionChanged)
......
......@@ -340,7 +340,7 @@ void BluetoothConfiguration::deviceDiscovered(QBluetoothDeviceInfo info)
qDebug() << "Address: " << info.address().toString();
qDebug() << "Service Classes:" << info.serviceClasses();
QList<QBluetoothUuid> uuids = info.serviceUuids();
foreach (QBluetoothUuid uuid, uuids) {
for (QBluetoothUuid uuid: uuids) {
qDebug() << "Service UUID: " << uuid.toString();
}
#endif
......@@ -373,7 +373,7 @@ void BluetoothConfiguration::doneScanning()
void BluetoothConfiguration::setDevName(const QString &name)
{
foreach(const BluetoothData& data, _deviceList)
for(const BluetoothData& data: _deviceList)
{
if(data.name == name)
{
......@@ -390,7 +390,7 @@ void BluetoothConfiguration::setDevName(const QString &name)
QString BluetoothConfiguration::address()
{
#ifdef __ios__
return QString("");
return {};
#else
return _device.address;
#endif
......
......@@ -19,7 +19,6 @@ class LinkInterface;
class LinkConfiguration : public QObject
{
Q_OBJECT
Q_ENUMS(LinkType)
public:
LinkConfiguration(const QString& name);
......@@ -63,6 +62,7 @@ public:
#endif
TypeLast // Last type value (type >= TypeLast == invalid)
};
Q_ENUM(LinkType)
/*!
*
......
......@@ -497,7 +497,7 @@ void LinkManager::_updateAutoConnectLinks(void)
#endif
// Iterate Comm Ports
foreach (QGCSerialPortInfo portInfo, portList) {
for (QGCSerialPortInfo portInfo: portList) {
qCDebug(LinkManagerVerboseLog) << "-----------------------------------------------------";
qCDebug(LinkManagerVerboseLog) << "portName: " << portInfo.portName();
qCDebug(LinkManagerVerboseLog) << "systemLocation: " << portInfo.systemLocation();
......@@ -638,7 +638,7 @@ void LinkManager::_updateAutoConnectLinks(void)
}
// Now remove all configs that are gone
foreach (LinkConfiguration* pDeleteConfig, _confToDelete) {
for (LinkConfiguration* pDeleteConfig: _confToDelete) {
qCDebug(LinkManagerLog) << "Removing unused autoconnect config" << pDeleteConfig->name();
if (pDeleteConfig->link()) {
disconnectLink(pDeleteConfig->link());
......@@ -703,7 +703,7 @@ void LinkManager::_updateSerialPorts()
_commPortDisplayList.clear();
#ifndef NO_SERIAL_LINK
QList<QSerialPortInfo> portList = QSerialPortInfo::availablePorts();
foreach (const QSerialPortInfo &info, portList)
for (const QSerialPortInfo &info: portList)
{
QString port = info.systemLocation().trimmed();
_commPortList += port;
......
......@@ -453,7 +453,7 @@ void MAVLinkProtocol::checkForLostLogFiles(void)
QFileInfoList fileInfoList = tempDir.entryInfoList(QStringList(filter), QDir::Files);
//qDebug() << "Orphaned log file count" << fileInfoList.count();
foreach(const QFileInfo fileInfo, fileInfoList) {
for(const QFileInfo fileInfo: fileInfoList) {
//qDebug() << "Orphaned log file" << fileInfo.filePath();
if (fileInfo.size() == 0) {
// Delete all zero length files
......@@ -476,7 +476,7 @@ void MAVLinkProtocol::deleteTempLogFiles(void)
QString filter(QString("*.%1").arg(_logFileExtension));
QFileInfoList fileInfoList = tempDir.entryInfoList(QStringList(filter), QDir::Files);
foreach(const QFileInfo fileInfo, fileInfoList) {
for(const QFileInfo fileInfo: fileInfoList) {
QFile::remove(fileInfo.filePath());
}
}
......
......@@ -156,7 +156,7 @@ void MockLinkMissionItemHandler::_handleMissionRequestList(const mavlink_message
mavlink_message_t responseMsg;
mavlink_msg_mission_count_pack_chan(_mockLink->vehicleId(),
MAV_COMP_ID_MISSIONPLANNER,
MAV_COMP_ID_AUTOPILOT1,
_mockLink->mavlinkChannel(),
&responseMsg, // Outgoing message
msg.sysid, // Target is original sender
......@@ -224,7 +224,7 @@ void MockLinkMissionItemHandler::_handleMissionRequest(const mavlink_message_t&
}
mavlink_msg_mission_item_pack_chan(_mockLink->vehicleId(),
MAV_COMP_ID_MISSIONPLANNER,
MAV_COMP_ID_AUTOPILOT1,
_mockLink->mavlinkChannel(),
&responseMsg, // Outgoing message
msg.sysid, // Target is original sender
......@@ -310,7 +310,7 @@ void MockLinkMissionItemHandler::_requestNextMissionItem(int sequenceNumber)
mavlink_message_t message;
mavlink_msg_mission_request_pack_chan(_mockLink->vehicleId(),
MAV_COMP_ID_MISSIONPLANNER,
MAV_COMP_ID_AUTOPILOT1,
_mockLink->mavlinkChannel(),
&message,
_mavlinkProtocol->getSystemId(),
......@@ -332,7 +332,7 @@ void MockLinkMissionItemHandler::_sendAck(MAV_MISSION_RESULT ackType)
mavlink_message_t message;
mavlink_msg_mission_ack_pack_chan(_mockLink->vehicleId(),
MAV_COMP_ID_MISSIONPLANNER,
MAV_COMP_ID_AUTOPILOT1,
_mockLink->mavlinkChannel(),
&message,
_mavlinkProtocol->getSystemId(),
......
......@@ -956,7 +956,7 @@ void QGCFlightGearLink::_printFgfsOutput(void)
QByteArray byteArray = _fgProcess->readAllStandardOutput();
QStringList strLines = QString(byteArray).split("\n");
foreach (const QString &line, strLines){
for (const QString &line: strLines){
qDebug() << line;
}
}
......@@ -968,7 +968,7 @@ void QGCFlightGearLink::_printFgfsError(void)
QByteArray byteArray = _fgProcess->readAllStandardError();
QStringList strLines = QString(byteArray).split("\n");
foreach (const QString &line, strLines){
for (const QString &line: strLines){
qDebug() << line;
}
}
......
......@@ -123,11 +123,11 @@ void QGCJSBSimLink::run()
if (_vehicle->vehicleType() == MAV_TYPE_QUADROTOR)
{
arguments << QString("--realtime --suspend --nice --simulation-rate=1000 --logdirectivefile=%s/flightgear.xml --script=%s/%s").arg(rootJSB).arg(rootJSB).arg(script);
arguments << QString("--realtime --suspend --nice --simulation-rate=1000 --logdirectivefile=%s/flightgear.xml --script=%s/%s").arg(rootJSB, rootJSB, script);
}
else
{
arguments << QString("JSBSim --realtime --suspend --nice --simulation-rate=1000 --logdirectivefile=%s/flightgear.xml --script=%s/%s").arg(rootJSB).arg(rootJSB).arg(script);
arguments << QString("JSBSim --realtime --suspend --nice --simulation-rate=1000 --logdirectivefile=%s/flightgear.xml --script=%s/%s").arg(rootJSB, rootJSB, script);
}
process->start(processJSB, arguments);
......@@ -285,23 +285,20 @@ void QGCJSBSimLink::readBytes()
if (s > maxLength) std::cerr << __FILE__ << __LINE__ << " UDP datagram overflow, allowed to read less bytes than datagram size" << std::endl;
socket->readDatagram(data, maxLength, &sender, &senderPort);
QByteArray b(data, s);
/*
// Print string
// QString state(b);
// // Parse string
// float roll, pitch, yaw, rollspeed, pitchspeed, yawspeed;
// double lat, lon, alt;
// double vx, vy, vz, xacc, yacc, zacc;
// // Send updated state
// emit hilStateChanged(QGC::groundTimeUsecs(), roll, pitch, yaw, rollspeed,
// pitchspeed, yawspeed, lat, lon, alt,
// vx, vy, vz, xacc, yacc, zacc);
QByteArray b(data, s);
QString state(b);
// Parse string
float roll, pitch, yaw, rollspeed, pitchspeed, yawspeed;
double lat, lon, alt;
double vx, vy, vz, xacc, yacc, zacc;
// Send updated state
emit hilStateChanged(QGC::groundTimeUsecs(), roll, pitch, yaw, rollspeed,
pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc);
*/
// Echo data for debugging purposes
std::cerr << __FILE__ << __LINE__ << "Received datagram:" << std::endl;
......
......@@ -252,7 +252,7 @@ QList<QGCSerialPortInfo> QGCSerialPortInfo::availablePorts(void)
{
QList<QGCSerialPortInfo> list;
foreach(QSerialPortInfo portInfo, QSerialPortInfo::availablePorts()) {
for(QSerialPortInfo portInfo: QSerialPortInfo::availablePorts()) {
if (!isSystemPort(&portInfo)) {
list << *((QGCSerialPortInfo*)&portInfo);
}
......
......@@ -65,7 +65,7 @@ bool SerialLink::_isBootloader()
if( portList.count() == 0){
return false;
}
foreach (const QSerialPortInfo &info, portList)
for (const QSerialPortInfo &info: portList)
{
qCDebug(SerialLinkLog) << "PortName : " << info.portName() << "Description : " << info.description();
qCDebug(SerialLinkLog) << "Manufacturer: " << info.manufacturer();
......
......@@ -253,7 +253,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
......@@ -263,7 +262,7 @@ static QString get_ip_address(const QString& address)
}
}
}
return QString("");
return {};
}
TCPConfiguration::TCPConfiguration(const QString& name) : LinkConfiguration(name)
......
......@@ -65,12 +65,12 @@ static QString get_ip_address(const QString& address)
}
}
}
return QString("");
return {};
}
static bool contains_target(const QList<UDPCLient*> list, const QHostAddress& address, quint16 port)
{
foreach(UDPCLient* target, list) {
for(UDPCLient* target: list) {
if(target->address == address && target->port == port) {
return true;
}
......@@ -91,7 +91,7 @@ UDPLink::UDPLink(SharedLinkConfigurationPointer& config)
if (!_udpConfig) {
qWarning() << "Internal error";
}
foreach (const QHostAddress &address, QNetworkInterface::allAddresses()) {
for (const QHostAddress &address: QNetworkInterface::allAddresses()) {
_localAddress.append(QHostAddress(address));
}
moveToThread(this);
......@@ -156,7 +156,7 @@ bool UDPLink::_isIpLocal(const QHostAddress& add)
// On Windows, this is a very expensive call only Redmond would know
// why. As such, we make it once and keep the list locally. If a new
// interface shows up after we start, it won't be on this list.
foreach (const QHostAddress &address, _localAddress) {
for (const QHostAddress &address: _localAddress) {
if (address == add) {
// This is a local address of the same host
return true;
......@@ -171,14 +171,14 @@ void UDPLink::_writeBytes(const QByteArray data)
return;
}
// Send to all manually targeted systems
foreach(UDPCLient* target, _udpConfig->targetHosts()) {
for(UDPCLient* target: _udpConfig->targetHosts()) {
// Skip it if it's part of the session clients below
if(!contains_target(_sessionTargets, target->address, target->port)) {
_writeDataGram(data, target);
}
}
// Send to all connected systems
foreach(UDPCLient* target, _sessionTargets) {
for(UDPCLient* target: _sessionTargets) {
_writeDataGram(data, target);
}
}
......@@ -401,7 +401,7 @@ void UDPConfiguration::_copyFrom(LinkConfiguration *source)
if (usource) {
_localPort = usource->localPort();
_clearTargetHosts();
foreach(UDPCLient* target, usource->targetHosts()) {
for(UDPCLient* target: usource->targetHosts()) {
if(!contains_target(_targetHosts, target->address, target->port)) {
UDPCLient* newTarget = new UDPCLient(target);
_targetHosts.append(newTarget);
......
......@@ -38,7 +38,7 @@ void MavlinkLogTest::init(void)
// Make sure temp directory is clear of mavlink logs
QDir tmpDir(QStandardPaths::writableLocation(QStandardPaths::TempLocation));
QStringList logFiles(tmpDir.entryList(QStringList(QString("*.%1").arg(_logFileExtension)), QDir::Files));
foreach(const QString &logFile, logFiles) {
for(const QString &logFile: logFiles) {
bool success = tmpDir.remove(logFile);
Q_UNUSED(success);
Q_ASSERT(success);
......
......@@ -207,7 +207,7 @@ void RadioConfigTest::_init(MAV_AUTOPILOT firmwareType)
// Find the radio component
QObject* vehicleComponent = NULL;
foreach (const QVariant& varVehicleComponent, _autopilot->vehicleComponents()) {
for (const QVariant& varVehicleComponent: _autopilot->vehicleComponents()) {
if (firmwareType == MAV_AUTOPILOT_PX4) {
PX4RadioComponent* radioComponent = qobject_cast<PX4RadioComponent*>(varVehicleComponent.value<VehicleComponent*>());
if (radioComponent) {
......@@ -370,7 +370,7 @@ void RadioConfigTest::_fullCalibrationWorker(MAV_AUTOPILOT firmwareType)
QStringList switchList;
switchList << "RC_MAP_MODE_SW" << "RC_MAP_LOITER_SW" << "RC_MAP_RETURN_SW" << "RC_MAP_POSCTL_SW" << "RC_MAP_ACRO_SW";
foreach (const QString &switchParam, switchList) {
for (const QString &switchParam: switchList) {
Q_ASSERT(_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, switchParam)->rawValue().toInt() != channel + 1);
}
}
......
......@@ -81,7 +81,7 @@ int UnitTest::run(QString& singleTest)
{
int ret = 0;
foreach (QObject* test, _testList()) {
for (QObject* test: _testList()) {
if (singleTest.isEmpty() || singleTest == test->objectName()) {
QStringList args;
args << "*" << "-maxwarnings" << "0";
......
......@@ -181,9 +181,6 @@ void UAS::receiveMessage(mavlink_message_t message)
// and we already got one attitude packet
if (message.sysid == uasId && (!attitudeStamped || lastAttitude != 0 || message.msgid == MAVLINK_MSG_ID_ATTITUDE))
{
QString uasState;
QString stateDescription;
bool multiComponentSourceDetected = false;
bool wrongComponent = false;
......
......@@ -236,7 +236,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
char buf[11];
strncpy(buf, debug.name, 10);
buf[10] = '\0';
name = QString("%1.%2").arg(buf).arg(fieldName);
name = QString("%1.%2").arg(buf, fieldName);
time = getUnixTimeFromMs(msg->sysid, (debug.time_usec+500)/1000); // Scale to milliseconds, round up/down correctly
}
else if (msgid == MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY)
......@@ -246,7 +246,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
char buf[11];
strncpy(buf, debug.name, 10);
buf[10] = '\0';
name = QString("%1.%2").arg(buf).arg(fieldName);
name = QString("%1.%2").arg(buf, fieldName);
time = getUnixTimeFromMs(msg->sysid, (debug.time_usec+500)/1000); // Scale to milliseconds, round up/down correctly
}
else if (msgid == MAVLINK_MSG_ID_DEBUG)
......@@ -281,7 +281,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
// XXX this is really ugly, but we do not know a better way to do this
mavlink_rc_channels_raw_t raw;
mavlink_msg_rc_channels_raw_decode(msg, &raw);
name = name.arg(msgInfo->name).arg(fieldName);
name = name.arg(msgInfo->name, fieldName);
name.prepend(QString("port%1_").arg(raw.port));
}
else if (msgid == MAVLINK_MSG_ID_RC_CHANNELS_SCALED)
......@@ -289,7 +289,7 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
// XXX this is really ugly, but we do not know a better way to do this
mavlink_rc_channels_scaled_t scaled;
mavlink_msg_rc_channels_scaled_decode(msg, &scaled);
name = name.arg(msgInfo->name).arg(fieldName);
name = name.arg(msgInfo->name, fieldName);
name.prepend(QString("port%1_").arg(scaled.port));
}
else if (msgid == MAVLINK_MSG_ID_SERVO_OUTPUT_RAW)
......@@ -297,12 +297,12 @@ void MAVLinkDecoder::emitFieldValue(mavlink_message_t* msg, int fieldid, quint64
// XXX this is really ugly, but we do not know a better way to do this
mavlink_servo_output_raw_t servo;
mavlink_msg_servo_output_raw_decode(msg, &servo);
name = name.arg(msgInfo->name).arg(fieldName);
name = name.arg(msgInfo->name, fieldName);
name.prepend(QString("port%1_").arg(servo.port));
}
else
{
name = name.arg(msgInfo->name).arg(fieldName);
name = name.arg(msgInfo->name, fieldName);
}
if (multiComponentSourceDetected)
......
......@@ -347,7 +347,7 @@ bool MainWindow::_createInnerDockWidget(const QString& widgetName)
void MainWindow::_hideAllDockWidgets(void)
{
foreach(QGCDockWidget* dockWidget, _mapName2DockWidget) {
for(QGCDockWidget* dockWidget: _mapName2DockWidget) {
dockWidget->setVisible(false);
}
}
......@@ -448,7 +448,7 @@ void MainWindow::_vehicleAdded(Vehicle* vehicle)
void MainWindow::_storeCurrentViewState(void)
{
#ifndef __mobile__
foreach(QGCDockWidget* dockWidget, _mapName2DockWidget) {
for(QGCDockWidget* dockWidget: _mapName2DockWidget) {
dockWidget->saveSettings();
}
#endif
......@@ -482,7 +482,7 @@ void MainWindow::_loadVisibleWidgetsSettings(void)
if (!widgets.isEmpty()) {
QStringList nameList = widgets.split(",");
foreach (const QString &name, nameList) {
for (const QString &name: nameList) {
_showDockWidget(name, true);
}
}
......@@ -493,7 +493,7 @@ void MainWindow::_storeVisibleWidgetsSettings(void)
QString widgetNames;
bool firstWidget = true;
foreach (const QString &name, _mapName2DockWidget.keys()) {
for (const QString &name: _mapName2DockWidget.keys()) {
if (_mapName2DockWidget[name]->isVisible()) {
if (!firstWidget) {
widgetNames += ",";
......
......@@ -164,7 +164,7 @@ Item {
onYes: activeConnectionsCloseDialog.check()
function check() {
if (planViewLoader.item && planViewLoader.item.syncNeeded) {
if (planViewLoader.item && planViewLoader.item.dirty) {
unsavedMissionCloseDialog.open()
} else {
activeConnectionsCloseDialog.check()
......
......@@ -83,7 +83,7 @@ void QGCMAVLinkInspector::rebuildComponentList()
{
UASInterface* uas = vehicle->uas();
QMap<int, QString> components = uas->getComponents();
foreach (int id, components.keys())
for (int id: components.keys())
{
QString name = components.value(id);
ui->componentComboBox->addItem(name, id);
......
......@@ -227,9 +227,6 @@ Again:
}
if (childItem) {
// Process this item
QString text = childItem->text(0);
// Move to the next item for processing at this level
_walkIndexStack.last() = ++walkIndex;
......
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