Fixed merge conflict on left_screen.

This commit is contained in:
2018-03-15 11:14:00 -07:00
4 changed files with 217 additions and 75 deletions

View File

@@ -349,6 +349,7 @@ class OverlayImage(object):
self.height = height self.height = height
self.big_image = None self.big_image = None
self.display_image = None self.display_image = None
self.indicator = None
self.helper = MapHelper.MapHelper() self.helper = MapHelper.MapHelper()
x, y = self._get_cartesian(latitude, longitude) x, y = self._get_cartesian(latitude, longitude)
@@ -370,6 +371,7 @@ class OverlayImage(object):
True) True)
self.display_image = self.helper.new_image(self.width, self.height, self.display_image = self.helper.new_image(self.width, self.height,
True) True)
self.generate_dot_and_hat()
def _get_cartesian(self, lat, lon): def _get_cartesian(self, lat, lon):
""" """
@@ -403,30 +405,38 @@ class OverlayImage(object):
return int(x), int(y) return int(x), int(y)
def update_new_location(self, latitude, longitude, compass): def update_new_location(self, latitude, longitude,
self._draw_rover(latitude, longitude, 10, compass) compass, navigation_list, landmark_list):
size = 5
draw = PIL.ImageDraw.Draw(self.big_image)
for element in navigation_list:
x, y = self._get_cartesian(element[1], element[2])
draw.ellipsis((x-size, y-size, x+size, y+size), fill="red")
for element in navigation_list:
x, y = self._get_cartesian(element[1], element[2])
draw.ellipsis((x-size, y-size, x+size, y+size), fill="blue")
self._draw_rover(latitude, longitude, compass)
self.update() self.update()
return self.display_image return self.display_image
def _draw_rover(self, lat, lon, size, scaler): def generate_dot_and_hat(self):
self.indicator = self.helper.new_image(100, 100, True)
draw = PIL.ImageDraw.Draw(self.indicator)
draw.ellipse((50-12, 50-12, 50+12, 50+12), fill="red")
draw.line((25, 40, 50, 12), fill="red", width=7)
draw.line((50, 12, 75, 40), fill="red", width=7)
def _draw_rover(self, lat, lon, angle=0):
x, y = self._get_cartesian(lat, lon) x, y = self._get_cartesian(lat, lon)
draw = PIL.ImageDraw.Draw(self.big_image) # Center of the circle on the indicator is (12.5, 37.5)
draw.ellipse((x-size, y-size, x+size, y+size), fill="red") x = x - 50
point_1 = tuple((math.cos(x-2*size * scaler), math.sin(y * scaler))) y = y - 50
point_2 = tuple((math.cos(x * scaler), math.sin(y+2*size * scaler))) rotated = self.indicator.copy()
point_3 = (math.cos(x+2*size * scaler), math.sin(y * scaler)) rotated = rotated.rotate(angle, expand=True)
draw.line( self.display_image.paste(self.indicator, (x, y))
(point_1, # self.display_image.save("Something.png")
point_2),
fill="red",
width=600)
draw.line(
(point_2,
point_3),
fill="red",
width=600)
self.display_image.save("Something.png")
def update(self): def update(self):
self.display_image.paste(self.big_image, (-self.left_x, -self.upper_y)) self.display_image.paste(self.big_image, (-self.left_x, -self.upper_y))

View File

