Skip to content

Commit b93f4c6

Browse files
committed
Refactor camera tracking and on-screen gimbal support
Camera Tracking Interface: - Remove flawed TrackingStatus bitmask enum - Separate point/rect tracking into distinct properties - Rename signals to match property names (trackingImageIsActiveChanged, etc.) - Add supportsTrackingPoint/supportsTrackingRect Q_PROPERTYs - Split startTracking() overloads into startTrackingPoint()/startTrackingRect() - Add capability guards with qCCritical to both methods - setTrackingEnabled(false) now calls stopTracking() to notify vehicle - Cache hasTrackingImageStatus to prevent redundant signal emissions - Zero-initialize _trackingImageStatus struct FlyView Mouse Handling: - Extract camera tracking into OnScreenCameraTrackingController.qml - Refactor OnScreenGimbalController to method-based API - Clean 4-method API: mouseClicked/mouseDragStart/mouseDragPositionChanged/mouseDragEnd - Add click vs drag separation with 10px threshold - Remove hoverEnabled (unnecessary in full-screen mode) - Fix operator precedence bug in tracking status overlay - Fix mode guards bug in gimbal controller (was !value == 0) - Fix ROI rectangle resize on drag direction reversal - Declarative tracking status overlay (replaces imperative createObject/timer) - Gimbal rate timer unconditionally stopped in mouseDragEnd MockLink: - Add tracking simulation with figure-8 drift animation - Handle TRACK_POINT, TRACK_RECTANGLE, STOP_TRACKING commands - Handle SET_MESSAGE_INTERVAL for CAMERA_TRACKING_IMAGE_STATUS - Capability-gated commands (DENIED if flag not set) Gimbal Settings: - Rename ControlType to clickAndDrag boolean Relates-to: #13363 Relates-to: #13957
1 parent 0b99d8b commit b93f4c6

18 files changed

+549
-321
lines changed

src/Camera/MavlinkCameraControlInterface.h

Lines changed: 22 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,8 @@ class MavlinkCameraControlInterface : public FactGroup
4444
Q_PROPERTY(bool hasFocus READ hasFocus NOTIFY infoChanged)
4545
Q_PROPERTY(bool hasVideoStream READ hasVideoStream NOTIFY infoChanged)
4646
Q_PROPERTY(bool hasTracking READ hasTracking NOTIFY infoChanged)
47+
Q_PROPERTY(bool supportsTrackingPoint READ supportsTrackingPoint NOTIFY infoChanged)
48+
Q_PROPERTY(bool supportsTrackingRect READ supportsTrackingRect NOTIFY infoChanged)
4749
Q_PROPERTY(bool photosInVideoMode READ photosInVideoMode NOTIFY infoChanged)
4850
Q_PROPERTY(bool videoInPhotoMode READ videoInPhotoMode NOTIFY infoChanged)
4951
Q_PROPERTY(bool isBasic READ isBasic NOTIFY infoChanged)
@@ -74,10 +76,14 @@ class MavlinkCameraControlInterface : public FactGroup
7476
Q_PROPERTY(QStringList streamLabels READ streamLabels NOTIFY streamLabelsChanged)
7577
Q_PROPERTY(ThermalViewMode thermalMode READ thermalMode WRITE setThermalMode NOTIFY thermalModeChanged)
7678
Q_PROPERTY(double thermalOpacity READ thermalOpacity WRITE setThermalOpacity NOTIFY thermalOpacityChanged)
79+
80+
// Camera tracking properties
7781
Q_PROPERTY(bool trackingEnabled READ trackingEnabled WRITE setTrackingEnabled NOTIFY trackingEnabledChanged)
78-
Q_PROPERTY(TrackingStatus trackingStatus READ trackingStatus CONSTANT)
79-
Q_PROPERTY(bool trackingImageStatus READ trackingImageStatus NOTIFY trackingImageStatusChanged)
80-
Q_PROPERTY(QRectF trackingImageRect READ trackingImageRect NOTIFY trackingImageStatusChanged)
82+
Q_PROPERTY(bool trackingImageIsActive READ trackingImageIsActive NOTIFY trackingImageIsActiveChanged)
83+
Q_PROPERTY(bool trackingImageIsPoint READ trackingImageIsPoint NOTIFY trackingImageIsPointChanged)
84+
Q_PROPERTY(QRectF trackingImageRect READ trackingImageRect NOTIFY trackingImageRectChanged)
85+
Q_PROPERTY(QPointF trackingImagePoint READ trackingImagePoint NOTIFY trackingImagePointChanged)
86+
Q_PROPERTY(qreal trackingImageRadius READ trackingImageRadius NOTIFY trackingImageRadiusChanged)
8187

