Skip to content

Commit

Permalink
Merge pull request mavlink#6937 from patrickelectric/aaaaaaaarg
Browse files Browse the repository at this point in the history
Use QString::arg and not multiple arg calls
  • Loading branch information
DonLakeFlyer authored Oct 24, 2018
2 parents 0dbc3ef + 37da7a8 commit 40f9e7e
Show file tree
Hide file tree
Showing 5 changed files with 18 additions and 18 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -168,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]);
}
}
}
Expand Down
6 changes: 3 additions & 3 deletions src/VehicleSetup/Bootloader.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand Down Expand Up @@ -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();
Expand Down Expand Up @@ -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;
}

Expand Down
12 changes: 6 additions & 6 deletions src/VehicleSetup/FirmwareImage.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}

Expand Down Expand Up @@ -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;
}

Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -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()));
}
}

Expand All @@ -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;
}

Expand Down Expand Up @@ -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;
}

Expand Down
4 changes: 2 additions & 2 deletions src/comm/QGCJSBSimLink.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
12 changes: 6 additions & 6 deletions src/ui/MAVLinkDecoder.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand All @@ -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)
Expand Down Expand Up @@ -281,28 +281,28 @@ 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)
{
// 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)
{
// 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)
Expand Down

0 comments on commit 40f9e7e

Please sign in to comment.