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 <QtCore/QLoggingCategory>
6#include "MAVLinkLib.h"
7
8Q_DECLARE_LOGGING_CATEGORY(MockConfigurationLog)
9
11{
12 Q_OBJECT
13 Q_PROPERTY(int firmware READ firmware WRITE setFirmware NOTIFY firmwareChanged)
14 Q_PROPERTY(int vehicle READ vehicle WRITE setVehicle NOTIFY vehicleChanged)
15 Q_PROPERTY(bool sendStatus READ sendStatusText WRITE setSendStatusText NOTIFY sendStatusChanged)
16 Q_PROPERTY(bool enableCamera READ enableCamera WRITE setEnableCamera NOTIFY enableCameraChanged)
17 Q_PROPERTY(bool enableGimbal READ enableGimbal WRITE setEnableGimbal NOTIFY enableGimbalChanged)
18 Q_PROPERTY(bool gimbalHasRollAxis READ gimbalHasRollAxis WRITE setGimbalHasRollAxis NOTIFY gimbalHasRollAxisChanged)
19 Q_PROPERTY(bool gimbalHasPitchAxis READ gimbalHasPitchAxis WRITE setGimbalHasPitchAxis NOTIFY gimbalHasPitchAxisChanged)
20 Q_PROPERTY(bool gimbalHasYawAxis READ gimbalHasYawAxis WRITE setGimbalHasYawAxis NOTIFY gimbalHasYawAxisChanged)
21 Q_PROPERTY(bool gimbalHasYawFollow READ gimbalHasYawFollow WRITE setGimbalHasYawFollow NOTIFY gimbalHasYawFollowChanged)
22 Q_PROPERTY(bool gimbalHasYawLock READ gimbalHasYawLock WRITE setGimbalHasYawLock NOTIFY gimbalHasYawLockChanged)
23 Q_PROPERTY(bool gimbalHasRetract READ gimbalHasRetract WRITE setGimbalHasRetract NOTIFY gimbalHasRetractChanged)
24 Q_PROPERTY(bool gimbalHasNeutral READ gimbalHasNeutral WRITE setGimbalHasNeutral NOTIFY gimbalHasNeutralChanged)
25 Q_PROPERTY(bool incrementVehicleId READ incrementVehicleId WRITE setIncrementVehicleId NOTIFY incrementVehicleIdChanged)
26 Q_PROPERTY(bool cameraCaptureVideo READ cameraCaptureVideo WRITE setCameraCaptureVideo NOTIFY cameraCaptureVideoChanged)
27 Q_PROPERTY(bool cameraCaptureImage READ cameraCaptureImage WRITE setCameraCaptureImage NOTIFY cameraCaptureImageChanged)
28 Q_PROPERTY(bool cameraHasModes READ cameraHasModes WRITE setCameraHasModes NOTIFY cameraHasModesChanged)
29 Q_PROPERTY(bool cameraHasVideoStream READ cameraHasVideoStream WRITE setCameraHasVideoStream NOTIFY cameraHasVideoStreamChanged)
30 Q_PROPERTY(bool cameraCanCaptureImageInVideoMode READ cameraCanCaptureImageInVideoMode WRITE setCameraCanCaptureImageInVideoMode NOTIFY cameraCanCaptureImageInVideoModeChanged)
31 Q_PROPERTY(bool cameraCanCaptureVideoInImageMode READ cameraCanCaptureVideoInImageMode WRITE setCameraCanCaptureVideoInImageMode NOTIFY cameraCanCaptureVideoInImageModeChanged)
32 Q_PROPERTY(bool cameraHasBasicZoom READ cameraHasBasicZoom WRITE setCameraHasBasicZoom NOTIFY cameraHasBasicZoomChanged)
33 Q_PROPERTY(bool cameraHasTrackingPoint READ cameraHasTrackingPoint WRITE setCameraHasTrackingPoint NOTIFY cameraHasTrackingPointChanged)
34 Q_PROPERTY(bool cameraHasTrackingRectangle READ cameraHasTrackingRectangle WRITE setCameraHasTrackingRectangle NOTIFY cameraHasTrackingRectangleChanged)
35
36public:
37 explicit MockConfiguration(const QString &name, QObject *parent = nullptr);
38 explicit MockConfiguration(const MockConfiguration *copy, QObject *parent = nullptr);
40
41 LinkType type() const final { return LinkConfiguration::TypeMock; }
42 void copyFrom(const LinkConfiguration *source) final;
43 void loadSettings(QSettings &settings, const QString &root) final;
44 void saveSettings(QSettings &settings, const QString &root) const final;
45 QString settingsURL() const final { return QStringLiteral("MockLinkSettings.qml"); }
46 QString settingsTitle() const final { return tr("Mock Link Settings"); }
47
48 int firmware() const { return static_cast<int>(_firmwareType); }
49 void setFirmware(int type) { _firmwareType = static_cast<MAV_AUTOPILOT>(type); emit firmwareChanged(); }
50 int vehicle() const { return static_cast<int>(_vehicleType); }
51 void setVehicle(int type) { _vehicleType = static_cast<MAV_TYPE>(type); emit vehicleChanged(); }
52 bool incrementVehicleId() const { return _incrementVehicleId; }
53 void setIncrementVehicleId(bool incrementVehicleId) { _incrementVehicleId = incrementVehicleId; emit incrementVehicleIdChanged(); }
54 MAV_AUTOPILOT firmwareType() const { return _firmwareType; }
55 void setFirmwareType(MAV_AUTOPILOT firmwareType) { _firmwareType = firmwareType; emit firmwareChanged(); }
56 uint16_t boardVendorId() const { return _boardVendorId; }
57 uint16_t boardProductId() const { return _boardProductId; }
58 void setBoardVendorProduct(uint16_t vendorId, uint16_t productId) { _boardVendorId = vendorId; _boardProductId = productId; }
59 MAV_TYPE vehicleType() const { return _vehicleType; }
60 void setVehicleType(MAV_TYPE vehicleType) { _vehicleType = vehicleType; emit vehicleChanged(); }
61 bool sendStatusText() const { return _sendStatusText; }
62 void setSendStatusText(bool sendStatusText) { _sendStatusText = sendStatusText; emit sendStatusChanged(); }
63 bool enableCamera() const { return _enableCamera; }
64 void setEnableCamera(bool enableCamera) { _enableCamera = enableCamera; emit enableCameraChanged(); }
65 bool enableGimbal() const { return _enableGimbal; }
66 void setEnableGimbal(bool enableGimbal) { _enableGimbal = enableGimbal; emit enableGimbalChanged(); }
67
68 bool gimbalHasRollAxis() const { return _gimbalHasRollAxis; }
69 void setGimbalHasRollAxis(bool value) { _gimbalHasRollAxis = value; emit gimbalHasRollAxisChanged(); }
70 bool gimbalHasPitchAxis() const { return _gimbalHasPitchAxis; }
71 void setGimbalHasPitchAxis(bool value) { _gimbalHasPitchAxis = value; emit gimbalHasPitchAxisChanged(); }
72 bool gimbalHasYawAxis() const { return _gimbalHasYawAxis; }
73 void setGimbalHasYawAxis(bool value) { _gimbalHasYawAxis = value; emit gimbalHasYawAxisChanged(); }
74 bool gimbalHasYawFollow() const { return _gimbalHasYawFollow; }
75 void setGimbalHasYawFollow(bool value) { _gimbalHasYawFollow = value; emit gimbalHasYawFollowChanged(); }
76 bool gimbalHasYawLock() const { return _gimbalHasYawLock; }
77 void setGimbalHasYawLock(bool value) { _gimbalHasYawLock = value; emit gimbalHasYawLockChanged(); }
78 bool gimbalHasRetract() const { return _gimbalHasRetract; }
79 void setGimbalHasRetract(bool value) { _gimbalHasRetract = value; emit gimbalHasRetractChanged(); }
80 bool gimbalHasNeutral() const { return _gimbalHasNeutral; }
81 void setGimbalHasNeutral(bool value) { _gimbalHasNeutral = value; emit gimbalHasNeutralChanged(); }
82
83 bool cameraCaptureVideo() const { return _cameraCaptureVideo; }
84 void setCameraCaptureVideo(bool value) { _cameraCaptureVideo = value; emit cameraCaptureVideoChanged(); }
85 bool cameraCaptureImage() const { return _cameraCaptureImage; }
86 void setCameraCaptureImage(bool value) { _cameraCaptureImage = value; emit cameraCaptureImageChanged(); }
87 bool cameraHasModes() const { return _cameraHasModes; }
88 void setCameraHasModes(bool value) { _cameraHasModes = value; emit cameraHasModesChanged(); }
89 bool cameraHasVideoStream() const { return _cameraHasVideoStream; }
90 void setCameraHasVideoStream(bool value) { _cameraHasVideoStream = value; emit cameraHasVideoStreamChanged(); }
91 bool cameraCanCaptureImageInVideoMode() const { return _cameraCanCaptureImageInVideoMode; }
92 void setCameraCanCaptureImageInVideoMode(bool value) { _cameraCanCaptureImageInVideoMode = value; emit cameraCanCaptureImageInVideoModeChanged(); }
93 bool cameraCanCaptureVideoInImageMode() const { return _cameraCanCaptureVideoInImageMode; }
94 void setCameraCanCaptureVideoInImageMode(bool value) { _cameraCanCaptureVideoInImageMode = value; emit cameraCanCaptureVideoInImageModeChanged(); }
95 bool cameraHasBasicZoom() const { return _cameraHasBasicZoom; }
96 void setCameraHasBasicZoom(bool value) { _cameraHasBasicZoom = value; emit cameraHasBasicZoomChanged(); }
97 bool cameraHasTrackingPoint() const { return _cameraHasTrackingPoint; }
98 void setCameraHasTrackingPoint(bool value) { _cameraHasTrackingPoint = value; emit cameraHasTrackingPointChanged(); }
99 bool cameraHasTrackingRectangle() const { return _cameraHasTrackingRectangle; }
100 void setCameraHasTrackingRectangle(bool value) { _cameraHasTrackingRectangle = value; emit cameraHasTrackingRectangleChanged(); }
101
102 enum FailureMode_t {
103 FailNone,
104 FailParamNoResponseToRequestList,
105 FailMissingParamOnInitialRequest,
106 FailMissingParamOnAllRequests,
107 FailInitialConnectRequestMessageAutopilotVersionFailure,
108 FailInitialConnectRequestMessageAutopilotVersionLost,
109 };
110 FailureMode_t failureMode() const { return _failureMode; }
111 void setFailureMode(FailureMode_t failureMode) { _failureMode = failureMode; }
112
113signals:
136
137private:
138 MAV_AUTOPILOT _firmwareType = MAV_AUTOPILOT_PX4;
139 MAV_TYPE _vehicleType = MAV_TYPE_QUADROTOR;
140 bool _sendStatusText = false;
141 bool _enableCamera = false;
142 bool _enableGimbal = false;
143 FailureMode_t _failureMode = FailNone;
144 bool _incrementVehicleId = true;
145 uint16_t _boardVendorId = 0;
146 uint16_t _boardProductId = 0;
147
148 // Camera capability flags (defaults match current Camera 1 configuration)
149 bool _cameraCaptureVideo = true;
150 bool _cameraCaptureImage = true;
151 bool _cameraHasModes = true;
152 bool _cameraHasVideoStream = true;
153 bool _cameraCanCaptureImageInVideoMode = true;
154 bool _cameraCanCaptureVideoInImageMode = false;
155 bool _cameraHasBasicZoom = true;
156 bool _cameraHasTrackingPoint = false;
157 bool _cameraHasTrackingRectangle = false;
158
159 // Gimbal capability flags (defaults - all enabled)
160 bool _gimbalHasRollAxis = true;
161 bool _gimbalHasPitchAxis = true;
162 bool _gimbalHasYawAxis = true;
163 bool _gimbalHasYawFollow = true;
164 bool _gimbalHasYawLock = true;
165 bool _gimbalHasRetract = true;
166 bool _gimbalHasNeutral = true;
167
168 static constexpr const char *_firmwareTypeKey = "FirmwareType";
169 static constexpr const char *_vehicleTypeKey = "VehicleType";
170 static constexpr const char *_sendStatusTextKey = "SendStatusText";
171 static constexpr const char *_enableCameraKey = "EnableCamera";
172 static constexpr const char *_enableGimbalKey = "EnableGimbal";
173 static constexpr const char *_gimbalHasRollAxisKey = "GimbalHasRollAxis";
174 static constexpr const char *_gimbalHasPitchAxisKey = "GimbalHasPitchAxis";
175 static constexpr const char *_gimbalHasYawAxisKey = "GimbalHasYawAxis";
176 static constexpr const char *_gimbalHasYawFollowKey = "GimbalHasYawFollow";
177 static constexpr const char *_gimbalHasYawLockKey = "GimbalHasYawLock";
178 static constexpr const char *_gimbalHasRetractKey = "GimbalHasRetract";
179 static constexpr const char *_gimbalHasNeutralKey = "GimbalHasNeutral";
180 static constexpr const char *_incrementVehicleIdKey = "IncrementVehicleId";
181 static constexpr const char *_failureModeKey = "FailureMode";
182 static constexpr const char *_cameraCaptureVideoKey = "CameraCaptureVideo";
183 static constexpr const char *_cameraCaptureImageKey = "CameraCaptureImage";
184 static constexpr const char *_cameraHasModesKey = "CameraHasModes";
185 static constexpr const char *_cameraHasVideoStreamKey = "CameraHasVideoStream";
186 static constexpr const char *_cameraCanCaptureImageInVideoModeKey = "CameraCanCaptureImageInVideoMode";
187 static constexpr const char *_cameraCanCaptureVideoInImageModeKey = "CameraCanCaptureVideoInImageMode";
188 static constexpr const char *_cameraHasBasicZoomKey = "CameraHasBasicZoom";
189 static constexpr const char *_cameraHasTrackingPointKey = "CameraHasTrackingPoint";
190 static constexpr const char *_cameraHasTrackingRectangleKey = "CameraHasTrackingRectangle";
191};
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)
Interface holding link specific settings.
void gimbalHasPitchAxisChanged()
void cameraCanCaptureVideoInImageModeChanged()
void cameraHasTrackingPointChanged()
void cameraHasBasicZoomChanged()
void enableCameraChanged()
void cameraCaptureImageChanged()
void cameraHasModesChanged()
void gimbalHasRetractChanged()
void sendStatusChanged()
void cameraCanCaptureImageInVideoModeChanged()
void cameraCaptureVideoChanged()
void cameraHasVideoStreamChanged()
void gimbalHasYawLockChanged()
void enableGimbalChanged()
void gimbalHasNeutralChanged()
void gimbalHasRollAxisChanged()
void incrementVehicleIdChanged()
void gimbalHasYawFollowChanged()
void cameraHasTrackingRectangleChanged()
void gimbalHasYawAxisChanged()