@@ -24,8 +24,10 @@ VideoStreamControl::VideoStreamControl()
2424 _cameraIdSetting = _videoSettings->cameraId ()->rawValue ().toUInt ();
2525 _cameraInfoReceived = false ;
2626 _currentHdmiInput = 0 ; // Default to HDMI 1
27+ _currentResolution = 1 ; // Default to 1080p
2728
2829 connect (_videoSettings->cameraId (), &Fact::rawValueChanged, this , &VideoStreamControl::_cameraIdChanged);
30+ connect (_videoSettings->resolution (), &Fact::rawValueChanged, this , &VideoStreamControl::_resolutionChanged);
2931 // connect(&_infoRequestTimer, &QTimer::timeout, this, &VideoStreamControl::_requestVideoStreamInfo);
3032 // _infoRequestTimer.setInterval(1000);
3133}
@@ -73,9 +75,11 @@ void VideoStreamControl::_handleVideoStreamInformation(mavlink_message_t& messag
7375 mavlink_msg_video_stream_information_decode (&message, &streamInfo);
7476
7577 qWarning () << " VideoStreamControl: Received video stream information: stream_id=" << streamInfo.stream_id
76- << " count=" << streamInfo.count ;
78+ << " count=" << streamInfo.count
79+ << " resolution=" << streamInfo.resolution_h << " x" << streamInfo.resolution_v ;
7780 qCDebug (VideoStreamControlLog) << " Received video stream information: stream_id=" << streamInfo.stream_id
78- << " count=" << streamInfo.count ;
81+ << " count=" << streamInfo.count
82+ << " resolution=" << streamInfo.resolution_h << " x" << streamInfo.resolution_v ;
7983
8084 // Convert stream_id from 1-based to 0-based for QGC camera setting
8185 uint32_t cameraIdZeroBased = (streamInfo.stream_id > 0 ) ? streamInfo.stream_id - 1 : 0 ;
@@ -102,8 +106,30 @@ void VideoStreamControl::_handleVideoStreamInformation(mavlink_message_t& messag
102106 qCDebug (VideoStreamControlLog) << " HDMI input changed to:" << (_currentHdmiInput == 0 ? " HDMI 1" : " HDMI 2" );
103107 }
104108
109+ // Detect and update current resolution from stream info
110+ uint8_t detectedResolution = 1 ; // Default to 1080p
111+ if (streamInfo.resolution_v == 720 ) {
112+ detectedResolution = 0 ; // 720p
113+ } else if (streamInfo.resolution_v == 1080 ) {
114+ detectedResolution = 1 ; // 1080p
115+ }
116+
117+ if (_currentResolution != detectedResolution) {
118+ qCDebug (VideoStreamControlLog) << " Resolution changed from"
119+ << (_currentResolution == 0 ? " 720p" : " 1080p" ) << " to"
120+ << (detectedResolution == 0 ? " 720p" : " 1080p" );
121+ _currentResolution = detectedResolution;
122+ emit currentResolutionChanged ();
123+
124+ // Synchronize UI setting with air unit's resolution
125+ disconnect (_videoSettings->resolution (), &Fact::rawValueChanged, this , &VideoStreamControl::_resolutionChanged);
126+ _videoSettings->resolution ()->setRawValue (detectedResolution);
127+ connect (_videoSettings->resolution (), &Fact::rawValueChanged, this , &VideoStreamControl::_resolutionChanged);
128+ }
129+
105130 // Always log current state for debugging button issues
106- qWarning () << " VideoStreamControl: Current HDMI input =" << _currentHdmiInput << " (" << (_currentHdmiInput == 0 ? " HDMI 1" : " HDMI 2" ) << " )" ;
131+ qWarning () << " VideoStreamControl: Current HDMI input =" << _currentHdmiInput << " (" << (_currentHdmiInput == 0 ? " HDMI 1" : " HDMI 2" ) << " )"
132+ << " Resolution =" << (detectedResolution == 0 ? " 720p" : " 1080p" );
107133
108134 // Update our camera setting to match the air unit's current camera
109135 if (cameraIdZeroBased != _cameraIdSetting) {
@@ -232,3 +258,51 @@ void VideoStreamControl::_setSettingInProgress(bool inProgress)
232258 emit settingInProgressChanged ();
233259 return ;
234260}
261+
262+ void VideoStreamControl::_resolutionChanged ()
263+ {
264+ uint32_t newResolution = _videoSettings->resolution ()->rawValue ().toUInt ();
265+ qCDebug (VideoStreamControlLog) << " Resolution changed to:" << (newResolution == 0 ? " 720p" : " 1080p" );
266+
267+ if (_linkInterface == NULL ) {
268+ qCDebug (VideoStreamControlLog) << " No link interface available, cannot change resolution" ;
269+ return ;
270+ }
271+
272+ // Only proceed if the resolution has actually changed
273+ if (newResolution != _currentResolution) {
274+ qCDebug (VideoStreamControlLog) << " User changed resolution from" << (_currentResolution == 0 ? " 720p" : " 1080p" )
275+ << " to" << (newResolution == 0 ? " 720p" : " 1080p" );
276+
277+ // Determine parameter name based on current camera ID
278+ const char * param_id = (_cameraIdSetting == 0 ) ? " VideoRes0" : " VideoRes1" ;
279+
280+ // Parameter value: "1" for 1080p, "0" for 720p
281+ const char * param_value = (newResolution == 1 ) ? " 1" : " 0" ;
282+
283+ qCDebug (VideoStreamControlLog) << " Sending PARAM_EXT_SET:" << param_id << " =" << param_value;
284+
285+ // Send PARAM_EXT_SET message
286+ mavlink_message_t msg;
287+ mavlink_param_ext_set_t param_set;
288+
289+ memset (¶m_set, 0 , sizeof (mavlink_param_ext_set_t ));
290+ param_set.target_system = _systemId;
291+ param_set.target_component = MAV_COMP_ID_CAMERA;
292+ strncpy (param_set.param_id , param_id, sizeof (param_set.param_id ) - 1 );
293+ strncpy (param_set.param_value , param_value, sizeof (param_set.param_value ) - 1 );
294+ param_set.param_type = MAV_PARAM_EXT_TYPE_UINT8;
295+
296+ mavlink_msg_param_ext_set_encode (_mavlinkProtocol->getSystemId (), _mavlinkProtocol->getComponentId (), &msg, ¶m_set);
297+
298+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
299+ int len = mavlink_msg_to_send_buffer (buffer, &msg);
300+ _linkInterface->writeBytesThreadSafe ((const char *)buffer, len);
301+
302+ // Update local state and emit signal
303+ _currentResolution = newResolution;
304+ emit currentResolutionChanged ();
305+ } else {
306+ qCDebug (VideoStreamControlLog) << " Resolution unchanged, no action needed" ;
307+ }
308+ }
0 commit comments