rename ui elements, fill in StatusCore

This commit is contained in:
Ken Steinfeldt
2018-03-13 11:52:49 -07:00
parent 10750a7a5f
commit 8d200cdfc7
2 changed files with 72 additions and 14 deletions

View File

@@ -17,6 +17,21 @@ 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
self.rover_conn = self.screen_main_window.rover # 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.joystick = self.screen_main_window.joystick # type: QtWidgets.QLabel
self.gps = self.screen_main_window.gps # type: QtWidgets.QLabel
self.zed = self.screen_main_window.zed # type: QtWidgets.QLabel
self.main_cam = self.screen_main_window.main_cam # type: QtWidgets.QLabel
self.chassis_cam = self.screen_main_window.chassis_cam # type: QtWidgets.QLabel
self.under_cam = self.screen_main_window.under_cam # type: QtWidgets.QLabel
self.bogie_right = self.screen_main_window.right_bogie # type: QtWidgets.QLabel
self.bogie_left = self.screen_main_window.left_bogie # type: QtWidgets.QLabel
self.bogie_rear = self.screen_main_window.rear_bogie # type: QtWidgets.QLabel
self.clock = self.screen_main_window.clock # type: QtWidgets.QLCDNumber
rospy.init_node('SensorCore') rospy.init_node('SensorCore')
# self.pub = rospy.Publisher('rover_statuses_chatter', RoverSysStatus, queue_size=10) # self.pub = rospy.Publisher('rover_statuses_chatter', RoverSysStatus, queue_size=10)
@@ -42,14 +57,53 @@ class SensorCore(QtCore.QThread):
self.camera_msg.camera_chassis = data.camera_chassis self.camera_msg.camera_chassis = data.camera_chassis
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:
self.zed.setStyleSheet("background-color: red;")
else:
self.zed.setStyleSheet("")
if self.camera_msg.camera_undercarriage is False:
self.under_cam.setStyleSheet("background-color: red;")
else:
self.under_cam.setStyleSheet("")
if self.camera_msg.camera_chassis is False:
self.chassis_cam.setStyleSheet("background-color: red;")
else:
self.chassis_cam.setStyleSheet("")
if self.camera_msg.camera_main_navigation is False:
self.main_cam.setStyleSheet("background-color: red;")
else:
self.main_cam.setStyleSheet("")
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:
self.frsky.setStyleSheet("background-color: red;")
else:
self.frsky.setStyleSheet("")
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
self.bogie_msg.bogie_connection_2 = data.bogie_connection_2 self.bogie_msg.bogie_connection_2 = data.bogie_connection_2
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:
self.bogie_right.setStyleSheet("background-color: red;")
else:
self.bogie_right.setStyleSheet("")
if self.bogie_msg.bogie_connection_2 is False:
self.bogie_left.setStyleSheet("background-color: red;")
else:
self.bogie_left.setStyleSheet("")
if self.bogie_msg.bogie_connection_3 is False:
self.bogie_rear.setStyleSheet("background-color: red;")
else:
self.bogie_rear.setStyleSheet("")
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
self.cpu_read.setText(str(self.jetson_msg.jetson_CPU)) self.cpu_read.setText(str(self.jetson_msg.jetson_CPU))
@@ -63,6 +117,11 @@ class SensorCore(QtCore.QThread):
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:
self.gps.setStyleSheet("background-color: red")
else:
self.gps.setStyleSheet("")
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
self.misc_msg.arm_end_effector_connection_statuses = data.arm_end_effector_connection_statuses self.misc_msg.arm_end_effector_connection_statuses = data.arm_end_effector_connection_statuses
@@ -81,7 +140,6 @@ class SensorCore(QtCore.QThread):
#print(self.jetson_msg.jetson_CPU) #print(self.jetson_msg.jetson_CPU)
rospy.spin() rospy.spin()
def on_kill_threads_requested__slot(self): def on_kill_threads_requested__slot(self):
self.not_abort = False self.not_abort = False

View File

@@ -98,7 +98,7 @@
<number>0</number> <number>0</number>
</property> </property>
<item row="2" column="2"> <item row="2" column="2">
<widget class="QLabel" name="label_9"> <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>
@@ -140,7 +140,7 @@ Connected</string>
</widget> </widget>
</item> </item>
<item row="1" column="2"> <item row="1" column="2">
<widget class="QLabel" name="label_4"> <widget class="QLabel" name="frsky">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred"> <sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch> <horstretch>0</horstretch>
@@ -185,7 +185,7 @@ Connected</string>
</widget> </widget>
</item> </item>
<item row="2" column="3"> <item row="2" column="3">
<widget class="QLabel" name="label_10"> <widget class="QLabel" name="right_bogie">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred"> <sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch> <horstretch>0</horstretch>
@@ -227,7 +227,7 @@ Connected</string>
</widget> </widget>
</item> </item>
<item row="2" column="0"> <item row="2" column="0">
<widget class="QLabel" name="label_8"> <widget class="QLabel" name="gps">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred"> <sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch> <horstretch>0</horstretch>
@@ -269,7 +269,7 @@ Fix</string>
</widget> </widget>
</item> </item>
<item row="1" column="4"> <item row="1" column="4">
<widget class="QLabel" name="label_19"> <widget class="QLabel" name="joystick">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred"> <sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch> <horstretch>0</horstretch>
@@ -311,7 +311,7 @@ Connected</string>
</widget> </widget>
</item> </item>
<item row="2" column="4"> <item row="2" column="4">
<widget class="QLabel" name="label_20"> <widget class="QLabel" name="rear_bogie">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred"> <sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch> <horstretch>0</horstretch>
@@ -353,7 +353,7 @@ Connected</string>
</widget> </widget>
</item> </item>
<item row="1" column="0"> <item row="1" column="0">
<widget class="QLabel" name="label"> <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>
@@ -395,7 +395,7 @@ Connected</string>
</widget> </widget>
</item> </item>
<item row="1" column="3"> <item row="1" column="3">
<widget class="QLabel" name="label_5"> <widget class="QLabel" name="nav_mouse">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred"> <sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch> <horstretch>0</horstretch>
@@ -437,7 +437,7 @@ Connected</string>
</widget> </widget>
</item> </item>
<item row="3" column="0"> <item row="3" column="0">
<widget class="QLabel" name="label_7"> <widget class="QLabel" name="zed">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred"> <sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch> <horstretch>0</horstretch>
@@ -478,7 +478,7 @@ Connected</string>
</widget> </widget>
</item> </item>
<item row="3" column="2"> <item row="3" column="2">
<widget class="QLabel" name="label_21"> <widget class="QLabel" name="main_cam">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred"> <sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch> <horstretch>0</horstretch>
@@ -520,7 +520,7 @@ Connected</string>
</widget> </widget>
</item> </item>
<item row="3" column="3"> <item row="3" column="3">
<widget class="QLabel" name="label_11"> <widget class="QLabel" name="chassis_cam">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred"> <sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch> <horstretch>0</horstretch>
@@ -565,7 +565,7 @@ Connected</string>
</widget> </widget>
</item> </item>
<item row="3" column="4"> <item row="3" column="4">
<widget class="QLabel" name="label_6"> <widget class="QLabel" name="under_cam">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred"> <sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch> <horstretch>0</horstretch>