From a88f5a6c5847bb9bc40e3f9d4e5f145d71f68cd8 Mon Sep 17 00:00:00 2001 From: Corwin Perren Date: Thu, 15 Mar 2018 16:33:03 -0700 Subject: [PATCH] Added keyfile copy. Tried to keep map from updating too much. Modified left screen UI. Split TCP topoics out to own senders/receivers. --- .../scripts/ground_station_launch.sh | 2 + .../MapSystems/RoverMapCoordinator.py | 6 ++- .../src/Framework/StatusSystems/StatusCore.py | 9 ++-- .../src/Resources/Ui/left_screen.ui | 12 +++++ .../topic_transport_receivers.launch | 22 ++++++++- .../topic_transport_senders.launch | 15 +++--- .../rover/topic_transport_receivers.launch | 4 +- .../rover/topic_transport_senders.launch | 49 ++++++++++++++++--- 8 files changed, 96 insertions(+), 23 deletions(-) diff --git a/software/ros_packages/ground_station/scripts/ground_station_launch.sh b/software/ros_packages/ground_station/scripts/ground_station_launch.sh index 7c674a0..f7b726a 100755 --- a/software/ros_packages/ground_station/scripts/ground_station_launch.sh +++ b/software/ros_packages/ground_station/scripts/ground_station_launch.sh @@ -11,6 +11,8 @@ launch_dir_length_without_current_folder=$(($launch_dir_length-$current_folder_n script_launch_path="${launch_dir:0:$launch_dir_length_without_current_folder}/src" cd $script_launch_path +cp ~/key . + sleep 1 export DISPLAY=:0 diff --git a/software/ros_packages/ground_station/src/Framework/MapSystems/RoverMapCoordinator.py b/software/ros_packages/ground_station/src/Framework/MapSystems/RoverMapCoordinator.py index cf1d8f2..40cb109 100644 --- a/software/ros_packages/ground_station/src/Framework/MapSystems/RoverMapCoordinator.py +++ b/software/ros_packages/ground_station/src/Framework/MapSystems/RoverMapCoordinator.py @@ -45,6 +45,7 @@ class RoverMapCoordinator(QtCore.QThread): self.overlay_image_object = None self.map_pixmap = None + self.last_map_pixmap_cache_key = None def run(self): self.logger.debug("Starting Map Coordinator Thread") @@ -102,7 +103,10 @@ class RoverMapCoordinator(QtCore.QThread): # get overlay here qim = ImageQt(self.map_image) self.map_pixmap = QtGui.QPixmap.fromImage(qim) - self.pixmap_ready_signal.emit() + + if self.map_pixmap.cacheKey() != self.last_map_pixmap_cache_key: + self.last_map_pixmap_cache_key = self.map_pixmap.cacheKey() + self.pixmap_ready_signal.emit() def connect_signals_and_slots(self): self.pixmap_ready_signal.connect(self.pixmap_ready__slot) diff --git a/software/ros_packages/ground_station/src/Framework/StatusSystems/StatusCore.py b/software/ros_packages/ground_station/src/Framework/StatusSystems/StatusCore.py index aa7d549..0b21218 100644 --- a/software/ros_packages/ground_station/src/Framework/StatusSystems/StatusCore.py +++ b/software/ros_packages/ground_station/src/Framework/StatusSystems/StatusCore.py @@ -1,4 +1,5 @@ #!/usr/bin/env python +# coding=utf-8 import rospy from rover_status.msg import * @@ -158,7 +159,7 @@ class SensorCore(QtCore.QThread): self.bogie_connection_3_stylesheet_change_ready__signal.emit("background-color: darkgreen;") def __jetson_callback(self, data): - self.jetson_cpu_update_ready__signal.emit(str(data.jetson_CPU)) + self.jetson_cpu_update_ready__signal.emit("Jetson CPU\n" + str(data.jetson_CPU) + "%") if data.jetson_CPU > 79: self.jetson_cpu_stylesheet_change_ready__signal.emit("background-color: orange;") @@ -167,7 +168,7 @@ class SensorCore(QtCore.QThread): else: self.jetson_cpu_stylesheet_change_ready__signal.emit("background-color: darkgreen;") - self.jetson_ram_update_ready__signal.emit(str(data.jetson_RAM)) + self.jetson_ram_update_ready__signal.emit("Jetson RAM\n" + str(data.jetson_RAM) + "%") if data.jetson_RAM > 79: self.jetson_ram_stylesheet_change_ready__signal.emit("background-color: orange;") @@ -176,7 +177,7 @@ class SensorCore(QtCore.QThread): else: self.jetson_ram_stylesheet_change_ready__signal.emit("background-color: darkgreen;") - self.jetson_gpu_temp_update_ready__signal.emit(str(data.jetson_GPU_temp)) + self.jetson_gpu_temp_update_ready__signal.emit("Jetson EMMC Used\n" + str(data.jetson_GPU_temp) + "%") if data.jetson_GPU_temp > 64: self.jetson_gpu_temp_stylesheet_change_ready__signal.emit("background-color: orange;") @@ -185,7 +186,7 @@ class SensorCore(QtCore.QThread): else: self.jetson_gpu_temp_stylesheet_change_ready__signal.emit("background-color: darkgreen;") - self.jetson_emmc_update_ready__signal.emit(str(data.jetson_EMMC)) + self.jetson_emmc_update_ready__signal.emit("Jetson Max Temp\n" + str(data.jetson_EMMC) + "°C") if data.jetson_EMMC > 79: self.jetson_emmc_stylesheet_change_ready__signal.emit("background-color: orange;") diff --git a/software/ros_packages/ground_station/src/Resources/Ui/left_screen.ui b/software/ros_packages/ground_station/src/Resources/Ui/left_screen.ui index 6314ef8..fe4e4b1 100644 --- a/software/ros_packages/ground_station/src/Resources/Ui/left_screen.ui +++ b/software/ros_packages/ground_station/src/Resources/Ui/left_screen.ui @@ -87,6 +87,9 @@ <html><head/><body><p align="center"><span style=" font-weight:600;">EMMC</span></p></body></html> + + Qt::AlignCenter + @@ -97,6 +100,9 @@ <html><head/><body><p align="center"><span style=" font-size:9pt; font-weight:600;">GPU Temp C</span></p></body></html> + + Qt::AlignCenter + @@ -538,6 +544,9 @@ Connected <html><head/><body><p align="center"><span style=" font-weight:600;">RAM</span></p></body></html> + + Qt::AlignCenter + @@ -548,6 +557,9 @@ Connected <html><head/><body><p align="center"><span style=" font-weight:600;">CPU %</span></p></body></html> + + Qt::AlignCenter + diff --git a/software/ros_packages/rover_main/launch/ground_station/topic_transport_receivers.launch b/software/ros_packages/rover_main/launch/ground_station/topic_transport_receivers.launch index 2c62436..d8a95c8 100644 --- a/software/ros_packages/rover_main/launch/ground_station/topic_transport_receivers.launch +++ b/software/ros_packages/rover_main/launch/ground_station/topic_transport_receivers.launch @@ -48,8 +48,28 @@ - + + + + + + + + + + + + + + + + + + + + + diff --git a/software/ros_packages/rover_main/launch/ground_station/topic_transport_senders.launch b/software/ros_packages/rover_main/launch/ground_station/topic_transport_senders.launch index 3daa5ec..af7eaae 100644 --- a/software/ros_packages/rover_main/launch/ground_station/topic_transport_senders.launch +++ b/software/ros_packages/rover_main/launch/ground_station/topic_transport_senders.launch @@ -4,7 +4,7 @@ - + [{name: "/rover_control/command_control/ground_station_drive", compress: true, rate: 15.0}] @@ -12,14 +12,13 @@ - + - [{name: "/cameras/chassis/camera_control", compress: true, rate: 5.0}, - {name: "/cameras/undercarriage/camera_control", compress: true, rate: 5.0}, - {name: "/cameras/main_navigation/camera_control", compress: true, rate: 5.0}, - {name: "/cameras/end_effector/camera_control", compress: true, rate: 5.0}, - {name: "/cameras/chassis/camera_control", compress: true, rate: 1.0}, - {name: "/rover_status/update_requested", compress: true, rate: 1.0}] + [{name: "/cameras/chassis/camera_control", compress: false, rate: 5.0}, + {name: "/cameras/undercarriage/camera_control", compress: false, rate: 5.0}, + {name: "/cameras/main_navigation/camera_control", compress: false, rate: 5.0}, + {name: "/cameras/end_effector/camera_control", compress: false, rate: 5.0}, + {name: "/rover_status/update_requested", compress: false, rate: 5.0}] diff --git a/software/ros_packages/rover_main/launch/rover/topic_transport_receivers.launch b/software/ros_packages/rover_main/launch/rover/topic_transport_receivers.launch index 67d59dd..822952c 100644 --- a/software/ros_packages/rover_main/launch/rover/topic_transport_receivers.launch +++ b/software/ros_packages/rover_main/launch/rover/topic_transport_receivers.launch @@ -1,11 +1,11 @@ - + - + diff --git a/software/ros_packages/rover_main/launch/rover/topic_transport_senders.launch b/software/ros_packages/rover_main/launch/rover/topic_transport_senders.launch index cc3df69..046815a 100644 --- a/software/ros_packages/rover_main/launch/rover/topic_transport_senders.launch +++ b/software/ros_packages/rover_main/launch/rover/topic_transport_senders.launch @@ -98,16 +98,51 @@ - + - [{name: "/rover_status/bogie_status", compress: true, rate: 1.0}, - {name: "/rover_status/camera_status", compress: true, rate: 1.0}, - {name: "/rover_status/frsky_status", compress: true, rate: 1.0}, - {name: "/rover_status/gps_status", compress: true, rate: 1.0}, - {name: "/rover_status/jetson_status", compress: true, rate: 1.0}, - {name: "/rover_status/misc_status", compress: true, rate: 1.0}] + [{name: "/rover_status/bogie_status", compress: false, rate: 1.0}] + + + + + + + + [{name: "/rover_status/camera_status", compress: false, rate: 1.0}] + + + + + + + + [{name: "/rover_status/frsky_status", compress: false, rate: 1.0}] + + + + + + + + [{name: "/rover_status/gps_status", compress: false, rate: 1.0}] + + + + + + + + [{name: "/rover_status/jetson_status", compress: false, rate: 1.0}] + + + + + + + + [{name: "/rover_status/misc_status", compress: false, rate: 1.0}]