Mavlink Camera Walkthrough

Documentation

Simple Camera Manager

Here we create an entire mavlink connection with client at the GCS and server at the camera. The client and server are connected via a UDP connection or a radio modem serial connection The camera can be controlled via the client, and the video stream is sent from the server to the client. The client can also request camera information, storage information, etc from the server. The operatrion of the two cameras is controlled from a gui, which allows streaming , jpeg snapshots and recodring to be controlled

import asyncio
import platform

from UAV.cameras.gst_cam import GSTCamera
from UAV.logging import LogLevels
from UAV.manager import Gui
from UAV.mavlink import CameraClient, CameraServer, MAVCom, mavlink, GimbalServerViewsheen

from UAV.utils import helpers
from UAV.utils.general import boot_time_str, toml_load, config_dir


# gst_utils.set_gst_debug_level(Gst.DebugLevel.FIXME)

async def main():
    con1, con2 = "udpin:localhost:14445", "udpout:localhost:14445"
    # con1, con2 = "/dev/ttyACM0", "/dev/ttyUSB1"
    # con1, con2 = "/dev/ttyACM0", "/dev/ttyACM2"
    # logger.disabled = True
    print(f"{boot_time_str =}")

    # with GstContext(loglevel=LogLevels.CRITICAL):  # GST main loop in thread (to process messages and display errors)
    
    # run both drone nd GCS MAV connections on this computer
    with MAVCom(con1, source_system=111, loglevel=LogLevels.CRITICAL) as GCS_client:  # This normally runs on GCS
        with MAVCom(con2, source_system=222, loglevel=LogLevels.CRITICAL) as UAV_server:  # This normally runs on drone

            # add GCS manager
            gcs: CameraClient = GCS_client.add_component(CameraClient(mav_type=mavlink.MAV_TYPE_GCS, source_component=11, loglevel=LogLevels.INFO))

            server_config_dict = toml_load(config_dir() / f"test_server_config.toml")
            print(server_config_dict)
            # add 2 UAV cameras, This normally runs on drone
            cam_0 = GSTCamera(server_config_dict, camera_dict=toml_load(config_dir() / "test_cam_0.toml"), loglevel=LogLevels.DEBUG)
            cam_1 = GSTCamera(server_config_dict, camera_dict=toml_load(config_dir() / "test_cam_1.toml"), loglevel=LogLevels.DEBUG)

            UAV_server.add_component(CameraServer(mav_type=mavlink.MAV_TYPE_CAMERA, source_component=mavlink.MAV_COMP_ID_CAMERA, camera=cam_0, loglevel=LogLevels.INFO))
            UAV_server.add_component(CameraServer(mav_type=mavlink.MAV_TYPE_CAMERA, source_component=mavlink.MAV_COMP_ID_CAMERA2, camera=cam_1, loglevel=LogLevels.INFO))

            # Wait till heartbeat found
            ret = await gcs.wait_heartbeat(remote_mav_type=mavlink.MAV_TYPE_CAMERA, timeout=2)
            print(f"Camera Heartbeat {ret = }")

            # Camera manager GUI
            gui = Gui(camera_client=gcs, gimbal_client=None)  # display GUI
            t1 = asyncio.create_task(gui.find_cameras())   # find cameras from heartbeat info
            t2 = asyncio.create_task(gui.run_gui())
            
            await asyncio.gather(t1, t2)
            
            # await asyncio.sleep(5)
            
            # try:
            #     await asyncio.gather(t1, t3)
            # except asyncio.CancelledError:
            #     print("CancelledError")
            #     pass

            cam_0.close()
            cam_1.close()




client_config_dict = toml_load(config_dir() / f"client_config.toml")
if platform.processor() != 'aarch64':
    client_config_dict['camera_udp_decoder'] = 'h264'  # on pc override as h264
