Commit bd4b4dfe authored by Don Gagne's avatar Don Gagne

High Latency Link bit support

parent 40708809
......@@ -127,6 +127,7 @@ Vehicle::Vehicle(LinkInterface* link,
, _maxProtoVersion(0)
, _vehicleCapabilitiesKnown(false)
, _capabilityBits(0)
, _highLatencyLink(false)
, _cameras(NULL)
, _connectionLost(false)
, _connectionLostEnabled(true)
......@@ -304,6 +305,7 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
, _defaultHoverSpeed(_settingsManager->appSettings()->offlineEditingHoverSpeed()->rawValue().toDouble())
, _vehicleCapabilitiesKnown(true)
, _capabilityBits(_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA ? 0 : MAV_PROTOCOL_CAPABILITY_MISSION_FENCE | MAV_PROTOCOL_CAPABILITY_MISSION_RALLY)
, _highLatencyLink(false)
, _cameras(NULL)
, _connectionLost(false)
, _connectionLostEnabled(true)
......@@ -1351,6 +1353,7 @@ void Vehicle::_addLink(LinkInterface* link)
_updatePriorityLink();
connect(_toolbox->linkManager(), &LinkManager::linkInactive, this, &Vehicle::_linkInactiveOrDeleted);
connect(_toolbox->linkManager(), &LinkManager::linkDeleted, this, &Vehicle::_linkInactiveOrDeleted);
connect(link, &LinkInterface::highLatencyChanged, this, &Vehicle::_updateHighLatencyLink);
}
}
......@@ -2962,6 +2965,14 @@ void Vehicle::_vehicleParamLoaded(bool ready)
}
}
void Vehicle::_updateHighLatencyLink(void)
{
if (_priorityLink->highLatency() != _highLatencyLink) {
_highLatencyLink = _priorityLink->highLatency();
emit highLatencyLinkChanged(_highLatencyLink);
}
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
......
......@@ -352,6 +352,7 @@ public:
Q_PROPERTY(QGCCameraManager* dynamicCameras READ dynamicCameras NOTIFY dynamicCamerasChanged)
Q_PROPERTY(QString hobbsMeter READ hobbsMeter NOTIFY hobbsMeterChanged)
Q_PROPERTY(bool vtolInFwdFlight READ vtolInFwdFlight WRITE setVtolInFwdFlight NOTIFY vtolInFwdFlightChanged)
Q_PROPERTY(bool highLatencyLink READ highLatencyLink NOTIFY highLatencyLinkChanged)
// Vehicle state used for guided control
Q_PROPERTY(bool flying READ flying NOTIFY flyingChanged) ///< Vehicle is flying
......@@ -638,6 +639,7 @@ public:
int telemetryLNoise () { return _telemetryLNoise; }
int telemetryRNoise () { return _telemetryRNoise; }
bool autoDisarm ();
bool highLatencyLink () const { return _highLatencyLink; }
/// Get the maximum MAVLink protocol version supported
/// @return the maximum version
unsigned maxProtoVersion () const { return _maxProtoVersion; }
......@@ -786,6 +788,7 @@ signals:
void initialPlanRequestCompleteChanged(bool initialPlanRequestComplete);
void capabilityBitsChanged(uint64_t capabilityBits);
void toolBarIndicatorsChanged(void);
void highLatencyLinkChanged(bool highLatencyLink);
void messagesReceivedChanged ();
void messagesSentChanged ();
......@@ -862,6 +865,7 @@ private slots:
void _offlineVehicleTypeSettingChanged(QVariant value);
void _offlineCruiseSpeedSettingChanged(QVariant value);
void _offlineHoverSpeedSettingChanged(QVariant value);
void _updateHighLatencyLink(void);
void _handleTextMessage (int newCount);
void _handletextMessageReceived (UASMessage* message);
......@@ -995,6 +999,7 @@ private:
unsigned _maxProtoVersion;
bool _vehicleCapabilitiesKnown;
uint64_t _capabilityBits;
bool _highLatencyLink;
QGCCameraManager* _cameras;
......
......@@ -21,11 +21,12 @@ uint8_t LinkInterface::mavlinkChannel(void) const
}
// Links are only created by LinkManager so constructor is not public
LinkInterface::LinkInterface(SharedLinkConfigurationPointer& config)
: QThread(0)
, _config(config)
, _mavlinkChannelSet(false)
, _active(false)
, _enableRateCollection(false)
: QThread (0)
, _config (config)
, _highLatency (false)
, _mavlinkChannelSet (false)
, _active (false)
, _enableRateCollection (false)
, _decodedFirstMavlinkPacket(false)
{
_config->setLink(this);
......
......@@ -116,6 +116,11 @@ public:
/// set into the link when it is added to LinkManager
uint8_t mavlinkChannel(void) const;
/// Returns whether this link is high latency or not. High latency links should only perform
/// minimal communication with vehicle.
/// signals: highLatencyChanged
bool highLatency(void) const { return _highLatency; }
bool decodedFirstMavlinkPacket(void) const { return _decodedFirstMavlinkPacket; }
bool setDecodedFirstMavlinkPacket(bool decodedFirstMavlinkPacket) { return _decodedFirstMavlinkPacket = decodedFirstMavlinkPacket; }
......@@ -149,6 +154,7 @@ signals:
void autoconnectChanged(bool autoconnect);
void activeChanged(bool active);
void _invokeWriteBytes(QByteArray);
void highLatencyChanged(bool highLatency);
/// Signalled when a link suddenly goes away due to it being removed by for example pulling the cable to the connection.
void connectionRemoved(LinkInterface* link);
......@@ -202,7 +208,8 @@ protected:
void _logOutputDataRate(quint64 byteCount, qint64 time);
SharedLinkConfigurationPointer _config;
bool _highLatency;
private:
/**
* @brief logDataRateToBuffer Stores transmission times/amounts for statistics
......
......@@ -44,6 +44,7 @@ const char* MockLink::_failParam = "COM_FLTMODE6";
const char* MockConfiguration::_firmwareTypeKey = "FirmwareType";
const char* MockConfiguration::_vehicleTypeKey = "VehicleType";
const char* MockConfiguration::_sendStatusTextKey = "SendStatusText";
const char* MockConfiguration::_highLatencyKey = "HighLatency";
const char* MockConfiguration::_failureModeKey = "FailureMode";
MockLink::MockLink(SharedLinkConfigurationPointer& config)
......@@ -79,6 +80,7 @@ MockLink::MockLink(SharedLinkConfigurationPointer& config)
_firmwareType = mockConfig->firmwareType();
_vehicleType = mockConfig->vehicleType();
_sendStatusText = mockConfig->sendStatusText();
_highLatency = mockConfig->highLatency();
_failureMode = mockConfig->failureMode();
union px4_custom_mode px4_cm;
......@@ -1012,10 +1014,11 @@ void MockLink::_sendStatusTextMessages(void)
MockConfiguration::MockConfiguration(const QString& name)
: LinkConfiguration(name)
, _firmwareType(MAV_AUTOPILOT_PX4)
, _vehicleType(MAV_TYPE_QUADROTOR)
, _sendStatusText(false)
, _failureMode(FailNone)
, _firmwareType (MAV_AUTOPILOT_PX4)
, _vehicleType (MAV_TYPE_QUADROTOR)
, _sendStatusText (false)
, _highLatency (false)
, _failureMode (FailNone)
{
}
......@@ -1026,6 +1029,7 @@ MockConfiguration::MockConfiguration(MockConfiguration* source)
_firmwareType = source->_firmwareType;
_vehicleType = source->_vehicleType;
_sendStatusText = source->_sendStatusText;
_highLatency = source->_highLatency;
_failureMode = source->_failureMode;
}
......@@ -1042,6 +1046,7 @@ void MockConfiguration::copyFrom(LinkConfiguration *source)
_firmwareType = usource->_firmwareType;
_vehicleType = usource->_vehicleType;
_sendStatusText = usource->_sendStatusText;
_highLatency = usource->_highLatency;
_failureMode = usource->_failureMode;
}
......@@ -1051,6 +1056,7 @@ void MockConfiguration::saveSettings(QSettings& settings, const QString& root)
settings.setValue(_firmwareTypeKey, (int)_firmwareType);
settings.setValue(_vehicleTypeKey, (int)_vehicleType);
settings.setValue(_sendStatusTextKey, _sendStatusText);
settings.setValue(_highLatencyKey, _highLatency);
settings.setValue(_failureModeKey, (int)_failureMode);
settings.sync();
settings.endGroup();
......@@ -1062,6 +1068,7 @@ void MockConfiguration::loadSettings(QSettings& settings, const QString& root)
_firmwareType = (MAV_AUTOPILOT)settings.value(_firmwareTypeKey, (int)MAV_AUTOPILOT_PX4).toInt();
_vehicleType = (MAV_TYPE)settings.value(_vehicleTypeKey, (int)MAV_TYPE_QUADROTOR).toInt();
_sendStatusText = settings.value(_sendStatusTextKey, false).toBool();
_highLatency = settings.value(_highLatencyKey, false).toBool();
_failureMode = (FailureMode_t)settings.value(_failureModeKey, (int)FailNone).toInt();
settings.endGroup();
}
......
......@@ -32,12 +32,15 @@ public:
Q_PROPERTY(int firmware READ firmware WRITE setFirmware NOTIFY firmwareChanged)
Q_PROPERTY(int vehicle READ vehicle WRITE setVehicle NOTIFY vehicleChanged)
Q_PROPERTY(bool sendStatus READ sendStatusText WRITE setSendStatusText NOTIFY sendStatusChanged)
Q_PROPERTY(bool highLatency READ highLatency WRITE setHighLatency NOTIFY highLatencyChanged)
// QML Access
int firmware () { return (int)_firmwareType; }
void setFirmware (int type) { _firmwareType = (MAV_AUTOPILOT)type; emit firmwareChanged(); }
int vehicle () { return (int)_vehicleType; }
bool highLatency () const { return _highLatency; }
void setVehicle (int type) { _vehicleType = (MAV_TYPE)type; emit vehicleChanged(); }
void setHighLatency (bool latency) { _highLatency = latency; emit highLatencyChanged(); }
MockConfiguration(const QString& name);
MockConfiguration(MockConfiguration* source);
......@@ -73,16 +76,19 @@ signals:
void firmwareChanged ();
void vehicleChanged ();
void sendStatusChanged ();
void highLatencyChanged ();
private:
MAV_AUTOPILOT _firmwareType;
MAV_TYPE _vehicleType;
bool _sendStatusText;
bool _highLatency;
FailureMode_t _failureMode;
static const char* _firmwareTypeKey;
static const char* _vehicleTypeKey;
static const char* _sendStatusTextKey;
static const char* _highLatencyKey;
static const char* _failureModeKey;
};
......
......@@ -35,6 +35,7 @@ Item {
else
subEditConfig.firmware = 0
subEditConfig.sendStatus = sendStatus.checked
subEditConfig.highLatency = highLatency.checked
}
Component.onCompleted: {
......@@ -49,6 +50,7 @@ Item {
else
copterVehicle.checked = true
sendStatus.checked = subEditConfig.sendStatus
highLatency.checked = subEditConfig.highLatency
}
Column {
......@@ -67,6 +69,11 @@ Item {
text: qsTr("Send Status Text and Voice")
checked: false
}
QGCCheckBox {
id: highLatency
text: qsTr("High latency")
checked: false
}
Item {
height: ScreenTools.defaultFontPixelHeight / 2
width: parent.width
......
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