Commit 8547fa05 authored by LM's avatar LM

Fixed UART baud rates. 921600 IS supported on all platforms, they just do not define / report it

parents 18340b64 821e0e63
......@@ -363,8 +363,7 @@ HEADERS += src/MG.h \
src/ui/mavlink/QGCMAVLinkMessageSender.h \
src/ui/firmwareupdate/QGCFirmwareUpdateWidget.h \
src/ui/QGCPluginHost.h \
src/ui/firmwareupdate/QGCPX4FirmwareUpdate.h \
src/ui/map3D/TerrainParamDialog.h
src/ui/firmwareupdate/QGCPX4FirmwareUpdate.h
# Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler
macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010::HEADERS += src/ui/map3D/QGCGoogleEarthView.h
......@@ -391,7 +390,8 @@ contains(DEPENDENCIES_PRESENT, osg) {
src/ui/map3D/Texture.h \
src/ui/map3D/Imagery.h \
src/ui/map3D/HUDScaleGeode.h \
src/ui/map3D/WaypointGroupNode.h
src/ui/map3D/WaypointGroupNode.h \
src/ui/map3D/TerrainParamDialog.h
}
contains(DEPENDENCIES_PRESENT, protobuf):contains(MAVLINK_CONF, pixhawk) {
message("Including headers for Protocol Buffers")
......@@ -504,8 +504,7 @@ SOURCES += src/main.cc \
src/ui/mavlink/QGCMAVLinkMessageSender.cc \
src/ui/firmwareupdate/QGCFirmwareUpdateWidget.cc \
src/ui/QGCPluginHost.cc \
src/ui/firmwareupdate/QGCPX4FirmwareUpdate.cc \
src/ui/map3D/TerrainParamDialog.cc
src/ui/firmwareupdate/QGCPX4FirmwareUpdate.cc
# Enable Google Earth only on Mac OS and Windows with Visual Studio compiler
macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010::SOURCES += src/ui/map3D/QGCGoogleEarthView.cc
......@@ -534,7 +533,8 @@ contains(DEPENDENCIES_PRESENT, osg) {
src/ui/map3D/Texture.cc \
src/ui/map3D/Imagery.cc \
src/ui/map3D/HUDScaleGeode.cc \
src/ui/map3D/WaypointGroupNode.cc
src/ui/map3D/WaypointGroupNode.cc \
src/ui/map3D/TerrainParamDialog.cc
contains(DEPENDENCIES_PRESENT, osgearth) {
message("Including sources for osgEarth")
......
......@@ -645,20 +645,23 @@ void SerialLink::setName(QString name)
}
/**
* This function maps baud rate constants to numerical equivalents.
* It relies on the mapping given in qportsettings.h from the QSerialPort library.
*/
qint64 SerialLink::getNominalDataRate()
{
qint64 dataRate = 0;
switch (portSettings.baudRate()) {
#ifndef Q_OS_WIN
// Baud rates supported only by POSIX systems
#if defined(Q_OS_UNIX) || defined(Q_OS_LINUX) || defined(Q_OS_DARWIN)
case QPortSettings::BAUDR_50:
dataRate = 50;
break;
case QPortSettings::BAUDR_75:
dataRate = 75;
break;
case QPortSettings::BAUDR_110:
dataRate = 110;
break;
case QPortSettings::BAUDR_134:
dataRate = 134;
break;
......@@ -668,7 +671,48 @@ qint64 SerialLink::getNominalDataRate()
case QPortSettings::BAUDR_200:
dataRate = 200;
break;
case QPortSettings::BAUDR_1800:
dataRate = 1800;
break;
#endif
// Baud rates supported only by Linux
#ifdef Q_OS_LINUX
case QPortSettings::BAUDR_230400:
dataRate = 230400;
break;
case QPortSettings::BAUDR_460800:
dataRate = 460800;
break;
case QPortSettings::BAUDR_500000:
dataRate = 500000;
break;
case QPortSettings::BAUDR_576000:
dataRate = 576000;
break;
case QPortSettings::BAUDR_921600:
dataRate = 921600;
break;
#endif
// Baud rates supported only by Windows
#if defined(Q_OS_WIN32) || defined(Q_OS_WINCE)
case QPortSettings::BAUDR_14400:
dataRate = 14400;
break;
case QPortSettings::BAUDR_56000:
dataRate = 56000;
break;
case QPortSettings::BAUDR_128000:
dataRate = 128000;
break;
case QPortSettings::BAUDR_256000:
dataRate = 256000;
#endif
case QPortSettings::BAUDR_110:
dataRate = 110;
break;
case QPortSettings::BAUDR_300:
dataRate = 300;
break;
......@@ -678,11 +722,6 @@ qint64 SerialLink::getNominalDataRate()
case QPortSettings::BAUDR_1200:
dataRate = 1200;
break;
#ifndef Q_OS_WIN
case QPortSettings::BAUDR_1800:
dataRate = 1800;
break;
#endif
case QPortSettings::BAUDR_2400:
dataRate = 2400;
break;
......@@ -692,52 +731,22 @@ qint64 SerialLink::getNominalDataRate()
case QPortSettings::BAUDR_9600:
dataRate = 9600;
break;
#ifdef Q_OS_WIN
case QPortSettings::BAUDR_14400:
dataRate = 14400;
break;
#endif
case QPortSettings::BAUDR_19200:
dataRate = 19200;
break;
case QPortSettings::BAUDR_38400:
dataRate = 38400;
break;
#ifdef Q_OS_WIN
case QPortSettings::BAUDR_56000:
dataRate = 56000;
break;
#endif
case QPortSettings::BAUDR_57600:
dataRate = 57600;
break;
#ifdef Q_OS_WIN_XXXX // FIXME
case QPortSettings::BAUDR_76800:
dataRate = 76800;
break;
#endif
case QPortSettings::BAUDR_115200:
dataRate = 115200;
break;
#ifdef Q_OS_WIN
// Windows-specific high-end baudrates
case QPortSettings::BAUDR_128000:
dataRate = 128000;
break;
case QPortSettings::BAUDR_256000:
dataRate = 256000;
case QPortSettings::BAUDR_230400:
dataRate = 230400;
case QPortSettings::BAUDR_460800:
dataRate = 460800;
#endif
// All-OS high-speed
case QPortSettings::BAUDR_921600:
dataRate = 921600;
break;
// Otherwise do nothing.
case QPortSettings::BAUDR_UNKNOWN:
default:
// Do nothing
break;
}
return dataRate;
......@@ -907,13 +916,19 @@ bool SerialLink::setBaudRateType(int rateIndex)
if(isConnected()) reconnect = true;
disconnect();
#ifdef Q_OS_WIN
const int minBaud = (int)QPortSettings::BAUDR_14400;
#else
// These minimum and maximum baud rates were based on those enumerated in qportsettings.h.
#if defined(Q_OS_WIN32) || defined(Q_OS_WINCE)
const int minBaud = (int)QPortSettings::BAUDR_110;
const int maxBaud = (int)QPortSettings::BAUDR_256000;
#elif defined(Q_OS_LINUX)
const int minBaud = (int)QPortSettings::BAUDR_50;
const int maxBaud = (int)QPortSettings::BAUDR_921600;
#elif defined(Q_OS_UNIX) || defined(Q_OS_DARWIN)
const int minBaud = (int)QPortSettings::BAUDR_50;
const int maxBaud = (int)QPortSettings::BAUDR_115200;
#endif
if (rateIndex >= minBaud && rateIndex <= (int)QPortSettings::BAUDR_921600)
if (rateIndex >= minBaud && rateIndex <= maxBaud)
{
portSettings.setBaudRate((QPortSettings::BaudRate)rateIndex);
}
......@@ -932,8 +947,6 @@ bool SerialLink::setBaudRateString(const QString& rate)
bool SerialLink::setBaudRate(int rate)
{
//qDebug() << "BAUD RATE:" << rate;
bool reconnect = false;
bool accepted = true; // This is changed if none of the data rates matches
if(isConnected()) {
......@@ -941,18 +954,17 @@ bool SerialLink::setBaudRate(int rate)
}
disconnect();
// This switch-statment relies on the mapping given in qportsettings.h from the QSerialPort library.
switch (rate) {
#ifndef Q_OS_WIN
// Baud rates supported only by non-Windows systems
#if defined(Q_OS_UNIX) || defined(Q_OS_LINUX) || defined(Q_OS_DARWIN)
case 50:
portSettings.setBaudRate(QPortSettings::BAUDR_50);
break;
case 75:
portSettings.setBaudRate(QPortSettings::BAUDR_75);
break;
case 110:
portSettings.setBaudRate(QPortSettings::BAUDR_110);
break;
case 134:
portSettings.setBaudRate(QPortSettings::BAUDR_134);
break;
......@@ -962,7 +974,50 @@ bool SerialLink::setBaudRate(int rate)
case 200:
portSettings.setBaudRate(QPortSettings::BAUDR_200);
break;
case 1800:
portSettings.setBaudRate(QPortSettings::BAUDR_1800);
break;
#endif
// Supported only by Linux
#ifdef Q_OS_LINUX
case 230400:
portSettings.setBaudRate(QPortSettings::BAUDR_230400);
break;
case 460800:
portSettings.setBaudRate(QPortSettings::BAUDR_460800);
break;
case 500000:
portSettings.setBaudRate(QPortSettings::BAUDR_500000);
break;
case 576000:
portSettings.setBaudRate(QPortSettings::BAUDR_576000);
break;
case 921600:
portSettings.setBaudRate(QPortSettings::BAUDR_921600);
break;
#endif
// Baud rates supported only by windows
#if defined(Q_OS_WIN32) || defined(Q_OS_WINCE)
case 14400:
portSettings.setBaudRate(QPortSettings::BAUDR_14400);
break;
case 56000:
portSettings.setBaudRate(QPortSettings::BAUDR_56000);
break;
case 128000:
portSettings.setBaudRate(QPortSettings::BAUDR_128000);
break;
case 256000:
portSettings.setBaudRate(QPortSettings::BAUDR_256000);
break;
#endif
// Supported by all OSes:
case 110:
portSettings.setBaudRate(QPortSettings::BAUDR_110);
break;
case 300:
portSettings.setBaudRate(QPortSettings::BAUDR_300);
break;
......@@ -972,11 +1027,6 @@ bool SerialLink::setBaudRate(int rate)
case 1200:
portSettings.setBaudRate(QPortSettings::BAUDR_1200);
break;
#ifndef Q_OS_WIN
case 1800:
portSettings.setBaudRate(QPortSettings::BAUDR_1800);
break;
#endif
case 2400:
portSettings.setBaudRate(QPortSettings::BAUDR_2400);
break;
......@@ -986,50 +1036,18 @@ bool SerialLink::setBaudRate(int rate)
case 9600:
portSettings.setBaudRate(QPortSettings::BAUDR_9600);
break;
#ifdef Q_OS_WIN
case 14400:
portSettings.setBaudRate(QPortSettings::BAUDR_14400);
break;
#endif
case 19200:
portSettings.setBaudRate(QPortSettings::BAUDR_19200);
break;
case 38400:
portSettings.setBaudRate(QPortSettings::BAUDR_38400);
break;
#ifdef Q_OS_WIN
case 56000:
portSettings.setBaudRate(QPortSettings::BAUDR_56000);
break;
#endif
case 57600:
portSettings.setBaudRate(QPortSettings::BAUDR_57600);
break;
#ifdef Q_OS_WIN_XXXX // FIXME CHECK THIS
case 76800:
portSettings.setBaudRate(QPortSettings::BAUDR_76800);
break;
#endif
case 115200:
portSettings.setBaudRate(QPortSettings::BAUDR_115200);
break;
#ifdef Q_OS_WIN
case 128000:
portSettings.setBaudRate(QPortSettings::BAUDR_128000);
break;
case 230400:
portSettings.setBaudRate(QPortSettings::BAUDR_230400);
break;
case 256000:
portSettings.setBaudRate(QPortSettings::BAUDR_256000);
break;
case 460800:
portSettings.setBaudRate(QPortSettings::BAUDR_460800);
break;
#endif
case 921600:
portSettings.setBaudRate(QPortSettings::BAUDR_921600);
break;
default:
// If none of the above cases matches, there must be an error
accepted = false;
......
......@@ -43,10 +43,13 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
waypointManager(this),
thrustSum(0),
thrustMax(10),
startVoltage(0),
startVoltage(-1.0f),
tickVoltage(10.5f),
lastTickVoltageValue(13.0f),
tickLowpassVoltage(12.0f),
warnVoltage(9.5f),
warnLevelPercent(20.0f),
currentVoltage(12.0f),
currentVoltage(12.6f),
lpVoltage(12.0f),
batteryRemainingEstimateEnabled(true),
mode(-1),
......@@ -333,15 +336,17 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
}
}
QString audiostring = "System " + getUASName();
QString audiostring = QString("System %1").arg(uasId);
QString stateAudio = "";
QString modeAudio = "";
QString navModeAudio = "";
bool statechanged = false;
bool modechanged = false;
QString audiomodeText = getAudioModeTextFor(static_cast<int>(state.base_mode));
if (state.system_status != this->status)
if ((state.system_status != this->status) && state.system_status != MAV_STATE_UNINIT)
{
statechanged = true;
this->status = state.system_status;
......@@ -362,7 +367,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit modeChanged(this->getUASID(), shortModeText, "");
modeAudio = " is now in " + shortModeText;
modeAudio = " is now in " + audiomodeText;
}
if (navMode != state.custom_mode)
......@@ -423,8 +428,22 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
// Battery charge/time remaining/voltage calculations
currentVoltage = state.voltage_battery/1000.0f;
lpVoltage = filterVoltage(currentVoltage);
tickLowpassVoltage = tickLowpassVoltage*0.8f + 0.2f*currentVoltage;
// We don't want to tick above the threshold
if (tickLowpassVoltage > tickVoltage)
{
lastTickVoltageValue = tickLowpassVoltage;
}
if ((startVoltage > 0.0f) && (tickLowpassVoltage < tickVoltage) && (fabs(lastTickVoltageValue - tickLowpassVoltage) > 0.1f)
&& (lpVoltage < tickVoltage))
{
GAudioOutput::instance()->say(QString("voltage warning: %1 volt").arg(lpVoltage, 2));
lastTickVoltageValue = tickLowpassVoltage;
}
if (startVoltage == 0) startVoltage = currentVoltage;
if (startVoltage == -1.0f && currentVoltage > 0.1f) startVoltage = currentVoltage;
timeRemaining = calculateTimeRemaining();
if (!batteryRemainingEstimateEnabled && chargeLevel != -1)
{
......@@ -442,7 +461,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
}
// LOW BATTERY ALARM
if (lpVoltage < warnVoltage)
if (lpVoltage < warnVoltage && (startVoltage > 0.0f))
{
startLowBattAlarm();
}
......@@ -451,6 +470,8 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
stopLowBattAlarm();
}
qDebug() << "START" << startVoltage;
// control_sensors_enabled:
// relevant bits: 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control
......@@ -2357,6 +2378,45 @@ const QString& UAS::getShortState() const
return shortStateText;
}
QString UAS::getAudioModeTextFor(int id)
{
QString mode;
uint8_t modeid = id;
// BASE MODE DECODING
if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_AUTO)
{
mode += "autonomous";
}
else if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_GUIDED)
{
mode += "guided";
}
else if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_MANUAL)
{
mode += "manual";
}
if (modeid != 0)
{
mode += " mode";
}
// ARMED STATE DECODING
if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_SAFETY)
{
mode.append(" and armed");
}
// HARDWARE IN THE LOOP DECODING
if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_HIL)
{
mode.append(" using hardware in the loop simulation");
}
return mode;
}
QString UAS::getShortModeTextFor(int id)
{
QString mode;
......
......@@ -75,6 +75,8 @@ public:
const QString& getShortMode() const;
/** @brief Translate from mode id to text */
static QString getShortModeTextFor(int id);
/** @brief Translate from mode id to audio text */
static QString getAudioModeTextFor(int id);
/** @brief Get the unique system id */
int getUASID() const;
/** @brief Get the airframe */
......@@ -211,6 +213,9 @@ protected: //COMMENTS FOR TEST UNIT
float fullVoltage; ///< Voltage of the fully charged battery (100%)
float emptyVoltage; ///< Voltage of the empty battery (0%)
float startVoltage; ///< Voltage at system start
float tickVoltage; ///< Voltage where 0.1 V ticks are told
float lastTickVoltageValue; ///< The last voltage where a tick was announced
float tickLowpassVoltage; ///< Lowpass-filtered voltage for the tick announcement
float warnVoltage; ///< Voltage where QGC will start to warn about low battery
float warnLevelPercent; ///< Warning level, in percent
double currentVoltage; ///< Voltage currently measured
......
......@@ -910,12 +910,6 @@ void HSIDisplay::sendBodySetPointCoordinates()
// Send the coordinates to the MAV
if (uas)
{
double dx = uiXSetCoordinate - uas->getLocalX();
double dy = uiYSetCoordinate - uas->getLocalY();
double dz = uiZSetCoordinate - uas->getLocalZ();
bool valid = (sqrt(dx*dx + dy*dy + dz*dz) < 200.0);//UASManager::instance()->isInLocalNEDSafetyLimits(uiXSetCoordinate, uiYSetCoordinate, uiZSetCoordinate);
// if (valid)
// {
uas->setLocalPositionSetpoint(uiXSetCoordinate, uiYSetCoordinate, uiZSetCoordinate, uiYawSet);
}
}
......
......@@ -1211,23 +1211,24 @@ void MainWindow::UASCreated(UASInterface* uas)
QIcon icon;
// Set matching icon
switch (uas->getSystemType()) {
case 0:
switch (uas->getSystemType())
{
case MAV_TYPE_GENERIC:
icon = QIcon(":/images/mavs/generic.svg");
break;
case 1:
case MAV_TYPE_FIXED_WING:
icon = QIcon(":/images/mavs/fixed-wing.svg");
break;
case 2:
case MAV_TYPE_QUADROTOR:
icon = QIcon(":/images/mavs/quadrotor.svg");
break;
case 3:
case MAV_TYPE_COAXIAL:
icon = QIcon(":/images/mavs/coaxial.svg");
break;
case 4:
case MAV_TYPE_HELICOPTER:
icon = QIcon(":/images/mavs/helicopter.svg");
break;
case 5:
case MAV_TYPE_GCS:
icon = QIcon(":/images/mavs/groundstation.svg");
break;
default:
......
......@@ -59,39 +59,55 @@ SerialConfigurationWindow::SerialConfigurationWindow(LinkInterface* link, QWidge
// Set up baud rates
ui.baudRate->clear();
ui.baudRate->addItem("50", 50);
ui.baudRate->addItem("70", 70);
ui.baudRate->addItem("110", 110);
ui.baudRate->addItem("134", 134);
ui.baudRate->addItem("150", 150);
ui.baudRate->addItem("200", 200);
ui.baudRate->addItem("300", 300);
ui.baudRate->addItem("600", 600);
ui.baudRate->addItem("1200", 1200);
ui.baudRate->addItem("1800", 1800);
ui.baudRate->addItem("2400", 2400);
ui.baudRate->addItem("4800", 4800);
ui.baudRate->addItem("9600", 9600);
#ifdef Q_OS_WIN
ui.baudRate->addItem("14400", 14400);
#endif
ui.baudRate->addItem("19200", 19200);
ui.baudRate->addItem("38400", 38400);
#ifdef Q_OS_WIN
ui.baudRate->addItem("56000", 56000);
// Keep track of all desired baud rates by OS. These are iterated through
// later and added to ui.baudRate.
QList<int> supportedBaudRates;
// Baud rates supported only by POSIX systems
#if defined(Q_OS_UNIX) || defined(Q_OS_LINUX) || defined(Q_OS_DARWIN)
supportedBaudRates << 50;
supportedBaudRates << 75;
supportedBaudRates << 134;
supportedBaudRates << 150;
supportedBaudRates << 200;
supportedBaudRates << 1800;
#endif
ui.baudRate->addItem("57600", 57600);
#ifdef Q_OS_WIN
ui.baudRate->addItem("76800", 76800);
// Baud rates supported only by Linux
#if defined(Q_OS_LINUX)
supportedBaudRates << 230400;
supportedBaudRates << 460800;
supportedBaudRates << 500000;
supportedBaudRates << 576000;
supportedBaudRates << 921600;
#endif
ui.baudRate->addItem("115200", 115200);
#ifdef Q_OS_WIN
ui.baudRate->addItem("128000", 128000);
ui.baudRate->addItem("230400", 230400);
ui.baudRate->addItem("256000", 256000);
ui.baudRate->addItem("460800", 460800);
// Baud rates supported only by Windows
#if defined(Q_OS_WIN)
supportedBaudRates << 14400;
supportedBaudRates << 56000;
supportedBaudRates << 128000;
supportedBaudRates << 256000;
#endif
ui.baudRate->addItem("921600", 921600);
// Baud rates supported by everyone
supportedBaudRates << 110;
supportedBaudRates << 300;
supportedBaudRates << 600;
supportedBaudRates << 1200;
supportedBaudRates << 2400;
supportedBaudRates << 4800;
supportedBaudRates << 9600;
supportedBaudRates << 19200;
supportedBaudRates << 38400;
supportedBaudRates << 57600;
supportedBaudRates << 115200;
// Now actually add all of our supported baud rates to the UI.
qSort(supportedBaudRates.begin(), supportedBaudRates.end());
for (int i = 0; i < supportedBaudRates.size(); ++i) {
ui.baudRate->addItem(QString::number(supportedBaudRates.at(i)), supportedBaudRates.at(i));
}
connect(action, SIGNAL(triggered()), this, SLOT(configureCommunication()));
......
......@@ -39,7 +39,7 @@ void QGCMAVLinkMessageSender::refresh()
bool QGCMAVLinkMessageSender::sendMessage()
{
sendMessage(ui->messageIdSpinBox->value());
return sendMessage(ui->messageIdSpinBox->value());
}
bool QGCMAVLinkMessageSender::sendMessage(unsigned int msgid)
......
......@@ -93,8 +93,10 @@ public:
BAUDR_200,
BAUDR_1800,
//BAUDR_76800,
BAUDR_500000,
BAUDR_576000,
#endif
#ifdef Q_OS_LINUX
// BAUDR_500000,
// BAUDR_576000,
#endif
#ifdef TNX_WINDOWS_SERIAL_PORT
BAUDR_14400,
......@@ -116,7 +118,9 @@ public:
BAUDR_115200,
BAUDR_230400,
BAUDR_460800,
BAUDR_921600
BAUDR_500000,
BAUDR_576000,
BAUDR_921600,
};
enum DataBits {
......@@ -168,7 +172,7 @@ public:
baudRate_ = baudRate;
switch ( baudRate_ ) {
#ifdef TNX_POSIX_SERIAL_PORT
#ifdef TNX_POSIX_SERIAL_PORT
case BAUDR_50: baudRateInt_=50; break;
case BAUDR_75: baudRateInt_=75; break;
case BAUDR_134: baudRateInt_=134; break;
......@@ -176,17 +180,17 @@ public:
case BAUDR_200: baudRateInt_=200; break;
case BAUDR_1800: baudRateInt_=1800; break;
//case 76800: baudRateInt_=76800; break;
#endif
#ifdef TNX_WINDOWS_SERIAL_PORT
#endif
#ifdef TNX_WINDOWS_SERIAL_PORT
case BAUDR_14400: baudRateInt_=14400; break;
case BAUDR_56000: baudRateInt_=56000; break;
case BAUDR_128000: baudRateInt_=128000; break;
case BAUDR_256000: baudRateInt_=256000; break;
#endif
#if defined(Q_OS_LINUX)
#endif
#if defined(Q_OS_LINUX)
case BAUDR_500000: baudRateInt_=500000; break;
case BAUDR_576000: baudRateInt_=576000; break;
#endif
#endif
// baud rates supported by all platforms
case BAUDR_110: baudRateInt_=110; break;
case BAUDR_300: baudRateInt_=300; break;
......
......@@ -147,16 +147,10 @@ QPortSettings::BaudRate QPortSettings::baudRateFromInt(int baud, bool &ok)
return BAUDR_256000;
#endif
#if defined(Q_OS_LINUX)
case 230400:
return BAUDR_230400;
case 460800:
return BAUDR_460800;
case 500000:
return BAUDR_500000;
case 576000:
return BAUDR_576000;
case 921600:
return BAUDR_921600;
#endif
// baud rates supported by all platforms
case 110:
......@@ -181,6 +175,12 @@ QPortSettings::BaudRate QPortSettings::baudRateFromInt(int baud, bool &ok)
return BAUDR_57600;
case 115200:
return BAUDR_115200;
case 230400:
return BAUDR_230400;
case 460800:
return BAUDR_460800;
case 921600:
return BAUDR_921600;
default:
ok = false;
return BAUDR_9600;
......
......@@ -316,16 +316,16 @@ void TermiosHelper::setBaudRate(QPortSettings::BaudRate baudRate)
"Unsupported baud rate";
}
//#ifdef Q_OS_MAC
// if ( ioctl( fileDescriptor_, IOSSIOSPEED, &baud ) == -1 )
// {
// qCritical() << QString("TermiosHelper::setBaudRate(file: %1) failed: %2(%3)")
// .arg(fileDescriptor_)
// .arg(strerror(errno))
// .arg(errno);
// return false;
// }
//#else
//#ifdef Q_OS_MAC
// if ( ioctl( fileDescriptor_, IOSSIOSPEED, &baud ) == -1 )
// {
// qCritical() << QString("TermiosHelper::setBaudRate(file: %1) failed: %2(%3)")
// .arg(fileDescriptor_)
// .arg(strerror(errno))
// .arg(errno);
// return false;
// }
//#else
if ( cfsetspeed(currentAttrs_, baud) == -1 ) {
qCritical() << QString("TermiosHelper::setBaudRate(file: %1) failed: %2(%3)")
......@@ -333,7 +333,7 @@ void TermiosHelper::setBaudRate(QPortSettings::BaudRate baudRate)
.arg(strerror(errno))
.arg(errno);
}
//#endif
//#endif
}
/*!
......@@ -386,19 +386,23 @@ QPortSettings::BaudRate TermiosHelper::baudRate() const
// return QPortSettings::BAUDR_76800;
case B115200:
return QPortSettings::BAUDR_115200;
#if defined(Q_OS_LINUX)
#ifdef B230400
case B230400:
return QPortSettings::BAUDR_230400;
// the baud rates listed below are not supported by all UARTs
// and Linux distros
#endif
#ifdef B460800
case B460800:
return QPortSettings::BAUDR_460800;
#endif
#ifdef B921600
case B921600:
return QPortSettings::BAUDR_921600;
#endif
#if defined(Q_OS_LINUX)
case B500000:
return QPortSettings::BAUDR_500000;
case B576000:
return QPortSettings::BAUDR_576000;
case B921600:
return QPortSettings::BAUDR_921600;
#endif
default:
qWarning() << "TermiosHelper::baudRate(): Unknown baud rate";
......
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