QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MockConfiguration.h
Go to the documentation of this file.
1#pragma once
2
3#include "LinkConfiguration.h"
4
5#include "MAVLinkEnums.h"
6
8{
9 Q_OBJECT
10 Q_PROPERTY(int firmware READ firmware WRITE setFirmware NOTIFY firmwareChanged)
11 Q_PROPERTY(int vehicle READ vehicle WRITE setVehicle NOTIFY vehicleChanged)
12 Q_PROPERTY(bool sendStatus READ sendStatusText WRITE setSendStatusText NOTIFY sendStatusChanged)
13 Q_PROPERTY(bool enableCamera READ enableCamera WRITE setEnableCamera NOTIFY enableCameraChanged)
14 Q_PROPERTY(bool enableGimbal READ enableGimbal WRITE setEnableGimbal NOTIFY enableGimbalChanged)
32
33public:
34 explicit MockConfiguration(const QString &name, QObject *parent = nullptr);
35 explicit MockConfiguration(const MockConfiguration *copy, QObject *parent = nullptr);
37
38 LinkType type() const final { return LinkConfiguration::TypeMock; }
39 void copyFrom(const LinkConfiguration *source) final;
40 void loadSettings(QSettings &settings, const QString &root) final;
41 void saveSettings(QSettings &settings, const QString &root) const final;
42 QString settingsURL() const final { return QStringLiteral("MockLinkSettings.qml"); }
43 QString settingsTitle() const final { return tr("Mock Link Settings"); }
44
45 int firmware() const { return static_cast<int>(_firmwareType); }
46 void setFirmware(int type) { _firmwareType = static_cast<MAV_AUTOPILOT>(type); emit firmwareChanged(); }
47 int vehicle() const { return static_cast<int>(_vehicleType); }
48 void setVehicle(int type) { _vehicleType = static_cast<MAV_TYPE>(type); emit vehicleChanged(); }
49 bool incrementVehicleId() const { return _incrementVehicleId; }
51 MAV_AUTOPILOT firmwareType() const { return _firmwareType; }
52 void setFirmwareType(MAV_AUTOPILOT firmwareType) { _firmwareType = firmwareType; emit firmwareChanged(); }
53 uint16_t boardVendorId() const { return _boardVendorId; }
54 uint16_t boardProductId() const { return _boardProductId; }
55 void setBoardVendorProduct(uint16_t vendorId, uint16_t productId) { _boardVendorId = vendorId; _boardProductId = productId; }
56 MAV_TYPE vehicleType() const { return _vehicleType; }
57 void setVehicleType(MAV_TYPE vehicleType) { _vehicleType = vehicleType; emit vehicleChanged(); }
58 bool sendStatusText() const { return _sendStatusText; }
59 void setSendStatusText(bool sendStatusText) { _sendStatusText = sendStatusText; emit sendStatusChanged(); }
60 bool enableCamera() const { return _enableCamera; }
61 void setEnableCamera(bool enableCamera) { _enableCamera = enableCamera; emit enableCameraChanged(); }
62 bool enableGimbal() const { return _enableGimbal; }
63 void setEnableGimbal(bool enableGimbal) { _enableGimbal = enableGimbal; emit enableGimbalChanged(); }
64
65 bool gimbalHasRollAxis() const { return _gimbalHasRollAxis; }
66 void setGimbalHasRollAxis(bool value) { _gimbalHasRollAxis = value; emit gimbalHasRollAxisChanged(); }
67 bool gimbalHasPitchAxis() const { return _gimbalHasPitchAxis; }
68 void setGimbalHasPitchAxis(bool value) { _gimbalHasPitchAxis = value; emit gimbalHasPitchAxisChanged(); }
69 bool gimbalHasYawAxis() const { return _gimbalHasYawAxis; }
70 void setGimbalHasYawAxis(bool value) { _gimbalHasYawAxis = value; emit gimbalHasYawAxisChanged(); }
71 bool gimbalHasYawFollow() const { return _gimbalHasYawFollow; }
72 void setGimbalHasYawFollow(bool value) { _gimbalHasYawFollow = value; emit gimbalHasYawFollowChanged(); }
73 bool gimbalHasYawLock() const { return _gimbalHasYawLock; }
74 void setGimbalHasYawLock(bool value) { _gimbalHasYawLock = value; emit gimbalHasYawLockChanged(); }
75 bool gimbalHasRetract() const { return _gimbalHasRetract; }
76 void setGimbalHasRetract(bool value) { _gimbalHasRetract = value; emit gimbalHasRetractChanged(); }
77 bool gimbalHasNeutral() const { return _gimbalHasNeutral; }
78 void setGimbalHasNeutral(bool value) { _gimbalHasNeutral = value; emit gimbalHasNeutralChanged(); }
79
80 bool cameraCaptureVideo() const { return _cameraCaptureVideo; }
81 void setCameraCaptureVideo(bool value) { _cameraCaptureVideo = value; emit cameraCaptureVideoChanged(); }
82 bool cameraCaptureImage() const { return _cameraCaptureImage; }
83 void setCameraCaptureImage(bool value) { _cameraCaptureImage = value; emit cameraCaptureImageChanged(); }
84 bool cameraHasModes() const { return _cameraHasModes; }
85 void setCameraHasModes(bool value) { _cameraHasModes = value; emit cameraHasModesChanged(); }
86 bool cameraHasVideoStream() const { return _cameraHasVideoStream; }
87 void setCameraHasVideoStream(bool value) { _cameraHasVideoStream = value; emit cameraHasVideoStreamChanged(); }
88 bool cameraCanCaptureImageInVideoMode() const { return _cameraCanCaptureImageInVideoMode; }
89 void setCameraCanCaptureImageInVideoMode(bool value) { _cameraCanCaptureImageInVideoMode = value; emit cameraCanCaptureImageInVideoModeChanged(); }
90 bool cameraCanCaptureVideoInImageMode() const { return _cameraCanCaptureVideoInImageMode; }
91 void setCameraCanCaptureVideoInImageMode(bool value) { _cameraCanCaptureVideoInImageMode = value; emit cameraCanCaptureVideoInImageModeChanged(); }
92 bool cameraHasBasicZoom() const { return _cameraHasBasicZoom; }
93 void setCameraHasBasicZoom(bool value) { _cameraHasBasicZoom = value; emit cameraHasBasicZoomChanged(); }
94 bool cameraHasTrackingPoint() const { return _cameraHasTrackingPoint; }
95 void setCameraHasTrackingPoint(bool value) { _cameraHasTrackingPoint = value; emit cameraHasTrackingPointChanged(); }
96 bool cameraHasTrackingRectangle() const { return _cameraHasTrackingRectangle; }
97 void setCameraHasTrackingRectangle(bool value) { _cameraHasTrackingRectangle = value; emit cameraHasTrackingRectangleChanged(); }
98
107 FailureMode_t failureMode() const { return _failureMode; }
109
110 // Test-only: not persisted via loadSettings/saveSettings
111 bool startArmed() const { return _startArmed; }
112 void setStartArmed(bool armed) { _startArmed = armed; }
113
114signals:
137
138private:
139 MAV_AUTOPILOT _firmwareType = MAV_AUTOPILOT_PX4;
140 MAV_TYPE _vehicleType = MAV_TYPE_QUADROTOR;
141 bool _sendStatusText = false;
142 bool _enableCamera = false;
143 bool _enableGimbal = false;
144 FailureMode_t _failureMode = FailNone;
145 bool _incrementVehicleId = true;
146 uint16_t _boardVendorId = 0;
147 uint16_t _boardProductId = 0;
148 bool _startArmed = false;
149
150 // Camera capability flags (defaults match current Camera 1 configuration)
151 bool _cameraCaptureVideo = true;
152 bool _cameraCaptureImage = true;
153 bool _cameraHasModes = true;
154 bool _cameraHasVideoStream = true;
155 bool _cameraCanCaptureImageInVideoMode = true;
156 bool _cameraCanCaptureVideoInImageMode = false;
157 bool _cameraHasBasicZoom = true;
158 bool _cameraHasTrackingPoint = true;
159 bool _cameraHasTrackingRectangle = true;
160
161 // Gimbal capability flags (defaults - all enabled)
162 bool _gimbalHasRollAxis = true;
163 bool _gimbalHasPitchAxis = true;
164 bool _gimbalHasYawAxis = true;
165 bool _gimbalHasYawFollow = true;
166 bool _gimbalHasYawLock = true;
167 bool _gimbalHasRetract = true;
168 bool _gimbalHasNeutral = true;
169
170 static constexpr const char *_firmwareTypeKey = "FirmwareType";
171 static constexpr const char *_vehicleTypeKey = "VehicleType";
172 static constexpr const char *_sendStatusTextKey = "SendStatusText";
173 static constexpr const char *_enableCameraKey = "EnableCamera";
174 static constexpr const char *_enableGimbalKey = "EnableGimbal";
175 static constexpr const char *_gimbalHasRollAxisKey = "GimbalHasRollAxis";
176 static constexpr const char *_gimbalHasPitchAxisKey = "GimbalHasPitchAxis";
177 static constexpr const char *_gimbalHasYawAxisKey = "GimbalHasYawAxis";
178 static constexpr const char *_gimbalHasYawFollowKey = "GimbalHasYawFollow";
179 static constexpr const char *_gimbalHasYawLockKey = "GimbalHasYawLock";
180 static constexpr const char *_gimbalHasRetractKey = "GimbalHasRetract";
181 static constexpr const char *_gimbalHasNeutralKey = "GimbalHasNeutral";
182 static constexpr const char *_incrementVehicleIdKey = "IncrementVehicleId";
183 static constexpr const char *_failureModeKey = "FailureMode";
184 static constexpr const char *_cameraCaptureVideoKey = "CameraCaptureVideo";
185 static constexpr const char *_cameraCaptureImageKey = "CameraCaptureImage";
186 static constexpr const char *_cameraHasModesKey = "CameraHasModes";
187 static constexpr const char *_cameraHasVideoStreamKey = "CameraHasVideoStream";
188 static constexpr const char *_cameraCanCaptureImageInVideoModeKey = "CameraCanCaptureImageInVideoMode";
189 static constexpr const char *_cameraCanCaptureVideoInImageModeKey = "CameraCanCaptureVideoInImageMode";
190 static constexpr const char *_cameraHasBasicZoomKey = "CameraHasBasicZoom";
191 static constexpr const char *_cameraHasTrackingPointKey = "CameraHasTrackingPoint";
192 static constexpr const char *_cameraHasTrackingRectangleKey = "CameraHasTrackingRectangle";
193};
Interface holding link specific settings.
QString name() const
void gimbalHasPitchAxisChanged()
void cameraCanCaptureVideoInImageModeChanged()
bool cameraHasTrackingRectangle() const
void cameraHasTrackingPointChanged()
uint16_t boardVendorId() const
bool gimbalHasYawAxis() const
void cameraHasBasicZoomChanged()
bool enableGimbal() const
void setCameraHasTrackingRectangle(bool value)
bool gimbalHasRollAxis() const
void setGimbalHasRollAxis(bool value)
void setCameraHasBasicZoom(bool value)
void setCameraCaptureVideo(bool value)
bool cameraCanCaptureImageInVideoMode() const
bool gimbalHasRetract() const
void enableCameraChanged()
void setVehicleType(MAV_TYPE vehicleType)
QString settingsURL() const final
Settings URL, Pure virtual method providing the URL for the (QML) settings dialog.
@ FailInitialConnectRequestMessageAutopilotVersionLost
REQUEST_MESSAGE:AUTOPILOT_VERSION success, AUTOPILOT_VERSION never sent.
@ FailMissingParamOnInitialRequest
Not all params are sent on initial request, should still succeed since QGC will re-query missing para...
@ FailMissingParamOnAllRequests
Not all params are sent on initial request, QGC retries will fail as well.
@ FailInitialConnectRequestMessageAutopilotVersionFailure
REQUEST_MESSAGE:AUTOPILOT_VERSION returns failure.
@ FailParamNoResponseToRequestList
Do not respond to PARAM_REQUEST_LIST.
void setFailureMode(FailureMode_t failureMode)
void setCameraCanCaptureImageInVideoMode(bool value)
void cameraCaptureImageChanged()
void cameraHasModesChanged()
void loadSettings(QSettings &settings, const QString &root) final
void setCameraCaptureImage(bool value)
void gimbalHasRetractChanged()
bool enableCamera() const
void setBoardVendorProduct(uint16_t vendorId, uint16_t productId)
bool cameraCaptureVideo() const
QString settingsTitle() const final
Settings Title, Pure virtual method providing the Title for the (QML) settings dialog.
bool sendStatusText() const
bool cameraHasBasicZoom() const
void copyFrom(const LinkConfiguration *source) final
bool gimbalHasPitchAxis() const
uint16_t boardProductId() const
void setStartArmed(bool armed)
void sendStatusChanged()
bool cameraCaptureImage() const
void setCameraHasVideoStream(bool value)
void setIncrementVehicleId(bool incrementVehicleId)
void setEnableCamera(bool enableCamera)
void setGimbalHasPitchAxis(bool value)
void setFirmware(int type)
void setCameraCanCaptureVideoInImageMode(bool value)
void setEnableGimbal(bool enableGimbal)
void setSendStatusText(bool sendStatusText)
void setGimbalHasYawLock(bool value)
void setGimbalHasYawAxis(bool value)
void setGimbalHasNeutral(bool value)
void cameraCanCaptureImageInVideoModeChanged()
void saveSettings(QSettings &settings, const QString &root) const final
void cameraCaptureVideoChanged()
void cameraHasVideoStreamChanged()
void setCameraHasTrackingPoint(bool value)
void gimbalHasYawLockChanged()
void enableGimbalChanged()
bool incrementVehicleId() const
bool gimbalHasYawFollow() const
bool cameraHasVideoStream() const
LinkType type() const final
void setCameraHasModes(bool value)
bool gimbalHasYawLock() const
void setGimbalHasYawFollow(bool value)
void gimbalHasNeutralChanged()
void gimbalHasRollAxisChanged()
bool cameraHasTrackingPoint() const
bool gimbalHasNeutral() const
void incrementVehicleIdChanged()
void setFirmwareType(MAV_AUTOPILOT firmwareType)
FailureMode_t failureMode() const
void setGimbalHasRetract(bool value)
void gimbalHasYawFollowChanged()
bool cameraHasModes() const
void cameraHasTrackingRectangleChanged()
MAV_TYPE vehicleType() const
void gimbalHasYawAxisChanged()
MAV_AUTOPILOT firmwareType() const
bool cameraCanCaptureVideoInImageMode() const
void setVehicle(int type)