8288
// These properties are used to determine what controls to show in the UI and are based on both the camera capabilities as well as the video manager status.
8389
// They are not necessarily directly related to the MAVLink camera capabilities.
@@ -141,14 +147,6 @@ class MavlinkCameraControlInterface : public FactGroup
141147
};
142148
Q_ENUM(ThermalViewMode)
143149

144-
enum TrackingStatus {
145-
TRACKING_UNKNOWN = 0,
146-
TRACKING_SUPPORTED = 1,
147-
TRACKING_ENABLED = 2,
148-
TRACKING_RECTANGLE = 4,
149-
TRACKING_POINT = 8
150-
};
151-
Q_ENUM(TrackingStatus)
152150

153151
Q_INVOKABLE virtual void setCameraModeVideo() = 0;
154152
Q_INVOKABLE virtual void setCameraModePhoto() = 0;
@@ -165,8 +163,8 @@ class MavlinkCameraControlInterface : public FactGroup
165163
Q_INVOKABLE virtual void stopZoom() = 0;
166164
Q_INVOKABLE virtual void stopStream() = 0;
167165
Q_INVOKABLE virtual void resumeStream() = 0;
168-
Q_INVOKABLE virtual void startTracking(QRectF rec) = 0;
169-
Q_INVOKABLE virtual void startTracking(QPointF point, double radius) = 0;
166+
Q_INVOKABLE virtual void startTrackingRect(QRectF rec) = 0;
167+
Q_INVOKABLE virtual void startTrackingPoint(QPointF point, double radius) = 0;
170168
Q_INVOKABLE virtual void stopTracking() = 0;
171169

172170
virtual int version() const = 0;
@@ -182,6 +180,8 @@ class MavlinkCameraControlInterface : public FactGroup
182180
virtual bool hasZoom() const = 0;
183181
virtual bool hasFocus() const = 0;
184182
virtual bool hasTracking() const = 0;
183+
virtual bool supportsTrackingPoint() const = 0;
184+
virtual bool supportsTrackingRect() const = 0;
185185
virtual bool hasVideoStream() const = 0;
186186
virtual bool photosInVideoMode() const = 0;
187187
virtual bool videoInPhotoMode() const = 0;
@@ -239,10 +239,11 @@ class MavlinkCameraControlInterface : public FactGroup
239239
virtual bool trackingEnabled() const = 0;
240240
virtual void setTrackingEnabled(bool set) = 0;
241241

242-
virtual TrackingStatus trackingStatus() const = 0;
243-
244-
virtual bool trackingImageStatus() const = 0;
242+
virtual bool trackingImageIsActive() const = 0;
243+
virtual bool trackingImageIsPoint() const = 0;
245244
virtual QRectF trackingImageRect() const = 0;
245+
virtual QPointF trackingImagePoint() const = 0;
246+
virtual qreal trackingImageRadius() const = 0;
246247

247248
virtual void factChanged(Fact *pFact) = 0; ///< Notify controller a parameter has changed
248249
virtual bool incomingParameter(Fact *pFact, QVariant &newValue) = 0; ///< Allow controller to modify or invalidate incoming parameter
@@ -286,7 +287,11 @@ class MavlinkCameraControlInterface : public FactGroup
286287
void recordTimeChanged();
287288
void streamLabelsChanged();
288289
void trackingEnabledChanged();
289-
void trackingImageStatusChanged();
290+
void trackingImageIsActiveChanged();
291+
void trackingImageIsPointChanged();
292+
void trackingImageRectChanged();
293+
void trackingImagePointChanged();
294+
void trackingImageRadiusChanged();
290295
void thermalModeChanged();
291296
void thermalOpacityChanged();
292297
void storageStatusChanged();