p = helpers.start_displays(client_config_dict, display_type='cv2')
await main()
p.terminate()
Found config directory at: /home/john/PycharmProjects/UAV/config
cv2_display udpsrc port={} ! application/x-rtp, media=(string)video, clock-rate=(int)90000, encoding-name=(string)H264, payload=(int)96 ! queue ! rtph264depay ! avdec_h264 ! videoconvert ! capsfilter caps=video/x-raw,format=BGR  ! appsink name=mysink emit-signals=true  sync=false 
boot_time_str ='2024-01-24|10:21:20'
Found config directory at: /home/john/PycharmProjects/UAV/config
{'source_system': 222, 'camera_UDP_IP': '127.0.0.1', 'cam_0_UDP_port': 5000, 'cam_1_UDP_port': 5001, 'cam_10_UDP_port': 5010, 'usb_mount_command': 'udisksctl mount -b /dev/sda', 'image_save_path': '/media/{user}/jpgs', 'mavlink': {'source_system': 222, 'connection': '/dev/ttyUSB1'}}
Found config directory at: /home/john/PycharmProjects/UAV/config
John Doe                        
Found config directory at: /home/john/PycharmProjects/UAV/config
John Doe                        
Camera Heartbeat ret = (222, 100)
find_gimbals exit_event =  <asyncio.locks.Event object at 0x7f6fe1d06200 [unset]>
 Found Camera 222/101
 Found Camera 222/100
