From b8ad65448603f6e6f21468eb355d9479bba84921 Mon Sep 17 00:00:00 2001 From: Gus Grubba Date: Mon, 10 Dec 2018 10:48:22 -0400 Subject: [PATCH] Fix stream configuration test --- src/FlightDisplay/VideoManager.cc | 4 +++- src/Settings/VideoSettings.cc | 12 ++++++++---- 2 files changed, 11 insertions(+), 5 deletions(-) diff --git a/src/FlightDisplay/VideoManager.cc b/src/FlightDisplay/VideoManager.cc index 889d1dd77..0de9efce0 100644 --- a/src/FlightDisplay/VideoManager.cc +++ b/src/FlightDisplay/VideoManager.cc @@ -238,8 +238,9 @@ VideoManager::_setActiveVehicle(Vehicle* vehicle) } //-- Video Stream Discovery connect(_activeVehicle, &Vehicle::mavlinkMessageReceived, this, &VideoManager::_vehicleMessageReceived); + qCDebug(VideoManagerLog) << "Requesting video stream info"; _activeVehicle->sendMavCommand( - 0, // Target component + MAV_COMP_ID_ALL, // Target component MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION, // Command id false, // ShowError 1, // First camera only @@ -254,6 +255,7 @@ VideoManager::_vehicleMessageReceived(const mavlink_message_t& message) //-- For now we only handle one stream. There is no UI to pick different streams. if(message.msgid == MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION) { mavlink_msg_video_stream_information_decode(&message, &_streamInfo); + qCDebug(VideoManagerLog) << "Received video stream info:" << _streamInfo.uri; _restartVideo(); emit aspectRatioChanged(); } diff --git a/src/Settings/VideoSettings.cc b/src/Settings/VideoSettings.cc index 29e9054f0..8be433f25 100644 --- a/src/Settings/VideoSettings.cc +++ b/src/Settings/VideoSettings.cc @@ -137,18 +137,22 @@ bool VideoSettings::streamConfigured(void) } //-- If UDP, check if port is set if(vSource == videoSourceUDP) { + qCDebug(VideoManagerLog) << "Testing configuration for UDP Stream:" << udpPort()->rawValue().toInt(); return udpPort()->rawValue().toInt() != 0; } //-- If RTSP, check for URL if(vSource == videoSourceRTSP) { + qCDebug(VideoManagerLog) << "Testing configuration for RTSP Stream:" << rtspUrl()->rawValue().toString(); return !rtspUrl()->rawValue().toString().isEmpty(); } - //-- If Auto, check for URL - if(vSource == videoSourceAuto) { - return !rtspUrl()->rawValue().toString().isEmpty(); + //-- If TCP, check for URL + if(vSource == videoSourceTCP) { + qCDebug(VideoManagerLog) << "Testing configuration for TCP Stream:" << tcpUrl()->rawValue().toString(); + return !tcpUrl()->rawValue().toString().isEmpty(); } //-- If Auto, check for received URL - if(vSource == videoSourceTCP) { + if(vSource == videoSourceAuto) { + qCDebug(VideoManagerLog) << "Testing configuration for Auto Stream:" << qgcApp()->toolbox()->videoManager()->autoURL(); return !qgcApp()->toolbox()->videoManager()->autoURL().isEmpty(); } return false; -- 2.22.0