|
|
@ -1796,7 +1796,7 @@ QGCCameraControl::_requestStreamInfo(uint8_t streamID) |
|
|
|
qCDebug(CameraControlLog) << "Requesting video stream info for:" << streamID; |
|
|
|
qCDebug(CameraControlLog) << "Requesting video stream info for:" << streamID; |
|
|
|
// By default, try to use new REQUEST_MESSAGE command instead of
|
|
|
|
// By default, try to use new REQUEST_MESSAGE command instead of
|
|
|
|
// deprecated MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION.
|
|
|
|
// deprecated MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION.
|
|
|
|
if (_videoStreamStatusRetries % 2 == 0) { |
|
|
|
if (_videoStreamStatusRetries++ % 2 == 0) { |
|
|
|
_vehicle->sendMavCommand( |
|
|
|
_vehicle->sendMavCommand( |
|
|
|
_compID, // target component
|
|
|
|
_compID, // target component
|
|
|
|
MAV_CMD_REQUEST_MESSAGE, // command id
|
|
|
|
MAV_CMD_REQUEST_MESSAGE, // command id
|
|
|
@ -1904,7 +1904,6 @@ QGCCameraControl::_streamInfoTimeout() |
|
|
|
void |
|
|
|
void |
|
|
|
QGCCameraControl::_streamStatusTimeout() |
|
|
|
QGCCameraControl::_streamStatusTimeout() |
|
|
|
{ |
|
|
|
{ |
|
|
|
_videoStreamStatusRetries++; |
|
|
|
|
|
|
|
QGCVideoStreamInfo* pStream = currentStreamInstance(); |
|
|
|
QGCVideoStreamInfo* pStream = currentStreamInstance(); |
|
|
|
if(pStream) { |
|
|
|
if(pStream) { |
|
|
|
_requestStreamStatus(static_cast<uint8_t>(pStream->streamID())); |
|
|
|
_requestStreamStatus(static_cast<uint8_t>(pStream->streamID())); |
|
|
|