import time, os, sys
from UAV.logging import logging
from UAV.mavlink.mavcom import MAVCom
from UAV.mavlink.component import Component, mavutil
# from viewsheen_sdk.gimbal_cntrl import pan_tilt, snapshot, zoom, VS_IP_ADDRESS, VS_PORT, KeyReleaseThread
from UAV.camera_sdks.viewsheen.gimbal_cntrl import pan_tilt, snapshot, zoom, VS_IP_ADDRESS, VS_PORT, KeyReleaseThread
from UAV.mavlink.vs_gimbal import *
# from UAV.imports import * # TODO why is this relative importMavlink ViewSheen Gimbal Component
Gimbal Component
https://mavlink.io/en/services/gimbal.html
https://mavlink.io/en/services/gimbal_v2.html > Concepts - Gimbal Manager and Gimbal Device - To accommodate gimbals with varying capabilities, and various hardware setups, “a gimbal” is conceptually split into two parts:
Gimbal Device: the actual gimbal device, hardware and software. Gimbal Manager: software to deconflict gimbal messages and commands from different sources, and to abstract the capabilities of the Gimbal Device from gimbal users. The Gimbal Manager and Gimbal Device expose respective message sets that can be used for: gimbal manager/device discovery, querying capabilities, publishing status, and various types of orientation/attitude control.
The key concept to understand is that a Gimbal Manager has a 1:1 relationship with a particular Gimbal Device, and is the only party on the M
GimbalClient
GimbalClient (source_component, mav_type, debug)
Create a Viewsheen mavlink gimbal client component for send commands to a gimbal on a companion computer or GCS
| Details | |
|---|---|
| source_component | used for component indication |
| mav_type | used for heartbeat MAV_TYPE indication |
| debug | logging level |
GimbalServer
GimbalServer (source_component, mav_type, debug)
Create a Viewsheen mavlink Camera Server Component for receiving commands from a gimbal on a companion computer or GCS
| Details | |
|---|---|
| source_component | used for component indication |
| mav_type | used for heartbeat MAV_TYPE indication |
| debug | logging level |
MAV_TYPE_GCS = mavutil.mavlink.MAV_TYPE_GCS
MAV_TYPE_CAMERA = mavutil.mavlink.MAV_TYPE_CAMERA
# cli = GimbalClient(mav_connection=None, source_component=11, mav_type=MAV_TYPE_GCS, debug=False)
# gim1 = GimbalServer(mav_connection=None, source_component=22, mav_type=MAV_TYPE_CAMERA, debug=False)
con1, con2 = "udpin:localhost:14445", "udpout:localhost:14445"
# con1, con2 = "/dev/ttyACM0", "/dev/ttyUSB0"
with MAVCom(con1, source_system=111, debug=False) as client:
with MAVCom(con2, source_system=222, debug=False) as server:
gimbal:GimbalClient = client.add_component(GimbalClient( mav_type=MAV_TYPE_GCS, source_component = 11, debug=False))
server.add_component(GimbalServer( mav_type=MAV_TYPE_CAMERA, source_component = 22, debug=False))
gimbal.wait_heartbeat(target_system=222, target_component=22, timeout=0.99)
time.sleep(0.1)
gimbal.set_target(222, 22)
NAN = float("nan")
# client.component[11]._test_command(222, 22, 1)
# for i in range (1) :
# time.sleep(0.01)
gimbal.set_attitude( NAN, NAN, 0.0, 0.2)
time.sleep(0.5)
gimbal.set_attitude( NAN, NAN, 0.0, -0.2)
time.sleep(0.5)
gimbal.start_capture()
# gimbal.set_zoom(1)
# client.component[11].set_attitude(0, 0, 0, 0, 0, 0)INFO | uav.MAVCom | 44.813 | mavcom.py:393 | Thread-7 (listen) | MAVLink Mav2: True, source_system: 111
INFO | uav.MAVCom | 44.915 | mavcom.py:393 | Thread-8 (listen) | MAVLink Mav2: True, source_system: 222
INFO | uav.GimbalClien | 44.917 | component.py:111 | MainThread | Component Started self.source_component = 11, self.mav_type = 6, self.source_system = 111
INFO | uav.MAVCom | 52.945 | mavcom.py:441 | MainThread | MAVCom closed
INFO | uav.GimbalClien | 53.953 | component.py:366 | MainThread | GimbalClient closed
INFO | uav.MAVCom | 53.955 | mavcom.py:441 | MainThread | MAVCom closed
set_mav_connection GimbalClient mavcom.py:107 self.mav_connection = <MAVCom>
KeyboardInterrupt:
# assert False, "Stop here"