@@ -21,6 +21,7 @@ import RoverMap
class RoverMapCoordinator(QtCore.QThread): class RoverMapCoordinator(QtCore.QThread):
pixmap_ready_signal = QtCore.pyqtSignal() pixmap_ready_signal = QtCore.pyqtSignal()
change_waypoint_signal = QtCore.pyqtSignal()
def __init__(self, shared_objects): def __init__(self, shared_objects):
super(RoverMapCoordinator, self).__init__() super(RoverMapCoordinator, self).__init__()
@@ -28,6 +29,8 @@ class RoverMapCoordinator(QtCore.QThread):
self.shared_objects = shared_objects self.shared_objects = shared_objects
self.left_screen = self.shared_objects["screens"]["left_screen"] self.left_screen = self.shared_objects["screens"]["left_screen"]
self.mapping_label = self.left_screen.mapping_label self.mapping_label = self.left_screen.mapping_label
self.navigation_label = self.left_screen.tableWidget
self.landmark_label = self.left_screen.tableWidget_2
self.setings = QtCore.QSettings() self.setings = QtCore.QSettings()
@@ -84,9 +87,18 @@ class RoverMapCoordinator(QtCore.QThread):
def _get_map_image(self): def _get_map_image(self):
while self.map_image is None: while self.map_image is None:
self.map_image = self.google_maps_object.display_image self.map_image = self.google_maps_object.display_image
self.overlay_image_object.update_new_location(44.567161,-123.278432, .7) # self.overlay_image_object.update_new_location(44.567161,
self.map_image.paste(self.overlay_image_object.display_image, (0,0), self.overlay_image_object.display_image) # -123.278432,
# self.map_image = Image.alpha_composite(self.google_maps_object.display_image, self.overlay_image_object.display_image) # .7,
# [],
# [])
self.update_overlay()
self.map_image.paste(self.overlay_image_object.display_image,
(0, 0),
self.overlay_image_object.display_image)
# self.map_image = Image.alpha_composite(
# self.google_maps_object.display_image,
# self.overlay_image_object.display_image)
# get overlay here # get overlay here
qim = ImageQt(self.map_image) qim = ImageQt(self.map_image)
self.map_pixmap = QtGui.QPixmap.fromImage(qim) self.map_pixmap = QtGui.QPixmap.fromImage(qim)
@@ -94,6 +106,7 @@ class RoverMapCoordinator(QtCore.QThread):
def connect_signals_and_slots(self): def connect_signals_and_slots(self):
self.pixmap_ready_signal.connect(self.pixmap_ready__slot) self.pixmap_ready_signal.connect(self.pixmap_ready__slot)
self.change_waypoint_signal.connect(self.update_overlay)
def on_kill_threads_requested_slot(self): def on_kill_threads_requested_slot(self):
self.run_thread_flag = False self.run_thread_flag = False
@@ -106,3 +119,23 @@ class RoverMapCoordinator(QtCore.QThread):
def pixmap_ready__slot(self): def pixmap_ready__slot(self):
self.mapping_label.setPixmap(self.map_pixmap) self.mapping_label.setPixmap(self.map_pixmap)
def _get_table_elements(self, UI_element):
temp_list = []
count = UI_element.rowCount()
for row in range(0, count):
num = UI_element.item(row, 0)
lat = UI_element.cellWidget(row, 1)
lng = UI_element.cellWidget(row, 2)
temp_tuple = (num, lat, lng)
temp_list.append(temp_tuple)
return temp_list
def update_overlay(self):
navigation_list = self._get_table_elements(self.navigation_label)
landmark_list = self._get_table_elements(self.landmark_label)
self.overlay_image_object.update_new_location(self.latitude,
self.longitude,
70,
navigation_list,
landmark_list)

View File

