diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 5c85ab357e2c11a8b80f565b29778916193f4528..6aee404a3f9a86a791cf11c71cf17c1b07c836cb 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -156,7 +156,8 @@ FORMS += src/ui/MainWindow.ui \ src/ui/designer/QGCActionButton.ui \ src/ui/QGCMAVLinkLogPlayer.ui \ src/ui/QGCWaypointListMulti.ui \ - src/ui/mission/QGCCustomWaypointAction.ui + src/ui/mission/QGCCustomWaypointAction.ui \ + src/ui/QGCUDPLinkConfiguration.ui INCLUDEPATH += src \ src/ui \ @@ -266,7 +267,8 @@ HEADERS += src/MG.h \ src/comm/MAVLinkSimulationWaypointPlanner.h \ src/comm/MAVLinkSimulationMAV.h \ src/uas/QGCMAVLinkUASFactory.h \ - src/ui/QGCWaypointListMulti.h + src/ui/QGCWaypointListMulti.h \ + src/ui/QGCUDPLinkConfiguration.h # Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler macx|win32-msvc2008: { @@ -391,7 +393,8 @@ SOURCES += src/main.cc \ src/comm/MAVLinkSimulationWaypointPlanner.cc \ src/comm/MAVLinkSimulationMAV.cc \ src/uas/QGCMAVLinkUASFactory.cc \ - src/ui/QGCWaypointListMulti.cc + src/ui/QGCWaypointListMulti.cc \ + src/ui/QGCUDPLinkConfiguration.cc macx|win32-msvc2008: { SOURCES += src/ui/map3D/QGCGoogleEarthView.cc diff --git a/src/comm/MAVLinkProtocol.cc b/src/comm/MAVLinkProtocol.cc index a12fa9dbe050254fa424fae5c562dce8198b2d56..e8b0965dc339f06fe04807fd78cbc3badd579327 100644 --- a/src/comm/MAVLinkProtocol.cc +++ b/src/comm/MAVLinkProtocol.cc @@ -74,7 +74,8 @@ void MAVLinkProtocol::loadSettings() settings.sync(); settings.beginGroup("QGC_MAVLINK_PROTOCOL"); enableHeartbeats(settings.value("HEARTBEATS_ENABLED", m_heartbeatsEnabled).toBool()); - enableVersionCheck(settings.value("VERION_CHECK_ENABLED", m_enable_version_check).toBool()); + enableVersionCheck(settings.value("VERSION_CHECK_ENABLED", m_enable_version_check).toBool()); + enableMultiplexing(settings.value("MULTIPLEXING_ENABLED", m_multiplexingEnabled).toBool()); // Only set logfile if there is a name present in settings if (settings.contains("LOGFILE_NAME") && m_logfile == NULL) @@ -100,7 +101,8 @@ void MAVLinkProtocol::storeSettings() settings.beginGroup("QGC_MAVLINK_PROTOCOL"); settings.setValue("HEARTBEATS_ENABLED", m_heartbeatsEnabled); settings.setValue("LOGGING_ENABLED", m_loggingEnabled); - settings.setValue("VERION_CHECK_ENABLED", m_enable_version_check); + settings.setValue("VERSION_CHECK_ENABLED", m_enable_version_check); + settings.setValue("MULTIPLEXING_ENABLED", m_multiplexingEnabled); settings.setValue("GCS_SYSTEM_ID", systemId); if (m_logfile) { @@ -298,6 +300,21 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) // kind of inefficient, but no issue for a groundstation pc. // It buys as reentrancy for the whole code over all threads emit messageReceived(link, message); + + // Multiplex message if enabled + if (m_multiplexingEnabled) + { + // Get all links connected to this unit + QList links = LinkManager::instance()->getLinksForProtocol(this); + + // Emit message on all links that are currently connected + foreach (LinkInterface* currLink, links) + { + // Only forward this message to the other links, + // not the link the message was received on + if (currLink != link) sendMessage(currLink, message); + } + } } } } @@ -388,6 +405,15 @@ void MAVLinkProtocol::enableHeartbeats(bool enabled) emit heartbeatChanged(enabled); } +void MAVLinkProtocol::enableMultiplexing(bool enabled) +{ + bool changed = false; + if (enabled != m_multiplexingEnabled) changed = true; + + m_multiplexingEnabled = enabled; + if (changed) emit multiplexingChanged(m_multiplexingEnabled); +} + void MAVLinkProtocol::enableLogging(bool enabled) { bool changed = false; @@ -447,21 +473,6 @@ void MAVLinkProtocol::enableVersionCheck(bool enabled) emit versionCheckChanged(enabled); } -bool MAVLinkProtocol::heartbeatsEnabled(void) -{ - return m_heartbeatsEnabled; -} - -bool MAVLinkProtocol::loggingEnabled(void) -{ - return m_loggingEnabled; -} - -bool MAVLinkProtocol::versionCheckEnabled(void) -{ - return m_enable_version_check; -} - /** * The default rate is 1 Hertz. * diff --git a/src/comm/MAVLinkProtocol.h b/src/comm/MAVLinkProtocol.h index d99034cf9445d5c2a2849d30858053cb289521f8..eaa8c10c9d2d918a3bb51db3b0735621ce2eb5f2 100644 --- a/src/comm/MAVLinkProtocol.h +++ b/src/comm/MAVLinkProtocol.h @@ -66,11 +66,13 @@ public: /** @brief The auto heartbeat emission rate in Hertz */ int getHeartbeatRate(); /** @brief Get heartbeat state */ - bool heartbeatsEnabled(void); + bool heartbeatsEnabled() const { return m_heartbeatsEnabled; } /** @brief Get logging state */ - bool loggingEnabled(void); + bool loggingEnabled() const { return m_loggingEnabled; } /** @brief Get protocol version check state */ - bool versionCheckEnabled(void); + bool versionCheckEnabled() const { return m_enable_version_check; } + /** @brief Get the multiplexing state */ + bool multiplexingEnabled() const { return m_multiplexingEnabled; } /** @brief Get the protocol version */ int getVersion() { return MAVLINK_VERSION; } /** @brief Get the name of the packet log file */ @@ -94,6 +96,9 @@ public slots: /** @brief Enable/disable binary packet logging */ void enableLogging(bool enabled); + /** @brief Enabled/disable packet multiplexing */ + void enableMultiplexing(bool enabled); + /** @brief Set log file name */ void setLogfileName(const QString& filename); @@ -113,6 +118,7 @@ protected: int heartbeatRate; ///< Heartbeat rate, controls the timer interval bool m_heartbeatsEnabled; ///< Enabled/disable heartbeat emission bool m_loggingEnabled; ///< Enable/disable packet logging + bool m_multiplexingEnabled; ///< Enable/disable packet multiplexing QFile* m_logfile; ///< Logfile bool m_enable_version_check; ///< Enable checking of version match of MAV and QGC QMutex receiveMutex; ///< Mutex to protect receiveBytes function @@ -131,6 +137,8 @@ signals: void heartbeatChanged(bool heartbeats); /** @brief Emitted if logging is started / stopped */ void loggingChanged(bool enabled); + /** @brief Emitted if multiplexing is started / stopped */ + void multiplexingChanged(bool enabled); /** @brief Emitted if version check is enabled / disabled */ void versionCheckChanged(bool enabled); /** @brief Emitted if a message from the protocol should reach the user */ diff --git a/src/comm/MAVLinkSimulationLink.cc b/src/comm/MAVLinkSimulationLink.cc index 6f08e619e5a5c089539bb97fc96df8675070521f..ed7f0bc7629056cf58a55979d3406bba774520e7 100644 --- a/src/comm/MAVLinkSimulationLink.cc +++ b/src/comm/MAVLinkSimulationLink.cc @@ -619,7 +619,8 @@ void MAVLinkSimulationLink::mainloop() uint8_t gpsLock = 2; uint8_t visLock = 3; uint8_t posLock = qMax(gpsLock, visLock); - messageSize = mavlink_msg_control_status_pack(systemId, componentId, &msg, posLock, visLock, gpsLock, attControl, posXYControl, posZControl, posYawControl); + uint8_t ahrsHealth = 240; + messageSize = mavlink_msg_control_status_pack(systemId, componentId, &msg, posLock, visLock, gpsLock, ahrsHealth, attControl, posXYControl, posZControl, posYawControl); #endif bufferlength = mavlink_msg_to_send_buffer(buffer, &msg); diff --git a/src/comm/MAVLinkSimulationMAV.cc b/src/comm/MAVLinkSimulationMAV.cc index 094fa64c0790298f4007751f9182428293dbd2a6..e896909b8cfd159fe8122cb54e195540ab86a10c 100644 --- a/src/comm/MAVLinkSimulationMAV.cc +++ b/src/comm/MAVLinkSimulationMAV.cc @@ -162,6 +162,29 @@ void MAVLinkSimulationMAV::mainloop() mavlink_msg_sys_status_encode(systemid, MAV_COMP_ID_IMU, &msg, &status); link->sendMAVLinkMessage(&msg); timer10Hz = 5; + + // VFR HUD + mavlink_vfr_hud_t hud; + hud.airspeed = 10; + hud.groundspeed = 9; + hud.alt = 123; + hud.heading = 90; + hud.climb = 0.1; + hud.throttle = 90; + mavlink_msg_vfr_hud_encode(systemid, MAV_COMP_ID_IMU, &msg, &hud); + link->sendMAVLinkMessage(&msg); + + // NAV CONTROLLER + mavlink_nav_controller_output_t nav; + nav.nav_roll = roll; + nav.nav_pitch = pitch; + nav.nav_bearing = yaw; + nav.target_bearing = yaw; + nav.wp_dist = 2; + nav.alt_error = 0.5; + // xtrack + mavlink_msg_nav_controller_output_encode(systemid, MAV_COMP_ID_IMU, &msg, &nav); + link->sendMAVLinkMessage(&msg); } // 25 Hz execution diff --git a/src/comm/UDPLink.cc b/src/comm/UDPLink.cc index 3c3240498e88aa37973cc056e29043c12805e7f5..496067f883a21805c6231f7a0d7a48fa50dd5462 100644 --- a/src/comm/UDPLink.cc +++ b/src/comm/UDPLink.cc @@ -78,9 +78,32 @@ void UDPLink::setAddress(QString address) //socket->setLocalAddress(QHostAddress(address)); } -void UDPLink::setPort(quint16 port) +void UDPLink::setPort(int port) { this->port = port; + disconnect(); + connect(); +} + +/** + * @param host Hostname in standard formatting, e.g. localhost:14551 or 192.168.1.1:14551 + */ +void UDPLink::addHost(const QString& host) +{ + if (host.contains(":")) + { + // Add host + hosts->append(QHostAddress(host.split(":").first())); + // Set port according to user input + ports->append(host.split(":").last().toInt()); + } + else + { + // Add host + hosts->append(QHostAddress(host)); + // Set port according to default (this port) + ports->append(port); + } } diff --git a/src/comm/UDPLink.h b/src/comm/UDPLink.h index fb1eb079c09cfbc57c209ebfe89c5f873cf4117e..cf5bcd573e7be98dfb83560e084613b81d7127e9 100644 --- a/src/comm/UDPLink.h +++ b/src/comm/UDPLink.h @@ -51,6 +51,7 @@ public: bool isConnected(); qint64 bytesAvailable(); + int getPort() const { return port; } /** * @brief The human readable port name @@ -82,7 +83,9 @@ public: public slots: void setAddress(QString address); - void setPort(quint16 port); + void setPort(int port); + /** @brief Add a new host to broadcast messages to */ + void addHost(const QString& host); // void readPendingDatagrams(); void readBytes(); diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 8937591baac195fe6c2de4bd67c0d65f0eb32320..16605184d88db2d5fbf163f690f0be5f8f1336af 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -162,13 +162,13 @@ void UAS::receiveMessageNamedValue(const mavlink_message_t& message) { mavlink_named_value_float_t val; mavlink_msg_named_value_float_decode(&message, &val); - emit valueChanged(this->getUASID(), QString((char *)val.name), tr("raw"), val.value, getUnixTime(0)); + emit valueChanged(this->getUASID(), QString((char *)val.name), tr("raw"), val.value, getUnixTime()); } else if (message.msgid == MAVLINK_MSG_ID_NAMED_VALUE_INT) { mavlink_named_value_int_t val; mavlink_msg_named_value_int_decode(&message, &val); - emit valueChanged(this->getUASID(), QString((char *)val.name), tr("raw"), (float)val.value, getUnixTime(0)); + emit valueChanged(this->getUASID(), QString((char *)val.name), tr("raw"), val.value, getUnixTime()); } } @@ -424,6 +424,37 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time); } break; + case MAVLINK_MSG_ID_VFR_HUD: + { + mavlink_vfr_hud_t hud; + mavlink_msg_vfr_hud_decode(&message, &hud); + quint64 time = getUnixTime(); + // Display updated values + emit valueChanged(uasId, "airspeed", "m/s", hud.airspeed, time); + emit valueChanged(uasId, "groundspeed", "m/s", hud.groundspeed, time); + emit valueChanged(uasId, "altitude", "m", hud.alt, time); + emit valueChanged(uasId, "heading", "deg", hud.heading, time); + emit valueChanged(uasId, "climbrate", "m/s", hud.climb, time); + emit valueChanged(uasId, "throttle", "m/s", hud.throttle, time); + emit thrustChanged(this, hud.throttle/100.0); + } + break; + case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT: + { + mavlink_nav_controller_output_t nav; + mavlink_msg_nav_controller_output_decode(&message, &nav); + quint64 time = getUnixTime(); + // Update UI + emit valueChanged(uasId, "nav roll", "deg", nav.nav_roll, time); + emit valueChanged(uasId, "nav pitch", "deg", nav.nav_pitch, time); + emit valueChanged(uasId, "nav bearing", "deg", nav.nav_bearing, time); + emit valueChanged(uasId, "target bearing", "deg", nav.target_bearing, time); + emit valueChanged(uasId, "wp dist", "m", nav.wp_dist, time); + emit valueChanged(uasId, "alt err", "m", nav.alt_error, time); + emit valueChanged(uasId, "airspeed err", "m/s", nav.alt_error, time); + //emit valueChanged(uasId, "xtrack err", "m", nav.xtrack_error, time); + } + break; case MAVLINK_MSG_ID_LOCAL_POSITION: //std::cerr << std::endl; //std::cerr << "Decoded attitude message:" << " roll: " << std::dec << mavlink_msg_attitude_get_roll(message.payload) << " pitch: " << mavlink_msg_attitude_get_pitch(message.payload) << " yaw: " << mavlink_msg_attitude_get_yaw(message.payload) << std::endl; @@ -736,7 +767,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) break; case MAVLINK_MSG_ID_SERVO_OUTPUT_RAW: { - qDebug() << "Received servo raw message"; mavlink_servo_output_raw_t servos; mavlink_msg_servo_output_raw_decode(&message, &servos); quint64 time = getUnixTime(0); diff --git a/src/uas/UAS.h b/src/uas/UAS.h index e7a048452b2cef523031480e6df885e64e8b4c05..da0b8b1932aa3eff3614cbe0b43f44cf27c1bcfb 100644 --- a/src/uas/UAS.h +++ b/src/uas/UAS.h @@ -316,8 +316,8 @@ signals: void imageStarted(quint64 timestamp); protected: - /** @brief Get the UNIX timestamp in microseconds */ - quint64 getUnixTime(quint64 time); + /** @brief Get the UNIX timestamp in milliseconds */ + quint64 getUnixTime(quint64 time=0); protected slots: /** @brief Write settings to disk */ diff --git a/src/ui/CommConfigurationWindow.cc b/src/ui/CommConfigurationWindow.cc index 8b0bfd8f0845bdd975944dac575b86a00ecb7878..2a87d59d4c58a7fd1a854777c6c7efa8e12c9207 100644 --- a/src/ui/CommConfigurationWindow.cc +++ b/src/ui/CommConfigurationWindow.cc @@ -47,6 +47,7 @@ This file is part of the QGROUNDCONTROL project #endif #include "MAVLinkProtocol.h" #include "MAVLinkSettingsWidget.h" +#include "QGCUDPLinkConfiguration.h" #include "LinkManager.h" CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolInterface* protocol, QWidget *parent, Qt::WindowFlags flags) : QWidget(parent, flags) @@ -57,20 +58,24 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn ui.setupUi(this); // add link types - ui.linkType->addItem("Serial",QGC_LINK_SERIAL); - ui.linkType->addItem("UDP",QGC_LINK_UDP); - ui.linkType->addItem("Simulation",QGC_LINK_SIMULATION); - ui.linkType->addItem("Serial Forwarding",QGC_LINK_FORWARDING); + ui.linkType->addItem(tr("Serial"), QGC_LINK_SERIAL); + ui.linkType->addItem(tr("UDP"), QGC_LINK_UDP); + ui.linkType->addItem(tr("Simulation"), QGC_LINK_SIMULATION); + ui.linkType->addItem(tr("Opal-RT Link"), QGC_LINK_OPAL); + ui.linkType->setEditable(false); + //ui.linkType->setEnabled(false); ui.connectionType->addItem("MAVLink", QGC_PROTOCOL_MAVLINK); - ui.connectionType->addItem("GPS NMEA", QGC_PROTOCOL_NMEA); + //ui.connectionType->addItem("GPS NMEA", QGC_PROTOCOL_NMEA); // Create action to open this menu // Create configuration action for this link // Connect the current UAS - action = new QAction(QIcon(":/images/devices/network-wireless.svg"), "", link); + action = new QAction(QIcon(":/images/devices/network-wireless.svg"), "", this); LinkManager::instance()->add(link); action->setData(LinkManager::instance()->getLinks().indexOf(link)); + action->setEnabled(true); + action->setVisible(true); setLinkName(link->getName()); connect(action, SIGNAL(triggered()), this, SLOT(show())); @@ -110,17 +115,24 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn layout->addWidget(conf); ui.linkGroupBox->setLayout(layout); ui.linkGroupBox->setTitle(tr("Serial Link")); + ui.linkType->setCurrentIndex(0); //ui.linkGroupBox->setTitle(link->getName()); //connect(link, SIGNAL(nameChanged(QString)), ui.linkGroupBox, SLOT(setTitle(QString))); } UDPLink* udp = dynamic_cast(link); if (udp != 0) { + QWidget* conf = new QGCUDPLinkConfiguration(udp, this); + QBoxLayout* layout = new QBoxLayout(QBoxLayout::LeftToRight, ui.linkGroupBox); + layout->addWidget(conf); + ui.linkGroupBox->setLayout(layout); ui.linkGroupBox->setTitle(tr("UDP Link")); + ui.linkType->setCurrentIndex(1); } MAVLinkSimulationLink* sim = dynamic_cast(link); if (sim != 0) { + ui.linkType->setCurrentIndex(2); ui.linkGroupBox->setTitle(tr("MAVLink Simulation Link")); } #ifdef OPAL_RT @@ -131,6 +143,7 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn QBoxLayout* layout = new QBoxLayout(QBoxLayout::LeftToRight, ui.linkGroupBox); layout->addWidget(conf); ui.linkGroupBox->setLayout(layout); + ui.linkType->setCurrentIndex(3); ui.linkGroupBox->setTitle(tr("Opal-RT Link")); } #endif @@ -201,10 +214,9 @@ void CommConfigurationWindow::setConnection() void CommConfigurationWindow::setLinkName(QString name) { - Q_UNUSED(name); // FIXME - action->setText(tr("Configure ") + link->getName()); - action->setStatusTip(tr("Configure ") + link->getName()); - this->window()->setWindowTitle(tr("Settings for ") + this->link->getName()); + action->setText(tr("%1 Settings").arg(name)); + action->setStatusTip(tr("Adjust setting for link %1").arg(name)); + this->window()->setWindowTitle(tr("Settings for %1").arg(name)); } void CommConfigurationWindow::remove() diff --git a/src/ui/CommConfigurationWindow.h b/src/ui/CommConfigurationWindow.h index 27b1ad2fb5fdb1b6ed7af153acb679553c4471d3..6b126f808f4619b13d3fa5598ceea661a8db3667 100644 --- a/src/ui/CommConfigurationWindow.h +++ b/src/ui/CommConfigurationWindow.h @@ -44,7 +44,8 @@ enum qgc_link_t QGC_LINK_SERIAL, QGC_LINK_UDP, QGC_LINK_SIMULATION, - QGC_LINK_FORWARDING + QGC_LINK_FORWARDING, + QGC_LINK_OPAL }; enum qgc_protocol_t diff --git a/src/ui/MAVLinkSettingsWidget.cc b/src/ui/MAVLinkSettingsWidget.cc index b63a8715ff21e73c86e085ba33e90e9b4c73403d..a96dc023ed4f0c26dc4db267cbabee7e8207ab4e 100644 --- a/src/ui/MAVLinkSettingsWidget.cc +++ b/src/ui/MAVLinkSettingsWidget.cc @@ -48,6 +48,7 @@ MAVLinkSettingsWidget::MAVLinkSettingsWidget(MAVLinkProtocol* protocol, QWidget m_ui->heartbeatCheckBox->setChecked(protocol->heartbeatsEnabled()); m_ui->loggingCheckBox->setChecked(protocol->loggingEnabled()); m_ui->versionCheckBox->setChecked(protocol->versionCheckEnabled()); + m_ui->multiplexingCheckBox->setChecked(protocol->multiplexingEnabled()); m_ui->systemIdSpinBox->setValue(protocol->getSystemId()); // Connect actions @@ -59,6 +60,7 @@ MAVLinkSettingsWidget::MAVLinkSettingsWidget(MAVLinkProtocol* protocol, QWidget connect(m_ui->versionCheckBox, SIGNAL(toggled(bool)), protocol, SLOT(enableVersionCheck(bool))); connect(m_ui->logFileButton, SIGNAL(clicked()), this, SLOT(chooseLogfileName())); connect(m_ui->systemIdSpinBox, SIGNAL(valueChanged(int)), protocol, SLOT(setSystemId(int))); + connect(m_ui->multiplexingCheckBox, SIGNAL(toggled(bool)), protocol, SLOT(enableMultiplexing(bool))); // Update values m_ui->versionLabel->setText(tr("MAVLINK_VERSION: %1").arg(protocol->getVersion())); @@ -73,6 +75,15 @@ MAVLinkSettingsWidget::MAVLinkSettingsWidget(MAVLinkProtocol* protocol, QWidget m_ui->logFileLabel->setVisible(protocol->loggingEnabled()); connect(protocol, SIGNAL(loggingChanged(bool)), m_ui->logFileButton, SLOT(setVisible(bool))); m_ui->logFileButton->setVisible(protocol->loggingEnabled()); + connect(protocol, SIGNAL(multiplexingChanged(bool)), m_ui->multiplexingFilterCheckBox, SLOT(setVisible(bool))); + m_ui->multiplexingFilterCheckBox->setVisible(protocol->multiplexingEnabled()); + connect(protocol, SIGNAL(multiplexingChanged(bool)), m_ui->multiplexingFilterLineEdit, SLOT(setVisible(bool))); + m_ui->multiplexingFilterLineEdit->setVisible(protocol->multiplexingEnabled()); + + // TODO implement filtering + // and then remove these two lines + m_ui->multiplexingFilterCheckBox->setVisible(false); + m_ui->multiplexingFilterLineEdit->setVisible(false); // Update settings m_ui->loggingCheckBox->setChecked(protocol->loggingEnabled()); diff --git a/src/ui/MAVLinkSettingsWidget.ui b/src/ui/MAVLinkSettingsWidget.ui index 1f5a9117e940982bcf6ddd6f52132d1cdb51fec9..8b1db6f6c1e2ca59d40b7e1d7d6356639825966b 100644 --- a/src/ui/MAVLinkSettingsWidget.ui +++ b/src/ui/MAVLinkSettingsWidget.ui @@ -7,7 +7,7 @@ 0 0 431 - 243 + 256 @@ -21,14 +21,14 @@ - + Log all MAVLink packets - + Qt::Horizontal @@ -44,14 +44,14 @@ - + Only accept MAVs with same protocol version - + Qt::Horizontal @@ -64,21 +64,21 @@ - + MAVLINK_VERSION: - + Logfile name - + Select.. @@ -114,6 +114,43 @@ + + + + Qt::Horizontal + + + QSizePolicy::MinimumExpanding + + + + 8 + 0 + + + + + + + + Enter a comma-separated list of allowed packets + + + + + + + Filter multiplexed packets: Only forward selected IDs + + + + + + + Enable Multiplexing: Forward packets to all other links + + + diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index 758adc23d2ccfeb6d64066b7dc36a3a502cb1907..2d41e72ece674203b170ea1fbc4a90df7472630e 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -406,8 +406,9 @@ void MainWindow::buildPxWidgets() acceptList->append("-60,pitchspeed d/s,deg/s,+60,s"); acceptList->append("-60,yawspeed d/s,deg/s,+60,s"); acceptList->append("0,airspeed,m/s,30"); - acceptList->append("0,gpsspeed,m/s,30"); - acceptList->append("0,truespeed,m/s,30"); + acceptList->append("0,groundspeed,m/s,30"); + acceptList->append("0,climbrate,m/s,30"); + acceptList->append("0,throttle,m/s,100"); //FIXME: memory of acceptList2 will never be freed again QStringList* acceptList2 = new QStringList(); @@ -1440,7 +1441,8 @@ void MainWindow::addLink(LinkInterface *link) LinkManager::instance()->addProtocol(link, mavlink); CommConfigurationWindow* commWidget = new CommConfigurationWindow(link, mavlink, this); - ui.menuNetwork->addAction(commWidget->getAction()); + QAction* action = commWidget->getAction(); + ui.menuNetwork->addAction(action); // Error handling connect(link, SIGNAL(communicationError(QString,QString)), this, SLOT(showCriticalMessage(QString,QString)), Qt::QueuedConnection); diff --git a/src/ui/MainWindow.ui b/src/ui/MainWindow.ui index 8fb8ca81bb65c144a0b2434c02ec2a74690736a8..122df9bdedea27b951a06f86f0cb55b8b3687cb1 100644 --- a/src/ui/MainWindow.ui +++ b/src/ui/MainWindow.ui @@ -64,6 +64,7 @@ + @@ -431,6 +432,11 @@ Meta+R + + + Settings + + diff --git a/src/ui/QGCUDPLinkConfiguration.cc b/src/ui/QGCUDPLinkConfiguration.cc new file mode 100644 index 0000000000000000000000000000000000000000..ff4c797e6e6c7f58338ea0d7f059d6be6f0c2e5d --- /dev/null +++ b/src/ui/QGCUDPLinkConfiguration.cc @@ -0,0 +1,42 @@ +#include + +#include "QGCUDPLinkConfiguration.h" +#include "ui_QGCUDPLinkConfiguration.h" + +QGCUDPLinkConfiguration::QGCUDPLinkConfiguration(UDPLink* link, QWidget *parent) : + QWidget(parent), + link(link), + ui(new Ui::QGCUDPLinkConfiguration) +{ + ui->setupUi(this); + ui->portSpinBox->setValue(link->getPort()); + connect(ui->portSpinBox, SIGNAL(valueChanged(int)), link, SLOT(setPort(int))); + connect(ui->addIPButton, SIGNAL(clicked()), this, SLOT(addHost())); +} + +QGCUDPLinkConfiguration::~QGCUDPLinkConfiguration() +{ + delete ui; +} + +void QGCUDPLinkConfiguration::changeEvent(QEvent *e) +{ + QWidget::changeEvent(e); + switch (e->type()) { + case QEvent::LanguageChange: + ui->retranslateUi(this); + break; + default: + break; + } +} + +void QGCUDPLinkConfiguration::addHost() +{ + bool ok; + QString hostName = QInputDialog::getText(this, tr("Add a new IP address / hostname to MAVLink"), + tr("Host (hostname:port):"), QLineEdit::Normal, + "localhost:14555", &ok); + if (ok && !hostName.isEmpty()) + link->addHost(hostName); +} diff --git a/src/ui/QGCUDPLinkConfiguration.h b/src/ui/QGCUDPLinkConfiguration.h new file mode 100644 index 0000000000000000000000000000000000000000..12343332d46781ac19a0de57d150008e6f143e5a --- /dev/null +++ b/src/ui/QGCUDPLinkConfiguration.h @@ -0,0 +1,32 @@ +#ifndef QGCUDPLINKCONFIGURATION_H +#define QGCUDPLINKCONFIGURATION_H + +#include + +#include "UDPLink.h" + +namespace Ui { + class QGCUDPLinkConfiguration; +} + +class QGCUDPLinkConfiguration : public QWidget +{ + Q_OBJECT + +public: + explicit QGCUDPLinkConfiguration(UDPLink* link, QWidget *parent = 0); + ~QGCUDPLinkConfiguration(); + +public slots: + void addHost(); + +protected: + void changeEvent(QEvent *e); + + UDPLink* link; ///< UDP link instance this widget configures + +private: + Ui::QGCUDPLinkConfiguration *ui; +}; + +#endif // QGCUDPLINKCONFIGURATION_H diff --git a/src/ui/QGCUDPLinkConfiguration.ui b/src/ui/QGCUDPLinkConfiguration.ui new file mode 100644 index 0000000000000000000000000000000000000000..156e0fd824e3b2bb5870056908486b3cf19c6906 --- /dev/null +++ b/src/ui/QGCUDPLinkConfiguration.ui @@ -0,0 +1,52 @@ + + + QGCUDPLinkConfiguration + + + + 0 + 0 + 400 + 300 + + + + Form + + + + + + UDP Port + + + + + + + 3000 + + + 100000 + + + + + + + Add remote communication target + + + + + + + Add IP + + + + + + + +