diff --git a/src/GAudioOutput.cc b/src/GAudioOutput.cc index 35aef2ff74dbcc8ef0634fda37c2d90c8310b839..9d479bc590b1f1928253b632c433c57d12ad0cef 100644 --- a/src/GAudioOutput.cc +++ b/src/GAudioOutput.cc @@ -223,7 +223,7 @@ bool GAudioOutput::say(QString text, int severity) text = "\\" + text; QStdWString str = text.toStdWString(); unsigned char str2[1024] = {}; - memcpy(str2, text.toAscii().data(), str.length()); + memcpy(str2, text.toLatin1().data(), str.length()); SpeakString(str2); res = true; #endif // Q_OS_MAC diff --git a/src/comm/QGCFlightGearLink.cc b/src/comm/QGCFlightGearLink.cc index ce54a3e7929190e2ca76eb60babe8605927aba56..f570adf5ef99fb0472f66900d15db368302c9cad 100644 --- a/src/comm/QGCFlightGearLink.cc +++ b/src/comm/QGCFlightGearLink.cc @@ -236,7 +236,7 @@ void QGCFlightGearLink::updateControls(quint64 time, float rollAilerons, float p { QString state("%1\t%2\t%3\t%4\t%5\n"); state = state.arg(rollAilerons).arg(pitchElevator).arg(yawRudder).arg(true).arg(throttle); - writeBytes(state.toAscii().constData(), state.length()); + writeBytes(state.toLatin1().constData(), state.length()); //qDebug() << "Updated controls" << rollAilerons << pitchElevator << yawRudder << throttle; //qDebug() << "Updated controls" << state; } diff --git a/src/comm/QGCJSBSimLink.cc b/src/comm/QGCJSBSimLink.cc index 947161d1488de60fb3b08791f8c492e2c5932cbb..56f03d71244b2f2341f4cbf330ca43124088db59 100644 --- a/src/comm/QGCJSBSimLink.cc +++ b/src/comm/QGCJSBSimLink.cc @@ -257,7 +257,7 @@ void QGCJSBSimLink::updateControls(quint64 time, float rollAilerons, float pitch { QString state("%1\t%2\t%3\t%4\t%5\n"); state = state.arg(rollAilerons).arg(pitchElevator).arg(yawRudder).arg(true).arg(throttle); - writeBytes(state.toAscii().constData(), state.length()); + writeBytes(state.toLatin1().constData(), state.length()); } else { diff --git a/src/comm/QGCParamID.h b/src/comm/QGCParamID.h index 2df351ff1b154ebe2368d6db90aabfd001094b69..44f9ddead9dc01d114a788a273a63fd7d81f4398 100644 --- a/src/comm/QGCParamID.h +++ b/src/comm/QGCParamID.h @@ -72,7 +72,7 @@ public: return static_cast(data); } int8_t* toInt8_t() const { - return (int8_t*)data.toAscii().data(); + return (int8_t*)data.toLatin1().data(); } protected: diff --git a/src/comm/QGCXPlaneLink.cc b/src/comm/QGCXPlaneLink.cc index f829b7e128e2cd4961034d995cd1ac41a59e0d08..2d35e0f8c0f2b77a2d68d5d09157412bf9c6f8f3 100644 --- a/src/comm/QGCXPlaneLink.cc +++ b/src/comm/QGCXPlaneLink.cc @@ -226,8 +226,8 @@ void QGCXPlaneLink::run() } ip.index = 0; - strncpy(ip.str_ipad_them, localAddrStr.toAscii(), qMin((int)sizeof(ip.str_ipad_them), 16)); - strncpy(ip.str_port_them, localPortStr.toAscii(), qMin((int)sizeof(ip.str_port_them), 6)); + strncpy(ip.str_ipad_them, localAddrStr.toLatin1(), qMin((int)sizeof(ip.str_ipad_them), 16)); + strncpy(ip.str_port_them, localPortStr.toLatin1(), qMin((int)sizeof(ip.str_port_them), 6)); ip.use_ip = 1; writeBytes((const char*)&ip, sizeof(ip)); diff --git a/src/comm/XbeeLink.cpp b/src/comm/XbeeLink.cpp index 767da686d5b1c057b9f591a19f473d5fda57d33d..337c961fcaee38ba209690bbe9a9f6853d7f31d6 100644 --- a/src/comm/XbeeLink.cpp +++ b/src/comm/XbeeLink.cpp @@ -73,7 +73,7 @@ bool XbeeLink::setPortName(QString portName) m_portName = new char[this->m_portNameLength]; for(int i=0;im_portName[i]=list[0][i].toAscii(); + this->m_portName[i]=list[0][i].toLatin1(); } this->m_portName[list[0].size()] = '\0'; } diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index da9c88423a0b3925335e2121cd9bf5e99569f6f6..652ad6a3cc897e2486f3ca8215f41d3fb4dc4cf3 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -2563,7 +2563,7 @@ void UAS::setParameter(const int compId, const QString& paramId, const QVariant& switch ((int)value.type()) { case QVariant::Char: - union_value.param_float = (unsigned char)value.toChar().toAscii(); + union_value.param_float = (unsigned char)value.toChar().toLatin1(); p.param_type = MAV_PARAM_TYPE_INT8; break; case QVariant::Int: @@ -2588,7 +2588,7 @@ void UAS::setParameter(const int compId, const QString& paramId, const QVariant& switch ((int)value.type()) { case QVariant::Char: - union_value.param_int8 = (unsigned char)value.toChar().toAscii(); + union_value.param_int8 = (unsigned char)value.toChar().toLatin1(); p.param_type = MAV_PARAM_TYPE_INT8; break; case QVariant::Int: @@ -2621,7 +2621,7 @@ void UAS::setParameter(const int compId, const QString& paramId, const QVariant& // String characters if ((int)i < paramId.length()) { - p.param_id[i] = paramId.toAscii()[i]; + p.param_id[i] = paramId.toLatin1()[i]; } else { diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index eb6e52597cea7b104c3f4cb4ba0fe9b9cb49e243..dc832b77e34d33d66c6e9fdb1ae0a8fb8d685102 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -1185,7 +1185,7 @@ void MainWindow::saveScreen() if (!screenFileName.isEmpty()) { - window.save(screenFileName, format.toAscii()); + window.save(screenFileName, format.toLatin1()); } } void MainWindow::enableDockWidgetTitleBars(bool enabled) diff --git a/src/ui/map3D/Q3DWidget.cc b/src/ui/map3D/Q3DWidget.cc index 54fc876fa9eb05694d7b7ca6f180c35d2eeec733..aa8918aa0066ff027347bd2389517e7352fab6b1 100644 --- a/src/ui/map3D/Q3DWidget.cc +++ b/src/ui/map3D/Q3DWidget.cc @@ -254,7 +254,7 @@ Q3DWidget::handleKeyPressEvent(QKeyEvent* event) { mOsgGW->getEventQueue()->keyPress( static_cast( - *(event->text().toAscii().data()))); + *(event->text().toLatin1().data()))); } } @@ -274,7 +274,7 @@ Q3DWidget::handleKeyReleaseEvent(QKeyEvent* event) { mOsgGW->getEventQueue()->keyRelease( static_cast( - *(event->text().toAscii().data()))); + *(event->text().toLatin1().data()))); } } diff --git a/src/ui/mavlink/QGCMAVLinkMessageSender.cc b/src/ui/mavlink/QGCMAVLinkMessageSender.cc index fabf2499780754edf0b306e53401b287900f9d41..6a93ed1950feb2ffd03439c33d9528c7cdad657e 100644 --- a/src/ui/mavlink/QGCMAVLinkMessageSender.cc +++ b/src/ui/mavlink/QGCMAVLinkMessageSender.cc @@ -81,7 +81,7 @@ bool QGCMAVLinkMessageSender::sendMessage(unsigned int msgid) { // Single char char* b = ((char*)(m+messageInfo[msgid].fields[fieldid].wire_offset)); - *b = field->data(1, Qt::DisplayRole).toChar().toAscii(); + *b = field->data(1, Qt::DisplayRole).toChar().toLatin1(); } break; case MAVLINK_TYPE_UINT8_T: @@ -100,7 +100,7 @@ bool QGCMAVLinkMessageSender::sendMessage(unsigned int msgid) { // Single value uint8_t* u = (m+messageInfo[msgid].fields[fieldid].wire_offset); - *u = field->data(1, Qt::DisplayRole).toChar().toAscii(); + *u = field->data(1, Qt::DisplayRole).toChar().toLatin1(); } break; case MAVLINK_TYPE_INT8_T: @@ -119,7 +119,7 @@ bool QGCMAVLinkMessageSender::sendMessage(unsigned int msgid) { // Single value int8_t* u = reinterpret_cast(m+messageInfo[msgid].fields[fieldid].wire_offset); - *u = field->data(1, Qt::DisplayRole).toChar().toAscii(); + *u = field->data(1, Qt::DisplayRole).toChar().toLatin1(); } break; case MAVLINK_TYPE_INT16_T: