diff --git a/qgroundcontrol.pri b/qgroundcontrol.pri index 4308af851a9a2432a27c99e5affe2f2de64cf33e..c20a4b3d86073987afb1952aad514248bde28dbf 100644 --- a/qgroundcontrol.pri +++ b/qgroundcontrol.pri @@ -192,7 +192,8 @@ linux-g++|linux-g++-64{ INCLUDEPATH += /usr/include \ /usr/local/include \ - /usr/include/qt4/phonon + /usr/include/qt4/phonon \ + /usr/include/phonon LIBS += \ -L/usr/lib \ @@ -228,7 +229,8 @@ linux-g++|linux-g++-64{ DEFINES += QGC_OSG_QT_ENABLED } - exists(/usr/local/include/google/protobuf) { + exists(/usr/local/include/google/protobuf) | + exists(/usr/include/google/protobuf) { message("Building support for Protocol Buffers") DEPENDENCIES_PRESENT += protobuf # Include Protocol Buffers libraries @@ -239,7 +241,8 @@ linux-g++|linux-g++-64{ DEFINES += QGC_PROTOBUF_ENABLED } - exists(/usr/local/include/libfreenect/libfreenect.h) { + exists(/usr/local/include/libfreenect/libfreenect.h) | + exists(/usr/include/libfreenect/libfreenect.h) { message("Building support for libfreenect") DEPENDENCIES_PRESENT += libfreenect INCLUDEPATH += /usr/include/libusb-1.0 @@ -269,7 +272,7 @@ linux-g++ { linux-g++-64 { message("Building for GNU/Linux 64bit/x64 (g++-64)") exists(/usr/local/lib64) { - LIBS += -L/usr/local/lib64 + LIBS += -L/usr/local/lib64 -L/usr/lib64 } } diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index df6f4f3d6b4ca4a64a6be8c2e401562a0be5d7ad..e3030dc99e598926ac496037590a326966423f67 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -382,7 +382,6 @@ HEADERS += src/MG.h \ src/ui/QGCMAVLinkInspector.h \ src/ui/MAVLinkDecoder.h \ src/ui/WaypointViewOnlyView.h \ - src/ui/WaypointViewOnlyView.h \ src/ui/WaypointEditableView.h \ src/ui/QGCRGBDView.h \ src/ui/mavlink/QGCMAVLinkMessageSender.h \ diff --git a/src/QGCCore.cc b/src/QGCCore.cc index 8aae8771fbf3bee83e37961081bf79e912b95289..51d6eee1e28892c72dd288e4bba13082a815d99b 100644 --- a/src/QGCCore.cc +++ b/src/QGCCore.cc @@ -148,6 +148,9 @@ QGCCore::QGCCore(int &argc, char* argv[]) : QApplication(argc, argv) // first messages arrive UDPLink* udpLink = new UDPLink(QHostAddress::Any, 14550); MainWindow::instance()->addLink(udpLink); + // Listen on Multicast-Address 239.255.77.77, Port 14550 + //QHostAddress * multicast_udp = new QHostAddress("239.255.77.77"); + //UDPLink* udpLink = new UDPLink(*multicast_udp, 14550); #ifdef OPAL_RT // Add OpalRT Link, but do not connect @@ -168,7 +171,27 @@ QGCCore::QGCCore(int &argc, char* argv[]) : QApplication(argc, argv) if (upgraded) mainWindow->showInfoMessage(tr("Default Settings Loaded"), tr("qgroundcontrol has been upgraded from version %1 to version %2. Some of your user preferences have been reset to defaults for safety reasons. Please adjust them where needed.").arg(lastApplicationVersion).arg(QGC_APPLICATION_VERSION)); - + // Check if link could be connected + if (!udpLink->connect()) + { + QMessageBox msgBox; + msgBox.setIcon(QMessageBox::Critical); + msgBox.setText("Could not connect UDP port. Is an instance of " + qAppName() + "already running?"); + msgBox.setInformativeText("It is recommended to close the application and stop all instances. Click Yes to close."); + msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::No); + msgBox.setDefaultButton(QMessageBox::No); + int ret = msgBox.exec(); + + // Close the message box shortly after the click to prevent accidental clicks + QTimer::singleShot(15000, &msgBox, SLOT(reject())); + + // Exit application + if (ret == QMessageBox::Yes) + { + //mainWindow->close(); + QTimer::singleShot(200, mainWindow, SLOT(close())); + } + } } /** diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 3076f3292dce9b4a3be6129fe3f3f2344361b1c8..0759a23cb1cc8b0e4921b81ace034260006420b2 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -38,7 +38,10 @@ * as the previous one created unless one calls deleteSettings in the code after * creating the UAS. */ + UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(), + lipoFull(4.2f), + lipoEmpty(3.5f), uasId(id), links(new QList()), unknownPackets(), @@ -3325,45 +3328,55 @@ QString UAS::getAudioModeTextFor(int id) return mode; } +/** +* The mode returned can be auto, stabilized, test, manual, preflight or unknown. +* @return the short text of the mode for the id given. +*/ /** * The mode returned can be auto, stabilized, test, manual, preflight or unknown. * @return the short text of the mode for the id given. */ QString UAS::getShortModeTextFor(int id) { - QString mode; + QString mode = ""; uint8_t modeid = id; - qDebug() << "MODE:" << modeid; // BASE MODE DECODING - if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_AUTO) - { - mode += "|AUTO"; - } - else if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_GUIDED) - { - mode += "|VECTOR"; - } - if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_STABILIZE) - { - mode += "|STABILIZED"; - } - else if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_TEST) - { - mode += "|TEST"; - } - else if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_MANUAL) - { - mode += "|MANUAL"; - } - else if (modeid == 0) + + if (modeid == 0) { mode = "|PREFLIGHT"; } - else + else { + if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_AUTO){ + mode += "|AUTO"; + } + + if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_MANUAL){ + mode += "|MANUAL"; + } + + if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_GUIDED){ + mode += "|VECTOR"; + } + + if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_STABILIZE){ + mode += "|STABILIZED"; + } + + + if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_TEST){ + mode += "|TEST"; + } + + + } + + if (mode.length() == 0) { mode = "|UNKNOWN"; + qDebug() << __FILE__ << __LINE__ << " Unknown modeid: " << modeid; } // ARMED STATE DECODING @@ -3382,6 +3395,8 @@ QString UAS::getShortModeTextFor(int id) mode.prepend("HIL:"); } + qDebug() << "MODE: " << modeid << " " << mode; + return mode; } @@ -3445,8 +3460,8 @@ void UAS::setBattery(BatteryType type, int cells) case LIION: break; case LIPOLY: - fullVoltage = this->cells * UAS::lipoFull; - emptyVoltage = this->cells * UAS::lipoEmpty; + fullVoltage = this->cells * lipoFull; + emptyVoltage = this->cells * lipoEmpty; break; case LIFE: break; diff --git a/src/uas/UAS.h b/src/uas/UAS.h index 95570049a10f8ce94339c6106521d58834c2d161..b1c027bd1f55cb9039a0c0351322702ff0237d38 100644 --- a/src/uas/UAS.h +++ b/src/uas/UAS.h @@ -56,8 +56,8 @@ public: UAS(MAVLinkProtocol* protocol, int id = 0); ~UAS(); - static const int lipoFull = 4.2f; ///< 100% charged voltage - static const int lipoEmpty = 3.5f; ///< Discharged voltage + float lipoFull; ///< 100% charged voltage + float lipoEmpty; ///< Discharged voltage /* MANAGEMENT */ diff --git a/src/ui/QGCParamWidget.cc b/src/ui/QGCParamWidget.cc index 4758fca14ea979790fa4de97899ac76924ee6c5b..94e1697b52a7502b2d6db2abb84dd6dc412fc8f3 100644 --- a/src/ui/QGCParamWidget.cc +++ b/src/ui/QGCParamWidget.cc @@ -705,7 +705,7 @@ void QGCParamWidget::parameterItemChanged(QTreeWidgetItem* current, int column) current->setBackground(1, QBrush(QColor(QGC::colorOrange))); } - switch (parameters.value(key)->value(str).type()) + switch ((int)parameters.value(key)->value(str).type()) { case QVariant::Int: { @@ -766,7 +766,7 @@ void QGCParamWidget::saveParameters() { QString paramValue("%1"); QString paramType("%1"); - switch (j.value().type()) + switch ((int)j.value().type()) { case QVariant::Int: paramValue = paramValue.arg(j.value().toInt()); @@ -777,7 +777,9 @@ void QGCParamWidget::saveParameters() paramType = paramType.arg(MAV_PARAM_TYPE_UINT32); break; case QMetaType::Float: - paramValue = paramValue.arg(j.value().toDouble(), 25, 'g', 12); + // We store parameters as floats, with only 6 digits of precision guaranteed for decimal string conversion + // (see IEEE 754, 32 bit single-precision) + paramValue = paramValue.arg((double)j.value().toFloat(), 25, 'g', 6); paramType = paramType.arg(MAV_PARAM_TYPE_REAL32); break; default: @@ -955,7 +957,7 @@ void QGCParamWidget::retransmissionGuardTick() if (count < retransmissionBurstRequestSize) { // Re-request write operation QVariant value = missingParams->value(key); - switch (parameters.value(component)->value(key).type()) + switch ((int)parameters.value(component)->value(key).type()) { case QVariant::Int: { @@ -1025,7 +1027,7 @@ void QGCParamWidget::setParameter(int component, QString parameterName, QVariant return; } - switch (parameters.value(component)->value(parameterName).type()) + switch ((int)parameters.value(component)->value(parameterName).type()) { case QVariant::Char: { diff --git a/src/ui/map/QGCMapToolBar.cc b/src/ui/map/QGCMapToolBar.cc index eebc1f75ee0bc9a3e650abf6cc138efe366f1437..067544bcd228941c50a5aeadeab70ef6dac2a9d4 100644 --- a/src/ui/map/QGCMapToolBar.cc +++ b/src/ui/map/QGCMapToolBar.cc @@ -7,8 +7,10 @@ QGCMapToolBar::QGCMapToolBar(QWidget *parent) : ui(new Ui::QGCMapToolBar), map(NULL), optionsMenu(this), + mapTypesMenu(this), trailPlotMenu(this), updateTimesMenu(this), + mapTypesGroup(new QActionGroup(this)), trailSettingsGroup(new QActionGroup(this)), updateTimesGroup(new QActionGroup(this)) { @@ -45,21 +47,43 @@ void QGCMapToolBar::setMap(QGCMapWidget* map) // Set exclusive items trailSettingsGroup->setExclusive(true); updateTimesGroup->setExclusive(true); - + mapTypesGroup->setExclusive(true); // Build up menu trailPlotMenu.setTitle(tr("&Add trail dot every..")); updateTimesMenu.setTitle(tr("&Limit map view update rate to..")); + mapTypesMenu.setTitle(tr("&Map type")); - // FIXME MARK CURRENT VALUES IN MENU - QAction* action = trailPlotMenu.addAction(tr("No trail"), this, SLOT(setUAVTrailTime())); - action->setData(-1); + + //setup the mapTypesMenu + QAction* action; + action = mapTypesMenu.addAction(tr("Bing Hybrid"),this,SLOT(setMapType())); + action->setData(MapType::BingHybrid); + action->setCheckable(true); + mapTypesGroup->addAction(action); + + action = mapTypesMenu.addAction(tr("Google Hybrid"),this,SLOT(setMapType())); + action->setData(MapType::GoogleHybrid); + action->setCheckable(true); + mapTypesGroup->addAction(action); + + action = mapTypesMenu.addAction(tr("OpenStreetMap"),this,SLOT(setMapType())); + action->setData(MapType::OpenStreetMap); action->setCheckable(true); - trailSettingsGroup->addAction(action); + mapTypesGroup->addAction(action); + //TODO check current item + optionsMenu.addMenu(&mapTypesMenu); + + + // FIXME MARK CURRENT VALUES IN MENU + QAction *defaultTrailAction = trailPlotMenu.addAction(tr("No trail"), this, SLOT(setUAVTrailTime())); + defaultTrailAction->setData(-1); + defaultTrailAction->setCheckable(true); + trailSettingsGroup->addAction(defaultTrailAction); for (int i = 0; i < uavTrailTimeCount; ++i) { - QAction* action = trailPlotMenu.addAction(tr("%1 second%2").arg(uavTrailTimeList[i]).arg((uavTrailTimeList[i] > 1) ? "s" : ""), this, SLOT(setUAVTrailTime())); + action = trailPlotMenu.addAction(tr("%1 second%2").arg(uavTrailTimeList[i]).arg((uavTrailTimeList[i] > 1) ? "s" : ""), this, SLOT(setUAVTrailTime())); action->setData(uavTrailTimeList[i]); action->setCheckable(true); trailSettingsGroup->addAction(action); @@ -71,7 +95,7 @@ void QGCMapToolBar::setMap(QGCMapWidget* map) } for (int i = 0; i < uavTrailDistanceCount; ++i) { - QAction* action = trailPlotMenu.addAction(tr("%1 meter%2").arg(uavTrailDistanceList[i]).arg((uavTrailDistanceList[i] > 1) ? "s" : ""), this, SLOT(setUAVTrailDistance())); + action = trailPlotMenu.addAction(tr("%1 meter%2").arg(uavTrailDistanceList[i]).arg((uavTrailDistanceList[i] > 1) ? "s" : ""), this, SLOT(setUAVTrailDistance())); action->setData(uavTrailDistanceList[i]); action->setCheckable(true); trailSettingsGroup->addAction(action); @@ -85,7 +109,7 @@ void QGCMapToolBar::setMap(QGCMapWidget* map) // Set no trail checked if no action is checked yet if (!trailSettingsGroup->checkedAction()) { - action->setChecked(true); + defaultTrailAction->setChecked(true); } optionsMenu.addMenu(&trailPlotMenu); @@ -119,7 +143,6 @@ void QGCMapToolBar::setMap(QGCMapWidget* map) } optionsMenu.addMenu(&updateTimesMenu); - ui->optionsButton->setMenu(&optionsMenu); } } @@ -175,6 +198,23 @@ void QGCMapToolBar::setUpdateInterval() } } +void QGCMapToolBar::setMapType() +{ + QObject* sender = QObject::sender(); + QAction* action = qobject_cast(sender); + + if (action) + { + bool ok; + int mapType = action->data().toInt(&ok); + if (ok) + { + map->SetMapType((MapType::Types)mapType); + ui->posLabel->setText(tr("Map type: %1").arg(mapType)); + } + } +} + void QGCMapToolBar::tileLoadStart() { ui->posLabel->setText(tr("Starting to load tiles..")); @@ -201,10 +241,12 @@ void QGCMapToolBar::tileLoadProgress(int progress) } } + QGCMapToolBar::~QGCMapToolBar() { delete ui; delete trailSettingsGroup; delete updateTimesGroup; + delete mapTypesGroup; // FIXME Delete all actions } diff --git a/src/ui/map/QGCMapToolBar.h b/src/ui/map/QGCMapToolBar.h index a7e75f220f64daf5c3a66f35a566a36d753447cb..b03d2b9fdb6864e003a98a9fb019971e1cab54f1 100644 --- a/src/ui/map/QGCMapToolBar.h +++ b/src/ui/map/QGCMapToolBar.h @@ -28,6 +28,7 @@ public slots: void setUAVTrailTime(); void setUAVTrailDistance(); void setUpdateInterval(); + void setMapType(); private: Ui::QGCMapToolBar *ui; @@ -37,8 +38,11 @@ protected: QMenu optionsMenu; QMenu trailPlotMenu; QMenu updateTimesMenu; + QMenu mapTypesMenu; + QActionGroup* trailSettingsGroup; QActionGroup* updateTimesGroup; + QActionGroup* mapTypesGroup; }; #endif // QGCMAPTOOLBAR_H diff --git a/src/ui/map/QGCMapWidget.cc b/src/ui/map/QGCMapWidget.cc index 67b3c711d2859d3ae5caad0a185eb56521297bf2..9146e347ab0093e32dd03e5d3f0da6e169af3195 100644 --- a/src/ui/map/QGCMapWidget.cc +++ b/src/ui/map/QGCMapWidget.cc @@ -30,6 +30,12 @@ QGCMapWidget::QGCMapWidget(QWidget *parent) : defaultGuidedAlt = -1; loadSettings(false); + //handy for debugging: + //this->SetShowTileGridLines(true); + + //default appears to be Google Hybrid, and is broken currently + this->SetMapType(MapType::BingHybrid); + this->setContextMenuPolicy(Qt::ActionsContextMenu); QAction *guidedaction = new QAction(this); @@ -519,6 +525,7 @@ void QGCMapWidget::updateHomePosition(double latitude, double longitude, double void QGCMapWidget::goHome() { SetCurrentPosition(Home->Coord()); + SetZoom(18); //zoom to "large RC park" size } /** diff --git a/src/ui/uas/QGCMessageView.cc b/src/ui/uas/QGCMessageView.cc index fcd0f18d7f8bac9dcb7c9015c4f09cac390f6fbc..67a28216f377c1ef70c5d5a6cc72d50dfe24e150 100644 --- a/src/ui/uas/QGCMessageView.cc +++ b/src/ui/uas/QGCMessageView.cc @@ -4,6 +4,7 @@ #include "UASManager.h" #include "QGCUnconnectedInfoWidget.h" #include +#include QGCMessageView::QGCMessageView(QWidget *parent) : QWidget(parent), @@ -55,9 +56,18 @@ void QGCMessageView::handleTextMessage(int uasid, int componentid, int severity, { // XXX color messages according to severity - ui->plainTextEdit->appendHtml(QString("[%2:%3] %4\n").arg(UASManager::instance()->getUASForId(uasid)->getColor().name()).arg(UASManager::instance()->getUASForId(uasid)->getUASName()).arg(componentid).arg(text)); + QPlainTextEdit *msgWidget = ui->plainTextEdit; + + //turn off updates while we're appending content to avoid breaking the autoscroll behavior + msgWidget->setUpdatesEnabled(false); + QScrollBar *scroller = msgWidget->verticalScrollBar(); + + UASInterface *uas = UASManager::instance()->getUASForId(uasid); + msgWidget->appendHtml(QString("[%2:%3] %4\n").arg(uas->getColor().name()).arg(uas->getUASName()).arg(componentid).arg(text)); // Ensure text area scrolls correctly - ui->plainTextEdit->ensureCursorVisible(); + scroller->setValue(scroller->maximum()); + msgWidget->setUpdatesEnabled(true); + } void QGCMessageView::contextMenuEvent(QContextMenuEvent* event) diff --git a/src/ui/uas/UASControlWidget.cc b/src/ui/uas/UASControlWidget.cc index 5c43eddce76117967531fcb66b702e81c1b15cbf..b7d8cf798144797df42414bcb927d3a2e4a02dc9 100644 --- a/src/ui/uas/UASControlWidget.cc +++ b/src/ui/uas/UASControlWidget.cc @@ -51,12 +51,17 @@ UASControlWidget::UASControlWidget(QWidget *parent) : QWidget(parent), connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setUAS(UASInterface*))); ui.modeComboBox->clear(); - ui.modeComboBox->insertItem(0, UAS::getShortModeTextFor(MAV_MODE_PREFLIGHT).remove(0, 2), MAV_MODE_PREFLIGHT); - ui.modeComboBox->insertItem(1, UAS::getShortModeTextFor((MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_MANUAL_INPUT_ENABLED)).remove(0, 2), (MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_MANUAL_INPUT_ENABLED)); - ui.modeComboBox->insertItem(2, UAS::getShortModeTextFor(MAV_MODE_FLAG_MANUAL_INPUT_ENABLED).remove(0, 2), MAV_MODE_FLAG_MANUAL_INPUT_ENABLED); - ui.modeComboBox->insertItem(3, UAS::getShortModeTextFor((MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED)).remove(0, 2), (MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED)); - ui.modeComboBox->insertItem(4, UAS::getShortModeTextFor((MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED | MAV_MODE_FLAG_AUTO_ENABLED)).remove(0, 2), (MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED | MAV_MODE_FLAG_AUTO_ENABLED)); - ui.modeComboBox->insertItem(5, UAS::getShortModeTextFor((MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_TEST_ENABLED)).remove(0, 2), (MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_TEST_ENABLED)); + int modes[] = { + MAV_MODE_PREFLIGHT, + MAV_MODE_FLAG_MANUAL_INPUT_ENABLED, + MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_MANUAL_INPUT_ENABLED, + MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_AUTO_ENABLED, + MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_TEST_ENABLED, + }; + for (int i = 0; i < sizeof(modes) / sizeof(int); i++) { + int mode = modes[i]; + ui.modeComboBox->insertItem(i, UAS::getShortModeTextFor(mode).remove(0, 2), mode); + } connect(ui.modeComboBox, SIGNAL(activated(int)), this, SLOT(setMode(int))); connect(ui.setModeButton, SIGNAL(clicked()), this, SLOT(transmitMode()));