diff --git a/src/Camera/QGCCameraControl.cc b/src/Camera/QGCCameraControl.cc index f46f974d5c46c3db191fc8a91b79b4034b9b1634..a03ecc01387cdc865248cd48a3418e00c39ff9b5 100644 --- a/src/Camera/QGCCameraControl.cc +++ b/src/Camera/QGCCameraControl.cc @@ -770,7 +770,7 @@ QGCCameraControl::_setVideoStatus(VideoStatus status) emit videoStatusChanged(); if(status == VIDEO_CAPTURE_STATUS_RUNNING) { _recordTime = 0; - _recTime.start(); + _recTime = QTime::currentTime(); _recTimer.start(); } else { _recTimer.stop(); @@ -784,7 +784,7 @@ QGCCameraControl::_setVideoStatus(VideoStatus status) void QGCCameraControl::_recTimerHandler() { - _recordTime = static_cast(_recTime.elapsed()); + _recordTime = static_cast(_recTime.msec()); emit recordTimeChanged(); } @@ -1524,7 +1524,7 @@ QGCCameraControl::handleCaptureStatus(const mavlink_camera_capture_status_t& cap //-- Do we have recording time? if(cap.recording_time_ms) { _recordTime = cap.recording_time_ms; - _recTime = _recTime.addMSecs(_recTime.elapsed() - static_cast(cap.recording_time_ms)); + _recTime = _recTime.addMSecs(_recTime.msec() - static_cast(cap.recording_time_ms)); emit recordTimeChanged(); } //-- Video/Image Capture Status