run_gui exit
find_cameras exit True
INFO |40.293| pygst.GstVideoS | gst_tools.:225 | MainThread | Process-2  | Starting GstVideoSource: udpsrc port=5000 ! application/x-rtp, media=(string)video, clock-rate=(int)90000, encoding-name=(string)H264, payload=(int)96 ! queue ! rtph264depay ! avdec_h264 ! videoconvert ! capsfilter caps=video/x-raw,format=BGR  ! appsink name=mysink emit-signals=true  sync=false 
DEBUG|40.294| pygst.GstVideoS | gst_tools.:229 | MainThread | Process-2  | GstVideoSource Setting pipeline state to PLAYING ... 
DEBUG|40.295| pygst.GstVideoS | gst_tools.:231 | MainThread | Process-2  | GstVideoSource Pipeline state set to PLAYING 
INFO |40.298| pygst.GstVideoS | gst_tools.:225 | MainThread | Process-2  | Starting GstVideoSource: udpsrc port=5001 ! application/x-rtp, media=(string)video, clock-rate=(int)90000, encoding-name=(string)H264, payload=(int)96 ! queue ! rtph264depay ! avdec_h264 ! videoconvert ! capsfilter caps=video/x-raw,format=BGR  ! appsink name=mysink emit-signals=true  sync=false 
DEBUG|40.299| pygst.GstVideoS | gst_tools.:229 | MainThread | Process-2  | GstVideoSource Setting pipeline state to PLAYING ... 
DEBUG|40.299| pygst.GstVideoS | gst_tools.:231 | MainThread | Process-2  | GstVideoSource Pipeline state set to PLAYING 
INFO |40.359| mavcom.CameraCl | basecompon:123 | MainThread | MainProces | Component Started self.source_component = 11, self.mav_type = 6, self.source_system = 111
INFO |40.361| uav.GSTCamera   | gst_cam.py:354 | MainThread | MainProces | GSTCamera Started
INFO |40.361| uav.GSTCamera   | gst_cam.py:580 | MainThread | MainProces | Setting camera_UDP_IP = 127.0.0.1
INFO |40.362| uav.GSTCamera   | gst_cam.py:580 | MainThread | MainProces | Setting cam_0_UDP_port = 5000
INFO |40.374| pygst.GstPipeli | gst_tools.:225 | MainThread | MainProces | Starting GstPipeline: videotestsrc pattern=ball is-live=true ! timeoverlay ! textoverlay text="Front" valignment=top halignment=right font-desc="Sans, 18" shaded-background=true ! capsfilter caps=video/x-raw,format=RGB,width=800,height=600,framerate=30/1 ! tee name=t t. ! queue ! videoscale  ! capsfilter caps=video/x-raw,format=RGB,width=400,height=300 ! videoconvert ! autovideosink t. ! interpipesink name=cam_0 
DEBUG|40.375| pygst.GstPipeli | gst_tools.:229 | MainThread | MainProces | GstPipeline Setting pipeline state to PLAYING ... 
DEBUG|40.375| pygst.GstPipeli | gst_tools.:231 | MainThread | MainProces | GstPipeline Pipeline state set to PLAYING 
INFO |40.377| pygst.GstStream | gst_tools.:225 | MainThread | MainProces | Starting GstStreamUDP: interpipesrc listen-to=cam_0 is-live=true allow-renegotiation=true format=time ! valve name=myvalve drop=False  ! queue ! videorate drop-only=true skip-to-first=true ! video/x-raw,framerate=2/1 ! videoconvert ! x264enc tune=zerolatency noise-reduction=10000 bitrate=2048 speed-preset=superfast ! rtph264pay ! udpsink host=127.0.0.1 port=5000 sync=true
DEBUG|40.377| pygst.GstStream | gst_tools.:229 | MainThread | MainProces | GstStreamUDP Setting pipeline state to PLAYING ... 
DEBUG|40.378| pygst.GstStream | gst_tools.:231 | MainThread | MainProces | GstStreamUDP Pipeline state set to PLAYING 
INFO |40.379| uav.GSTCamera   | gst_cam.py:748 | MainThread | MainProces | Video streaming pipeline "gstreamer_udpsink" created on port 5000
DEBUG|40.479| pygst.GstStream | gst_tools.:265 | MainThread | MainProces | Valve "myvalve" state set to True
INFO |40.480| uav.GSTCamera   | gst_cam.py:764 | MainThread | MainProces | Video streaming "gstreamer_udpsink" stopped (paused) on port 5000
INFO |40.482| uav.GSTCamera   | gst_cam.py:354 | MainThread | MainProces | GSTCamera Started
INFO |40.483| uav.GSTCamera   | gst_cam.py:580 | MainThread | MainProces | Setting camera_UDP_IP = 127.0.0.1
INFO |40.483| uav.GSTCamera   | gst_cam.py:580 | MainThread | MainProces | Setting cam_1_UDP_port = 5001
INFO |40.497| pygst.GstPipeli | gst_tools.:225 | MainThread | MainProces | Starting GstPipeline: videotestsrc pattern=ball is-live=true ! timeoverlay ! textoverlay text="Left" valignment=top halignment=right font-desc="Sans, 18" shaded-background=true ! capsfilter caps=video/x-raw,format=RGB,width=800,height=600,framerate=30/1 ! tee name=t t. ! queue ! videoscale  ! capsfilter caps=video/x-raw,format=RGB,width=400,height=300 ! videoconvert ! autovideosink t. ! interpipesink name=cam_1 
DEBUG|40.498| pygst.GstPipeli | gst_tools.:229 | MainThread | MainProces | GstPipeline Setting pipeline state to PLAYING ... 
DEBUG|40.498| pygst.GstPipeli | gst_tools.:231 | MainThread | MainProces | GstPipeline Pipeline state set to PLAYING 
INFO |40.500| pygst.GstStream | gst_tools.:225 | MainThread | MainProces | Starting GstStreamUDP: interpipesrc listen-to=cam_1 is-live=true allow-renegotiation=true format=time ! valve name=myvalve drop=False  ! queue ! videorate drop-only=true skip-to-first=true ! video/x-raw,framerate=2/1 ! videoconvert ! x264enc tune=zerolatency noise-reduction=10000 bitrate=2048 speed-preset=superfast ! rtph264pay ! udpsink host=127.0.0.1 port=5001 sync=true
DEBUG|40.500| pygst.GstStream | gst_tools.:229 | MainThread | MainProces | GstStreamUDP Setting pipeline state to PLAYING ... 
DEBUG|40.501| pygst.GstStream | gst_tools.:231 | MainThread | MainProces | GstStreamUDP Pipeline state set to PLAYING 
INFO |40.502| uav.GSTCamera   | gst_cam.py:748 | MainThread | MainProces | Video streaming pipeline "gstreamer_udpsink" created on port 5001
DEBUG|40.602| pygst.GstStream | gst_tools.:265 | MainThread | MainProces | Valve "myvalve" state set to True
INFO |40.603| uav.GSTCamera   | gst_cam.py:764 | MainThread | MainProces | Video streaming "gstreamer_udpsink" stopped (paused) on port 5001
INFO |40.604| mavcom.CameraSe | basecompon:123 | MainThread | MainProces | Component Started self.source_component = 100, self.mav_type = 30, self.source_system = 222
INFO |40.605| mavcom.CameraSe | basecompon:123 | MainThread | MainProces | Component Started self.source_component = 101, self.mav_type = 30, self.source_system = 222
WARNI|40.606| root            | asyncio_gu:271 | MainThread | MainProces | Gui auto is not callable
WARNI|40.607| root            | asyncio_gu:273 | MainThread | MainProces | Gui reset is not callable
WARNI|40.607| root            | asyncio_gu:275 | MainThread | MainProces | Gui pause is not callable
DEBUG|43.667| pygst.GstPipeli | gst_tools.:294 | MainThread | MainProces | GstPipeline Stopping pipeline ...
DEBUG|43.669| pygst.GstPipeli | gst_tools.:298 | MainThread | MainProces | GstPipeline Sending EOS event ...
DEBUG|43.771| pygst.GstPipeli | gst_tools.:315 | MainThread | MainProces | GstPipeline Reseting pipeline state ....
DEBUG|43.814| pygst.GstPipeli | gst_tools.:322 | MainThread | MainProces | GstPipeline Gst.Pipeline successfully destroyed
INFO |43.815| pygst.GstPipeli | gst_tools.:335 | MainThread | MainProces | GstPipeline Shutdown
INFO |43.817| uav.GSTCamera   | gst_cam.py:516 | MainThread | MainProces | GSTCamera closed
DEBUG|43.987| pygst.GstStream | gst_tools.:967 | Thread-22  | MainProces | Sending EOS event, to trigger shutdown of pipeline
INFO |43.989| pygst.GstStream | gst_tools.:335 | MainThread | MainProces | GstStreamUDP Shutdown
INFO |43.990| uav.GSTCamera   | gst_cam.py:803 | MainThread | MainProces | !!!!!! Closed "gstreamer_udpsink" 
DEBUG|43.991| pygst.GstPipeli | gst_tools.:294 | MainThread | MainProces | GstPipeline Stopping pipeline ...
DEBUG|43.992| pygst.GstPipeli | gst_tools.:298 | MainThread | MainProces | GstPipeline Sending EOS event ...
DEBUG|44.094| pygst.GstPipeli | gst_tools.:315 | MainThread | MainProces | GstPipeline Reseting pipeline state ....
DEBUG|44.110| pygst.GstPipeli | gst_tools.:322 | MainThread | MainProces | GstPipeline Gst.Pipeline successfully destroyed
INFO |44.111| pygst.GstPipeli | gst_tools.:335 | MainThread | MainProces | GstPipeline Shutdown
INFO |44.112| uav.GSTCamera   | gst_cam.py:516 | MainThread | MainProces | GSTCamera closed
DEBUG|44.309| pygst.GstStream | gst_tools.:967 | Thread-23  | MainProces | Sending EOS event, to trigger shutdown of pipeline
INFO |44.311| pygst.GstStream | gst_tools.:335 | MainThread | MainProces | GstStreamUDP Shutdown
INFO |44.312| uav.GSTCamera   | gst_cam.py:803 | MainThread | MainProces | !!!!!! Closed "gstreamer_udpsink" 
INFO |44.363| pygst.GstPipeli | gst_tools.:335 | MainThread | MainProces | GstPipeline Shutdown
INFO |44.364| uav.GSTCamera   | gst_cam.py:516 | MainThread | MainProces | GSTCamera closed
INFO |44.465| pygst.GstStream | gst_tools.:335 | MainThread | MainProces | GstStreamUDP Shutdown
INFO |44.466| uav.GSTCamera   | gst_cam.py:803 | MainThread | MainProces | !!!!!! Closed "gstreamer_udpsink" 
INFO |44.467| mavcom.CameraSe | basecompon:417 | MainThread | MainProces | CameraServer closed (not waiting for _t_heartbeat daemon thread)
INFO |44.469| pygst.GstPipeli | gst_tools.:335 | MainThread | MainProces | GstPipeline Shutdown
INFO |44.470| uav.GSTCamera   | gst_cam.py:516 | MainThread | MainProces | GSTCamera closed
INFO |44.571| pygst.GstStream | gst_tools.:335 | MainThread | MainProces | GstStreamUDP Shutdown
INFO |44.573| uav.GSTCamera   | gst_cam.py:803 | MainThread | MainProces | !!!!!! Closed "gstreamer_udpsink" 
INFO |44.574| mavcom.CameraSe | basecompon:417 | MainThread | MainProces | CameraServer closed (not waiting for _t_heartbeat daemon thread)
INFO |44.611| mavcom.CameraCl | basecompon:417 | MainThread | MainProces | CameraClient closed (not waiting for _t_heartbeat daemon thread)

