Skip to content

Commit f2f8147

Browse files
committed
SIYI: display click mode in window titles
1 parent 4b1464d commit f2f8147

File tree

3 files changed

+27
-16
lines changed

3 files changed

+27
-16
lines changed

Diff for: MAVProxy/modules/mavproxy_SIYI/__init__.py

+13-5
Original file line numberDiff line numberDiff line change
@@ -364,6 +364,7 @@ def __init__(self, mpstate):
364364
self.last_armed = False
365365
self.getconfig_pending = False
366366
self.last_getconfig = time.time()
367+
self.click_mode = "Flag"
367368

368369
if mp_util.has_wxpython:
369370
menu = MPMenuSubMenu('SIYI',
@@ -1002,12 +1003,13 @@ def parse_packet(self, pkt):
10021003
self.send_named_float('TMAX', self.tmax)
10031004
self.last_temp_t = time.time()
10041005
frame_counter = -1 if self.thermal_view is None else self.thermal_view.frame_counter
1005-
self.logf.write('SITR', 'QffHHHHi', 'TimeUS,TMin,TMax,TMinX,TMinY,TMaxX,TMaxY,FC',
1006+
self.logf.write('SITR', 'QffHHHHiI', 'TimeUS,TMin,TMax,TMinX,TMinY,TMaxX,TMaxY,FC,TCAP',
10061007
self.micros64(),
10071008
self.tmin, self.tmax,
10081009
self.tmin_x, self.tmin_y,
10091010
self.tmax_x, self.tmax_y,
1010-
frame_counter)
1011+
frame_counter,
1012+
self.thermal_capture_count)
10111013
if self.thermal_view is not None:
10121014
threshold = self.siyi_settings.threshold_temp
10131015
threshold_value = int(255*(threshold - self.tmin)/max(1,(self.tmax-self.tmin)))
@@ -1254,8 +1256,15 @@ def get_view_vector(self, x, y, FOV, aspect_ratio):
12541256
(roll,pitch,yaw) = (math.radians(fov_att[0]),math.radians(fov_att[1]),math.radians(fov_att[2]))
12551257
yaw += att.yaw
12561258
FOV_half = math.radians(0.5*FOV)
1257-
yaw += FOV_half*x
1259+
1260+
pitch = math.radians(-90)
1261+
aspect_ratio = 1.0
1262+
12581263
pitch -= y*FOV_half/aspect_ratio
1264+
if pitch < math.radians(-90):
1265+
yaw -= FOV_half*x
1266+
else:
1267+
yaw += FOV_half*x
12591268
m.from_euler(roll, pitch, yaw)
12601269
v = m * v
12611270
return v
@@ -1448,8 +1457,7 @@ def mavlink_packet(self, m):
14481457
self.armed_checks()
14491458

14501459
if mtype == 'GPS_RAW_INT':
1451-
# ?!? why off by 18 hours
1452-
gwk, gms = mp_util.get_gps_time(time.time()+18*3600)
1460+
gwk, gms = mp_util.get_gps_time(time.time())
14531461
self.logf.write('GPS', "QBIHLLff", "TimeUS,Status,GMS,GWk,Lat,Lng,Alt,Spd",
14541462
self.micros64(), m.fix_type, gms, gwk, m.lat, m.lon, m.alt*0.001, m.vel*0.01)
14551463
if mtype == 'ATTITUDE':

Diff for: MAVProxy/modules/mavproxy_SIYI/camera_view.py

+4-4
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,6 @@ def __init__(self, siyi, rtsp_url, filename, res, thermal=False, fps=10, video_i
2626
self.res = res
2727
self.rtsp_url = rtsp_url
2828
self.filename = filename
29-
self.mode = "Flag"
3029
self.last_frame_t = time.time()
3130
self.fps = fps
3231
self.frame_counter = -1
@@ -140,6 +139,7 @@ def set_title(self, title):
140139
"""set image title"""
141140
if self.im is None:
142141
return
142+
title += " (mode %s)" % self.siyi.click_mode
143143
self.im.set_title(title)
144144

145145
def get_pixel_temp(self, event):
@@ -213,8 +213,8 @@ def check_events(self):
213213
self.im.set_colormap(event.returnkey[9:])
214214
self.siyi.cmd_palette(["WhiteHot"])
215215
elif event.returnkey.startswith("Mode:"):
216-
self.mode = event.returnkey[5:]
217-
print("ViewMode: %s" % self.mode)
216+
self.siyi.click_mode = event.returnkey[5:]
217+
print("ViewMode: %s" % self.siyi.click_mode)
218218
elif event.returnkey.startswith("Marker:"):
219219
self.siyi.handle_marker(event.returnkey[7:])
220220
elif event.returnkey.startswith("Lens:") and self.siyi is not None:
@@ -261,7 +261,7 @@ def check_events(self):
261261
elif event.controlDown:
262262
self.siyi.end_tracking()
263263
else:
264-
self.siyi.camera_click(self.mode, latlonalt)
264+
self.siyi.camera_click(self.siyi.click_mode, latlonalt)
265265

266266
if __name__ == '__main__':
267267
from optparse import OptionParser

Diff for: MAVProxy/modules/mavproxy_SIYI/raw_thermal.py

+10-7
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,6 @@ def __init__(self, siyi, res):
3232
self.cap = None
3333
self.res = res
3434
self.FOV = 24.2
35-
self.mode = "Flag"
3635
self.last_frame_t = time.time()
3736
self.logdir = 'thermal'
3837
self.should_exit = False
@@ -81,6 +80,8 @@ def __init__(self, siyi, res):
8180
def fetch_loop(self):
8281
'''main thread'''
8382
while True:
83+
if self.im is None:
84+
break
8485
time.sleep(0.25)
8586
ret = self.fetch_latest()
8687
if ret is None:
@@ -159,8 +160,7 @@ def display_image(self, fname, data):
159160
self.tmin = minv - C_TO_KELVIN
160161
self.tmax = maxv - C_TO_KELVIN
161162
if maxv <= minv:
162-
print("Bad range")
163-
return
163+
maxv = minv + 1
164164

165165
self.last_data = a
166166

@@ -174,6 +174,8 @@ def display_image(self, fname, data):
174174
a = a.reshape(512, 640)
175175

176176
a = cv2.cvtColor(a, cv2.COLOR_GRAY2RGB)
177+
if self.im is None:
178+
return
177179
self.im.set_image(a)
178180
self.image_count += 1
179181
self.update_title()
@@ -277,7 +279,8 @@ def end_tracking(self):
277279

278280
def update_title(self):
279281
"""update thermal view title"""
280-
self.set_title("RawThermal(%u): (%.1fC to %.1fC) %.1fC" % (self.image_count, self.tmin, self.tmax, self.mouse_temp))
282+
self.set_title("RawThermal(%u): (%.1fC to %.1fC) %.1fC (mode %s)" % (self.image_count, self.tmin, self.tmax,
283+
self.mouse_temp, self.siyi.click_mode))
281284

282285
def xy_to_latlon(self, x, y):
283286
'''convert x,y pixel coordinates to a latlon tuple'''
@@ -302,8 +305,8 @@ def check_events(self):
302305
for event in self.im.events():
303306
if isinstance(event, MPMenuItem):
304307
if event.returnkey.startswith("Mode:"):
305-
self.mode = event.returnkey[5:]
306-
print("ViewMode: %s" % self.mode)
308+
self.siyi.click_mode = event.returnkey[5:]
309+
print("ViewMode: %s" % self.siyi.click_mode)
307310
elif event.returnkey.startswith("Marker:"):
308311
self.siyi.handle_marker(event.returnkey[7:])
309312
elif event.returnkey == "fitWindow":
@@ -343,7 +346,7 @@ def check_events(self):
343346
elif event.controlDown:
344347
self.siyi.end_tracking()
345348
else:
346-
self.siyi.camera_click(self.mode, latlonalt)
349+
self.siyi.camera_click(self.siyi.click_mode, latlonalt)
347350

348351
if __name__ == '__main__':
349352
from optparse import OptionParser

0 commit comments

Comments
 (0)