QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MockLinkCamera.h
Go to the documentation of this file.
1#pragma once
2
3#include "MAVLinkLib.h"
4
5#include <QtCore/QMutex>
6
7class MockLink;
8
36{
37public:
45
47 struct CameraState {
48 uint8_t compId = MAV_COMP_ID_CAMERA;
49 uint32_t capFlags = 0;
50 uint8_t cameraMode = CAMERA_MODE_IMAGE;
51 bool recording = false;
53 float zoomLevel = 1.0f;
54 float focusLevel = 0.0f;
56 float image_interval = 0.0f;
57 qint64 singleShotStartMs = 0;
58
59 // Tracking state
60 uint8_t trackingMode = CAMERA_TRACKING_MODE_NONE;
61 float trackPointX = 0.0f;
62 float trackPointY = 0.0f;
63 float trackRadius = 0.0f;
64 float trackRecTopX = 0.0f;
65 float trackRecTopY = 0.0f;
66 float trackRecBottomX = 0.0f;
67 float trackRecBottomY = 0.0f;
70 qint64 trackingStartMs = 0;
71 float trackAnchorX = 0.0f;
72 float trackAnchorY = 0.0f;
73 };
74
75 explicit MockLinkCamera(MockLink *mockLink,
76 bool captureVideo = true,
77 bool captureImage = true,
78 bool hasModes = true,
79 bool hasVideoStream = true,
80 bool canCaptureImageInVideoMode = true,
81 bool canCaptureVideoInImageMode = false,
82 bool hasBasicZoom = true,
83 bool hasTrackingPoint = false,
84 bool hasTrackingRectangle = false);
85 ~MockLinkCamera() = default;
86
89
91 void run10HzTasks();
92
96
97private:
100 bool _handleCameraCommand(const mavlink_command_long_t &request, uint8_t targetCompId);
101
104 bool _handleRequestMessage(const mavlink_command_long_t &request, uint8_t targetCompId);
105
106 void _sendCameraInformation(uint8_t compId);
107 void _sendCameraSettings(uint8_t compId);
108 void _sendStorageInformation(uint8_t compId);
109 void _sendCameraCaptureStatus(uint8_t compId);
110 void _sendCameraImageCaptured(uint8_t compId);
111 void _sendVideoStreamInformation(uint8_t compId, uint8_t streamId);
112 void _sendVideoStreamStatus(uint8_t compId, uint8_t streamId);
113 void _sendCameraTrackingImageStatus(uint8_t compId);
114 void _sendCommandAck(uint8_t compId, uint16_t command, uint8_t result, int requestedMsgId = -1);
115
116 CameraState *_findCamera(uint8_t compId);
117 static const char *_imageCaptureStatusToString(uint8_t status);
118
119 static constexpr uint8_t kNumCameras = 2;
120 static constexpr uint8_t kNumStreams = 2;
121 static constexpr uint32_t kStorageTotalMiB = 16384;
122 static constexpr uint32_t kStorageFreeMiB = 8192;
123
124 MockLink *_mockLink = nullptr;
125 CameraState _cameras[kNumCameras];
130 QMutex _camerasMutex;
131};
struct __mavlink_message mavlink_message_t
struct __mavlink_command_long_t mavlink_command_long_t
Simulates MAVLink Camera Protocol v2 components for MockLink.
void sendCameraHeartbeats()
Send heartbeats for all simulated camera components (call from 1Hz tasks)
bool handleMavlinkMessage(const mavlink_message_t &msg)
void run10HzTasks()
Update camera states (call from 10Hz tasks)
ImageCaptureStatus
Image capture status values.
@ ImageCaptureInProgress
Single image capture in progress.
@ ImageCaptureInterval
Interval capture enabled.
@ ImageCaptureIntervalCapture
Interval capture with capture in progress.
@ ImageCaptureIdle
No capture in progress.
~MockLinkCamera()=default
Per-camera simulated state.
qint64 trackingStatusLastSentMs
Timestamp of last tracking status message.
float trackAnchorX
Original center X of tracked target.
float image_interval
Interval between image captures (seconds)
qint64 singleShotStartMs
Timestamp when single-shot capture started (0 = not active)
qint64 trackingStatusIntervalUs
Interval for CAMERA_TRACKING_IMAGE_STATUS (-1 = disabled)
qint64 trackingStartMs
Timestamp when tracking was started (for drift animation)
uint8_t trackingMode
CAMERA_TRACKING_MODE enum.
float trackAnchorY
Original center Y of tracked target.
uint32_t capFlags
CAMERA_CAP_FLAGS.
uint8_t cameraMode
CAMERA_MODE enum.
uint8_t image_status
ImageCaptureStatus enum.