mirror of
https://github.com/OSURoboticsClub/Rover_2017_2018.git
synced 2025-11-08 18:21:15 +00:00
Added keyfile copy. Tried to keep map from updating too much. Modified left screen UI. Split TCP topoics out to own senders/receivers.
This commit is contained in:
@@ -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"
|
script_launch_path="${launch_dir:0:$launch_dir_length_without_current_folder}/src"
|
||||||
cd $script_launch_path
|
cd $script_launch_path
|
||||||
|
|
||||||
|
cp ~/key .
|
||||||
|
|
||||||
sleep 1
|
sleep 1
|
||||||
|
|
||||||
export DISPLAY=:0
|
export DISPLAY=:0
|
||||||
|
|||||||
@@ -45,6 +45,7 @@ class RoverMapCoordinator(QtCore.QThread):
|
|||||||
self.overlay_image_object = None
|
self.overlay_image_object = None
|
||||||
|
|
||||||
self.map_pixmap = None
|
self.map_pixmap = None
|
||||||
|
self.last_map_pixmap_cache_key = None
|
||||||
|
|
||||||
def run(self):
|
def run(self):
|
||||||
self.logger.debug("Starting Map Coordinator Thread")
|
self.logger.debug("Starting Map Coordinator Thread")
|
||||||
@@ -102,6 +103,9 @@ class RoverMapCoordinator(QtCore.QThread):
|
|||||||
# 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)
|
||||||
|
|
||||||
|
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()
|
self.pixmap_ready_signal.emit()
|
||||||
|
|
||||||
def connect_signals_and_slots(self):
|
def connect_signals_and_slots(self):
|
||||||
|
|||||||
@@ -1,4 +1,5 @@
|
|||||||
#!/usr/bin/env python
|
#!/usr/bin/env python
|
||||||
|
# coding=utf-8
|
||||||
|
|
||||||
import rospy
|
import rospy
|
||||||
from rover_status.msg import *
|
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;")
|
self.bogie_connection_3_stylesheet_change_ready__signal.emit("background-color: darkgreen;")
|
||||||
|
|
||||||
def __jetson_callback(self, data):
|
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:
|
if data.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;")
|
||||||
@@ -167,7 +168,7 @@ class SensorCore(QtCore.QThread):
|
|||||||
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.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:
|
if data.jetson_RAM > 79:
|
||||||
self.jetson_ram_stylesheet_change_ready__signal.emit("background-color: orange;")
|
self.jetson_ram_stylesheet_change_ready__signal.emit("background-color: orange;")
|
||||||
@@ -176,7 +177,7 @@ class SensorCore(QtCore.QThread):
|
|||||||
else:
|
else:
|
||||||
self.jetson_ram_stylesheet_change_ready__signal.emit("background-color: darkgreen;")
|
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:
|
if data.jetson_GPU_temp > 64:
|
||||||
self.jetson_gpu_temp_stylesheet_change_ready__signal.emit("background-color: orange;")
|
self.jetson_gpu_temp_stylesheet_change_ready__signal.emit("background-color: orange;")
|
||||||
@@ -185,7 +186,7 @@ class SensorCore(QtCore.QThread):
|
|||||||
else:
|
else:
|
||||||
self.jetson_gpu_temp_stylesheet_change_ready__signal.emit("background-color: darkgreen;")
|
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:
|
if data.jetson_EMMC > 79:
|
||||||
self.jetson_emmc_stylesheet_change_ready__signal.emit("background-color: orange;")
|
self.jetson_emmc_stylesheet_change_ready__signal.emit("background-color: orange;")
|
||||||
|
|||||||
@@ -87,6 +87,9 @@
|
|||||||
<property name="text">
|
<property name="text">
|
||||||
<string><html><head/><body><p align="center"><span style=" font-weight:600;">EMMC</span></p></body></html></string>
|
<string><html><head/><body><p align="center"><span style=" font-weight:600;">EMMC</span></p></body></html></string>
|
||||||
</property>
|
</property>
|
||||||
|
<property name="alignment">
|
||||||
|
<set>Qt::AlignCenter</set>
|
||||||
|
</property>
|
||||||
</widget>
|
</widget>
|
||||||
</item>
|
</item>
|
||||||
<item row="1" column="5">
|
<item row="1" column="5">
|
||||||
@@ -97,6 +100,9 @@
|
|||||||
<property name="text">
|
<property name="text">
|
||||||
<string><html><head/><body><p align="center"><span style=" font-size:9pt; font-weight:600;">GPU Temp C</span></p></body></html></string>
|
<string><html><head/><body><p align="center"><span style=" font-size:9pt; font-weight:600;">GPU Temp C</span></p></body></html></string>
|
||||||
</property>
|
</property>
|
||||||
|
<property name="alignment">
|
||||||
|
<set>Qt::AlignCenter</set>
|
||||||
|
</property>
|
||||||
</widget>
|
</widget>
|
||||||
</item>
|
</item>
|
||||||
<item row="4" column="4">
|
<item row="4" column="4">
|
||||||
@@ -538,6 +544,9 @@ Connected</string>
|
|||||||
<property name="text">
|
<property name="text">
|
||||||
<string><html><head/><body><p align="center"><span style=" font-weight:600;">RAM</span></p></body></html></string>
|
<string><html><head/><body><p align="center"><span style=" font-weight:600;">RAM</span></p></body></html></string>
|
||||||
</property>
|
</property>
|
||||||
|
<property name="alignment">
|
||||||
|
<set>Qt::AlignCenter</set>
|
||||||
|
</property>
|
||||||
</widget>
|
</widget>
|
||||||
</item>
|
</item>
|
||||||
<item row="1" column="1">
|
<item row="1" column="1">
|
||||||
@@ -548,6 +557,9 @@ Connected</string>
|
|||||||
<property name="text">
|
<property name="text">
|
||||||
<string><html><head/><body><p align="center"><span style=" font-weight:600;">CPU %</span></p></body></html></string>
|
<string><html><head/><body><p align="center"><span style=" font-weight:600;">CPU %</span></p></body></html></string>
|
||||||
</property>
|
</property>
|
||||||
|
<property name="alignment">
|
||||||
|
<set>Qt::AlignCenter</set>
|
||||||
|
</property>
|
||||||
</widget>
|
</widget>
|
||||||
</item>
|
</item>
|
||||||
<item row="5" column="4">
|
<item row="5" column="4">
|
||||||
|
|||||||
@@ -48,8 +48,28 @@
|
|||||||
<param name="port" value="17012" />
|
<param name="port" value="17012" />
|
||||||
</node>
|
</node>
|
||||||
|
|
||||||
<node name="rover_status" pkg="nimbro_topic_transport" type="tcp_receiver" output="screen">
|
<node name="bogie_status_tcp" pkg="nimbro_topic_transport" type="tcp_receiver" output="screen">
|
||||||
<param name="port" value="17013" />
|
<param name="port" value="17013" />
|
||||||
</node>
|
</node>
|
||||||
|
|
||||||
|
<node name="camera_status_tcp" pkg="nimbro_topic_transport" type="tcp_receiver" output="screen">
|
||||||
|
<param name="port" value="17014" />
|
||||||
|
</node>
|
||||||
|
|
||||||
|
<node name="frsky_status_tcp" pkg="nimbro_topic_transport" type="tcp_receiver" output="screen">
|
||||||
|
<param name="port" value="17015" />
|
||||||
|
</node>
|
||||||
|
|
||||||
|
<node name="gps_status_tcp" pkg="nimbro_topic_transport" type="tcp_receiver" output="screen">
|
||||||
|
<param name="port" value="17016" />
|
||||||
|
</node>
|
||||||
|
|
||||||
|
<node name="jetson_status_tcp" pkg="nimbro_topic_transport" type="tcp_receiver" output="screen">
|
||||||
|
<param name="port" value="17017" />
|
||||||
|
</node>
|
||||||
|
|
||||||
|
<node name="misc_status_tcp" pkg="nimbro_topic_transport" type="tcp_receiver" output="screen">
|
||||||
|
<param name="port" value="17018" />
|
||||||
|
</node>
|
||||||
</group>
|
</group>
|
||||||
</launch>
|
</launch>
|
||||||
|
|||||||
@@ -4,7 +4,7 @@
|
|||||||
|
|
||||||
<node name="ground_station_drive_udp_sender" pkg="nimbro_topic_transport" type="udp_sender" output="screen">
|
<node name="ground_station_drive_udp_sender" pkg="nimbro_topic_transport" type="udp_sender" output="screen">
|
||||||
<param name="destination_addr" value="$(arg target)" />
|
<param name="destination_addr" value="$(arg target)" />
|
||||||
<param name="destination_port" value="17020" />
|
<param name="destination_port" value="17100" />
|
||||||
<rosparam param="topics">
|
<rosparam param="topics">
|
||||||
[{name: "/rover_control/command_control/ground_station_drive", compress: true, rate: 15.0}]
|
[{name: "/rover_control/command_control/ground_station_drive", compress: true, rate: 15.0}]
|
||||||
</rosparam>
|
</rosparam>
|
||||||
@@ -12,14 +12,13 @@
|
|||||||
|
|
||||||
<node name="ground_station_tcp_sender" pkg="nimbro_topic_transport" type="tcp_sender" output="screen">
|
<node name="ground_station_tcp_sender" pkg="nimbro_topic_transport" type="tcp_sender" output="screen">
|
||||||
<param name="destination_addr" value="$(arg target)" />
|
<param name="destination_addr" value="$(arg target)" />
|
||||||
<param name="destination_port" value="17021" />
|
<param name="destination_port" value="17101" />
|
||||||
<rosparam param="topics">
|
<rosparam param="topics">
|
||||||
[{name: "/cameras/chassis/camera_control", compress: true, rate: 5.0},
|
[{name: "/cameras/chassis/camera_control", compress: false, rate: 5.0},
|
||||||
{name: "/cameras/undercarriage/camera_control", compress: true, rate: 5.0},
|
{name: "/cameras/undercarriage/camera_control", compress: false, rate: 5.0},
|
||||||
{name: "/cameras/main_navigation/camera_control", compress: true, rate: 5.0},
|
{name: "/cameras/main_navigation/camera_control", compress: false, rate: 5.0},
|
||||||
{name: "/cameras/end_effector/camera_control", compress: true, rate: 5.0},
|
{name: "/cameras/end_effector/camera_control", compress: false, rate: 5.0},
|
||||||
{name: "/cameras/chassis/camera_control", compress: true, rate: 1.0},
|
{name: "/rover_status/update_requested", compress: false, rate: 5.0}]
|
||||||
{name: "/rover_status/update_requested", compress: true, rate: 1.0}]
|
|
||||||
</rosparam>
|
</rosparam>
|
||||||
</node>
|
</node>
|
||||||
</group>
|
</group>
|
||||||
|
|||||||
@@ -1,11 +1,11 @@
|
|||||||
<launch>
|
<launch>
|
||||||
<group ns="rover_control">
|
<group ns="rover_control">
|
||||||
<node name="ground_station_drive_command" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">
|
<node name="ground_station_drive_command" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">
|
||||||
<param name="port" value="17020" />
|
<param name="port" value="17100" />
|
||||||
</node>
|
</node>
|
||||||
|
|
||||||
<node name="ground_station_tcp_topics" pkg="nimbro_topic_transport" type="tcp_receiver" output="screen">
|
<node name="ground_station_tcp_topics" pkg="nimbro_topic_transport" type="tcp_receiver" output="screen">
|
||||||
<param name="port" value="17021" />
|
<param name="port" value="17101" />
|
||||||
</node>
|
</node>
|
||||||
</group>
|
</group>
|
||||||
</launch>
|
</launch>
|
||||||
|
|||||||
@@ -98,16 +98,51 @@
|
|||||||
</rosparam>
|
</rosparam>
|
||||||
</node>
|
</node>
|
||||||
|
|
||||||
<node name="rover_tcp_topics" pkg="nimbro_topic_transport" type="tcp_sender" output="screen">
|
<node name="bogie_status_tcp" pkg="nimbro_topic_transport" type="tcp_sender" output="screen">
|
||||||
<param name="destination_addr" value="$(arg target)" />
|
<param name="destination_addr" value="$(arg target)" />
|
||||||
<param name="destination_port" value="17013" />
|
<param name="destination_port" value="17013" />
|
||||||
<rosparam param="topics">
|
<rosparam param="topics">
|
||||||
[{name: "/rover_status/bogie_status", compress: true, rate: 1.0},
|
[{name: "/rover_status/bogie_status", compress: false, rate: 1.0}]
|
||||||
{name: "/rover_status/camera_status", compress: true, rate: 1.0},
|
</rosparam>
|
||||||
{name: "/rover_status/frsky_status", compress: true, rate: 1.0},
|
</node>
|
||||||
{name: "/rover_status/gps_status", compress: true, rate: 1.0},
|
|
||||||
{name: "/rover_status/jetson_status", compress: true, rate: 1.0},
|
<node name="camera_status_tcp" pkg="nimbro_topic_transport" type="tcp_sender" output="screen">
|
||||||
{name: "/rover_status/misc_status", compress: true, rate: 1.0}]
|
<param name="destination_addr" value="$(arg target)" />
|
||||||
|
<param name="destination_port" value="17014" />
|
||||||
|
<rosparam param="topics">
|
||||||
|
[{name: "/rover_status/camera_status", compress: false, rate: 1.0}]
|
||||||
|
</rosparam>
|
||||||
|
</node>
|
||||||
|
|
||||||
|
<node name="frsky_status_tcp" pkg="nimbro_topic_transport" type="tcp_sender" output="screen">
|
||||||
|
<param name="destination_addr" value="$(arg target)" />
|
||||||
|
<param name="destination_port" value="17015" />
|
||||||
|
<rosparam param="topics">
|
||||||
|
[{name: "/rover_status/frsky_status", compress: false, rate: 1.0}]
|
||||||
|
</rosparam>
|
||||||
|
</node>
|
||||||
|
|
||||||
|
<node name="gps_status_tcp" pkg="nimbro_topic_transport" type="tcp_sender" output="screen">
|
||||||
|
<param name="destination_addr" value="$(arg target)" />
|
||||||
|
<param name="destination_port" value="17016" />
|
||||||
|
<rosparam param="topics">
|
||||||
|
[{name: "/rover_status/gps_status", compress: false, rate: 1.0}]
|
||||||
|
</rosparam>
|
||||||
|
</node>
|
||||||
|
|
||||||
|
<node name="jetson_status_tcp" pkg="nimbro_topic_transport" type="tcp_sender" output="screen">
|
||||||
|
<param name="destination_addr" value="$(arg target)" />
|
||||||
|
<param name="destination_port" value="17017" />
|
||||||
|
<rosparam param="topics">
|
||||||
|
[{name: "/rover_status/jetson_status", compress: false, rate: 1.0}]
|
||||||
|
</rosparam>
|
||||||
|
</node>
|
||||||
|
|
||||||
|
<node name="misc_status_tcp" pkg="nimbro_topic_transport" type="tcp_sender" output="screen">
|
||||||
|
<param name="destination_addr" value="$(arg target)" />
|
||||||
|
<param name="destination_port" value="17018" />
|
||||||
|
<rosparam param="topics">
|
||||||
|
[{name: "/rover_status/misc_status", compress: false, rate: 1.0}]
|
||||||
</rosparam>
|
</rosparam>
|
||||||
</node>
|
</node>
|
||||||
</group>
|
</group>
|
||||||
|
|||||||
Reference in New Issue
Block a user