diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 746e28476ec9868574d8ed0abecced48f8fcadd3..60c1cfe8da58f1b6563d69094102086de158f603 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -363,9 +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/map3D/GLOverlayGeode.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 @@ -392,14 +390,16 @@ 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") # Enable only if protobuf is available HEADERS += thirdParty/mavlink/include/pixhawk/pixhawk.pb.h \ - src/ui/map3D/ObstacleGroupNode.h + src/ui/map3D/ObstacleGroupNode.h \ + src/ui/map3D/GLOverlayGeode.h } contains(DEPENDENCIES_PRESENT, libfreenect) { message("Including headers for libfreenect") @@ -505,9 +505,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/map3D/GLOverlayGeode.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 @@ -536,7 +534,9 @@ 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") @@ -549,7 +549,8 @@ contains(DEPENDENCIES_PRESENT, protobuf):contains(MAVLINK_CONF, pixhawk) { # Enable only if protobuf is available SOURCES += thirdParty/mavlink/src/pixhawk/pixhawk.pb.cc \ - src/ui/map3D/ObstacleGroupNode.cc + src/ui/map3D/ObstacleGroupNode.cc \ + src/ui/map3D/GLOverlayGeode.cc } contains(DEPENDENCIES_PRESENT, libfreenect) { message("Including sources for libfreenect") diff --git a/src/comm/SerialLink.cc b/src/comm/SerialLink.cc index 6a296e4236df6bc5162ba63c32d1af8f826a277d..717c3bcfef66531610a5e38e9d21be52855e529b 100644 --- a/src/comm/SerialLink.cc +++ b/src/comm/SerialLink.cc @@ -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 + default: 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,27 +947,24 @@ 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()) { reconnect = true; } 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; diff --git a/src/ui/HSIDisplay.cc b/src/ui/HSIDisplay.cc index 6b61807d51e4009f3653c8a41c6f1d5cad04379e..7aed0c220f2d3781823c7e0398c8915e66de3134 100644 --- a/src/ui/HSIDisplay.cc +++ b/src/ui/HSIDisplay.cc @@ -910,13 +910,7 @@ 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); + uas->setLocalPositionSetpoint(uiXSetCoordinate, uiYSetCoordinate, uiZSetCoordinate, uiYawSet); } } diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index f1f53e4f83a05ce51b96729d9f6e51fe6da1ca90..88a596603dc45096a9c0a223d3206bcf8ac44892 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -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: diff --git a/src/ui/SerialConfigurationWindow.cc b/src/ui/SerialConfigurationWindow.cc index 0d086f5d0e82e8c4d44299198485cbe525fd20b7..2b9f95020bcb3d67acef5e6e036aefbc091c8cd3 100644 --- a/src/ui/SerialConfigurationWindow.cc +++ b/src/ui/SerialConfigurationWindow.cc @@ -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 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())); diff --git a/src/ui/mavlink/QGCMAVLinkMessageSender.cc b/src/ui/mavlink/QGCMAVLinkMessageSender.cc index 82b8d14a65925362b700898df766691cb109d25b..a0c1fcec93c661402c30d471bdf2fa761f9d57d1 100644 --- a/src/ui/mavlink/QGCMAVLinkMessageSender.cc +++ b/src/ui/mavlink/QGCMAVLinkMessageSender.cc @@ -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) diff --git a/thirdParty/qserialport/include/QtSerialPort/qportsettings.h b/thirdParty/qserialport/include/QtSerialPort/qportsettings.h index df0f18852cd6b86e6fed8a9aa5cd41cfe28b549d..390a93e1fa4df2d37715d9c91e3a28695e101aee 100644 --- a/thirdParty/qserialport/include/QtSerialPort/qportsettings.h +++ b/thirdParty/qserialport/include/QtSerialPort/qportsettings.h @@ -95,8 +95,11 @@ public: //BAUDR_76800, #endif #ifdef Q_OS_LINUX + BAUDR_230400, + BAUDR_460800, BAUDR_500000, BAUDR_576000, + BAUDR_921600, #endif #ifdef TNX_WINDOWS_SERIAL_PORT BAUDR_14400, @@ -115,10 +118,7 @@ public: BAUDR_19200, BAUDR_38400, BAUDR_57600, - BAUDR_115200, - BAUDR_230400, - BAUDR_460800, - BAUDR_921600 + BAUDR_115200 }; enum DataBits { @@ -186,8 +186,11 @@ public: case BAUDR_256000: baudRateInt_=256000; break; #endif #if defined(Q_OS_LINUX) + case BAUDR_230400: baudRateInt_=230400; break; + case BAUDR_460800: baudRateInt_=460800; break; case BAUDR_500000: baudRateInt_=500000; break; case BAUDR_576000: baudRateInt_=576000; break; + case BAUDR_921600: baudRateInt_=921600; break; #endif // baud rates supported by all platforms case BAUDR_110: baudRateInt_=110; break; @@ -201,9 +204,6 @@ public: case BAUDR_38400: baudRateInt_=38400; break; case BAUDR_57600: baudRateInt_=57600; break; case BAUDR_115200: baudRateInt_=115200; break; - case BAUDR_230400: baudRateInt_=230400; break; - case BAUDR_460800: baudRateInt_=460800; break; - case BAUDR_921600: baudRateInt_=921600; break; default: baudRateInt_ = 0; // unknown baudrate }