Integrated system_statuses with main launcher.

This commit is contained in:
2018-03-13 18:43:09 -07:00
parent 595a51a0d7
commit a256c7d231
3 changed files with 174 additions and 199 deletions

View File

@@ -8,14 +8,23 @@ from std_msgs.msg import Empty
REQUEST_UPDATE_TOPIC = "/rover_status/update_requested"
class SensorCore(QtCore.QThread):
CAMERA_TOPIC_NAME = "/rover_status/camera_status"
BOGIE_TOPIC_NAME = "/rover_status/bogie_status"
FRSKY_TOPIC_NAME = "/rover_status/frsky_status"
GPS_TOPIC_NAME = "/rover_status/gps_status"
JETSON_TOPIC_NAME = "/rover_status/jetson_status"
MISC_TOPIC_NAME = "/rover_status/misc_status"
def __init__(self, screen):
class SensorCore(QtCore.QThread):
def __init__(self, shared_objects):
super(SensorCore, self).__init__()
self.not_abort = True
self.run_thread_flag = True
self.screen_main_window = screen
# ########## Reference to class init variables ##########
self.shared_objects = shared_objects
self.screen_main_window = self.shared_objects["screens"]["left_screen"]
self.cpu_read = self.screen_main_window.lineEdit # type: QtWidgets.QLabel
self.ram_read = self.screen_main_window.lineEdit_2 # type: QtWidgets.QLabel
@@ -36,18 +45,13 @@ class SensorCore(QtCore.QThread):
self.cpu = self.screen_main_window.cpu # type: QtWidgets.QLabel
self.ram = self.screen_main_window.ram # type: QtWidgets.QLabel
rospy.init_node('SensorCore')
# self.pub = rospy.Publisher('rover_statuses_chatter', RoverSysStatus, queue_size=10)
# Subscription examples on pulling data from system_statuses_node.py
rospy.Subscriber('camera_system_status_chatter', CameraStatuses, self.__camera_callback)
rospy.Subscriber('bogie_system_status_chatter', BogieStatuses, self.__bogie_callback)
rospy.Subscriber('FrSky_system_status_chatter', FrSkyStatus, self.__frsky_callback)
rospy.Subscriber('GPS_system_status_chatter', GPSInfo, self.__gps_callback)
rospy.Subscriber('jetson_system_status_chatter', JetsonInfo, self.__jetson_callback)
rospy.Subscriber('misc_system_status_chatter', MiscStatuses, self.__misc_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.frsky_status = rospy.Subscriber(FRSKY_TOPIC_NAME, FrSkyStatus, self.__frsky_callback)
self.gps_status = rospy.Subscriber(GPS_TOPIC_NAME, GPSInfo, self.__gps_callback)
self.jetson_status = rospy.Subscriber(JETSON_TOPIC_NAME, JetsonInfo, self.__jetson_callback)
self.misc_status = rospy.Subscriber(MISC_TOPIC_NAME, MiscStatuses, self.__misc_callback)
self.camera_msg = CameraStatuses()
self.bogie_msg = BogieStatuses()
@@ -56,9 +60,7 @@ class SensorCore(QtCore.QThread):
self.jetson_msg = JetsonInfo()
self.misc_msg = MiscStatuses()
self.req = rospy.Publisher(REQUEST_UPDATE_TOPIC, Empty, queue_size=1)
self.req.publish(Empty())
rospy.Publisher(REQUEST_UPDATE_TOPIC, Empty, queue_size=1).publish(Empty())
def __camera_callback(self, data):
self.camera_msg.camera_zed = data.camera_zed
@@ -161,22 +163,20 @@ class SensorCore(QtCore.QThread):
self.clock.display(temp)
def run(self):
rospy.Subscriber('camera_system_status_chatter', CameraStatuses, self.__camera_callback)
rospy.Subscriber('bogie_system_status_chatter', BogieStatuses, self.__bogie_callback)
rospy.Subscriber('FrSky_system_status_chatter', FrSkyStatus, self.__frsky_callback)
rospy.Subscriber('GPS_system_status_chatter', GPSInfo, self.__gps_callback)
rospy.Subscriber('jetson_system_status_chatter', JetsonInfo, self.__jetson_callback)
rospy.Subscriber('misc_system_status_chatter', MiscStatuses, self.__misc_callback)
#self.gui_element = self.jetson_msg.jetson_CPU
#print(self.jetson_msg.jetson_CPU)
rospy.spin()
def on_kill_threads_requested__slot(self):
self.not_abort = False
while self.run_thread_flag:
self.msleep(100)
def connect_signals_and_slots(self):
pass
def setup_signals(self, start_signal, signals_and_slots_signal, kill_signal):
start_signal.connect(self.start)
signals_and_slots_signal.connect(self.connect_signals_and_slots)
kill_signal.connect(self.on_kill_threads_requested__slot)
def on_kill_threads_requested__slot(self):
self.run_thread_flag = False
if __name__ == '__main__':
rover_statuses = SensorCore()

View File

@@ -39,16 +39,7 @@
<property name="spacing">
<number>0</number>
</property>
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<property name="margin">
<number>0</number>
</property>
<item>
@@ -77,22 +68,13 @@
</size>
</property>
<layout class="QGridLayout" name="gridLayout_4">
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<property name="margin">
<number>0</number>
</property>
<property name="spacing">
<number>0</number>
</property>
<item row="0" column="3">
<item row="0" column="1">
<layout class="QGridLayout" name="gridLayout_5">
<property name="spacing">
<number>0</number>
@@ -107,16 +89,6 @@
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="cpu">
<property name="styleSheet">
<string notr="true">background-color: darkgreen;</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="1" column="5">
<widget class="QLabel" name="label_5">
<property name="styleSheet">
@@ -256,48 +228,6 @@ Connected</string>
</property>
</widget>
</item>
<item row="3" column="0">
<widget class="QLabel" name="gps">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>9999999</width>
<height>9999999</height>
</size>
</property>
<property name="font">
<font>
<pointsize>10</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="autoFillBackground">
<bool>false</bool>
</property>
<property name="styleSheet">
<string notr="true">background-color:darkgreen;</string>
</property>
<property name="text">
<string>GPS
Fix</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="2" column="5">
<widget class="QLabel" name="joystick">
<property name="sizePolicy">
@@ -375,48 +305,6 @@ Connected</string>
</property>
<property name="text">
<string>Rear Bogie
Connected</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="rover">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>9999999</width>
<height>9999999</height>
</size>
</property>
<property name="font">
<font>
<pointsize>10</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color:darkgreen;</string>
</property>
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<property name="text">
<string>Rover
Connected</string>
</property>
<property name="alignment">
@@ -466,47 +354,6 @@ Connected</string>
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QLabel" name="zed">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>9999999</width>
<height>9999999</height>
</size>
</property>
<property name="font">
<font>
<pointsize>10</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color:darkred;</string>
</property>
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<property name="text">
<string>ZED Connected</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="4" column="2">
<widget class="QLabel" name="main_cam">
<property name="sizePolicy">
@@ -594,9 +441,6 @@ Connected</string>
</property>
</widget>
</item>
<item row="0" column="0" colspan="3">
<widget class="QLCDNumber" name="clock"/>
</item>
<item row="4" column="5">
<widget class="QLabel" name="under_cam">
<property name="sizePolicy">
@@ -655,6 +499,144 @@ Connected</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QLabel" name="cpu">
<property name="styleSheet">
<string notr="true">background-color: darkgreen;</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">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>9999999</width>
<height>9999999</height>
</size>
</property>
<property name="font">
<font>
<pointsize>10</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color:darkgreen;</string>
</property>
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<property name="text">
<string>Rover
Connected</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="3" column="1">
<widget class="QLabel" name="gps">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>9999999</width>
<height>9999999</height>
</size>
</property>
<property name="font">
<font>
<pointsize>10</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="autoFillBackground">
<bool>false</bool>
</property>
<property name="styleSheet">
<string notr="true">background-color:darkgreen;</string>
</property>
<property name="text">
<string>GPS
Fix</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="4" column="1">
<widget class="QLabel" name="zed">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="maximumSize">
<size>
<width>9999999</width>
<height>9999999</height>
</size>
</property>
<property name="font">
<font>
<pointsize>10</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="styleSheet">
<string notr="true">background-color:darkred;</string>
</property>
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
<property name="text">
<string>ZED Connected</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item row="0" column="4">
<widget class="QLCDNumber" name="clock"/>
</item>
</layout>
</item>
</layout>
@@ -816,16 +798,7 @@ Connected</string>
</size>
</property>
<layout class="QGridLayout" name="gridLayout">
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<property name="margin">
<number>0</number>
</property>
<property name="spacing">

View File

@@ -18,6 +18,7 @@ import Framework.MapSystems.RoverMapCoordinator as RoverMapCoordinator
import Framework.JoystickControlSystems.JoystickControlSender as JoystickControlSender
import Framework.NavigationSystems.SpeedAndHeadingIndication as SpeedAndHeading
import Framework.ArmSystems.ArmIndication as ArmIndication
import Framework.StatusSystems.StatusCore as StatusCore
#####################################
# Global Variables
@@ -103,6 +104,7 @@ class GroundStation(QtCore.QObject):
self.__add_thread("Joystick Sender", JoystickControlSender.JoystickControlSender(self.shared_objects))
self.__add_thread("Speed and Heading", SpeedAndHeading.SpeedAndHeadingIndication(self.shared_objects))
self.__add_thread("Arm Indication", ArmIndication.ArmIndication(self.shared_objects))
self.__add_thread("Rover Status", StatusCore.SensorCore(self.shared_objects))
self.connect_signals_and_slots_signal.emit()
self.__connect_signals_to_slots()