Commit 799d20aa authored by Don Gagne's avatar Don Gagne

Move GCS heartbeat to MutiVehicleManager

parent ad9a07d7
......@@ -6,8 +6,6 @@
/** @brief Polling interval in ms */
#define SERIAL_POLL_INTERVAL 4
/** @brief Heartbeat emission rate, in Hertz (times per second) */
#define MAVLINK_HEARTBEAT_DEFAULT_RATE 1
#define WITH_TEXT_TO_SPEECH 1
// If you need to make an incompatible changes to stored settings, bump this version number
......
......@@ -178,12 +178,6 @@ void QGroundControlQmlGlobal::setIsSaveLogPromptNotArmed(bool prompt)
emit isSaveLogPromptNotArmedChanged(prompt);
}
void QGroundControlQmlGlobal::setIsHeartBeatEnabled(bool enable)
{
qgcApp()->toolbox()->mavlinkProtocol()->enableHeartbeats(enable);
emit isHeartBeatEnabledChanged(enable);
}
void QGroundControlQmlGlobal::setIsMultiplexingEnabled(bool enable)
{
qgcApp()->toolbox()->mavlinkProtocol()->enableMultiplexing(enable);
......
......@@ -69,7 +69,6 @@ public:
Q_PROPERTY(bool virtualTabletJoystick READ virtualTabletJoystick WRITE setVirtualTabletJoystick NOTIFY virtualTabletJoystickChanged)
// MavLink Protocol
Q_PROPERTY(bool isHeartBeatEnabled READ isHeartBeatEnabled WRITE setIsHeartBeatEnabled NOTIFY isHeartBeatEnabledChanged)
Q_PROPERTY(bool isMultiplexingEnabled READ isMultiplexingEnabled WRITE setIsMultiplexingEnabled NOTIFY isMultiplexingEnabledChanged)
Q_PROPERTY(bool isVersionCheckEnabled READ isVersionCheckEnabled WRITE setIsVersionCheckEnabled NOTIFY isVersionCheckEnabledChanged)
Q_PROPERTY(int mavlinkSystemID READ mavlinkSystemID WRITE setMavlinkSystemID NOTIFY mavlinkSystemIDChanged)
......@@ -110,7 +109,6 @@ public:
bool isSaveLogPromptNotArmed () { return _app->promptFlightDataSaveNotArmed(); }
bool virtualTabletJoystick () { return _virtualTabletJoystick; }
bool isHeartBeatEnabled () { return _toolbox->mavlinkProtocol()->heartbeatsEnabled(); }
bool isMultiplexingEnabled () { return _toolbox->mavlinkProtocol()->multiplexingEnabled(); }
bool isVersionCheckEnabled () { return _toolbox->mavlinkProtocol()->versionCheckEnabled(); }
int mavlinkSystemID () { return _toolbox->mavlinkProtocol()->getSystemId(); }
......@@ -128,7 +126,6 @@ public:
void setIsSaveLogPromptNotArmed (bool prompt);
void setVirtualTabletJoystick (bool enabled);
void setIsHeartBeatEnabled (bool enable);
void setIsMultiplexingEnabled (bool enable);
void setIsVersionCheckEnabled (bool enable);
void setMavlinkSystemID (int id);
......@@ -142,7 +139,6 @@ signals:
void isSaveLogPromptChanged (bool prompt);
void isSaveLogPromptNotArmedChanged (bool prompt);
void virtualTabletJoystickChanged (bool enabled);
void isHeartBeatEnabledChanged (bool enabled);
void isMultiplexingEnabledChanged (bool enabled);
void isVersionCheckEnabledChanged (bool enabled);
void mavlinkSystemIDChanged (int id);
......
......@@ -32,6 +32,8 @@
QGC_LOGGING_CATEGORY(MultiVehicleManagerLog, "MultiVehicleManagerLog")
const char* MultiVehicleManager::_gcsHeartbeatEnabledKey = "gcsHeartbeatEnabled";
MultiVehicleManager::MultiVehicleManager(QGCApplication* app)
: QGCTool(app)
, _activeVehicleAvailable(false)
......@@ -41,8 +43,18 @@ MultiVehicleManager::MultiVehicleManager(QGCApplication* app)
, _autopilotPluginManager(NULL)
, _joystickManager(NULL)
, _mavlinkProtocol(NULL)
, _gcsHeartbeatEnabled(true)
{
QSettings settings;
_gcsHeartbeatEnabled = settings.value(_gcsHeartbeatEnabledKey, true).toBool();
_gcsHeartbeatTimer.setInterval(_gcsHeartbeatRateMSecs);
_gcsHeartbeatTimer.setSingleShot(false);
connect(&_gcsHeartbeatTimer, &QTimer::timeout, this, &MultiVehicleManager::_sendGCSHeartbeat);
if (_gcsHeartbeatEnabled) {
_gcsHeartbeatTimer.start();
}
}
void MultiVehicleManager::setToolbox(QGCToolbox *toolbox)
......@@ -238,3 +250,38 @@ Vehicle* MultiVehicleManager::getVehicleById(int vehicleId)
return NULL;
}
void MultiVehicleManager::setGcsHeartbeatEnabled(bool gcsHeartBeatEnabled)
{
if (gcsHeartBeatEnabled != _gcsHeartbeatEnabled) {
_gcsHeartbeatEnabled = gcsHeartBeatEnabled;
emit gcsHeartBeatEnabledChanged(gcsHeartBeatEnabled);
QSettings settings;
settings.setValue(_gcsHeartbeatEnabledKey, gcsHeartBeatEnabled);
if (gcsHeartBeatEnabled) {
_gcsHeartbeatTimer.start();
} else {
_gcsHeartbeatTimer.stop();
}
}
}
void MultiVehicleManager::_sendGCSHeartbeat(void)
{
for (int i=0; i< _vehicles.count(); i++) {
Vehicle* vehicle = qobject_cast<Vehicle*>(_vehicles[i]);
mavlink_message_t message;
mavlink_msg_heartbeat_pack(_mavlinkProtocol->getSystemId(),
_mavlinkProtocol->getComponentId(),
&message,
MAV_TYPE_GCS, // MAV_TYPE
MAV_AUTOPILOT_INVALID, // MAV_AUTOPILOT
MAV_MODE_MANUAL_ARMED, // MAV_MODE
0, // custom mode
MAV_STATE_ACTIVE); // MAV_STATE
vehicle->sendMessage(message);
}
}
......@@ -51,10 +51,11 @@ public:
Q_INVOKABLE void saveSetting (const QString &key, const QString& value);
Q_INVOKABLE QString loadSetting (const QString &key, const QString& defaultValue);
Q_PROPERTY(bool activeVehicleAvailable READ activeVehicleAvailable NOTIFY activeVehicleAvailableChanged)
Q_PROPERTY(bool parameterReadyVehicleAvailable READ parameterReadyVehicleAvailable NOTIFY parameterReadyVehicleAvailableChanged)
Q_PROPERTY(Vehicle* activeVehicle READ activeVehicle WRITE setActiveVehicle NOTIFY activeVehicleChanged)
Q_PROPERTY(QmlObjectListModel* vehicles READ vehicles CONSTANT)
Q_PROPERTY(bool activeVehicleAvailable READ activeVehicleAvailable NOTIFY activeVehicleAvailableChanged)
Q_PROPERTY(bool parameterReadyVehicleAvailable READ parameterReadyVehicleAvailable NOTIFY parameterReadyVehicleAvailableChanged)
Q_PROPERTY(Vehicle* activeVehicle READ activeVehicle WRITE setActiveVehicle NOTIFY activeVehicleChanged)
Q_PROPERTY(QmlObjectListModel* vehicles READ vehicles CONSTANT)
Q_PROPERTY(bool gcsHeartBeatEnabled READ gcsHeartbeatEnabled WRITE setGcsHeartbeatEnabled NOTIFY gcsHeartBeatEnabledChanged)
// Methods
......@@ -73,6 +74,9 @@ public:
QmlObjectListModel* vehicles(void) { return &_vehicles; }
bool gcsHeartbeatEnabled(void) const { return _gcsHeartbeatEnabled; }
void setGcsHeartbeatEnabled(bool gcsHeartBeatEnabled);
// Override from QGCTool
virtual void setToolbox(QGCToolbox *toolbox);
......@@ -82,6 +86,7 @@ signals:
void activeVehicleAvailableChanged(bool activeVehicleAvailable);
void parameterReadyVehicleAvailableChanged(bool parameterReadyVehicleAvailable);
void activeVehicleChanged(Vehicle* activeVehicle);
void gcsHeartBeatEnabledChanged(bool gcsHeartBeatEnabled);
void _deleteVehiclePhase2Signal(void);
......@@ -91,6 +96,7 @@ private slots:
void _setActiveVehiclePhase2(void);
void _autopilotParametersReadyChanged(bool parametersReady);
void _linkActive(LinkInterface* link, int vehicleId, int vehicleFirmwareType, int vehicleType);
void _sendGCSHeartbeat(void);
private:
bool _vehicleExists(int vehicleId);
......@@ -111,6 +117,10 @@ private:
JoystickManager* _joystickManager;
MAVLinkProtocol* _mavlinkProtocol;
QTimer _gcsHeartbeatTimer; ///< Timer to emit heartbeats
bool _gcsHeartbeatEnabled; ///< Enabled/disable heartbeat emission
static const int _gcsHeartbeatRateMSecs = 1000; ///< Heartbeat rate
static const char* _gcsHeartbeatEnabledKey;
};
#endif
......@@ -60,8 +60,6 @@ MAVLinkProtocol::MAVLinkProtocol(QGCApplication* app)
, _logPromptForSave(false)
, _tempLogFile(QString("%2.%3").arg(_tempLogFileTemplate).arg(_logFileExtension))
#endif
, _heartbeatRate(MAVLINK_HEARTBEAT_DEFAULT_RATE)
, _heartbeatsEnabled(true)
, _linkMgr(NULL)
, _multiVehicleManager(NULL)
{
......@@ -101,10 +99,6 @@ void MAVLinkProtocol::setToolbox(QGCToolbox *toolbox)
}
}
// Start heartbeat timer, emitting a heartbeat at the configured rate
connect(&_heartbeatTimer, &QTimer::timeout, this, &MAVLinkProtocol::sendHeartbeat);
_heartbeatTimer.start(1000/_heartbeatRate);
connect(this, &MAVLinkProtocol::protocolStatusMessage, _app, &QGCApplication::criticalMessageBoxOnMainThread);
#ifndef __mobile__
connect(this, &MAVLinkProtocol::saveTempFlightDataLog, _app, &QGCApplication::saveTempFlightDataLogOnMainThread);
......@@ -120,7 +114,6 @@ void MAVLinkProtocol::loadSettings()
// Load defaults from settings
QSettings settings;
settings.beginGroup("QGC_MAVLINK_PROTOCOL");
enableHeartbeats(settings.value("HEARTBEATS_ENABLED", _heartbeatsEnabled).toBool());
enableVersionCheck(settings.value("VERSION_CHECK_ENABLED", m_enable_version_check).toBool());
enableMultiplexing(settings.value("MULTIPLEXING_ENABLED", m_multiplexingEnabled).toBool());
......@@ -150,7 +143,6 @@ void MAVLinkProtocol::storeSettings()
// Store settings
QSettings settings;
settings.beginGroup("QGC_MAVLINK_PROTOCOL");
settings.setValue("HEARTBEATS_ENABLED", _heartbeatsEnabled);
settings.setValue("VERSION_CHECK_ENABLED", m_enable_version_check);
settings.setValue("MULTIPLEXING_ENABLED", m_multiplexingEnabled);
settings.setValue("GCS_SYSTEM_ID", systemId);
......@@ -473,37 +465,6 @@ void MAVLinkProtocol::_sendMessage(LinkInterface* link, mavlink_message_t messag
}
}
/**
* The heartbeat is sent out of order and does not reset the
* periodic heartbeat emission. It will be just sent in addition.
* @return mavlink_message_t heartbeat message sent on serial link
*/
void MAVLinkProtocol::sendHeartbeat()
{
if (_heartbeatsEnabled)
{
mavlink_message_t beat;
mavlink_msg_heartbeat_pack(getSystemId(), getComponentId(),&beat, MAV_TYPE_GCS, MAV_AUTOPILOT_INVALID, MAV_MODE_MANUAL_ARMED, 0, MAV_STATE_ACTIVE);
_sendMessage(beat);
}
if (m_authEnabled)
{
mavlink_message_t msg;
mavlink_auth_key_t auth;
memset(&auth, 0, sizeof(auth));
memcpy(auth.key, m_authKey.toStdString().c_str(), qMin(m_authKey.length(), MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN));
mavlink_msg_auth_key_encode(getSystemId(), getComponentId(), &msg, &auth);
_sendMessage(msg);
}
}
/** @param enabled true to enable heartbeats emission at _heartbeatRate, false to disable */
void MAVLinkProtocol::enableHeartbeats(bool enabled)
{
_heartbeatsEnabled = enabled;
emit heartbeatChanged(enabled);
}
void MAVLinkProtocol::enableMultiplexing(bool enabled)
{
bool changed = false;
......@@ -569,23 +530,6 @@ void MAVLinkProtocol::enableVersionCheck(bool enabled)
emit versionCheckChanged(enabled);
}
/**
* The default rate is 1 Hertz.
*
* @param rate heartbeat rate in hertz (times per second)
*/
void MAVLinkProtocol::setHeartbeatRate(int rate)
{
_heartbeatRate = rate;
_heartbeatTimer.setInterval(1000/_heartbeatRate);
}
/** @return heartbeat rate in Hertz */
int MAVLinkProtocol::getHeartbeatRate()
{
return _heartbeatRate;
}
void MAVLinkProtocol::_vehicleCountChanged(int count)
{
#ifndef __mobile__
......
......@@ -72,12 +72,6 @@ public:
int getSystemId();
/** @brief Get the component id of this application */
int getComponentId();
/** @brief The auto heartbeat emission rate in Hertz */
int getHeartbeatRate();
/** @brief Get heartbeat state */
bool heartbeatsEnabled() const {
return _heartbeatsEnabled;
}
/** @brief Get protocol version check state */
bool versionCheckEnabled() const {
......@@ -155,14 +149,9 @@ public slots:
/** @brief Receive bytes from a communication interface */
void receiveBytes(LinkInterface* link, QByteArray b);
/** @brief Set the rate at which heartbeats are emitted */
void setHeartbeatRate(int rate);
/** @brief Set the system id of this application */
void setSystemId(int id);
/** @brief Enable / disable the heartbeat emission */
void enableHeartbeats(bool enabled);
/** @brief Enabled/disable packet multiplexing */
void enableMultiplexing(bool enabled);
......@@ -192,9 +181,6 @@ public slots:
m_authKey = key;
}
/** @brief Send an extra heartbeat to all connected units */
void sendHeartbeat();
/** @brief Load protocol settings */
void loadSettings();
/** @brief Store protocol settings */
......@@ -234,8 +220,6 @@ signals:
/** @brief Message received and directly copied via signal */
void messageReceived(LinkInterface* link, mavlink_message_t message);
/** @brief Emitted if heartbeat emission mode is changed */
void heartbeatChanged(bool heartbeats);
/** @brief Emitted if multiplexing is started / stopped */
void multiplexingChanged(bool enabled);
/** @brief Emitted if authentication support is enabled / disabled */
......@@ -300,10 +284,6 @@ private:
static const char* _logFileExtension; ///< Extension for log files
#endif
QTimer _heartbeatTimer; ///< Timer to emit heartbeats
int _heartbeatRate; ///< Heartbeat rate, controls the timer interval
bool _heartbeatsEnabled; ///< Enabled/disable heartbeat emission
LinkManager* _linkMgr;
MultiVehicleManager* _multiVehicleManager;
};
......
......@@ -399,10 +399,7 @@ void MockLink::_handleIncomingMavlinkBytes(const uint8_t* bytes, int cBytes)
void MockLink::_handleHeartBeat(const mavlink_message_t& msg)
{
Q_UNUSED(msg);
#if 0
mavlink_heartbeat_t heartbeat;
mavlink_msg_heartbeat_decode(&msg, &heartbeat);
#endif
qCDebug(MockLinkLog) << "Heartbeat";
}
void MockLink::_handleSetMode(const mavlink_message_t& msg)
......
......@@ -53,7 +53,6 @@ MAVLinkSettingsWidget::MAVLinkSettingsWidget(MAVLinkProtocol* protocol, QWidget
m_ui->droneOSLineEdit->setText(protocol->getAuthKey());
// Initialize state
m_ui->heartbeatCheckBox->setChecked(protocol->heartbeatsEnabled());
m_ui->versionCheckBox->setChecked(protocol->versionCheckEnabled());
m_ui->multiplexingCheckBox->setChecked(protocol->multiplexingEnabled());
m_ui->systemIdSpinBox->setValue(protocol->getSystemId());
......@@ -65,11 +64,6 @@ MAVLinkSettingsWidget::MAVLinkSettingsWidget(MAVLinkProtocol* protocol, QWidget
m_ui->actionGuardCheckBox->setChecked(protocol->actionGuardEnabled());
m_ui->actionRetransmissionSpinBox->setValue(protocol->getActionRetransmissionTimeout());
// Connect actions
// Heartbeat
connect(protocol, &MAVLinkProtocol::heartbeatChanged, m_ui->heartbeatCheckBox, &QCheckBox::setChecked);
connect(m_ui->heartbeatCheckBox, &QCheckBox::toggled, protocol, &MAVLinkProtocol::enableHeartbeats);
// Version check
connect(protocol, &MAVLinkProtocol::versionCheckChanged, m_ui->versionCheckBox, &QCheckBox::setChecked);
connect(m_ui->versionCheckBox, &QCheckBox::toggled, protocol, &MAVLinkProtocol::enableVersionCheck);
......
......@@ -14,21 +14,57 @@
<string>Form</string>
</property>
<layout class="QGridLayout" name="gridLayout" columnstretch="1,0,0">
<item row="16" column="0">
<spacer name="horizontalSpacer_4">
<property name="orientation">
<enum>Qt::Horizontal</enum>
<item row="11" column="0" colspan="3">
<widget class="QCheckBox" name="actionGuardCheckBox">
<property name="text">
<string>Enable retransmission of actions / commands</string>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>8</width>
<height>0</height>
</size>
</widget>
</item>
<item row="14" column="0" colspan="3">
<widget class="QCheckBox" name="droneOSCheckBox">
<property name="text">
<string>Forward MAVLink packets of all links to the host below</string>
</property>
</spacer>
</widget>
</item>
<item row="13" column="0">
<spacer name="horizontalSpacer_3">
<item row="6" column="0" colspan="3">
<widget class="QCheckBox" name="versionCheckBox">
<property name="text">
<string>Only accept MAVs with same protocol version</string>
</property>
</widget>
</item>
<item row="9" column="1">
<widget class="QLabel" name="paramRetransmissionLabel">
<property name="text">
<string>Read request retransmission timeout</string>
</property>
</widget>
</item>
<item row="8" column="0" colspan="3">
<widget class="QCheckBox" name="paramGuardCheckBox">
<property name="text">
<string>Enable retransmission of parameter read/write requests</string>
</property>
</widget>
</item>
<item row="2" column="0" colspan="3">
<widget class="QCheckBox" name="multiplexingCheckBox">
<property name="text">
<string>Enable Multiplexing: Forward packets to all other links</string>
</property>
</widget>
</item>
<item row="4" column="1" colspan="2">
<widget class="QLineEdit" name="multiplexingFilterLineEdit">
<property name="text">
<string>Enter a comma-separated list of allowed packets</string>
</property>
</widget>
</item>
<item row="10" column="0">
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
......@@ -40,13 +76,13 @@
</property>
</spacer>
</item>
<item row="11" column="2">
<widget class="QSpinBox" name="paramRewriteSpinBox">
<item row="9" column="2">
<widget class="QSpinBox" name="paramRetransmissionSpinBox">
<property name="toolTip">
<string>Time in milliseconds after which a not acknowledged write request is sent again.</string>
<string>Time in milliseconds after which a not acknowledged read request is sent again.</string>
</property>
<property name="statusTip">
<string>Time in milliseconds after which a not acknowledged write request is sent again.</string>
<string>Time in milliseconds after which a not acknowledged read request is sent again.</string>
</property>
<property name="suffix">
<string> ms</string>
......@@ -60,32 +96,22 @@
<property name="singleStep">
<number>50</number>
</property>
</widget>
</item>
<item row="5" column="1" colspan="2">
<widget class="QLineEdit" name="multiplexingFilterLineEdit">
<property name="text">
<string>Enter a comma-separated list of allowed packets</string>
<property name="value">
<number>50</number>
</property>
</widget>
</item>
<item row="13" column="2">
<widget class="QSpinBox" name="actionRetransmissionSpinBox">
<property name="suffix">
<string> ms</string>
</property>
<property name="minimum">
<number>20</number>
</property>
<property name="maximum">
<number>1000</number>
<item row="15" column="1" colspan="2">
<widget class="QLineEdit" name="droneOSLineEdit">
<property name="text">
<string>Enter your authentication token</string>
</property>
<property name="singleStep">
<number>10</number>
<property name="maxLength">
<number>32</number>
</property>
</widget>
</item>
<item row="10" column="0">
<item row="9" column="0">
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
......@@ -99,12 +125,12 @@
</spacer>
</item>
<item row="10" column="2">
<widget class="QSpinBox" name="paramRetransmissionSpinBox">
<widget class="QSpinBox" name="paramRewriteSpinBox">
<property name="toolTip">
<string>Time in milliseconds after which a not acknowledged read request is sent again.</string>
<string>Time in milliseconds after which a not acknowledged write request is sent again.</string>
</property>
<property name="statusTip">
<string>Time in milliseconds after which a not acknowledged read request is sent again.</string>
<string>Time in milliseconds after which a not acknowledged write request is sent again.</string>
</property>
<property name="suffix">
<string> ms</string>
......@@ -118,12 +144,65 @@
<property name="singleStep">
<number>50</number>
</property>
<property name="value">
<number>50</number>
</widget>
</item>
<item row="12" column="1">
<widget class="QLabel" name="actionRetransmissionLabel">
<property name="text">
<string>Action request retransmission timeout</string>
</property>
</widget>
</item>
<item row="14" column="0" colspan="3">
<item row="0" column="0" colspan="2">
<widget class="QLabel" name="systemIdLabel">
<property name="toolTip">
<string>The system ID is the number the MAV associates with this computer</string>
</property>
<property name="statusTip">
<string>The system ID is the number the MAV associates with this computer</string>
</property>
<property name="text">
<string>Groundstation MAVLink System ID</string>
</property>
</widget>
</item>
<item row="7" column="1" colspan="2">
<widget class="QLabel" name="versionLabel">
<property name="text">
<string>MAVLINK_VERSION: </string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QSpinBox" name="systemIdSpinBox">
<property name="toolTip">
<string>Set the groundstation number</string>
</property>
<property name="statusTip">
<string>Set the groundstation number</string>
</property>
<property name="minimum">
<number>1</number>
</property>
<property name="maximum">
<number>255</number>
</property>
</widget>
</item>
<item row="15" column="0">
<spacer name="horizontalSpacer_4">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>8</width>
<height>0</height>
</size>
</property>
</spacer>
</item>
<item row="13" column="0" colspan="3">
<widget class="Line" name="line">
<property name="minimumSize">
<size>
......@@ -139,7 +218,7 @@
</property>
</widget>
</item>
<item row="17" column="1" colspan="2">
<item row="16" column="1" colspan="2">
<widget class="QComboBox" name="droneOSComboBox">
<property name="editable">
<bool>true</bool>
......@@ -156,56 +235,15 @@
</item>
</widget>
</item>
<item row="11" column="0">
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>8</width>
<height>0</height>
</size>
</property>
</spacer>
</item>
<item row="11" column="1">
<widget class="QLabel" name="paramRewriteLabel">
<property name="text">
<string>Write request retransmission timeout</string>
</property>
</widget>
</item>
<item row="10" column="1">
<widget class="QLabel" name="paramRetransmissionLabel">
<property name="text">
<string>Read request retransmission timeout</string>
</property>
</widget>
</item>
<item row="1" column="0" colspan="3">
<widget class="QCheckBox" name="heartbeatCheckBox">
<property name="text">
<string>Emit heartbeat</string>
</property>
</widget>
</item>
<item row="3" column="0" colspan="3">
<widget class="QCheckBox" name="multiplexingCheckBox">
<property name="text">
<string>Enable Multiplexing: Forward packets to all other links</string>
</property>
</widget>
</item>
<item row="13" column="1">
<widget class="QLabel" name="actionRetransmissionLabel">
<widget class="QCheckBox" name="multiplexingFilterCheckBox">
<property name="text">
<string>Action request retransmission timeout</string>
<string>Filter multiplexed packets: Only forward selected IDs</string>
</property>
</widget>
</item>
<item row="8" column="0">
<spacer name="versionSpacer">
<item row="12" column="0">
<spacer name="horizontalSpacer_3">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
......@@ -217,51 +255,7 @@
</property>
</spacer>
</item>
<item row="0" column="2">
<widget class="QSpinBox" name="systemIdSpinBox">
<property name="toolTip">
<string>Set the groundstation number</string>
</property>
<property name="statusTip">
<string>Set the groundstation number</string>
</property>
<property name="minimum">
<number>1</number>
</property>
<property name="maximum">
<number>255</number>
</property>
</widget>
</item>
<item row="15" column="0" colspan="3">
<widget class="QCheckBox" name="droneOSCheckBox">
<property name="text">
<string>Forward MAVLink packets of all links to the host below</string>
</property>
</widget>
</item>
<item row="12" column="0" colspan="3">
<widget class="QCheckBox" name="actionGuardCheckBox">
<property name="text">
<string>Enable retransmission of actions / commands</string>
</property>
</widget>
</item>
<item row="4" column="0" colspan="3">
<widget class="QCheckBox" name="multiplexingFilterCheckBox">
<property name="text">
<string>Filter multiplexed packets: Only forward selected IDs</string>
</property>
</widget>
</item>
<item row="7" column="0" colspan="3">
<widget class="QCheckBox" name="versionCheckBox">
<property name="text">
<string>Only accept MAVs with same protocol version</string>
</property>
</widget>
</item>
<item row="5" column="0">
<item row="4" column="0">
<spacer name="multiplexingFilterSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
......@@ -277,42 +271,41 @@
</property>
</spacer>
</item>
<item row="16" column="1" colspan="2">
<widget class="QLineEdit" name="droneOSLineEdit">
<item row="10" column="1">
<widget class="QLabel" name="paramRewriteLabel">
<property name="text">
<string>Enter your authentication token</string>
</property>
<property name="maxLength">
<number>32</number>
<string>Write request retransmission timeout</string>
</property>
</widget>
</item>
<item row="9" column="0" colspan="3">
<widget class="QCheckBox" name="paramGuardCheckBox">
<property name="text">
<string>Enable retransmission of parameter read/write requests</string>
<item row="12" column="2">
<widget class="QSpinBox" name="actionRetransmissionSpinBox">
<property name="suffix">
<string> ms</string>
</property>
</widget>
</item>
<item row="8" column="1" colspan="2">
<widget class="QLabel" name="versionLabel">
<property name="text">
<string>MAVLINK_VERSION: </string>
<property name="minimum">
<number>20</number>
</property>
<property name="maximum">
<number>1000</number>
</property>
<property name="singleStep">
<number>10</number>
</property>
</widget>
</item>
<item row="0" column="0" colspan="2">
<widget class="QLabel" name="systemIdLabel">
<property name="toolTip">
<string>The system ID is the number the MAV associates with this computer</string>
</property>
<property name="statusTip">
<string>The system ID is the number the MAV associates with this computer</string>
<item row="7" column="0">
<spacer name="versionSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="text">
<string>Groundstation MAVLink System ID</string>
<property name="sizeHint" stdset="0">
<size>
<width>8</width>
<height>0</height>
</size>
</property>
</widget>
</spacer>
</item>
</layout>
</widget>
......
......@@ -89,9 +89,9 @@ Rectangle {
//-- Mavlink Heartbeats
QGCCheckBox {
text: "Emit heartbeat"
checked: QGroundControl.isHeartBeatEnabled
checked: multiVehicleManager.gcsHeartBeatEnabled
onClicked: {
QGroundControl.isHeartBeatEnabled = checked
multiVehicleManager.gcsHeartBeatEnabled = checked
}
}
//-----------------------------------------------------------------
......
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