3#include <QtCore/QElapsedTimer>
4#include <QtCore/QTimer>
42 int version()
const override {
return 0; }
43 QString
modelName()
const override {
return QStringLiteral(
"Simulated Camera"); }
44 QString
vendor()
const override {
return QStringLiteral(
"QGroundControl"); }
47 QSizeF
sensorSize()
const override {
return QSizeF(qQNaN(), qQNaN()); }
48 QSize
resolution()
const override {
return QSize(0, 0); }
52 bool hasZoom()
const override {
return false; }
53 bool hasFocus()
const override {
return false; }
61 int compID()
const override {
return 0; }
62 bool isBasic()
const override {
return true; }
84 Fact *
ev()
override {
return nullptr; }
88 Fact *
wb()
override {
return nullptr; }
91 QStringList
streamLabels()
const override {
return QStringList(); }
133 QElapsedTimer _videoRecordTimeElapsedTimer;
A Fact is used to hold a single value within the system.
Abstract base class for all camera controls: real and simulated.
virtual CameraMode cameraMode() const
Encapsulates the contents of a VIDEO_STREAM_INFORMATION message.
QRectF trackingImageRect() const override
QGCVideoStreamInfo * thermalStreamInstance() override
QString storageFreeStr() const override
void handleVideoStreamInformation(const mavlink_video_stream_information_t &) override
QGCVideoStreamInfo * currentStreamInstance() override
qreal focalLength() const override
quint32 storageTotal() const override
void startZoom(int) override
void setCameraMode(CameraMode cameraMode) override
bool stopVideoRecording() override
qreal focusLevel() const override
bool capturesPhotos() const override
bool validateParameter(Fact *, QVariant &) override
Allow controller to modify or invalidate parameter change.
void handleVideoStreamStatus(const mavlink_video_stream_status_t &) override
void setZoomLevel(qreal) override
CapturePhotosState capturePhotosState() const override
QmlObjectListModel * streams() override
QString batteryRemainingStr() const override
void handleParamExtAck(const mavlink_param_ext_ack_t &) override
Fact * exposureMode() override
void setPhotoCaptureMode(PhotoCaptureMode mode) override
void stepZoom(int) override
void startTracking(QRectF) override
void resumeStream() override
bool hasFocus() const override
~SimulatedCameraControl() override
bool trackingImageStatus() const override
qreal zoomLevel() const override
bool stopTakePhoto() override
void setCameraModePhoto() override
bool paramComplete() const override
void factChanged(Fact *) override
Notify controller a parameter has changed.
QString recordTimeStr() const override
void formatCard(int id=1) override
bool photosInVideoMode() const override
ThermalViewMode thermalMode() const override
quint32 storageFree() const override
void setTrackingEnabled(bool) override
void setPhotoLapse(qreal) override
QSizeF sensorSize() const override
void setThermalOpacity(double) override
QString modelName() const override
void handleBatteryStatus(const mavlink_battery_status_t &) override
bool toggleVideoRecording() override
bool trackingEnabled() const override
QSize resolution() const override
QStringList streamLabels() const override
Stream names to show the user (for selection)
bool autoStream() const override
int currentStream() const override
QString firmwareVersion() const override
int compID() const override
double thermalOpacity() const override
QStringList activeSettings() const override
void handleParamExtValue(const mavlink_param_ext_value_t &) override
bool videoInPhotoMode() const override
void setCurrentStream(int) override
bool hasVideoStream() const override
void handleStorageInformation(const mavlink_storage_information_t &) override
QString vendor() const override
void handleCameraCaptureStatus(const mavlink_camera_capture_status_t &) override
void setFocusLevel(qreal) override
void resetSettings() override
bool hasZoom() const override
void stopStream() override
TrackingStatus trackingStatus() const override
CaptureVideoState captureVideoState() const override
int batteryRemaining() const override
int version() const override
void stopTracking() override
quint32 recordTime() const override
void handleCameraSettings(const mavlink_camera_settings_t &) override
void handleTrackingImageStatus(const mavlink_camera_tracking_image_status_t &) override
void setPhotoLapseCount(int) override
bool takePhoto() override
bool incomingParameter(Fact *, QVariant &) override
Allow controller to modify or invalidate incoming parameter.
void startTracking(QPointF, double) override
Fact * aperture() override
bool isBasic() const override
StorageStatus storageStatus() const override
bool capturesVideo() const override
bool startVideoRecording() override
void toggleCameraMode() override
Fact * shutterSpeed() override
void setCameraModeVideo() override
bool hasModes() const override
void _paramDone() override
void setThermalMode(ThermalViewMode) override
bool hasTracking() const override