14 qCDebug(SimulatedCameraControlLog) <<
this;
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(SimulatedCameraControlLog) <<
"Set camera mode denied - camera does not support modes";
76 qCWarning(SimulatedCameraControlLog) <<
"Invalid mode" <<
cameraMode;
81void SimulatedCameraControl::_setCameraMode(CameraMode mode)
92 qCWarning(SimulatedCameraControlLog) <<
"Toggle camera mode denied - camera does not support modes";
110 qCWarning(SimulatedCameraControlLog) <<
"Camera does not support modes";
120 qCWarning(SimulatedCameraControlLog) <<
"Camera does not support modes";
130 qCWarning(SimulatedCameraControlLog) <<
"Camera does not handle image capture";
135 qCWarning(SimulatedCameraControlLog) <<
"Camera not idle";
163 qCWarning(SimulatedCameraControlLog) <<
"Camera does not handle video capture";
167 qCWarning(SimulatedCameraControlLog) <<
"Camera does not take video in photo mode";
171 qCWarning(SimulatedCameraControlLog) <<
"Camera already recording";
176 _videoRecordTimeElapsedTimer.start();
184 qCWarning(SimulatedCameraControlLog) <<
"Camera not recording";
247 qCWarning(SimulatedCameraControlLog) <<
"Time lapse capture not supported by simulated camera";
#define QGC_LOGGING_CATEGORY(name, categoryStr)
void rawValueChanged(const QVariant &value)
Abstract base class for all camera controls: real and simulated.
@ CapturePhotosStateDisabled
@ CapturePhotosStateCapturingSinglePhoto
@ CapturePhotosStateCapturingMultiplePhotos
@ PHOTO_CAPTURE_INTERVAL_IDLE
@ PHOTO_CAPTURE_INTERVAL_IN_PROGRESS
@ PHOTO_CAPTURE_IN_PROGRESS
void videoCaptureStatusChanged()
PhotoCaptureStatus _photoCaptureStatus() const
PhotoCaptureMode _photoCaptureMode
QString cameraModeToStr(CameraMode mode)
virtual PhotoCaptureMode photoCaptureMode() const
void photoCaptureStatusChanged()
VideoCaptureStatus _videoCaptureStatus() const
void capturePhotosStateChanged()
@ VIDEO_CAPTURE_STATUS_RUNNING
void captureVideoStateChanged()
virtual CameraMode cameraMode() const
PhotoCaptureStatus _photoCaptureStatusValue
@ PHOTO_CAPTURE_TIMELAPSE
@ CaptureVideoStateDisabled
@ CaptureVideoStateCapturing
void photoCaptureModeChanged()
QTimer _videoRecordTimeUpdateTimer
static SettingsManager * instance()
FlyViewSettings * flyViewSettings() const
Creates a simulated Camera Control which supports:
CapturePhotosState capturePhotosState() const override
void setCameraMode(CameraMode cameraMode) override
bool stopVideoRecording() override
bool capturesPhotos() const override
CaptureVideoState captureVideoState() const override
void setPhotoCaptureMode(PhotoCaptureMode mode) override
~SimulatedCameraControl() override
void setCameraModePhoto() override
QString recordTimeStr() const override
bool toggleVideoRecording() override
bool hasVideoStream() 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
Q_INVOKABLE void triggerSimpleCamera(void)
Trigger camera using MAV_CMD_DO_DIGICAM_CONTROL command.
Q_INVOKABLE void stopRecording()
Q_INVOKABLE void startRecording(const QString &videoFile=QString())
static VideoManager * instance()
void recordingChanged(bool recording)
void showAppMessage(const QString &message, const QString &title)
Modal application message. Queued if the UI isn't ready yet.