src/Camera/QGCCameraManager.cc

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -796,8 +796,8 @@ void QGCCameraManager::_handleCameraFovStatus(const mavlink_message_t& message)
796796
}
797797

798798
auto* settings = SettingsManager::instance()->gimbalControllerSettings();
799-
settings->CameraHFov()->setRawValue(fov.hfov);
800-
settings->CameraVFov()->setRawValue(vfovDeg);
799+
settings->cameraHFov()->setRawValue(fov.hfov);
800+
settings->cameraVFov()->setRawValue(vfovDeg);
801801
}
802802

803803
void QGCCameraManager::_setCurrentZoomLevel(int level)

src/Camera/SimulatedCameraControl.h

Lines changed: 8 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -35,8 +35,8 @@ class SimulatedCameraControl : public MavlinkCameraControlInterface
3535
void stopStream() override {}
3636
bool stopTakePhoto() override { return false;}
3737
void resumeStream() override {}
38-
void startTracking(QRectF /*rec*/) override {}
39-
void startTracking(QPointF /*point*/, double /*radius*/) override {}
38+
void startTrackingRect(QRectF /*rec*/) override {}
39+
void startTrackingPoint(QPointF /*point*/, double /*radius*/) override {}
4040
void stopTracking() override {}
4141

4242
int version() const override { return 0; }
@@ -52,6 +52,8 @@ class SimulatedCameraControl : public MavlinkCameraControlInterface
5252
bool hasZoom() const override { return false; }
5353
bool hasFocus() const override { return false; }
5454
bool hasTracking() const override { return false; }
55+
bool supportsTrackingPoint() const override { return false; }
56+
bool supportsTrackingRect() const override { return false; }
5557
bool hasVideoStream() const override;
5658
bool photosInVideoMode() const override { return true; }
5759
bool videoInPhotoMode() const override { return false; }
@@ -105,10 +107,11 @@ class SimulatedCameraControl : public MavlinkCameraControlInterface
105107
bool trackingEnabled() const override { return false; }
106108
void setTrackingEnabled(bool /*set*/) override {}
107109

108-
TrackingStatus trackingStatus() const override { return TRACKING_UNKNOWN; }
109-
110-
bool trackingImageStatus() const override { return false; }
110+
bool trackingImageIsActive() const override { return false; }
111+
bool trackingImageIsPoint() const override { return false; }
111112
QRectF trackingImageRect() const override { return QRectF(); }
113+
QPointF trackingImagePoint() const override { return QPointF(); }
114+
qreal trackingImageRadius() const override { return 0.0; }
112115

113116
void factChanged(Fact* /*pFact*/) override {};
114117
bool incomingParameter(Fact* /*pFact*/, QVariant& /*newValue*/) override { return false; }

src/Camera/VehicleCameraControl.cc

Lines changed: 79 additions & 40 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,8 @@
1717

