QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MockLinkCamera Class Reference

#include <MockLinkCamera.h>

Classes

struct  CameraState
 Per-camera simulated state. More...
 

Public Types

enum  ImageCaptureStatus { ImageCaptureIdle = 0 , ImageCaptureInProgress = 1 , ImageCaptureInterval = 2 , ImageCaptureIntervalCapture = 3 }
 Image capture status values. More...
 

Public Member Functions

 MockLinkCamera (MockLink *mockLink, bool captureVideo=true, bool captureImage=true, bool hasModes=true, bool hasVideoStream=true, bool canCaptureImageInVideoMode=true, bool canCaptureVideoInImageMode=false, bool hasBasicZoom=true, bool hasTrackingPoint=false, bool hasTrackingRectangle=false)
 
 ~MockLinkCamera ()=default
 
void sendCameraHeartbeats ()
 Send heartbeats for all simulated camera components (call from 1Hz tasks)
 
void run10HzTasks ()
 Update camera states (call from 10Hz tasks)
 
bool handleMavlinkMessage (const mavlink_message_t &msg)
 

Detailed Description

Simulates MAVLink Camera Protocol v2 components for MockLink.

Two cameras are provided: Camera 1 (MAV_COMP_ID_CAMERA) – full-featured: video capture, photo capture, mode switching, basic zoom, video streaming (udp://127.0.0.1:5600, H.264 RTP, 1920×1080 @ 30 fps), and image capture while in video mode. Camera 2 (MAV_COMP_ID_CAMERA2) – photo-only: image capture only; video, mode switching, zoom, focus, and streaming commands are denied.

Supported MAVLink commands: MAV_CMD_REQUEST_MESSAGE (CAMERA_INFORMATION, CAMERA_SETTINGS, STORAGE_INFORMATION, CAMERA_CAPTURE_STATUS, VIDEO_STREAM_INFORMATION, VIDEO_STREAM_STATUS) MAV_CMD_REQUEST_CAMERA_INFORMATION / SETTINGS / STORAGE / CAPTURE_STATUS MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION / STATUS MAV_CMD_SET_CAMERA_MODE MAV_CMD_IMAGE_START_CAPTURE / IMAGE_STOP_CAPTURE MAV_CMD_VIDEO_START_CAPTURE / VIDEO_STOP_CAPTURE MAV_CMD_STORAGE_FORMAT MAV_CMD_SET_CAMERA_ZOOM / SET_CAMERA_FOCUS MAV_CMD_RESET_CAMERA_SETTINGS MAV_CMD_CAMERA_TRACK_POINT / TRACK_RECTANGLE / STOP_TRACKING

Simulated storage: 16 GiB total, 8 GiB free, SD card.

Definition at line 37 of file MockLinkCamera.h.

Member Enumeration Documentation

◆ ImageCaptureStatus

Image capture status values.

Enumerator
ImageCaptureIdle 

No capture in progress.

ImageCaptureInProgress 

Single image capture in progress.

ImageCaptureInterval 

Interval capture enabled.

ImageCaptureIntervalCapture 

Interval capture with capture in progress.

Definition at line 41 of file MockLinkCamera.h.

Constructor & Destructor Documentation

◆ MockLinkCamera()

MockLinkCamera::MockLinkCamera ( MockLink mockLink,
bool  captureVideo = true,
bool  captureImage = true,
bool  hasModes = true,
bool  hasVideoStream = true,
bool  canCaptureImageInVideoMode = true,
bool  canCaptureVideoInImageMode = false,
bool  hasBasicZoom = true,
bool  hasTrackingPoint = false,
bool  hasTrackingRectangle = false 
)
explicit

Definition at line 11 of file MockLinkCamera.cc.

◆ ~MockLinkCamera()

MockLinkCamera::~MockLinkCamera ( )
default

Member Function Documentation

◆ handleMavlinkMessage()

bool MockLinkCamera::handleMavlinkMessage ( const mavlink_message_t msg)

Handle all incoming MAVLink messages for camera.

Returns
true if the message was handled by the camera

Definition at line 111 of file MockLinkCamera.cc.

◆ run10HzTasks()

void MockLinkCamera::run10HzTasks ( )

◆ sendCameraHeartbeats()

void MockLinkCamera::sendCameraHeartbeats ( )

Send heartbeats for all simulated camera components (call from 1Hz tasks)

Definition at line 70 of file MockLinkCamera.cc.

References MockLinkCamera::CameraState::compId, LinkInterface::mavlinkChannel(), MockLink::respondWithMavlinkMessage(), and MockLink::vehicleId().

Referenced by MockLink::run1HzTasks().


The documentation for this class was generated from the following files: