Skip to content

Commit 0d63a43

Browse files
committed
added SIYI camera module
for basic control of a SIYI camera
1 parent b0394c1 commit 0d63a43

File tree

1 file changed

+183
-0
lines changed

1 file changed

+183
-0
lines changed

MAVProxy/modules/mavproxy_SIYI.py

Lines changed: 183 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,183 @@
1+
'''
2+
control SIYI camera over UDP
3+
'''
4+
5+
from MAVProxy.modules.lib import mp_module
6+
from MAVProxy.modules.lib import mp_settings
7+
from MAVProxy.modules.lib import mp_util
8+
from pymavlink import mavutil
9+
10+
import socket, time, os, struct
11+
12+
SIYI_RATE_MAX_DPS = 90.0
13+
SIYI_HEADER1 = 0x55
14+
SIYI_HEADER2 = 0x66
15+
16+
ACQUIRE_FIRMWARE_VERSION = 0x01
17+
HARDWARE_ID = 0x02
18+
AUTO_FOCUS = 0x04
19+
MANUAL_ZOOM_AND_AUTO_FOCUS = 0x05
20+
MANUAL_FOCUS = 0x06
21+
GIMBAL_ROTATION = 0x07
22+
CENTER = 0x08
23+
ACQUIRE_GIMBAL_CONFIG_INFO = 0x0A
24+
FUNCTION_FEEDBACK_INFO = 0x0B
25+
PHOTO = 0x0C
26+
ACQUIRE_GIMBAL_ATTITUDE = 0x0D
27+
ABSOLUTE_ZOOM = 0x0F
28+
29+
def crc16_from_bytes(bytes, initial=0xFFFF):
30+
# CRC-16-CCITT
31+
# Initial value: 0xFFFF
32+
# Poly: 0x1021
33+
# Reverse: no
34+
# Output xor: 0
35+
# Check string: '123456789'
36+
# Check value: 0x29B1
37+
38+
try:
39+
if isinstance(bytes, basestring): # Python 2.7 compatibility
40+
bytes = map(ord, bytes)
41+
except NameError:
42+
if isinstance(bytes, str): # This branch will be taken on Python 3
43+
bytes = map(ord, bytes)
44+
45+
crc = initial
46+
for byte in bytes:
47+
crc ^= byte << 8
48+
for bit in range(8):
49+
if crc & 0x8000:
50+
crc = ((crc << 1) ^ 0x1021) & 0xFFFF
51+
else:
52+
crc = (crc << 1) & 0xFFFF
53+
return crc & 0xFFFF
54+
55+
56+
class SIYIModule(mp_module.MPModule):
57+
58+
def __init__(self, mpstate):
59+
super(SIYIModule, self).__init__(mpstate, "SIYI", "SIYI camera support")
60+
61+
self.add_command('siyi', self.cmd_siyi, "SIYI camera control",
62+
["<rates|connect>","set (SIYISETTING)"])
63+
64+
# filter_dist is distance in metres
65+
self.siyi_settings = mp_settings.MPSettings([("port", int, 37260),
66+
('ip', str, "192.168.144.25"),
67+
('rates_hz', float, 5),
68+
('att_hz', float, 5)])
69+
self.add_completion_function('(SIYISETTING)',
70+
self.siyi_settings.completion)
71+
self.sock = None
72+
self.rates = (0.0, 0.0)
73+
self.sequence = 0
74+
self.last_rates_send = time.time()
75+
self.last_att_send = time.time()
76+
self.have_version = False
77+
self.console.set_status('SIYI', 'SIYI - -')
78+
79+
def cmd_siyi(self, args):
80+
'''siyi command parser'''
81+
usage = "usage: siyi <set|rates>"
82+
if len(args) == 0:
83+
print(usage)
84+
return
85+
if args[0] == "set":
86+
self.siyi_settings.command(args[1:])
87+
elif args[0] == "connect":
88+
self.cmd_connect()
89+
elif args[0] == "rates":
90+
self.cmd_rates(args[1:])
91+
else:
92+
print(usage)
93+
94+
def cmd_connect(self):
95+
'''connect to the camera'''
96+
self.sock = socket.socket(socket.AF_INET, socket.SOCK_DGRAM, socket.IPPROTO_UDP)
97+
self.sock.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1)
98+
self.sock.connect((self.siyi_settings.ip, self.siyi_settings.port))
99+
self.sock.setblocking(False)
100+
print("Connected to SIYI")
101+
102+
def cmd_rates(self, args):
103+
'''update rates'''
104+
if len(args) < 2:
105+
print("Usage: siyi rates PAN_RATE PITCH_RATE")
106+
return
107+
print(args)
108+
self.rates = (float(args[0]), args(args[1]))
109+
print(self.rates)
110+
111+
def send_rates(self):
112+
'''send rates packet'''
113+
now = time.time()
114+
if self.siyi_settings.rates_hz <= 0 or now - self.last_rates_send < 1.0/self.siyi_settings.rates_hz:
115+
return
116+
self.last_rates_send = now
117+
pkt = struct.pack("<bb",
118+
int(100.0*self.rates[0]/SIYI_RATE_MAX_DPS),
119+
int(100.0*self.rates[1]/SIYI_RATE_MAX_DPS))
120+
self.send_packet(GIMBAL_ROTATION, pkt)
121+
122+
def request_attitude(self):
123+
'''request attitude'''
124+
now = time.time()
125+
if self.siyi_settings.att_hz <= 0 or now - self.last_att_send < 1.0/self.siyi_settings.att_hz:
126+
return
127+
self.last_att_send = now
128+
self.send_packet(ACQUIRE_GIMBAL_ATTITUDE, None)
129+
130+
def send_packet(self, command_id, pkt):
131+
'''send SIYI packet'''
132+
plen = len(pkt) if pkt else 0
133+
buf = struct.pack("<BBBHHB", SIYI_HEADER1, SIYI_HEADER2, 1, plen,
134+
self.sequence, command_id)
135+
if pkt:
136+
buf += pkt
137+
buf += struct.pack("<H", crc16_from_bytes(buf))
138+
self.sequence += 1
139+
try:
140+
self.sock.send(buf)
141+
except Exception:
142+
pass
143+
144+
def parse_packet(self, pkt):
145+
'''parse SIYI packet'''
146+
if len(pkt) < 10:
147+
return
148+
(h1,h2,rack,plen,seq,cmd) = struct.unpack("<BBBHHB", pkt[:8])
149+
data = pkt[8:-2]
150+
crc = struct.unpack("<H", pkt[-2:])
151+
if crc != crc16_from_bytes(pkt[0:-2]):
152+
print("SIYI bad CRC")
153+
return
154+
155+
if cmd == ACQUIRE_FIRMWARE_VERSION:
156+
(patch,minor,major) = struct.unpack("<BBB", data[:3])
157+
print("SIYI CAM %u.%u.%u" % (major, minor, patch))
158+
(patch,minor,major) = struct.unpack("<BBB", data[3:6])
159+
print("SIYI Gimbal %u.%u.%u" % (major, minor, patch))
160+
self.have_version = True
161+
162+
elif cmd == ACQUIRE_GIMBAL_ATTITUDE:
163+
(z,y,x) = struct.unpack("<hhh", data[:6])
164+
self.console.set_status('SIYI', 'SIYI %.1f %.1f %.1f' % (x*0.1, y*0.1, z*0.1))
165+
166+
def idle_task(self):
167+
'''called on idle'''
168+
if not self.sock:
169+
return
170+
self.send_rates()
171+
self.request_attitude()
172+
if not self.have_version:
173+
self.send_packet(ACQUIRE_FIRMWARE_VERSION, None)
174+
175+
try:
176+
pkt = self.sock.recv(10240)
177+
self.parse_packet(pkt)
178+
except Exception:
179+
pass
180+
181+
def init(mpstate):
182+
'''initialise module'''
183+
return SIYIModule(mpstate)

0 commit comments

Comments
 (0)