1818
#include <QtNetwork/QNetworkAccessManager>
1919
#include <QtCore/QDir>
20+
21+
#include <algorithm>
2022
#include <QtCore/QSettings>
2123
#include <QtXml/QDomDocument>
2224
#include <QtXml/QDomNodeList>
@@ -130,15 +132,9 @@ VehicleCameraControl::VehicleCameraControl(const mavlink_camera_information_t *i
130132
_videoRecordTimeUpdateTimer.setInterval(333);
131133
connect(&_videoRecordTimeUpdateTimer, &QTimer::timeout, this, &VehicleCameraControl::_recTimerHandler);
132134

133-
//-- Tracking
134-
if(_mavlinkCameraInfo.flags & CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE) {
135-
_trackingStatus = static_cast<TrackingStatus>(_trackingStatus | TRACKING_RECTANGLE);
136-
_trackingStatus = static_cast<TrackingStatus>(_trackingStatus | TRACKING_SUPPORTED);
137-
}
138-
if(_mavlinkCameraInfo.flags & CAMERA_CAP_FLAGS_HAS_TRACKING_POINT) {
139-
_trackingStatus = static_cast<TrackingStatus>(_trackingStatus | TRACKING_POINT);
140-
_trackingStatus = static_cast<TrackingStatus>(_trackingStatus | TRACKING_SUPPORTED);
141-
}
135+
//-- Tracking capabilities
136+
_hasTrackingRectCapability = _mavlinkCameraInfo.flags & CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE;
137+
_hasTrackingPointCapability = _mavlinkCameraInfo.flags & CAMERA_CAP_FLAGS_HAS_TRACKING_POINT;
142138

143139
connect(this, &VehicleCameraControl::dataReady, this, &VehicleCameraControl::_dataReady);
144140

@@ -1693,35 +1689,56 @@ void VehicleCameraControl::handleTrackingImageStatus(const mavlink_camera_tracki
16931689

16941690
_trackingImageStatus = trackingImageStatus;
16951691

1696-
if (_trackingImageStatus.tracking_status == CAMERA_TRACKING_STATUS_FLAGS_IDLE || !trackingEnabled()) {
1697-
_trackingImageRect = {};
1692+
const bool active = ((_trackingImageStatus.tracking_status & CAMERA_TRACKING_STATUS_FLAGS_ACTIVE) != 0) && trackingEnabled();
1693+
const bool isPoint = active && (_trackingImageStatus.tracking_mode == CAMERA_TRACKING_MODE_POINT);
1694+
1695+
if (!active) {
16981696
qCDebug(CameraControlLog) << "Tracking off";
1699-
} else {
1700-
if (_trackingImageStatus.tracking_mode == CAMERA_TRACKING_MODE_RECTANGLE) {
1701-
_trackingImageRect = QRectF(QPointF(_trackingImageStatus.rec_top_x, _trackingImageStatus.rec_top_y),
1702-
QPointF(_trackingImageStatus.rec_bottom_x, _trackingImageStatus.rec_bottom_y));
1697+
_trackingImageRect = {};
1698+
_trackingImagePoint = {};
1699+
_trackingImageRadius = 0.0;
1700+
} else if (isPoint) {
1701+
const QPointF point(std::clamp(static_cast<qreal>(_trackingImageStatus.point_x), 0.0, 1.0),
1702+
std::clamp(static_cast<qreal>(_trackingImageStatus.point_y), 0.0, 1.0));
1703+
qreal radius = static_cast<qreal>(_trackingImageStatus.radius);
1704+
if (qIsNaN(radius) || radius <= 0) {
1705+
radius = 0.05;
17031706
} else {
1704-
float r = _trackingImageStatus.radius;
1705-
if (qIsNaN(r) || r <= 0 ) {
1706-
r = 0.05f;
1707-
}
1708-
// Bottom is NAN so that we can draw perfect square using video aspect ratio
1709-
_trackingImageRect = QRectF(QPointF(_trackingImageStatus.point_x - r, _trackingImageStatus.point_y - r),
1710-
QPointF(_trackingImageStatus.point_x + r, NAN));
1707+
radius = std::clamp(radius, 0.0, 1.0);
1708+
}
1709+
qCDebug(CameraControlLog) << "Tracking Point [" << point << "] radius:" << radius;
1710+
_trackingImageRect = {};
1711+
if (_trackingImagePoint != point) {
1712+
_trackingImagePoint = point;
1713+
emit trackingImagePointChanged();
1714+
}
1715+
if (!qFuzzyCompare(_trackingImageRadius, radius)) {
1716+
_trackingImageRadius = radius;
1717+
emit trackingImageRadiusChanged();
1718+
}
1719+
} else {
1720+
// Rectangle tracking
1721+
const QRectF rect = QRectF(QPointF(std::clamp(static_cast<qreal>(_trackingImageStatus.rec_top_x), 0.0, 1.0),
1722+
std::clamp(static_cast<qreal>(_trackingImageStatus.rec_top_y), 0.0, 1.0)),
1723+
QPointF(std::clamp(static_cast<qreal>(_trackingImageStatus.rec_bottom_x), 0.0, 1.0),
1724+
std::clamp(static_cast<qreal>(_trackingImageStatus.rec_bottom_y), 0.0, 1.0))).normalized();
1725+
qCDebug(CameraControlLog) << "Tracking Rect [" << rect << "]";
1726+
_trackingImagePoint = {};
1727+
_trackingImageRadius = 0.0;
1728+
if (_trackingImageRect != rect) {
1729+
_trackingImageRect = rect;
1730+
emit trackingImageRectChanged();
17111731
}
1712-
// get rectangle into [0..1] boundaries
1713-
_trackingImageRect.setLeft(std::min(std::max(_trackingImageRect.left(), 0.0), 1.0));
1714-
_trackingImageRect.setTop(std::min(std::max(_trackingImageRect.top(), 0.0), 1.0));
1715-
_trackingImageRect.setRight(std::min(std::max(_trackingImageRect.right(), 0.0), 1.0));
1716-
_trackingImageRect.setBottom(std::min(std::max(_trackingImageRect.bottom(), 0.0), 1.0));
1717-
1718-
qCDebug(CameraControlLog) << "Tracking Image Status [left:" << _trackingImageRect.left()
1719-
<< "top:" << _trackingImageRect.top()
1720-
<< "right:" << _trackingImageRect.right()
1721-
<< "bottom:" << _trackingImageRect.bottom() << "]";
17221732
}
17231733

1724-
emit trackingImageStatusChanged();
1734+
if (_trackingImageIsActive != active) {
1735+
_trackingImageIsActive = active;
1736+
emit trackingImageIsActiveChanged();
1737+
}
1738+
if (_trackingImageIsPoint != isPoint) {
1739+
_trackingImageIsPoint = isPoint;
1740+
emit trackingImageIsPointChanged();
1741+
}
17251742
}
17261743

17271744
void VehicleCameraControl::setCurrentStream(int stream)
@@ -2323,16 +2340,23 @@ VehicleCameraControl::mode()
23232340

23242341
void VehicleCameraControl::setTrackingEnabled(bool set)
23252342
{
2326-
if(set) {
2327-
_trackingStatus = static_cast<TrackingStatus>(_trackingStatus | TRACKING_ENABLED);
2328-
} else {
2329-
_trackingStatus = static_cast<TrackingStatus>(_trackingStatus & ~TRACKING_ENABLED);
2343+
if (_trackingEnabled == set) {
2344+
return;
2345+
}
2346+
_trackingEnabled = set;
2347+
if (!set) {
2348+
stopTracking();
23302349
}
23312350
emit trackingEnabledChanged();
23322351
}
23332352

2334-
void VehicleCameraControl::startTracking(QRectF rec)
2353+
void VehicleCameraControl::startTrackingRect(QRectF rec)
23352354
{
2355+
if (!_hasTrackingRectCapability) {
2356+
qCCritical(CameraControlLog) << "startTrackingRect called but camera does not have rectangle tracking capability";
2357+
return;
2358+
}
2359+
23362360
qCDebug(CameraControlLog) << "Start Tracking (Rectangle: ["
23372361
<< static_cast<float>(rec.x()) << ", "
23382362
<< static_cast<float>(rec.y()) << "] - ["
@@ -2350,8 +2374,13 @@ void VehicleCameraControl::startTracking(QRectF rec)
23502374
_requestTrackingStatus();
23512375
}
23522376

2353-
void VehicleCameraControl::startTracking(QPointF point, double radius)
2377+
void VehicleCameraControl::startTrackingPoint(QPointF point, double radius)
23542378
{
2379+
if (!_hasTrackingPointCapability) {
2380+
qCCritical(CameraControlLog) << "startTrackingPoint called but camera does not have point tracking capability";
2381+
return;
2382+
}
2383+
23552384
qCDebug(CameraControlLog) << "Start Tracking (Point: ["
23562385
<< static_cast<float>(point.x()) << ", "
23572386
<< static_cast<float>(point.y()) << "], Radius: "
@@ -2383,8 +2412,18 @@ void VehicleCameraControl::stopTracking()
23832412
MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS,
23842413
-1);
23852414

2386-
// reset tracking image rectangle
2415+
// reset tracking state
23872416
_trackingImageRect = {};
2417+
_trackingImagePoint = {};
2418+
_trackingImageRadius = 0.0;
2419+
if (_trackingImageIsActive) {
2420+
_trackingImageIsActive = false;
2421+
emit trackingImageIsActiveChanged();
2422+
}
2423+
if (_trackingImageIsPoint) {
2424+
_trackingImageIsPoint = false;
2425+
emit trackingImageIsPointChanged();
2426+
}
23882427
}
23892428

23902429
void VehicleCameraControl::_requestTrackingStatus()

0 commit comments

Comments
 (0)