63 bool captureVideo =
true,
64 bool captureImage =
true,
66 bool hasVideoStream =
true,
67 bool canCaptureImageInVideoMode =
true,
68 bool canCaptureVideoInImageMode =
false,
69 bool hasBasicZoom =
true,
70 bool hasTrackingPoint =
false,
71 bool hasTrackingRectangle =
false);
87 bool _handleCameraCommand(
const mavlink_command_long_t &request, uint8_t targetCompId);
91 bool _handleRequestMessage(
const mavlink_command_long_t &request, uint8_t targetCompId);
93 void _sendCameraInformation(uint8_t compId);
94 void _sendCameraSettings(uint8_t compId);
95 void _sendStorageInformation(uint8_t compId);
96 void _sendCameraCaptureStatus(uint8_t compId);
97 void _sendCameraImageCaptured(uint8_t compId);
98 void _sendVideoStreamInformation(uint8_t compId, uint8_t streamId);
99 void _sendVideoStreamStatus(uint8_t compId, uint8_t streamId);
100 void _sendCommandAck(uint8_t compId, uint16_t command, uint8_t result,
int requestedMsgId = -1);
103 static const char *_imageCaptureStatusToString(uint8_t status);
105 static constexpr uint8_t kNumCameras = 2;
106 static constexpr uint8_t kNumStreams = 2;
107 static constexpr uint32_t kStorageTotalMiB = 16384;
108 static constexpr uint32_t kStorageFreeMiB = 8192;
116 QMutex _camerasMutex;