More Detail

Create a GST Camera

Create physical camera object, as either a CV2Camera or GSTCamera The toml file contains the camera parameters, such as resolution, framerate, etc and also the gstreamer pipeline command to create the video streams.

server_config_dict = toml_load(config_dir() / f"test_server_config.toml")
cam_0 = GSTCamera(server_config_dict, camera_dict=toml_load(config_dir() / "test_cam_0.toml"), loglevel=LogLevels.DEBUG)
INFO |48.505| uav.GSTCamera   | gst_cam.py:354 | MainThread | MainProces | GSTCamera Started
INFO |48.505| uav.GSTCamera   | gst_cam.py:580 | MainThread | MainProces | Setting camera_UDP_IP = 127.0.0.1
INFO |48.506| uav.GSTCamera   | gst_cam.py:580 | MainThread | MainProces | Setting cam_0_UDP_port = 5000
INFO |48.529| pygst.GstPipeli | gst_tools.:225 | MainThread | MainProces | Starting GstPipeline: videotestsrc pattern=ball is-live=true ! timeoverlay ! textoverlay text="Front" valignment=top halignment=right font-desc="Sans, 18" shaded-background=true ! capsfilter caps=video/x-raw,format=RGB,width=800,height=600,framerate=30/1 ! tee name=t t. ! queue ! videoscale  ! capsfilter caps=video/x-raw,format=RGB,width=400,height=300 ! videoconvert ! autovideosink t. ! interpipesink name=cam_0 
DEBUG|48.529| pygst.GstPipeli | gst_tools.:229 | MainThread | MainProces | GstPipeline Setting pipeline state to PLAYING ... 
DEBUG|48.530| pygst.GstPipeli | gst_tools.:231 | MainThread | MainProces | GstPipeline Pipeline state set to PLAYING 
INFO |48.532| pygst.GstStream | gst_tools.:225 | MainThread | MainProces | Starting GstStreamUDP: interpipesrc listen-to=cam_0 is-live=true allow-renegotiation=true format=time ! valve name=myvalve drop=False  ! queue ! videorate drop-only=true skip-to-first=true ! video/x-raw,framerate=2/1 ! videoconvert ! x264enc tune=zerolatency noise-reduction=10000 bitrate=2048 speed-preset=superfast ! rtph264pay ! udpsink host=127.0.0.1 port=5000 sync=true
DEBUG|48.532| pygst.GstStream | gst_tools.:229 | MainThread | MainProces | GstStreamUDP Setting pipeline state to PLAYING ... 
DEBUG|48.534| pygst.GstStream | gst_tools.:231 | MainThread | MainProces | GstStreamUDP Pipeline state set to PLAYING 
INFO |48.535| uav.GSTCamera   | gst_cam.py:748 | MainThread | MainProces | Video streaming pipeline "gstreamer_udpsink" created on port 5000
DEBUG|48.635| pygst.GstStream | gst_tools.:265 | MainThread | MainProces | Valve "myvalve" state set to True
INFO |48.636| uav.GSTCamera   | gst_cam.py:764 | MainThread | MainProces | Video streaming "gstreamer_udpsink" stopped (paused) on port 5000
Found config directory at: /home/john/PycharmProjects/UAV/config
Found config directory at: /home/john/PycharmProjects/UAV/config
John Doe                        