@@ -17,8 +17,29 @@ MISC_TOPIC_NAME = "/rover_status/misc_status"
class SensorCore(QtCore.QThread): class SensorCore(QtCore.QThread):
# ########## create signals for slots ##########
jetson_cpu_update_ready__signal = QtCore.pyqtSignal(str) jetson_cpu_update_ready__signal = QtCore.pyqtSignal(str)
jetson_cpu_stylesheet_change_ready__signal = QtCore.pyqtSignal(str) jetson_cpu_stylesheet_change_ready__signal = QtCore.pyqtSignal(str)
jetson_emmc_update_ready__signal = QtCore.pyqtSignal(str)
jetson_emmc_stylesheet_change_ready__signal = QtCore.pyqtSignal(str)
jetson_gpu_temp_update_ready__signal = QtCore.pyqtSignal(str)
jetson_gpu_temp_stylesheet_change_ready__signal = QtCore.pyqtSignal(str)
jetson_ram_update_ready__signal = QtCore.pyqtSignal(str)
jetson_ram_stylesheet_change_ready__signal = QtCore.pyqtSignal(str)
bogie_connection_1_stylesheet_change_ready__signal = QtCore.pyqtSignal(str)
bogie_connection_2_stylesheet_change_ready__signal = QtCore.pyqtSignal(str)
bogie_connection_3_stylesheet_change_ready__signal = QtCore.pyqtSignal(str)
camera_zed_stylesheet_change_ready__signal = QtCore.pyqtSignal(str)
camera_under_stylesheet_change_ready__signal = QtCore.pyqtSignal(str)
camera_chassis_stylesheet_change_ready__signal = QtCore.pyqtSignal(str)
camera_main_stylesheet_change_ready__signal = QtCore.pyqtSignal(str)
gps_stylesheet_change_ready__signal = QtCore.pyqtSignal(str)
frsky_stylesheet_change_ready__signal = QtCore.pyqtSignal(str)
def __init__(self, shared_objects): def __init__(self, shared_objects):
super(SensorCore, self).__init__() super(SensorCore, self).__init__()
@@ -32,6 +53,7 @@ class SensorCore(QtCore.QThread):
self.cpu_read = self.screen_main_window.lineEdit # type: QtWidgets.QLabel self.cpu_read = self.screen_main_window.lineEdit # type: QtWidgets.QLabel
self.ram_read = self.screen_main_window.lineEdit_2 # type: QtWidgets.QLabel self.ram_read = self.screen_main_window.lineEdit_2 # type: QtWidgets.QLabel
# ########## set vars to gui elements
self.rover_conn = self.screen_main_window.rover # type: QtWidgets.QLabel self.rover_conn = self.screen_main_window.rover # type: QtWidgets.QLabel
self.frsky = self.screen_main_window.frsky # type: QtWidgets.QLabel self.frsky = self.screen_main_window.frsky # type: QtWidgets.QLabel
self.nav_mouse = self.screen_main_window.nav_mouse # type: QtWidgets.QLabel self.nav_mouse = self.screen_main_window.nav_mouse # type: QtWidgets.QLabel
@@ -47,8 +69,10 @@ class SensorCore(QtCore.QThread):
self.clock = self.screen_main_window.clock # type: QtWidgets.QLCDNumber self.clock = self.screen_main_window.clock # type: QtWidgets.QLCDNumber
self.cpu = self.screen_main_window.cpu # type: QtWidgets.QLabel self.cpu = self.screen_main_window.cpu # type: QtWidgets.QLabel
self.ram = self.screen_main_window.ram # type: QtWidgets.QLabel self.ram = self.screen_main_window.ram # type: QtWidgets.QLabel
self.gpu_temp = self.screen_main_window.gpu_temp # type: QtWidgets.QLabel
self.emmc = self.screen_main_window.emmc # type: QtWidgets.QLabel
# Subscription examples on pulling data from system_statuses_node.py # ########## subscriptions pulling data from system_statuses_node.py ##########
self.camera_status = rospy.Subscriber(CAMERA_TOPIC_NAME, CameraStatuses, self.__camera_callback) self.camera_status = rospy.Subscriber(CAMERA_TOPIC_NAME, CameraStatuses, self.__camera_callback)
self.bogie_status = rospy.Subscriber(BOGIE_TOPIC_NAME, BogieStatuses, self.__bogie_callback) self.bogie_status = rospy.Subscriber(BOGIE_TOPIC_NAME, BogieStatuses, self.__bogie_callback)
self.frsky_status = rospy.Subscriber(FRSKY_TOPIC_NAME, FrSkyStatus, self.__frsky_callback) self.frsky_status = rospy.Subscriber(FRSKY_TOPIC_NAME, FrSkyStatus, self.__frsky_callback)
@@ -72,32 +96,40 @@ class SensorCore(QtCore.QThread):
self.camera_msg.camera_main_navigation = data.camera_main_navigation self.camera_msg.camera_main_navigation = data.camera_main_navigation
if self.camera_msg.camera_zed is False: if self.camera_msg.camera_zed is False:
self.zed.setStyleSheet("background-color: red;") # self.zed.setStyleSheet("background-color: red;")
self.camera_zed_stylesheet_change_ready__signal.emit("background-color: darkred;")
else: else:
self.zed.setStyleSheet("background-color: darkgreen;") # self.zed.setStyleSheet("background-color: darkgreen;")
self.camera_zed_stylesheet_change_ready__signal.emit("background-color: darkgreen;")
if self.camera_msg.camera_undercarriage is False: if self.camera_msg.camera_undercarriage is False:
self.under_cam.setStyleSheet("background-color: red;") # self.under_cam.setStyleSheet("background-color: darkred;")
self.camera_under_stylesheet_change_ready__signal.emit("background-color: darkred;")
else: else:
self.under_cam.setStyleSheet("background-color: darkgreen;") # self.under_cam.setStyleSheet("background-color: darkgreen;")
self.camera_under_stylesheet_change_ready__signal.emit("background-color: darkgreen;")
if self.camera_msg.camera_chassis is False: if self.camera_msg.camera_chassis is False:
self.chassis_cam.setStyleSheet("background-color: red;") # self.chassis_cam.setStyleSheet("background-color: darkred;")
self.camera_chassis_stylesheet_change_ready__signal.emit("background-color: darkred;")
else: else:
self.chassis_cam.setStyleSheet("background-color: darkgreen;") # self.chassis_cam.setStyleSheet("background-color: darkgreen;")
self.camera_chassis_stylesheet_change_ready__signal.emit("background-color: darkgreen;")
if self.camera_msg.camera_main_navigation is False: if self.camera_msg.camera_main_navigation is False:
self.main_cam.setStyleSheet("background-color: red;") # self.main_cam.setStyleSheet("background-color: darkred;")
self.camera_main_stylesheet_change_ready__signal.emit("background-color: darkred;")
else: else:
self.main_cam.setStyleSheet("background-color: darkgreen;") # self.main_cam.setStyleSheet("background-color: darkgreen;")
self.camera_main_stylesheet_change_ready__signal.emit("background-color: darkgreen;")
def __frsky_callback(self, data): def __frsky_callback(self, data):
self.FrSky_msg.FrSky_controller_connection_status = data.FrSky_controller_connection_status self.FrSky_msg.FrSky_controller_connection_status = data.FrSky_controller_connection_status
if self.FrSky_msg.FrSky_controller_connection_status is False: if self.FrSky_msg.FrSky_controller_connection_status is False:
self.frsky.setStyleSheet("background-color: red;") self.frsky_stylesheet_change_ready__signal.emit("background-color: darkred;")
else: else:
self.frsky.setStyleSheet("background-color: darkgreen;") self.frsky_stylesheet_change_ready__signal.emit("background-color: darkgreen;")
def __bogie_callback(self, data): def __bogie_callback(self, data):
self.bogie_msg.bogie_connection_1 = data.bogie_connection_1 self.bogie_msg.bogie_connection_1 = data.bogie_connection_1
@@ -105,19 +137,25 @@ class SensorCore(QtCore.QThread):
self.bogie_msg.bogie_connection_3 = data.bogie_connection_3 self.bogie_msg.bogie_connection_3 = data.bogie_connection_3
if self.bogie_msg.bogie_connection_1 is False: if self.bogie_msg.bogie_connection_1 is False:
self.bogie_right.setStyleSheet("background-color: red;") # self.bogie_right.setStyleSheet("background-color: darkred;")
self.bogie_connection_1_stylesheet_change_ready__signal.emit("background-color: darkred;")
else: else:
self.bogie_right.setStyleSheet("background-color: darkgreen;") # self.bogie_right.setStyleSheet("background-color: darkgreen;")
self.bogie_connection_1_stylesheet_change_ready__signal.emit("background-color: darkgreen;")
if self.bogie_msg.bogie_connection_2 is False: if self.bogie_msg.bogie_connection_2 is False:
self.bogie_left.setStyleSheet("background-color: red;") # self.bogie_left.setStyleSheet("background-color: darkred;")
self.bogie_connection_2_stylesheet_change_ready__signal.emit("background-color: darkred;")
else: else:
self.bogie_left.setStyleSheet("background-color: darkgreen;") # self.bogie_left.setStyleSheet("background-color: darkgreen;")
self.bogie_connection_2_stylesheet_change_ready__signal.emit("background-color: darkgreen;")
if self.bogie_msg.bogie_connection_3 is False: if self.bogie_msg.bogie_connection_3 is False:
self.bogie_rear.setStyleSheet("background-color: red;") # self.bogie_rear.setStyleSheet("background-color: darkred;")
self.bogie_connection_3_stylesheet_change_ready__signal.emit("background-color: darkred;")
else: else:
self.bogie_rear.setStyleSheet("background-color: darkgreen;") # self.bogie_rear.setStyleSheet("background-color: darkgreen;")
self.bogie_connection_3_stylesheet_change_ready__signal.emit("background-color: darkgreen;")
def __jetson_callback(self, data): def __jetson_callback(self, data):
self.jetson_msg.jetson_CPU = data.jetson_CPU self.jetson_msg.jetson_CPU = data.jetson_CPU
@@ -128,35 +166,48 @@ class SensorCore(QtCore.QThread):
if self.jetson_msg.jetson_CPU > 79: if self.jetson_msg.jetson_CPU > 79:
self.jetson_cpu_stylesheet_change_ready__signal.emit("background-color: orange;") self.jetson_cpu_stylesheet_change_ready__signal.emit("background-color: orange;")
# self.cpu.setStyleSheet("background-color: orange;")
elif self.jetson_msg.jetson_CPU > 89: elif self.jetson_msg.jetson_CPU > 89:
self.jetson_cpu_stylesheet_change_ready__signal.emit("background-color: red;") self.jetson_cpu_stylesheet_change_ready__signal.emit("background-color: darkred;")
# self.cpu.setStyleSheet("background-color: red;")
else: else:
self.jetson_cpu_stylesheet_change_ready__signal.emit("background-color: darkgreen;") self.jetson_cpu_stylesheet_change_ready__signal.emit("background-color: darkgreen;")
# self.cpu.setStyleSheet("background-color: darkgreen;")
# self.jetson_msg.jetson_RAM = data.jetson_RAM self.jetson_ram_update_ready__signal.emit(str(self.jetson_msg.jetson_RAM))
# self.ram.setText(str(self.jetson_msg.jetson_RAM))
# if self.jetson_msg.jetson_RAM > 79: if self.jetson_msg.jetson_RAM > 79:
# self.ram.setStyleSheet("background-color: orange;") self.jetson_ram_stylesheet_change_ready__signal.emit("background-color: orange;")
# elif self.jetson_msg.jetson_RAM > 89: elif self.jetson_msg.jetson_RAM > 89:
# self.ram.setStyleSheet("background-color: red;") self.jetson_ram_stylesheet_change_ready__signal.emit("background-color: darkred;")
# else: else:
# self.ram.setStyleSheet("background-color: darkgreen;") self.jetson_ram_stylesheet_change_ready__signal.emit("background-color: darkgreen;")
#
# self.jetson_msg.jetson_EMMC = data.jetson_EMMC self.jetson_gpu_temp_update_ready__signal.emit(str(self.jetson_msg.jetson_GPU_temp))
# self.jetson_msg.jetson_NVME_SSD = data.jetson_NVME_SSD
#rospy.loginfo(self.jetson_msg) if self.jetson_msg.jetson_GPU_temp > 64:
self.jetson_gpu_temp_stylesheet_change_ready__signal.emit("background-color: orange;")
elif self.jetson_msg.jetson_GPU_temp > 79:
self.jetson_gpu_temp_stylesheet_change_ready__signal.emit("background-color: darkred;")
else:
self.jetson_gpu_temp_stylesheet_change_ready__signal.emit("background-color: darkgreen;")
self.jetson_emmc_update_ready__signal.emit(str(self.jetson_msg.jetson_EMMC))
if self.jetson_msg.jetson_EMMC > 79:
self.jetson_emmc_stylesheet_change_ready__signal.emit("background-color: orange;")
elif self.jetson_msg.jetson_EMMC > 89:
self.jetson_emmc_stylesheet_change_ready__signal.emit("background-color: darkred;")
else:
self.jetson_emmc_stylesheet_change_ready__signal.emit("background-color: darkgreen")
def __gps_callback(self, data): def __gps_callback(self, data):
self.GPS_msg.UTC_GPS_time = data.UTC_GPS_time self.GPS_msg.UTC_GPS_time = data.UTC_GPS_time
self.GPS_msg.GPS_connection_status = data.GPS_connection_status self.GPS_msg.GPS_connection_status = data.GPS_connection_status
if self.GPS_msg.GPS_connection_status is False: if self.GPS_msg.GPS_connection_status is False:
self.gps.setStyleSheet("background-color: red") # self.gps.setStyleSheet("background-color: darkred")
self.gps_stylesheet_change_ready__signal.emit("background-color: darkred;")
else: else:
self.gps.setStyleSheet("background-color: darkgreen;") # self.gps.setStyleSheet("background-color: darkgreen;")
self.gps_stylesheet_change_ready__signal.emit("background-color: darkgreen;")
def __misc_callback(self, data): def __misc_callback(self, data):
self.misc_msg.arm_connection_status = data.arm_connection_status self.misc_msg.arm_connection_status = data.arm_connection_status
@@ -177,6 +228,21 @@ class SensorCore(QtCore.QThread):
def connect_signals_and_slots(self): def connect_signals_and_slots(self):
self.jetson_cpu_update_ready__signal.connect(self.cpu.setText) self.jetson_cpu_update_ready__signal.connect(self.cpu.setText)
self.jetson_cpu_stylesheet_change_ready__signal.connect(self.cpu.setStyleSheet) self.jetson_cpu_stylesheet_change_ready__signal.connect(self.cpu.setStyleSheet)
self.jetson_ram_update_ready__signal.connect(self.ram.setText)
self.jetson_ram_stylesheet_change_ready__signal(self.ram.setStyleSheet)
self.jetson_emmc_update_ready__signal.connect(self.emmc.setText)
self.jetson_emmc_stylesheet_change_ready__signal.connect(self.emmc.setStyleSheet)
self.jetson_gpu_temp_update_ready__signal.connect(self.gpu_temp.setText)
self.jetson_gpu_temp_stylesheet_change_ready__signal(self.gpu_temp.setStyleSheet)
self.bogie_connection_1_stylesheet_change_ready__signal.connect(self.bogie_right.setStyleSheet)
self.bogie_connection_2_stylesheet_change_ready__signal.connect(self.bogie_left.setStyleSheet)
self.bogie_connection_3_stylesheet_change_ready__signal.connect(self.bogie_rear.setStyleSheet)
self.camera_zed_stylesheet_change_ready__signal.connect(self.zed.setStyleSheet)
self.camera_under_stylesheet_change_ready__signal.connect(self.under_cam.setStyleSheet)
self.camera_chassis_stylesheet_change_ready__signal.connect(self.chassis_cam.setStyleSheet)
self.camera_main_stylesheet_change_ready__signal.connect(self.main_cam.setStyleSheet)
self.gps_stylesheet_change_ready__signal.connect(self.gps.setStyleSheet)
self.frsky_stylesheet_change_ready__signal.connect(self.frsky.setStyleSheet)
def setup_signals(self, start_signal, signals_and_slots_signal, kill_signal): def setup_signals(self, start_signal, signals_and_slots_signal, kill_signal):
start_signal.connect(self.start) start_signal.connect(self.start)

