Commit a9c57c55 authored by Tomaz Canabrava's avatar Tomaz Canabrava

use QStringLiteral for QString creation of constants and QLatin1Literal for comparisson

Strings can be expensive to create, all the issues with allocation,
copy of the char members, conversion to UTF-16. QStringLiteral creates
one in compile time.
Signed-off-by: 's avatarTomaz Canabrava <tomaz.canabrava@intel.com>
parent 01f6ea7c
...@@ -54,7 +54,7 @@ QString APMAirframeComponent::description(void) const ...@@ -54,7 +54,7 @@ QString APMAirframeComponent::description(void) const
QString APMAirframeComponent::iconResource(void) const QString APMAirframeComponent::iconResource(void) const
{ {
return "/qmlimages/AirframeComponentIcon.png"; return QStringLiteral("/qmlimages/AirframeComponentIcon.png");
} }
bool APMAirframeComponent::requiresSetup(void) const bool APMAirframeComponent::requiresSetup(void) const
...@@ -65,7 +65,7 @@ bool APMAirframeComponent::requiresSetup(void) const ...@@ -65,7 +65,7 @@ bool APMAirframeComponent::requiresSetup(void) const
bool APMAirframeComponent::setupComplete(void) const bool APMAirframeComponent::setupComplete(void) const
{ {
if (_requiresFrameSetup) { if (_requiresFrameSetup) {
return _autopilot->getParameterFact(FactSystem::defaultComponentId, "FRAME")->rawValue().toInt() >= 0; return _autopilot->getParameterFact(FactSystem::defaultComponentId, QStringLiteral("FRAME"))->rawValue().toInt() >= 0;
} else { } else {
return true; return true;
} }
...@@ -76,7 +76,7 @@ QStringList APMAirframeComponent::setupCompleteChangedTriggerList(void) const ...@@ -76,7 +76,7 @@ QStringList APMAirframeComponent::setupCompleteChangedTriggerList(void) const
QStringList list; QStringList list;
if (_requiresFrameSetup) { if (_requiresFrameSetup) {
list << "FRAME"; list << QStringLiteral("FRAME");
} }
return list; return list;
...@@ -85,7 +85,7 @@ QStringList APMAirframeComponent::setupCompleteChangedTriggerList(void) const ...@@ -85,7 +85,7 @@ QStringList APMAirframeComponent::setupCompleteChangedTriggerList(void) const
QUrl APMAirframeComponent::setupSource(void) const QUrl APMAirframeComponent::setupSource(void) const
{ {
if (_requiresFrameSetup) { if (_requiresFrameSetup) {
return QUrl::fromUserInput("qrc:/qml/APMAirframeComponent.qml"); return QUrl::fromUserInput(QStringLiteral("qrc:/qml/APMAirframeComponent.qml"));
} else { } else {
return QUrl(); return QUrl();
} }
...@@ -94,7 +94,7 @@ QUrl APMAirframeComponent::setupSource(void) const ...@@ -94,7 +94,7 @@ QUrl APMAirframeComponent::setupSource(void) const
QUrl APMAirframeComponent::summaryQmlSource(void) const QUrl APMAirframeComponent::summaryQmlSource(void) const
{ {
if (_requiresFrameSetup) { if (_requiresFrameSetup) {
return QUrl::fromUserInput("qrc:/qml/APMAirframeComponentSummary.qml"); return QUrl::fromUserInput(QStringLiteral("qrc:/qml/APMAirframeComponentSummary.qml"));
} else { } else {
return QUrl(); return QUrl();
} }
......
...@@ -40,7 +40,7 @@ void APMAirframeComponentAirframes::insert(const QString& group, int groupId, co ...@@ -40,7 +40,7 @@ void APMAirframeComponentAirframes::insert(const QString& group, int groupId, co
g = new AirframeType_t; g = new AirframeType_t;
g->name = group; g->name = group;
g->type = groupId; g->type = groupId;
g->imageResource = image.isEmpty() ? "" : QString("qrc:/qmlimages/") + image; g->imageResource = image.isEmpty() ? QString() : QStringLiteral("qrc:/qmlimages/") + image;
rgAirframeTypes.insert(group, g); rgAirframeTypes.insert(group, g);
} else { } else {
g = rgAirframeTypes.value(group); g = rgAirframeTypes.value(group);
......
...@@ -42,12 +42,12 @@ APMAirframeComponentController::APMAirframeComponentController(void) : ...@@ -42,12 +42,12 @@ APMAirframeComponentController::APMAirframeComponentController(void) :
{ {
if (!_typesRegistered) { if (!_typesRegistered) {
_typesRegistered = true; _typesRegistered = true;
qmlRegisterUncreatableType<APMAirframeType>("QGroundControl.Controllers", 1, 0, "APMAiframeType", "Can only reference APMAirframeType"); qmlRegisterUncreatableType<APMAirframeType>("QGroundControl.Controllers", 1, 0, "APMAiframeType", QStringLiteral("Can only reference APMAirframeType"));
qmlRegisterUncreatableType<APMAirframe>("QGroundControl.Controllers", 1, 0, "APMAiframe", "Can only reference APMAirframe"); qmlRegisterUncreatableType<APMAirframe>("QGroundControl.Controllers", 1, 0, "APMAiframe", QStringLiteral("Can only reference APMAirframe"));
} }
_fillAirFrames(); _fillAirFrames();
Fact *frame = getParameterFact(FactSystem::defaultComponentId, "FRAME"); Fact *frame = getParameterFact(FactSystem::defaultComponentId, QStringLiteral("FRAME"));
connect(frame, &Fact::vehicleUpdated, this, &APMAirframeComponentController::_factFrameChanged); connect(frame, &Fact::vehicleUpdated, this, &APMAirframeComponentController::_factFrameChanged);
_factFrameChanged(frame->rawValue()); _factFrameChanged(frame->rawValue());
} }
...@@ -201,7 +201,7 @@ void APMAirframeComponentController::setCurrentAirframe(APMAirframe *t) ...@@ -201,7 +201,7 @@ void APMAirframeComponentController::setCurrentAirframe(APMAirframe *t)
void APMAirframeComponentController::setCurrentAirframeType(APMAirframeType *t) void APMAirframeComponentController::setCurrentAirframeType(APMAirframeType *t)
{ {
Fact *param = getParameterFact(-1, "FRAME"); Fact *param = getParameterFact(-1, QStringLiteral("FRAME"));
Q_ASSERT(param); Q_ASSERT(param);
param->setRawValue(t->type()); param->setRawValue(t->type());
} }
......
...@@ -57,7 +57,7 @@ void APMAirframeLoader::loadAirframeFactMetaData(void) ...@@ -57,7 +57,7 @@ void APMAirframeLoader::loadAirframeFactMetaData(void)
Q_ASSERT(APMAirframeComponentAirframes::get().count() == 0); Q_ASSERT(APMAirframeComponentAirframes::get().count() == 0);
QString airframeFilename = ":/AutoPilotPlugins/APM/APMAirframeFactMetaData.xml"; QString airframeFilename(QStringLiteral(":/AutoPilotPlugins/APM/APMAirframeFactMetaData.xml"));
qCDebug(APMAirframeLoaderLog) << "Loading meta data file:" << airframeFilename; qCDebug(APMAirframeLoaderLog) << "Loading meta data file:" << airframeFilename;
...@@ -82,14 +82,14 @@ void APMAirframeLoader::loadAirframeFactMetaData(void) ...@@ -82,14 +82,14 @@ void APMAirframeLoader::loadAirframeFactMetaData(void)
if (xml.isStartElement()) { if (xml.isStartElement()) {
QString elementName = xml.name().toString(); QString elementName = xml.name().toString();
QXmlStreamAttributes attr = xml.attributes(); QXmlStreamAttributes attr = xml.attributes();
if (elementName == "airframe_group") { if (elementName == QLatin1Literal("airframe_group")) {
airframeGroup = attr.value("name").toString(); airframeGroup = attr.value(QStringLiteral("name")).toString();
image = attr.value("image").toString(); image = attr.value(QStringLiteral("image")).toString();
groupId = attr.value("id").toInt(); groupId = attr.value(QStringLiteral("id")).toInt();
APMAirframeComponentAirframes::insert(airframeGroup, groupId, image); APMAirframeComponentAirframes::insert(airframeGroup, groupId, image);
} else if (elementName == "airframe") { } else if (elementName == QLatin1Literal("airframe")) {
QString name = attr.value("name").toString(); QString name = attr.value(QStringLiteral("name")).toString();
QString file = attr.value("file").toString(); QString file = attr.value(QStringLiteral("file")).toString();
APMAirframeComponentAirframes::insert(airframeGroup, groupId, image, name, file); APMAirframeComponentAirframes::insert(airframeGroup, groupId, image, name, file);
} }
} }
......
...@@ -47,7 +47,7 @@ QString APMCameraComponent::description(void) const ...@@ -47,7 +47,7 @@ QString APMCameraComponent::description(void) const
QString APMCameraComponent::iconResource(void) const QString APMCameraComponent::iconResource(void) const
{ {
return "/qmlimages/CameraComponentIcon.png"; return QStringLiteral("/qmlimages/CameraComponentIcon.png");
} }
bool APMCameraComponent::requiresSetup(void) const bool APMCameraComponent::requiresSetup(void) const
...@@ -67,12 +67,12 @@ QStringList APMCameraComponent::setupCompleteChangedTriggerList(void) const ...@@ -67,12 +67,12 @@ QStringList APMCameraComponent::setupCompleteChangedTriggerList(void) const
QUrl APMCameraComponent::setupSource(void) const QUrl APMCameraComponent::setupSource(void) const
{ {
return QUrl::fromUserInput("qrc:/qml/APMCameraComponent.qml"); return QUrl::fromUserInput(QStringLiteral("qrc:/qml/APMCameraComponent.qml"));
} }
QUrl APMCameraComponent::summaryQmlSource(void) const QUrl APMCameraComponent::summaryQmlSource(void) const
{ {
return QUrl::fromUserInput("qrc:/qml/APMCameraComponentSummary.qml"); return QUrl::fromUserInput(QStringLiteral("qrc:/qml/APMCameraComponentSummary.qml"));
} }
QString APMCameraComponent::prerequisiteSetup(void) const QString APMCameraComponent::prerequisiteSetup(void) const
......
...@@ -99,7 +99,7 @@ CalWorkerThread::calibrate_return CalWorkerThread::calibrate(void) ...@@ -99,7 +99,7 @@ CalWorkerThread::calibrate_return CalWorkerThread::calibrate(void)
worker_data.y[cur_mag] = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_points_maxcount)); worker_data.y[cur_mag] = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_points_maxcount));
worker_data.z[cur_mag] = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_points_maxcount)); worker_data.z[cur_mag] = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_points_maxcount));
if (worker_data.x[cur_mag] == NULL || worker_data.y[cur_mag] == NULL || worker_data.z[cur_mag] == NULL) { if (worker_data.x[cur_mag] == NULL || worker_data.y[cur_mag] == NULL || worker_data.z[cur_mag] == NULL) {
_emitVehicleTextMessage("[cal] ERROR: out of memory"); _emitVehicleTextMessage(QStringLiteral("[cal] ERROR: out of memory"));
result = calibrate_return_error; result = calibrate_return_error;
} }
} }
...@@ -170,7 +170,7 @@ CalWorkerThread::calibrate_return CalWorkerThread::mag_calibration_worker(detect ...@@ -170,7 +170,7 @@ CalWorkerThread::calibrate_return CalWorkerThread::mag_calibration_worker(detect
mag_worker_data_t* worker_data = (mag_worker_data_t*)(data); mag_worker_data_t* worker_data = (mag_worker_data_t*)(data);
_emitVehicleTextMessage("[cal] Rotate vehicle around the detected orientation"); _emitVehicleTextMessage(QStringLiteral("[cal] Rotate vehicle around the detected orientation"));
_emitVehicleTextMessage(QString("[cal] Continue rotation for %1 seconds").arg(worker_data->calibration_interval_perside_seconds)); _emitVehicleTextMessage(QString("[cal] Continue rotation for %1 seconds").arg(worker_data->calibration_interval_perside_seconds));
uint64_t calibration_deadline = QGC::groundTimeUsecs() + worker_data->calibration_interval_perside_useconds; uint64_t calibration_deadline = QGC::groundTimeUsecs() + worker_data->calibration_interval_perside_useconds;
......
...@@ -39,12 +39,12 @@ QString APMFlightModesComponent::name(void) const ...@@ -39,12 +39,12 @@ QString APMFlightModesComponent::name(void) const
QString APMFlightModesComponent::description(void) const QString APMFlightModesComponent::description(void) const
{ {
return QString("The Flight Modes Component is used to assign FLight Modes to Channel 5."); return QStringLiteral("The Flight Modes Component is used to assign FLight Modes to Channel 5.");
} }
QString APMFlightModesComponent::iconResource(void) const QString APMFlightModesComponent::iconResource(void) const
{ {
return "/qmlimages/FlightModesComponentIcon.png"; return QStringLiteral("/qmlimages/FlightModesComponentIcon.png");
} }
bool APMFlightModesComponent::requiresSetup(void) const bool APMFlightModesComponent::requiresSetup(void) const
...@@ -64,12 +64,12 @@ QStringList APMFlightModesComponent::setupCompleteChangedTriggerList(void) const ...@@ -64,12 +64,12 @@ QStringList APMFlightModesComponent::setupCompleteChangedTriggerList(void) const
QUrl APMFlightModesComponent::setupSource(void) const QUrl APMFlightModesComponent::setupSource(void) const
{ {
return QUrl::fromUserInput("qrc:/qml/APMFlightModesComponent.qml"); return QUrl::fromUserInput(QStringLiteral("qrc:/qml/APMFlightModesComponent.qml"));
} }
QUrl APMFlightModesComponent::summaryQmlSource(void) const QUrl APMFlightModesComponent::summaryQmlSource(void) const
{ {
return QUrl::fromUserInput("qrc:/qml/APMFlightModesComponentSummary.qml"); return QUrl::fromUserInput(QStringLiteral("qrc:/qml/APMFlightModesComponentSummary.qml"));
} }
QString APMFlightModesComponent::prerequisiteSetup(void) const QString APMFlightModesComponent::prerequisiteSetup(void) const
......
...@@ -34,7 +34,8 @@ APMFlightModesComponentController::APMFlightModesComponentController(void) ...@@ -34,7 +34,8 @@ APMFlightModesComponentController::APMFlightModesComponentController(void)
, _fixedWing(_vehicle->vehicleType() == MAV_TYPE_FIXED_WING) , _fixedWing(_vehicle->vehicleType() == MAV_TYPE_FIXED_WING)
{ {
QStringList usedParams; QStringList usedParams;
usedParams << "FLTMODE1" << "FLTMODE2" << "FLTMODE3" << "FLTMODE4" << "FLTMODE5" << "FLTMODE6"; usedParams << QStringLiteral("FLTMODE1") << QStringLiteral("FLTMODE2") << QStringLiteral("FLTMODE3")
<< QStringLiteral("FLTMODE4") << QStringLiteral("FLTMODE5") << QStringLiteral("FLTMODE6");
if (!_allParametersExists(FactSystem::defaultComponentId, usedParams)) { if (!_allParametersExists(FactSystem::defaultComponentId, usedParams)) {
return; return;
} }
......
...@@ -43,7 +43,7 @@ QString APMPowerComponent::description(void) const ...@@ -43,7 +43,7 @@ QString APMPowerComponent::description(void) const
QString APMPowerComponent::iconResource(void) const QString APMPowerComponent::iconResource(void) const
{ {
return "/qmlimages/PowerComponentIcon.png"; return QStringLiteral("/qmlimages/PowerComponentIcon.png");
} }
bool APMPowerComponent::requiresSetup(void) const bool APMPowerComponent::requiresSetup(void) const
...@@ -53,26 +53,26 @@ bool APMPowerComponent::requiresSetup(void) const ...@@ -53,26 +53,26 @@ bool APMPowerComponent::requiresSetup(void) const
bool APMPowerComponent::setupComplete(void) const bool APMPowerComponent::setupComplete(void) const
{ {
return _autopilot->getParameterFact(FactSystem::defaultComponentId, "BATT_CAPACITY")->rawValue().toInt() != 0; return _autopilot->getParameterFact(FactSystem::defaultComponentId, QStringLiteral("BATT_CAPACITY"))->rawValue().toInt() != 0;
} }
QStringList APMPowerComponent::setupCompleteChangedTriggerList(void) const QStringList APMPowerComponent::setupCompleteChangedTriggerList(void) const
{ {
QStringList list; QStringList list;
list << "BATT_CAPACITY"; list << QStringLiteral("BATT_CAPACITY");
return list; return list;
} }
QUrl APMPowerComponent::setupSource(void) const QUrl APMPowerComponent::setupSource(void) const
{ {
return QUrl::fromUserInput("qrc:/qml/APMPowerComponent.qml"); return QUrl::fromUserInput(QStringLiteral("qrc:/qml/APMPowerComponent.qml"));
} }
QUrl APMPowerComponent::summaryQmlSource(void) const QUrl APMPowerComponent::summaryQmlSource(void) const
{ {
return QUrl::fromUserInput("qrc:/qml/APMPowerComponentSummary.qml"); return QUrl::fromUserInput(QStringLiteral("qrc:/qml/APMPowerComponentSummary.qml"));
} }
QString APMPowerComponent::prerequisiteSetup(void) const QString APMPowerComponent::prerequisiteSetup(void) const
......
...@@ -53,7 +53,7 @@ QString APMRadioComponent::description(void) const ...@@ -53,7 +53,7 @@ QString APMRadioComponent::description(void) const
QString APMRadioComponent::iconResource(void) const QString APMRadioComponent::iconResource(void) const
{ {
return "/qmlimages/RadioComponentIcon.png"; return QStringLiteral("/qmlimages/RadioComponentIcon.png");
} }
bool APMRadioComponent::requiresSetup(void) const bool APMRadioComponent::requiresSetup(void) const
...@@ -100,12 +100,12 @@ QStringList APMRadioComponent::setupCompleteChangedTriggerList(void) const ...@@ -100,12 +100,12 @@ QStringList APMRadioComponent::setupCompleteChangedTriggerList(void) const
QUrl APMRadioComponent::setupSource(void) const QUrl APMRadioComponent::setupSource(void) const
{ {
return QUrl::fromUserInput("qrc:/qml/RadioComponent.qml"); return QUrl::fromUserInput(QStringLiteral("qrc:/qml/RadioComponent.qml"));
} }
QUrl APMRadioComponent::summaryQmlSource(void) const QUrl APMRadioComponent::summaryQmlSource(void) const
{ {
return QUrl::fromUserInput("qrc:/qml/APMRadioComponentSummary.qml"); return QUrl::fromUserInput(QStringLiteral("qrc:/qml/APMRadioComponentSummary.qml"));
} }
QString APMRadioComponent::prerequisiteSetup(void) const QString APMRadioComponent::prerequisiteSetup(void) const
......
...@@ -47,7 +47,7 @@ QString APMSafetyComponent::description(void) const ...@@ -47,7 +47,7 @@ QString APMSafetyComponent::description(void) const
QString APMSafetyComponent::iconResource(void) const QString APMSafetyComponent::iconResource(void) const
{ {
return "/qmlimages/SafetyComponentIcon.png"; return QStringLiteral("/qmlimages/SafetyComponentIcon.png");
} }
bool APMSafetyComponent::requiresSetup(void) const bool APMSafetyComponent::requiresSetup(void) const
...@@ -72,7 +72,7 @@ QUrl APMSafetyComponent::setupSource(void) const ...@@ -72,7 +72,7 @@ QUrl APMSafetyComponent::setupSource(void) const
switch (_vehicle->vehicleType()) { switch (_vehicle->vehicleType()) {
case MAV_TYPE_FIXED_WING: case MAV_TYPE_FIXED_WING:
qmlFile = "qrc:/qml/APMSafetyComponentPlane.qml"; qmlFile = QStringLiteral("qrc:/qml/APMSafetyComponentPlane.qml");
break; break;
case MAV_TYPE_QUADROTOR: case MAV_TYPE_QUADROTOR:
case MAV_TYPE_COAXIAL: case MAV_TYPE_COAXIAL:
...@@ -80,13 +80,13 @@ QUrl APMSafetyComponent::setupSource(void) const ...@@ -80,13 +80,13 @@ QUrl APMSafetyComponent::setupSource(void) const
case MAV_TYPE_HEXAROTOR: case MAV_TYPE_HEXAROTOR:
case MAV_TYPE_OCTOROTOR: case MAV_TYPE_OCTOROTOR:
case MAV_TYPE_TRICOPTER: case MAV_TYPE_TRICOPTER:
qmlFile = "qrc:/qml/APMSafetyComponentCopter.qml"; qmlFile = QStringLiteral("qrc:/qml/APMSafetyComponentCopter.qml");
break; break;
case MAV_TYPE_GROUND_ROVER: case MAV_TYPE_GROUND_ROVER:
qmlFile = "qrc:/qml/APMSafetyComponentRover.qml"; qmlFile = QStringLiteral("qrc:/qml/APMSafetyComponentRover.qml");
break; break;
default: default:
qmlFile = "qrc:/qml/APMNotSupported.qml"; qmlFile = QStringLiteral("qrc:/qml/APMNotSupported.qml");
break; break;
} }
...@@ -99,7 +99,7 @@ QUrl APMSafetyComponent::summaryQmlSource(void) const ...@@ -99,7 +99,7 @@ QUrl APMSafetyComponent::summaryQmlSource(void) const
switch (_vehicle->vehicleType()) { switch (_vehicle->vehicleType()) {
case MAV_TYPE_FIXED_WING: case MAV_TYPE_FIXED_WING:
qmlFile = "qrc:/qml/APMSafetyComponentSummaryPlane.qml"; qmlFile = QStringLiteral("qrc:/qml/APMSafetyComponentSummaryPlane.qml");
break; break;
case MAV_TYPE_QUADROTOR: case MAV_TYPE_QUADROTOR:
case MAV_TYPE_COAXIAL: case MAV_TYPE_COAXIAL:
...@@ -107,13 +107,13 @@ QUrl APMSafetyComponent::summaryQmlSource(void) const ...@@ -107,13 +107,13 @@ QUrl APMSafetyComponent::summaryQmlSource(void) const
case MAV_TYPE_HEXAROTOR: case MAV_TYPE_HEXAROTOR:
case MAV_TYPE_OCTOROTOR: case MAV_TYPE_OCTOROTOR:
case MAV_TYPE_TRICOPTER: case MAV_TYPE_TRICOPTER:
qmlFile = "qrc:/qml/APMSafetyComponentSummaryCopter.qml"; qmlFile = QStringLiteral("qrc:/qml/APMSafetyComponentSummaryCopter.qml");
break; break;
case MAV_TYPE_GROUND_ROVER: case MAV_TYPE_GROUND_ROVER:
qmlFile = "qrc:/qml/APMSafetyComponentSummaryRover.qml"; qmlFile = QStringLiteral("qrc:/qml/APMSafetyComponentSummaryRover.qml");
break; break;
default: default:
qmlFile = "qrc:/qml/APMNotSupported.qml"; qmlFile = QStringLiteral("qrc:/qml/APMNotSupported.qml");
break; break;
} }
......
...@@ -115,10 +115,10 @@ bool APMSensorsComponent::compassSetupNeeded(void) const ...@@ -115,10 +115,10 @@ bool APMSensorsComponent::compassSetupNeeded(void) const
QStringList devicesIds; QStringList devicesIds;
QStringList rgOffsets[cCompass]; QStringList rgOffsets[cCompass];
devicesIds << "COMPASS_DEV_ID" << "COMPASS_DEV_ID2" << "COMPASS_DEV_ID3"; devicesIds << QStringLiteral("COMPASS_DEV_ID") << QStringLiteral("COMPASS_DEV_ID2") << QStringLiteral("COMPASS_DEV_ID3");
rgOffsets[0] << "COMPASS_OFS_X" << "COMPASS_OFS_X" << "COMPASS_OFS_X"; rgOffsets[0] << QStringLiteral("COMPASS_OFS_X") << QStringLiteral("COMPASS_OFS_X") << QStringLiteral("COMPASS_OFS_X");
rgOffsets[1] << "COMPASS_OFS2_X" << "COMPASS_OFS2_X" << "COMPASS_OFS2_X"; rgOffsets[1] << QStringLiteral("COMPASS_OFS2_X") << QStringLiteral("COMPASS_OFS2_X") << QStringLiteral("COMPASS_OFS2_X");
rgOffsets[2] << "COMPASS_OFS3_X" << "COMPASS_OFS3_X" << "COMPASS_OFS3_X"; rgOffsets[2] << QStringLiteral("COMPASS_OFS3_X") << QStringLiteral("COMPASS_OFS3_X") << QStringLiteral("COMPASS_OFS3_X");
for (size_t i=0; i<cCompass; i++) { for (size_t i=0; i<cCompass; i++) {
if (_autopilot->getParameterFact(FactSystem::defaultComponentId, devicesIds[i])->rawValue().toInt() != 0) { if (_autopilot->getParameterFact(FactSystem::defaultComponentId, devicesIds[i])->rawValue().toInt() != 0) {
...@@ -141,14 +141,14 @@ bool APMSensorsComponent::accelSetupNeeded(void) const ...@@ -141,14 +141,14 @@ bool APMSensorsComponent::accelSetupNeeded(void) const
QStringList rgOffsets[cAccel]; QStringList rgOffsets[cAccel];
if (_autopilot->parameterExists(FactSystem::defaultComponentId, "INS_USE")) { if (_autopilot->parameterExists(FactSystem::defaultComponentId, "INS_USE")) {
insUse << "INS_USE" << "INS_USE2" << "INS_USE3"; insUse << QStringLiteral("INS_USE") << QStringLiteral("INS_USE2") << QStringLiteral("INS_USE3");
rgOffsets[0] << "INS_ACCOFFS_X" << "INS_ACCOFFS_Y" << "INS_ACCOFFS_Z"; rgOffsets[0] << QStringLiteral("INS_ACCOFFS_X") << QStringLiteral("INS_ACCOFFS_Y") << QStringLiteral("INS_ACCOFFS_Z");
rgOffsets[1] << "INS_ACC2OFFS_X" << "INS_ACC2OFFS_Y" << "INS_ACC2OFFS_Z"; rgOffsets[1] << QStringLiteral("INS_ACC2OFFS_X") << QStringLiteral("INS_ACC2OFFS_Y") << QStringLiteral("INS_ACC2OFFS_Z");
rgOffsets[2] << "INS_ACC3OFFS_X" << "INS_ACC3OFFS_Y" << "INS_ACC3OFFS_Z"; rgOffsets[2] << QStringLiteral("INS_ACC3OFFS_X") << QStringLiteral("INS_ACC3OFFS_Y") << QStringLiteral("INS_ACC3OFFS_Z");
} else { } else {
// For older firmwares which don't support the INS_USE parameter we can't determine which secondary accels are in use. // For older firmwares which don't support the INS_USE parameter we can't determine which secondary accels are in use.
// So we just base things off the the first accel. // So we just base things off the the first accel.
rgOffsets[0] << "INS_ACCOFFS_X" << "INS_ACCOFFS_Y" << "INS_ACCOFFS_Z"; rgOffsets[0] << QStringLiteral("INS_ACCOFFS_X") << QStringLiteral("INS_ACCOFFS_Y") << QStringLiteral("INS_ACCOFFS_Z");
} }
for (size_t i=0; i<cAccel; i++) { for (size_t i=0; i<cAccel; i++) {
......
...@@ -186,7 +186,7 @@ void APMSensorsComponentController::_stopCalibration(APMSensorsComponentControll ...@@ -186,7 +186,7 @@ void APMSensorsComponentController::_stopCalibration(APMSensorsComponentControll
default: default:
// Assume failed // Assume failed
_hideAllCalAreas(); _hideAllCalAreas();
qgcApp()->showMessage("Calibration failed. Calibration log will be displayed."); qgcApp()->showMessage(QStringLiteral("Calibration failed. Calibration log will be displayed."));
break; break;
} }
...@@ -219,11 +219,12 @@ void APMSensorsComponentController::_handleUASTextMessage(int uasId, int compId, ...@@ -219,11 +219,12 @@ void APMSensorsComponentController::_handleUASTextMessage(int uasId, int compId,
return; return;
} }
if (text.startsWith("PreArm:") || text.startsWith("EKF") || text.startsWith("Arm") || text.startsWith("Initialising")) { if (text.startsWith(QLatin1Literal("PreArm:")) || text.startsWith(QLatin1Literal("EKF"))
|| text.startsWith(QLatin1Literal("Arm")) || text.startsWith(QLatin1Literal("Initialising"))) {
return; return;
} }
if (text.contains("progress <")) { if (text.contains(QLatin1Literal("progress <"))) {
QString percent = text.split("<").last().split(">").first(); QString percent = text.split("<").last().split(">").first();
bool ok; bool ok;
int p = percent.toInt(&ok); int p = percent.toInt(&ok);
...@@ -234,39 +235,39 @@ void APMSensorsComponentController::_handleUASTextMessage(int uasId, int compId, ...@@ -234,39 +235,39 @@ void APMSensorsComponentController::_handleUASTextMessage(int uasId, int compId,
return; return;
} }
QString anyKey("and press any"); QString anyKey(QStringLiteral("and press any"));
if (text.contains(anyKey)) { if (text.contains(anyKey)) {
text = text.left(text.indexOf(anyKey)) + "and click Next to continue."; text = text.left(text.indexOf(anyKey)) + QStringLiteral("and click Next to continue.");
_nextButton->setEnabled(true); _nextButton->setEnabled(true);
} }
_appendStatusLog(text); _appendStatusLog(text);
qCDebug(APMSensorsComponentControllerLog) << text << severity; qCDebug(APMSensorsComponentControllerLog) << text << severity;
if (text.contains("Calibration successful")) { if (text.contains(QLatin1String("Calibration successful"))) {
_stopCalibration(StopCalibrationSuccess); _stopCalibration(StopCalibrationSuccess);
return; return;
} }
if (text.contains("FAILED")) { if (text.contains(QLatin1String("FAILED"))) {
_stopCalibration(StopCalibrationFailed); _stopCalibration(StopCalibrationFailed);
return; return;
} }
// All calibration messages start with [cal] // All calibration messages start with [cal]
QString calPrefix("[cal] "); QString calPrefix(QStringLiteral("[cal] "));
if (!text.startsWith(calPrefix)) { if (!text.startsWith(calPrefix)) {
return; return;
} }
text = text.right(text.length() - calPrefix.length()); text = text.right(text.length() - calPrefix.length());
QString calStartPrefix("calibration started: "); QString calStartPrefix(QStringLiteral("calibration started: "));
if (text.startsWith(calStartPrefix)) { if (text.startsWith(calStartPrefix)) {
text = text.right(text.length() - calStartPrefix.length()); text = text.right(text.length() - calStartPrefix.length());
_startVisualCalibration(); _startVisualCalibration();
if (text == "accel" || text == "mag" || text == "gyro") { if (text == QLatin1Literal("accel") || text == QLatin1Literal("mag") || text == QLatin1Literal("gyro")) {
// Reset all progress indication // Reset all progress indication
_orientationCalDownSideDone = false; _orientationCalDownSideDone = false;
_orientationCalUpsideDownSideDone = false; _orientationCalUpsideDownSideDone = false;
...@@ -318,36 +319,36 @@ void APMSensorsComponentController::_handleUASTextMessage(int uasId, int compId, ...@@ -318,36 +319,36 @@ void APMSensorsComponentController::_handleUASTextMessage(int uasId, int compId,
return; return;
} }
if (text.endsWith("orientation detected")) { if (text.endsWith(QLatin1Literal("orientation detected"))) {
QString side = text.section(" ", 0, 0); QString side = text.section(" ", 0, 0);
qDebug() << "Side started" << side; qDebug() << "Side started" << side;
if (side == "down") { if (side == QLatin1Literal("down")) {
_orientationCalDownSideInProgress = true; _orientationCalDownSideInProgress = true;
if (_magCalInProgress) { if (_magCalInProgress) {
_orientationCalDownSideRotate = true; _orientationCalDownSideRotate = true;
} }
} else if (side == "up") { } else if (side == QLatin1Literal("up")) {
_orientationCalUpsideDownSideInProgress = true; _orientationCalUpsideDownSideInProgress = true;
if (_magCalInProgress) { if (_magCalInProgress) {
_orientationCalUpsideDownSideRotate = true; _orientationCalUpsideDownSideRotate = true;
} }
} else if (side == "left") { } else if (side == QLatin1Literal("left")) {
_orientationCalLeftSideInProgress = true; _orientationCalLeftSideInProgress = true;
if (_magCalInProgress) { if (_magCalInProgress) {
_orientationCalLeftSideRotate = true; _orientationCalLeftSideRotate = true;
} }
} else if (side == "right") { } else if (side == QLatin1Literal("right")) {
_orientationCalRightSideInProgress = true; _orientationCalRightSideInProgress = true;
if (_magCalInProgress) { if (_magCalInProgress) {
_orientationCalRightSideRotate = true; _orientationCalRightSideRotate = true;
} }
} else if (side == "front") { } else if (side == QLatin1Literal("front")) {
_orientationCalNoseDownSideInProgress = true; _orientationCalNoseDownSideInProgress = true;
if (_magCalInProgress) { if (_magCalInProgress) {
_orientationCalNoseDownSideRotate = true; _orientationCalNoseDownSideRotate = true;
} }
} else if (side == "back") { } else if (side == QLatin1Literal("back")) {
_orientationCalTailDownSideInProgress = true; _orientationCalTailDownSideInProgress = true;
if (_magCalInProgress) { if (_magCalInProgress) {
_orientationCalTailDownSideRotate = true; _orientationCalTailDownSideRotate = true;
...@@ -365,31 +366,31 @@ void APMSensorsComponentController::_handleUASTextMessage(int uasId, int compId, ...@@ -365,31 +366,31 @@ void APMSensorsComponentController::_handleUASTextMessage(int uasId, int compId,
return; return;
} }
if (text.endsWith("side done, rotate to a different side")) { if (text.endsWith(QLatin1Literal("side done, rotate to a different side"))) {
QString side = text.section(" ", 0, 0); QString side = text.section(" ", 0, 0);
qDebug() << "Side finished" << side; qDebug() << "Side finished" << side;
if (side == "down") { if (side == QLatin1Literal("down")) {
_orientationCalDownSideInProgress = false; _orientationCalDownSideInProgress = false;
_orientationCalDownSideDone = true; _orientationCalDownSideDone = true;
_orientationCalDownSideRotate = false; _orientationCalDownSideRotate = false;
} else if (side == "up") { } else if (side == QLatin1Literal("up")) {
_orientationCalUpsideDownSideInProgress = false; _orientationCalUpsideDownSideInProgress = false;
_orientationCalUpsideDownSideDone = true; _orientationCalUpsideDownSideDone = true;
_orientationCalUpsideDownSideRotate = false; _orientationCalUpsideDownSideRotate = false;
} else if (side == "left") { } else if (side == QLatin1Literal("left")) {
_orientationCalLeftSideInProgress = false; _orientationCalLeftSideInProgress = false;
_orientationCalLeftSideDone = true; _orientationCalLeftSideDone = true;
_orientationCalLeftSideRotate = false; _orientationCalLeftSideRotate = false;
} else if (side == "right") { } else if (side == QLatin1Literal("right")) {
_orientationCalRightSideInProgress = false; _orientationCalRightSideInProgress = false;
_orientationCalRightSideDone = true; _orientationCalRightSideDone = true;
_orientationCalRightSideRotate = false; _orientationCalRightSideRotate = false;
} else if (side == "front") { } else if (side == QLatin1Literal("front")) {
_orientationCalNoseDownSideInProgress = false; _orientationCalNoseDownSideInProgress = false;
_orientationCalNoseDownSideDone = true; _orientationCalNoseDownSideDone = true;
_orientationCalNoseDownSideRotate = false; _orientationCalNoseDownSideRotate = false;
} else if (side == "back") { } else if (side == QLatin1Literal("back")) {
_orientationCalTailDownSideInProgress = false; _orientationCalTailDownSideInProgress = false;
_orientationCalTailDownSideDone = true; _orientationCalTailDownSideDone = true;
_orientationCalTailDownSideRotate = false; _orientationCalTailDownSideRotate = false;
...@@ -403,18 +404,17 @@ void APMSensorsComponentController::_handleUASTextMessage(int uasId, int compId, ...@@ -403,18 +404,17 @@ void APMSensorsComponentController::_handleUASTextMessage(int uasId, int compId,
return; return;
} }
QString calCompletePrefix("calibration done:"); if (text.startsWith(QLatin1Literal("calibration done:"))) {
if (text.startsWith(calCompletePrefix)) {
_stopCalibration(StopCalibrationSuccess); _stopCalibration(StopCalibrationSuccess);
return; return;
} }
if (text.startsWith("calibration cancelled")) { if (text.startsWith(QLatin1Literal("calibration cancelled"))) {
_stopCalibration(_waitingForCancel ? StopCalibrationCancelled : StopCalibrationFailed); _stopCalibration(_waitingForCancel ? StopCalibrationCancelled : StopCalibrationFailed);
return; return;
} }
if (text.startsWith("calibration failed")) { if (text.startsWith(QLatin1Literal("calibration failed"))) {
_stopCalibration(StopCalibrationFailed); _stopCalibration(StopCalibrationFailed);
return; return;
} }
...@@ -424,15 +424,15 @@ void APMSensorsComponentController::_refreshParams(void) ...@@ -424,15 +424,15 @@ void APMSensorsComponentController::_refreshParams(void)
{ {
QStringList fastRefreshList; QStringList fastRefreshList;
fastRefreshList << "COMPASS_OFS_X" << "COMPASS_OFS_X" << "COMPASS_OFS_X" fastRefreshList << QStringLiteral("COMPASS_OFS_X") << QStringLiteral("COMPASS_OFS_X") << QStringLiteral("COMPASS_OFS_X")
<< "INS_ACCOFFS_X" << "INS_ACCOFFS_Y" << "INS_ACCOFFS_Z"; << QStringLiteral("INS_ACCOFFS_X") << QStringLiteral("INS_ACCOFFS_Y") << QStringLiteral("INS_ACCOFFS_Z");
foreach (const QString &paramName, fastRefreshList) { foreach (const QString &paramName, fastRefreshList) {
_autopilot->refreshParameter(FactSystem::defaultComponentId, paramName); _autopilot->refreshParameter(FactSystem::defaultComponentId, paramName);
} }
// Now ask for all to refresh // Now ask for all to refresh
_autopilot->refreshParametersPrefix(FactSystem::defaultComponentId, "COMPASS_"); _autopilot->refreshParametersPrefix(FactSystem::defaultComponentId, QStringLiteral("COMPASS_"));
_autopilot->refreshParametersPrefix(FactSystem::defaultComponentId, "INS_"); _autopilot->refreshParametersPrefix(FactSystem::defaultComponentId, QStringLiteral("INS_"));
} }
bool APMSensorsComponentController::fixedWing(void) bool APMSensorsComponentController::fixedWing(void)
......
...@@ -43,7 +43,7 @@ QString APMTuningComponent::description(void) const ...@@ -43,7 +43,7 @@ QString APMTuningComponent::description(void) const
QString APMTuningComponent::iconResource(void) const QString APMTuningComponent::iconResource(void) const
{ {
return "/qmlimages/TuningComponentIcon.png"; return QStringLiteral("/qmlimages/TuningComponentIcon.png");
} }
bool APMTuningComponent::requiresSetup(void) const bool APMTuningComponent::requiresSetup(void) const
...@@ -74,7 +74,7 @@ QUrl APMTuningComponent::setupSource(void) const ...@@ -74,7 +74,7 @@ QUrl APMTuningComponent::setupSource(void) const
case MAV_TYPE_TRICOPTER: case MAV_TYPE_TRICOPTER:
// Older firmwares do not have CH9_OPT, we don't support Tuning on older firmwares // Older firmwares do not have CH9_OPT, we don't support Tuning on older firmwares
if (_autopilot->parameterExists(-1, "CH9_OPT")) { if (_autopilot->parameterExists(-1, "CH9_OPT")) {
qmlFile = "qrc:/qml/APMTuningComponentCopter.qml"; qmlFile = QStringLiteral("qrc:/qml/APMTuningComponentCopter.qml");
} }
break; break;
default: default:
......
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