Camera Configuration toml file printout

cam_name = 'cam_0'

[camera_info]
vendor_name = "John Doe                   "
model_name = "Fake Camera                  "
firmware_version = 1
focal_length = 8.0
sensor_size_h = 6.0
sensor_size_v = 4.0
resolution_h = 1920
resolution_v = 1080
lens_id = 0
flags = 0
cam_definition_version = 1
cam_definition_uri = "http://example.com/camera_definition.xml"

[camera_position]
x = 0.0
y = 0.0
z = 0.0
roll = 0.0
pitch = 0.0
yaw = 0.0

[gstreamer_video_src]
fps = 30   # Frames per second
width = 800
height = 600
loglevel = 'DEBUG'   # todo add loglevel to all pipelines and to gst_utils

pipeline = [
    'videotestsrc pattern=ball is-live=true ! timeoverlay',
    'textoverlay text="Front" valignment=top halignment=right font-desc="Sans, 18" shaded-background=true',
    'capsfilter caps=video/x-raw,format=RGB,width={width},height={height},framerate={fps}/1',
    'tee name=t',

    "t.",
    'queue', 'videoscale ', 'capsfilter caps=video/x-raw,format=RGB,width=400,height=300',
    'videoconvert ! autovideosink',

#    "t.",
#    'queue leaky=2 ! intervideosink channel=channel_0  sync=false',
#
#    "t.",
#    'queue leaky=2 ! intervideosink channel={cam_name}  sync=false',

    "t.",
    'interpipesink name={cam_name} ',
]

