QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MockConfiguration.cc
Go to the documentation of this file.
1#include "MockConfiguration.h"
3
4QGC_LOGGING_CATEGORY(MockConfigurationLog, "Comms.MockLink.MockConfiguration")
5
6MockConfiguration::MockConfiguration(const QString &name, QObject *parent)
7 : LinkConfiguration(name, parent)
8{
9 qCDebug(MockConfigurationLog) << this;
10}
11
12MockConfiguration::MockConfiguration(const MockConfiguration *copy, QObject *parent)
13 : LinkConfiguration(copy, parent)
14 , _firmwareType(copy->firmwareType())
15 , _vehicleType(copy->vehicleType())
16 , _sendStatusText(copy->sendStatusText())
17 , _enableCamera(copy->enableCamera())
18 , _enableGimbal(copy->enableGimbal())
19 , _failureMode(copy->failureMode())
20 , _incrementVehicleId(copy->incrementVehicleId())
21 , _cameraCaptureVideo(copy->cameraCaptureVideo())
22 , _cameraCaptureImage(copy->cameraCaptureImage())
23 , _cameraHasModes(copy->cameraHasModes())
24 , _cameraHasVideoStream(copy->cameraHasVideoStream())
25 , _cameraCanCaptureImageInVideoMode(copy->cameraCanCaptureImageInVideoMode())
26 , _cameraCanCaptureVideoInImageMode(copy->cameraCanCaptureVideoInImageMode())
27 , _cameraHasBasicZoom(copy->cameraHasBasicZoom())
28 , _cameraHasTrackingPoint(copy->cameraHasTrackingPoint())
29 , _cameraHasTrackingRectangle(copy->cameraHasTrackingRectangle())
30 , _gimbalHasRollAxis(copy->gimbalHasRollAxis())
31 , _gimbalHasPitchAxis(copy->gimbalHasPitchAxis())
32 , _gimbalHasYawAxis(copy->gimbalHasYawAxis())
33 , _gimbalHasYawFollow(copy->gimbalHasYawFollow())
34 , _gimbalHasYawLock(copy->gimbalHasYawLock())
35 , _gimbalHasRetract(copy->gimbalHasRetract())
36 , _gimbalHasNeutral(copy->gimbalHasNeutral())
37{
38 qCDebug(MockConfigurationLog) << this;
39}
40
41MockConfiguration::~MockConfiguration()
42{
43 qCDebug(MockConfigurationLog) << this;
44}
45
46void MockConfiguration::copyFrom(const LinkConfiguration *source)
47{
48 LinkConfiguration::copyFrom(source);
49
50 const MockConfiguration *mockLinkSource = qobject_cast<const MockConfiguration*>(source);
51
52 setFirmwareType(mockLinkSource->firmwareType());
53 setVehicleType(mockLinkSource->vehicleType());
54 setSendStatusText(mockLinkSource->sendStatusText());
55 setEnableCamera(mockLinkSource->enableCamera());
56 setEnableGimbal(mockLinkSource->enableGimbal());
57 setIncrementVehicleId(mockLinkSource->incrementVehicleId());
58 setFailureMode(mockLinkSource->failureMode());
59 setCameraCaptureVideo(mockLinkSource->cameraCaptureVideo());
60 setCameraCaptureImage(mockLinkSource->cameraCaptureImage());
61 setCameraHasModes(mockLinkSource->cameraHasModes());
62 setCameraHasVideoStream(mockLinkSource->cameraHasVideoStream());
63 setCameraCanCaptureImageInVideoMode(mockLinkSource->cameraCanCaptureImageInVideoMode());
64 setCameraCanCaptureVideoInImageMode(mockLinkSource->cameraCanCaptureVideoInImageMode());
65 setCameraHasBasicZoom(mockLinkSource->cameraHasBasicZoom());
66 setCameraHasTrackingPoint(mockLinkSource->cameraHasTrackingPoint());
67 setCameraHasTrackingRectangle(mockLinkSource->cameraHasTrackingRectangle());
68 setGimbalHasRollAxis(mockLinkSource->gimbalHasRollAxis());
69 setGimbalHasPitchAxis(mockLinkSource->gimbalHasPitchAxis());
70 setGimbalHasYawAxis(mockLinkSource->gimbalHasYawAxis());
71 setGimbalHasYawFollow(mockLinkSource->gimbalHasYawFollow());
72 setGimbalHasYawLock(mockLinkSource->gimbalHasYawLock());
73 setGimbalHasRetract(mockLinkSource->gimbalHasRetract());
74 setGimbalHasNeutral(mockLinkSource->gimbalHasNeutral());
75}
76
77void MockConfiguration::loadSettings(QSettings &settings, const QString &root)
78{
79 settings.beginGroup(root);
80
81 setFirmwareType(static_cast<MAV_AUTOPILOT>(settings.value(_firmwareTypeKey, static_cast<int>(MAV_AUTOPILOT_PX4)).toInt()));
82 setVehicleType(static_cast<MAV_TYPE>(settings.value(_vehicleTypeKey, static_cast<int>(MAV_TYPE_QUADROTOR)).toInt()));
83 setSendStatusText(settings.value(_sendStatusTextKey, false).toBool());
84 setEnableCamera(settings.value(_enableCameraKey, false).toBool());
85 setEnableGimbal(settings.value(_enableGimbalKey, false).toBool());
86 setIncrementVehicleId(settings.value(_incrementVehicleIdKey, true).toBool());
87 setFailureMode(static_cast<FailureMode_t>(settings.value(_failureModeKey, static_cast<int>(FailNone)).toInt()));
88 setCameraCaptureVideo(settings.value(_cameraCaptureVideoKey, true).toBool());
89 setCameraCaptureImage(settings.value(_cameraCaptureImageKey, true).toBool());
90 setCameraHasModes(settings.value(_cameraHasModesKey, true).toBool());
91 setCameraHasVideoStream(settings.value(_cameraHasVideoStreamKey, true).toBool());
92 setCameraCanCaptureImageInVideoMode(settings.value(_cameraCanCaptureImageInVideoModeKey, true).toBool());
93 setCameraCanCaptureVideoInImageMode(settings.value(_cameraCanCaptureVideoInImageModeKey, false).toBool());
94 setCameraHasBasicZoom(settings.value(_cameraHasBasicZoomKey, true).toBool());
95 setCameraHasTrackingPoint(settings.value(_cameraHasTrackingPointKey, false).toBool());
96 setCameraHasTrackingRectangle(settings.value(_cameraHasTrackingRectangleKey, false).toBool());
97 setGimbalHasRollAxis(settings.value(_gimbalHasRollAxisKey, true).toBool());
98 setGimbalHasPitchAxis(settings.value(_gimbalHasPitchAxisKey, true).toBool());
99 setGimbalHasYawAxis(settings.value(_gimbalHasYawAxisKey, true).toBool());
100 setGimbalHasYawFollow(settings.value(_gimbalHasYawFollowKey, true).toBool());
101 setGimbalHasYawLock(settings.value(_gimbalHasYawLockKey, true).toBool());
102 setGimbalHasRetract(settings.value(_gimbalHasRetractKey, true).toBool());
103 setGimbalHasNeutral(settings.value(_gimbalHasNeutralKey, true).toBool());
104
105 settings.endGroup();
106}
107
108void MockConfiguration::saveSettings(QSettings &settings, const QString &root) const
109{
110 settings.beginGroup(root);
111
112 settings.setValue(_firmwareTypeKey, firmwareType());
113 settings.setValue(_vehicleTypeKey, vehicleType());
114 settings.setValue(_sendStatusTextKey, sendStatusText());
115 settings.setValue(_enableCameraKey, enableCamera());
116 settings.setValue(_enableGimbalKey, enableGimbal());
117 settings.setValue(_incrementVehicleIdKey, incrementVehicleId());
118 settings.setValue(_failureModeKey, failureMode());
119 settings.setValue(_cameraCaptureVideoKey, cameraCaptureVideo());
120 settings.setValue(_cameraCaptureImageKey, cameraCaptureImage());
121 settings.setValue(_cameraHasModesKey, cameraHasModes());
122 settings.setValue(_cameraHasVideoStreamKey, cameraHasVideoStream());
123 settings.setValue(_cameraCanCaptureImageInVideoModeKey, cameraCanCaptureImageInVideoMode());
124 settings.setValue(_cameraCanCaptureVideoInImageModeKey, cameraCanCaptureVideoInImageMode());
125 settings.setValue(_cameraHasBasicZoomKey, cameraHasBasicZoom());
126 settings.setValue(_cameraHasTrackingPointKey, cameraHasTrackingPoint());
127 settings.setValue(_cameraHasTrackingRectangleKey, cameraHasTrackingRectangle());
128 settings.setValue(_gimbalHasRollAxisKey, gimbalHasRollAxis());
129 settings.setValue(_gimbalHasPitchAxisKey, gimbalHasPitchAxis());
130 settings.setValue(_gimbalHasYawAxisKey, gimbalHasYawAxis());
131 settings.setValue(_gimbalHasYawFollowKey, gimbalHasYawFollow());
132 settings.setValue(_gimbalHasYawLockKey, gimbalHasYawLock());
133 settings.setValue(_gimbalHasRetractKey, gimbalHasRetract());
134 settings.setValue(_gimbalHasNeutralKey, gimbalHasNeutral());
135
136 settings.endGroup();
137}
#define QGC_LOGGING_CATEGORY(name, categoryStr)
Interface holding link specific settings.