Skip to content

Commit

Permalink
SIYI: display click mode in window titles
Browse files Browse the repository at this point in the history
  • Loading branch information
tridge authored and peterbarker committed Apr 10, 2024
1 parent a6f0e8c commit 6290943
Show file tree
Hide file tree
Showing 3 changed files with 27 additions and 16 deletions.
18 changes: 13 additions & 5 deletions MAVProxy/modules/mavproxy_SIYI/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -364,6 +364,7 @@ def __init__(self, mpstate):
self.last_armed = False
self.getconfig_pending = False
self.last_getconfig = time.time()
self.click_mode = "Flag"

if mp_util.has_wxpython:
menu = MPMenuSubMenu('SIYI',
Expand Down Expand Up @@ -1002,12 +1003,13 @@ def parse_packet(self, pkt):
self.send_named_float('TMAX', self.tmax)
self.last_temp_t = time.time()
frame_counter = -1 if self.thermal_view is None else self.thermal_view.frame_counter
self.logf.write('SITR', 'QffHHHHi', 'TimeUS,TMin,TMax,TMinX,TMinY,TMaxX,TMaxY,FC',
self.logf.write('SITR', 'QffHHHHiI', 'TimeUS,TMin,TMax,TMinX,TMinY,TMaxX,TMaxY,FC,TCAP',
self.micros64(),
self.tmin, self.tmax,
self.tmin_x, self.tmin_y,
self.tmax_x, self.tmax_y,
frame_counter)
frame_counter,
self.thermal_capture_count)
if self.thermal_view is not None:
threshold = self.siyi_settings.threshold_temp
threshold_value = int(255*(threshold - self.tmin)/max(1,(self.tmax-self.tmin)))
Expand Down Expand Up @@ -1254,8 +1256,15 @@ def get_view_vector(self, x, y, FOV, aspect_ratio):
(roll,pitch,yaw) = (math.radians(fov_att[0]),math.radians(fov_att[1]),math.radians(fov_att[2]))
yaw += att.yaw
FOV_half = math.radians(0.5*FOV)
yaw += FOV_half*x

pitch = math.radians(-90)
aspect_ratio = 1.0

pitch -= y*FOV_half/aspect_ratio
if pitch < math.radians(-90):
yaw -= FOV_half*x
else:
yaw += FOV_half*x
m.from_euler(roll, pitch, yaw)
v = m * v
return v
Expand Down Expand Up @@ -1448,8 +1457,7 @@ def mavlink_packet(self, m):
self.armed_checks()

if mtype == 'GPS_RAW_INT':
# ?!? why off by 18 hours
gwk, gms = mp_util.get_gps_time(time.time()+18*3600)
gwk, gms = mp_util.get_gps_time(time.time())
self.logf.write('GPS', "QBIHLLff", "TimeUS,Status,GMS,GWk,Lat,Lng,Alt,Spd",
self.micros64(), m.fix_type, gms, gwk, m.lat, m.lon, m.alt*0.001, m.vel*0.01)
if mtype == 'ATTITUDE':
Expand Down
8 changes: 4 additions & 4 deletions MAVProxy/modules/mavproxy_SIYI/camera_view.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,6 @@ def __init__(self, siyi, rtsp_url, filename, res, thermal=False, fps=10, video_i
self.res = res
self.rtsp_url = rtsp_url
self.filename = filename
self.mode = "Flag"
self.last_frame_t = time.time()
self.fps = fps
self.frame_counter = -1
Expand Down Expand Up @@ -140,6 +139,7 @@ def set_title(self, title):
"""set image title"""
if self.im is None:
return
title += " (mode %s)" % self.siyi.click_mode
self.im.set_title(title)

def get_pixel_temp(self, event):
Expand Down Expand Up @@ -213,8 +213,8 @@ def check_events(self):
self.im.set_colormap(event.returnkey[9:])
self.siyi.cmd_palette(["WhiteHot"])
elif event.returnkey.startswith("Mode:"):
self.mode = event.returnkey[5:]
print("ViewMode: %s" % self.mode)
self.siyi.click_mode = event.returnkey[5:]
print("ViewMode: %s" % self.siyi.click_mode)
elif event.returnkey.startswith("Marker:"):
self.siyi.handle_marker(event.returnkey[7:])
elif event.returnkey.startswith("Lens:") and self.siyi is not None:
Expand Down Expand Up @@ -261,7 +261,7 @@ def check_events(self):
elif event.controlDown:
self.siyi.end_tracking()
else:
self.siyi.camera_click(self.mode, latlonalt)
self.siyi.camera_click(self.siyi.click_mode, latlonalt)

if __name__ == '__main__':
from optparse import OptionParser
Expand Down
17 changes: 10 additions & 7 deletions MAVProxy/modules/mavproxy_SIYI/raw_thermal.py
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,6 @@ def __init__(self, siyi, res):
self.cap = None
self.res = res
self.FOV = 24.2
self.mode = "Flag"
self.last_frame_t = time.time()
self.logdir = 'thermal'
self.should_exit = False
Expand Down Expand Up @@ -81,6 +80,8 @@ def __init__(self, siyi, res):
def fetch_loop(self):
'''main thread'''
while True:
if self.im is None:
break
time.sleep(0.25)
ret = self.fetch_latest()
if ret is None:
Expand Down Expand Up @@ -159,8 +160,7 @@ def display_image(self, fname, data):
self.tmin = minv - C_TO_KELVIN
self.tmax = maxv - C_TO_KELVIN
if maxv <= minv:
print("Bad range")
return
maxv = minv + 1

self.last_data = a

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

a = cv2.cvtColor(a, cv2.COLOR_GRAY2RGB)
if self.im is None:
return
self.im.set_image(a)
self.image_count += 1
self.update_title()
Expand Down Expand Up @@ -277,7 +279,8 @@ def end_tracking(self):

def update_title(self):
"""update thermal view title"""
self.set_title("RawThermal(%u): (%.1fC to %.1fC) %.1fC" % (self.image_count, self.tmin, self.tmax, self.mouse_temp))
self.set_title("RawThermal(%u): (%.1fC to %.1fC) %.1fC (mode %s)" % (self.image_count, self.tmin, self.tmax,
self.mouse_temp, self.siyi.click_mode))

def xy_to_latlon(self, x, y):
'''convert x,y pixel coordinates to a latlon tuple'''
Expand All @@ -302,8 +305,8 @@ def check_events(self):
for event in self.im.events():
if isinstance(event, MPMenuItem):
if event.returnkey.startswith("Mode:"):
self.mode = event.returnkey[5:]
print("ViewMode: %s" % self.mode)
self.siyi.click_mode = event.returnkey[5:]
print("ViewMode: %s" % self.siyi.click_mode)
elif event.returnkey.startswith("Marker:"):
self.siyi.handle_marker(event.returnkey[7:])
elif event.returnkey == "fitWindow":
Expand Down Expand Up @@ -343,7 +346,7 @@ def check_events(self):
elif event.controlDown:
self.siyi.end_tracking()
else:
self.siyi.camera_click(self.mode, latlonalt)
self.siyi.camera_click(self.siyi.click_mode, latlonalt)

if __name__ == '__main__':
from optparse import OptionParser
Expand Down

0 comments on commit 6290943

Please sign in to comment.