[gstreamer_udpsink]
fps=2
host = '*camera_UDP_IP*'     # overwrite with server_config.toml
port = '*cam_0_UDP_port*'    # overwrite with server_config.toml
pipeline = [

    'interpipesrc listen-to={cam_name} is-live=true allow-renegotiation=true format=time',
#    'queue max-size-buffers=1 leaky=downstream',
    'valve name=myvalve drop=False ',
    'queue',
    'videorate drop-only=true skip-to-first=true ! video/x-raw,framerate={fps}/1',
    'videoconvert',
     'x264enc tune=zerolatency noise-reduction=10000 bitrate=2048 speed-preset=superfast',
#    'x264enc tune=zerolatency',
    'rtph264pay ! udpsink host={host} port={port} sync=true',
    ]

[gstreamer_jpg_filesink]
fps = 10   # Frames per second * 10
quality = 85
filenames = '%03d.jpg'
index = 0

pipeline = [
    'interpipesrc listen-to={cam_name} is-live=false allow-renegotiation=true format=time',
    'queue',
    'videorate drop-only=true skip-to-first=true ! video/x-raw,framerate={fps}/10',
    'videoconvert ! video/x-raw, format=I420',
    'jpegenc quality={quality}',  # Quality of encoding, default is 85
    'multifilesink location={save_path}/{cam_name}/{filenames} max-files=10 index={index}',
    ]

Add Camera

Add the camera client to the client mavlink connection

cam = client.add_component(CameraClient(mav_type=mavlink.MAV_TYPE_GCS, source_component=11))
INFO |48.895| mavcom.CameraCl | basecompon:123 | MainThread | MainProces | Component Started self.source_component = 11, self.mav_type = 6, self.source_system = 111

Add the camera server to the server mavlink connection

server.add_component(CameraServer(mav_type=mavlink.MAV_TYPE_CAMERA, source_component=mavlink.MAV_COMP_ID_CAMERA, camera=cam_0))
INFO |48.908| mavcom.CameraSe | basecompon:123 | MainThread | MainProces | Component Started self.source_component = 100, self.mav_type = 30, self.source_system = 222
<CameraServer>

