Unverified Commit 02216607 authored by Don Gagne's avatar Don Gagne Committed by GitHub

New Solo video handshake sequence (#9155)

* Add 3DR Solo, Parrot Discovery video sources

* New solo video handshake, remove stale code
parent 10a51723
This diff is collapsed.
......@@ -23,29 +23,6 @@
Q_DECLARE_LOGGING_CATEGORY(APMFirmwarePluginLog)
class APMFirmwareVersion
{
public:
APMFirmwareVersion(const QString &versionText = "");
bool isValid() const;
bool isBeta() const;
bool isDev() const;
bool operator<(const APMFirmwareVersion& other) const;
QString versionString() const { return _versionString; }
QString vehicleType() const { return _vehicleType; }
int majorNumber() const { return _major; }
int minorNumber() const { return _minor; }
int patchNumber() const { return _patch; }
private:
void _parseVersion(const QString &versionText);
QString _versionString;
QString _vehicleType;
int _major;
int _minor;
int _patch;
};
class APMCustomMode
{
public:
......@@ -118,16 +95,14 @@ private slots:
void _artooSocketError(QAbstractSocket::SocketError socketError);
private:
void _adjustSeverity(mavlink_message_t* message) const;
void _adjustCalibrationMessageSeverity(mavlink_message_t* message) const;
static bool _isTextSeverityAdjustmentNeeded(const APMFirmwareVersion& firmwareVersion);
void _setInfoSeverity(mavlink_message_t* message) const;
QString _getMessageText(mavlink_message_t* message) const;
void _handleIncomingParamValue(Vehicle* vehicle, mavlink_message_t* message);
bool _handleIncomingStatusText(Vehicle* vehicle, mavlink_message_t* message);
void _handleIncomingHeartbeat(Vehicle* vehicle, mavlink_message_t* message);
void _handleOutgoingParamSetThreadSafe(Vehicle* vehicle, LinkInterface* outgoingLink, mavlink_message_t* message);
void _soloVideoHandshake(Vehicle* vehicle, bool originalSoloFirmware);
void _soloVideoHandshake(void);
bool _guidedModeTakeoff(Vehicle* vehicle, double altitudeRel);
void _handleRCChannels(Vehicle* vehicle, mavlink_message_t* message);
void _handleRCChannelsRaw(Vehicle* vehicle, mavlink_message_t* message);
......@@ -146,14 +121,4 @@ private:
static const int _artooVideoHandshakePort;
};
class APMFirmwarePluginInstanceData : public QObject
{
Q_OBJECT
public:
APMFirmwarePluginInstanceData(QObject* parent = nullptr);
bool textSeverityAdjustmentNeeded;
};
#endif
......@@ -19,13 +19,15 @@
#include <QCameraInfo>
#endif
const char* VideoSettings::videoSourceNoVideo = "No Video Available";
const char* VideoSettings::videoDisabled = "Video Stream Disabled";
const char* VideoSettings::videoSourceRTSP = "RTSP Video Stream";
const char* VideoSettings::videoSourceUDPH264 = "UDP h.264 Video Stream";
const char* VideoSettings::videoSourceUDPH265 = "UDP h.265 Video Stream";
const char* VideoSettings::videoSourceTCP = "TCP-MPEG2 Video Stream";
const char* VideoSettings::videoSourceMPEGTS = "MPEG-TS (h.264) Video Stream";
const char* VideoSettings::videoSourceNoVideo = "No Video Available";
const char* VideoSettings::videoDisabled = "Video Stream Disabled";
const char* VideoSettings::videoSourceRTSP = "RTSP Video Stream";
const char* VideoSettings::videoSourceUDPH264 = "UDP h.264 Video Stream";
const char* VideoSettings::videoSourceUDPH265 = "UDP h.265 Video Stream";
const char* VideoSettings::videoSourceTCP = "TCP-MPEG2 Video Stream";
const char* VideoSettings::videoSourceMPEGTS = "MPEG-TS (h.264) Video Stream";
const char* VideoSettings::videoSource3DRSolo = "3DR Solo";
const char* VideoSettings::videoSourceParrotDiscovery = "Parrot Discovery";
DECLARE_SETTINGGROUP(Video, "Video")
{
......@@ -41,6 +43,8 @@ DECLARE_SETTINGGROUP(Video, "Video")
#endif
videoSourceList.append(videoSourceTCP);
videoSourceList.append(videoSourceMPEGTS);
videoSourceList.append(videoSource3DRSolo);
videoSourceList.append(videoSourceParrotDiscovery);
#endif
#ifndef QGC_DISABLE_UVC
QList<QCameraInfo> cameras = QCameraInfo::availableCameras();
......
......@@ -42,7 +42,7 @@ public:
Q_PROPERTY(QString udp265VideoSource READ udp265VideoSource CONSTANT)
Q_PROPERTY(QString tcpVideoSource READ tcpVideoSource CONSTANT)
Q_PROPERTY(QString mpegtsVideoSource READ mpegtsVideoSource CONSTANT)
Q_PROPERTY(QString disabledVideoSource READ disabledVideoSource CONSTANT)
Q_PROPERTY(QString disabledVideoSource READ disabledVideoSource CONSTANT)
bool streamConfigured ();
QString rtspVideoSource () { return videoSourceRTSP; }
......@@ -59,6 +59,8 @@ public:
static const char* videoSourceRTSP;
static const char* videoSourceTCP;
static const char* videoSourceMPEGTS;
static const char* videoSource3DRSolo;
static const char* videoSourceParrotDiscovery;
signals:
void streamConfiguredChanged (bool configured);
......
......@@ -525,13 +525,14 @@ VideoManager::isGStreamer()
{
#if defined(QGC_GST_STREAMING)
QString videoSource = _videoSettings->videoSource()->rawValue().toString();
return
videoSource == VideoSettings::videoSourceUDPH264 ||
videoSource == VideoSettings::videoSourceUDPH265 ||
videoSource == VideoSettings::videoSourceRTSP ||
videoSource == VideoSettings::videoSourceTCP ||
videoSource == VideoSettings::videoSourceMPEGTS ||
autoStreamConfigured();
return videoSource == VideoSettings::videoSourceUDPH264 ||
videoSource == VideoSettings::videoSourceUDPH265 ||
videoSource == VideoSettings::videoSourceRTSP ||
videoSource == VideoSettings::videoSourceTCP ||
videoSource == VideoSettings::videoSourceMPEGTS ||
videoSource == VideoSettings::videoSource3DRSolo ||
videoSource == VideoSettings::videoSourceParrotDiscovery ||
autoStreamConfigured();
#else
return false;
#endif
......@@ -685,6 +686,10 @@ VideoManager::_updateSettings(unsigned id)
settingsChanged |= _updateVideoUri(0, _videoSettings->rtspUrl()->rawValue().toString());
else if (source == VideoSettings::videoSourceTCP)
settingsChanged |= _updateVideoUri(0, QStringLiteral("tcp://%1").arg(_videoSettings->tcpUrl()->rawValue().toString()));
else if (source == VideoSettings::videoSource3DRSolo)
settingsChanged |= _updateVideoUri(0, QStringLiteral("udp://0.0.0.0:5600"));
else if (source == VideoSettings::videoSourceParrotDiscovery)
settingsChanged |= _updateVideoUri(0, QStringLiteral("udp://0.0.0.0:8888"));
return settingsChanged;
}
......
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