View File

@@ -80,17 +80,27 @@
<number>0</number> <number>0</number>
</property> </property>
<item row="1" column="4"> <item row="1" column="4">
<widget class="QLabel" name="label_4"> <widget class="QLabel" name="emmc">
<property name="styleSheet"> <property name="styleSheet">
<string notr="true">background-color: darkgreen;</string> <string notr="true">background-color: darkred;</string>
</property> </property>
<property name="text"> <property name="text">
<string>placeholder</string> <string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p align=&quot;center&quot;&gt;&lt;span style=&quot; font-weight:600;&quot;&gt;EMMC&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="4" column="5"> <item row="1" column="5">
<widget class="QLabel" name="under_cam"> <widget class="QLabel" name="gpu_temp">
<property name="styleSheet">
<string notr="true">background-color: darkred;</string>
</property>
<property name="text">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p align=&quot;center&quot;&gt;&lt;span style=&quot; font-weight:600;&quot;&gt;GPU &lt;/span&gt;&lt;span style=&quot; font-weight:600;&quot;&gt;Temp&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
</widget>
</item>
<item row="3" column="2">
<widget class="QLabel" name="left_bogie">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred"> <sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch> <horstretch>0</horstretch>
@@ -123,7 +133,7 @@
</font> </font>
</property> </property>
<property name="styleSheet"> <property name="styleSheet">
<string notr="true">background-color:darkgreen;</string> <string notr="true">background-color:darkred;</string>
</property> </property>
<property name="text"> <property name="text">
<string>Undercarriage Camera <string>Undercarriage Camera
@@ -175,7 +185,7 @@ Connected</string>
<bool>false</bool> <bool>false</bool>
</property> </property>
<property name="styleSheet"> <property name="styleSheet">
<string notr="true">background-color:darkgreen;</string> <string notr="true">background-color:darkred;</string>
</property> </property>
<property name="text"> <property name="text">
<string>Right Bogie <string>Right Bogie
@@ -237,7 +247,7 @@ Connected</string>
</font> </font>
</property> </property>
<property name="styleSheet"> <property name="styleSheet">
<string notr="true">background-color:darkgreen;</string> <string notr="true">background-color:darkred;</string>
</property> </property>
<property name="frameShape"> <property name="frameShape">
<enum>QFrame::NoFrame</enum> <enum>QFrame::NoFrame</enum>
@@ -282,7 +292,7 @@ Connected</string>
<bool>false</bool> <bool>false</bool>
</property> </property>
<property name="styleSheet"> <property name="styleSheet">
<string notr="true">background-color:darkgreen;</string> <string notr="true">background-color:darkred;</string>
</property> </property>
<property name="text"> <property name="text">
<string>GPS <string>GPS
@@ -365,7 +375,7 @@ Fix</string>
</font> </font>
</property> </property>
<property name="styleSheet"> <property name="styleSheet">
<string notr="true">background-color:darkgreen;</string> <string notr="true">background-color:darkred;</string>
</property> </property>
<property name="frameShape"> <property name="frameShape">
<enum>QFrame::NoFrame</enum> <enum>QFrame::NoFrame</enum>
@@ -407,7 +417,7 @@ Connected</string>
</font> </font>
</property> </property>
<property name="styleSheet"> <property name="styleSheet">
<string notr="true">background-color:darkgreen;</string> <string notr="true">background-color:darkred;</string>
</property> </property>
<property name="frameShape"> <property name="frameShape">
<enum>QFrame::NoFrame</enum> <enum>QFrame::NoFrame</enum>
@@ -452,7 +462,7 @@ Connected</string>
<bool>false</bool> <bool>false</bool>
</property> </property>
<property name="styleSheet"> <property name="styleSheet">
<string notr="true">background-color:darkgreen;</string> <string notr="true">background-color:darkred;</string>
</property> </property>
<property name="text"> <property name="text">
<string>3D Nav Mouse <string>3D Nav Mouse
@@ -491,7 +501,7 @@ Connected</string>
</font> </font>
</property> </property>
<property name="styleSheet"> <property name="styleSheet">
<string notr="true">background-color:darkgreen;</string> <string notr="true">background-color:darkred;</string>
</property> </property>
<property name="frameShape"> <property name="frameShape">
<enum>QFrame::NoFrame</enum> <enum>QFrame::NoFrame</enum>
@@ -505,8 +515,31 @@ Connected</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="4" column="4"> <item row="0" column="5">
<widget class="QLabel" name="chassis_cam"> <widget class="QLCDNumber" name="timer"/>
</item>
<item row="1" column="2">
<widget class="QLabel" name="ram">
<property name="styleSheet">
<string notr="true">background-color: darkred;</string>
</property>
<property name="text">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p align=&quot;center&quot;&gt;&lt;span style=&quot; font-weight:600;&quot;&gt;RAM&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QLabel" name="cpu">
<property name="styleSheet">
<string notr="true">background-color: darkred;</string>
</property>
<property name="text">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p align=&quot;center&quot;&gt;&lt;span style=&quot; font-weight:600;&quot;&gt;CPU %&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QLabel" name="rover">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred"> <sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch> <horstretch>0</horstretch>
@@ -539,7 +572,7 @@ Connected</string>
</font> </font>
</property> </property>
<property name="styleSheet"> <property name="styleSheet">
<string notr="true">background-color:darkgreen;</string> <string notr="true">background-color:darkred;</string>
</property> </property>
<property name="text"> <property name="text">
<string>Chassis Camera <string>Chassis Camera
@@ -584,7 +617,7 @@ Connected</string>
</font> </font>
</property> </property>
<property name="styleSheet"> <property name="styleSheet">
<string notr="true">background-color:darkgreen;</string> <string notr="true">background-color:darkred;</string>
</property> </property>
<property name="text"> <property name="text">
<string>FrSky <string>FrSky
@@ -998,7 +1031,7 @@ Connected</string>
</widget> </widget>
</item> </item>
<item> <item>
<layout class="QHBoxLayout" name="horizontalLayout_2"> <layout class="QHBoxLayout" name="horizontalLayout_2">Connection
<property name="spacing"> <property name="spacing">
<number>0</number> <number>0</number>
</property> </property>