14 qCDebug(SimulatedCameraControlLog) <<
this;
16 auto videoManager = VideoManager::instance();
18 _videoCaptureStatusValue = recording ? VIDEO_CAPTURE_STATUS_RUNNING : VIDEO_CAPTURE_STATUS_STOPPED;
19 emit videoCaptureStatusChanged();
37 if (capturesVideo()) {
38 _cameraMode = CAM_MODE_VIDEO;
39 }
else if (capturesPhotos()) {
40 _cameraMode = CAM_MODE_PHOTO;
42 _cameraMode = CAM_MODE_UNDEFINED;
45 _videoRecordTimeUpdateTimer.setInterval(1000);
51 qCDebug(SimulatedCameraControlLog) <<
this;
56 return QTime(0, 0).addMSecs(
static_cast<int>(
recordTime())).toString(
"hh:mm:ss");
64 qCWarning(CameraControlLog) <<
"Set camera mode denied - camera does not support modes";
76 qCWarning(CameraControlLog) <<
"Invalid mode" <<
cameraMode;
81void SimulatedCameraControl::_setCameraMode(CameraMode mode)
92 qCWarning(CameraControlLog) <<
"Toggle camera mode denied - camera does not support modes";
110 qCWarning(CameraControlLog) <<
"Camera does not support modes";
120 qCWarning(CameraControlLog) <<
"Camera does not support modes";
130 qCWarning(CameraControlLog) <<
"Camera does not handle image capture";
135 qCWarning(CameraControlLog) <<
"Camera not idle";
152 qgcApp()->showAppMessage(tr(
"Time lapse capture not supported by this camera"));
163 qCWarning(CameraControlLog) <<
"Camera does not handle video capture";
167 qCWarning(CameraControlLog) <<
"Camera does not take video in photo mode";
171 qCWarning(CameraControlLog) <<
"Camera already recording";
176 _videoRecordTimeElapsedTimer.start();
177 VideoManager::instance()->startRecording();
184 qCWarning(CameraControlLog) <<
"Camera not recording";
189 VideoManager::instance()->stopRecording();
200 return VideoManager::instance()->hasVideo();
216 return VideoManager::instance()->decoding();
247 qCWarning(CameraControlLog) <<
"Time lapse capture not supported by simulated camera";
#define QGC_LOGGING_CATEGORY(name, categoryStr)
void rawValueChanged(const QVariant &value)
Fact *showSimpleCameraControl READ showSimpleCameraControl CONSTANT Fact * showSimpleCameraControl()
Abstract base class for all camera controls: real and simulated.
void photoCaptureModeChanged()
virtual CameraMode cameraMode() const
@ PHOTO_CAPTURE_TIMELAPSE
void photoCaptureStatusChanged()
PhotoCaptureStatus _photoCaptureStatus() const
@ CapturePhotosStateCapturingMultiplePhotos
@ CapturePhotosStateCapturingSinglePhoto
@ CapturePhotosStateDisabled
QTimer _videoRecordTimeUpdateTimer
VideoCaptureStatus _videoCaptureStatus() const
PhotoCaptureStatus _photoCaptureStatusValue
void videoCaptureStatusChanged()
void capturePhotosStateChanged()
void captureVideoStateChanged()
@ PHOTO_CAPTURE_IN_PROGRESS
@ PHOTO_CAPTURE_INTERVAL_IN_PROGRESS
@ PHOTO_CAPTURE_INTERVAL_IDLE
@ CaptureVideoStateDisabled
@ CaptureVideoStateCapturing
QString cameraModeToStr(CameraMode mode)
@ VIDEO_CAPTURE_STATUS_RUNNING
PhotoCaptureMode _photoCaptureMode
virtual PhotoCaptureMode photoCaptureMode() const
void setCameraMode(CameraMode cameraMode) override
bool stopVideoRecording() override
bool capturesPhotos() const override
CapturePhotosState capturePhotosState() const override
void setPhotoCaptureMode(PhotoCaptureMode mode) override
~SimulatedCameraControl() override
void setCameraModePhoto() override
QString recordTimeStr() const override
bool toggleVideoRecording() override
bool hasVideoStream() const override
CaptureVideoState captureVideoState() const override
quint32 recordTime() const override
bool takePhoto() override
bool capturesVideo() const override
bool startVideoRecording() override
void toggleCameraMode() override
void setCameraModeVideo() override
bool hasModes() const override
void triggerSimpleCamera(void)
Trigger camera using MAV_CMD_DO_DIGICAM_CONTROL command.
void recordingChanged(bool recording)