Wait for the heartbeat from the camera server

async def doit():
    ret = await cam.wait_heartbeat(remote_mav_type=mavlink.MAV_TYPE_CAMERA)
    print(f"Heartbeat received {ret = }")
await doit()
Heartbeat received ret = (222, 100)

Set the target system and component for the camera client and request camera information, storage information, camera capture status, and camera settings

async def doit():
    msg = await cam.request_message(mavlink.MAVLINK_MSG_ID_CAMERA_INFORMATION, target_system=222, target_component=mavlink.MAV_COMP_ID_CAMERA)
    print (f"1 MAVLINK_MSG_ID_CAMERA_INFORMATION {msg }")
    msg = await cam.request_message(mavlink.MAVLINK_MSG_ID_STORAGE_INFORMATION, target_system=222, target_component=mavlink.MAV_COMP_ID_CAMERA)
    print (f"2 MAVLINK_MSG_ID_STORAGE_INFORMATION {msg }")
    msg = await cam.request_message(mavlink.MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS, target_system=222, target_component=mavlink.MAV_COMP_ID_CAMERA)
    print (f"3 MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS {msg }")
    msg = await cam.request_message(mavlink.MAVLINK_MSG_ID_CAMERA_SETTINGS, target_system=222, target_component=mavlink.MAV_COMP_ID_CAMERA)
    print (f"4 MAVLINK_MSG_ID_CAMERA_SETTINGS {msg }")
await doit()
DEBUG|48.934| uav.GSTCamera   | gst_cam.py:273 | Thread-30  | MainProces | self.mav.srcSystem = 222 self.mav.srcComponent = 100
DEBUG|48.935| uav.GSTCamera   | gst_cam.py:274 | Thread-30  | MainProces | camera_information_send self.camera_info = {'vendor_name': [74, 111, 104, 110, 32, 68, 111, 101, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32], 'model_name': [70, 97, 107, 101, 32, 67, 97, 109, 101, 114, 97, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32], 'firmware_version': 1, 'focal_length': 8.0, 'sensor_size_h': 6.0, 'sensor_size_v': 4.0, 'resolution_h': 1920, 'resolution_v': 1080, 'lens_id': 0, 'flags': 0, 'cam_definition_version': 1, 'cam_definition_uri': 'http://example.com/camera_definition.xml'} self.mav = <pymavlink.dialects.v20.ardupilotmega.MAVLink object>
1 MAVLINK_MSG_ID_CAMERA_INFORMATION CAMERA_INFORMATION {time_boot_ms : 220300, vendor_name : John Doe, model_name : Fake Camera, firmware_version : 1, focal_length : 8.0, sensor_size_h : 6.0, sensor_size_v : 4.0, resolution_h : 1920, resolution_v : 1080, lens_id : 0, flags : 0, cam_definition_version : 1, cam_definition_uri : http://example.com/camera_definition.xml, gimbal_device_id : 0}
2 MAVLINK_MSG_ID_STORAGE_INFORMATION STORAGE_INFORMATION {time_boot_ms : 220401, storage_id : 0, storage_count : 1, status : 0, total_capacity : 100000000.0, used_capacity : 0.0, available_capacity : 100000000.0, read_speed : 0.0, write_speed : 0.0, type : 0, name : }
3 MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS CAMERA_CAPTURE_STATUS {time_boot_ms : 220502, image_status : 0, video_status : 0, image_interval : 0.0, recording_time_ms : 0, available_capacity : 0.0, image_count : 0}
4 MAVLINK_MSG_ID_CAMERA_SETTINGS CAMERA_SETTINGS {time_boot_ms : 220604, mode_id : 0, zoomLevel : 0.0, focusLevel : 0.0}

Start an image capture seqeunce,

and display the images as they arrive

# cam.image_start_capture(interval=0.1, count=10)
# while cam_gst_1.capture_thread.is_alive():
#     if cam_gst_1.last_image is not None:
#         cv2.imshow('gst_src', cam_gst_1.last_image)
#         cam_gst_1.last_image = None
#     cv2.waitKey(10)