mirror of
https://github.com/OSURoboticsClub/Rover_2017_2018.git
synced 2025-11-09 02:31:14 +00:00
Merge remote-tracking branch 'upstream/master'
This commit is contained in:
@@ -11,7 +11,7 @@ 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
|
||||
|
||||
sleep 5
|
||||
sleep 1
|
||||
|
||||
export DISPLAY=:0
|
||||
python ground_station.py
|
||||
@@ -19,6 +19,11 @@ DEFAULT_DRIVE_COMMAND_TOPIC = "/rover_control/command_control/ground_station_dri
|
||||
|
||||
DRIVE_COMMAND_HERTZ = 15
|
||||
|
||||
Y_AXIS_DEADBAND = 0.05
|
||||
X_AXIS_DEADBAND = 0.05
|
||||
|
||||
THROTTLE_MIN = 0.05
|
||||
|
||||
|
||||
#####################################
|
||||
# Controller Class Definition
|
||||
@@ -37,59 +42,51 @@ class LogitechJoystick(QtCore.QThread):
|
||||
self.gamepad = None # type: GamePad
|
||||
|
||||
self.controller_states = {
|
||||
"left_stick_x_axis": 0,
|
||||
"x_axis": 512,
|
||||
"y_axis": 512,
|
||||
"left_stick_center_pressed": 0,
|
||||
|
||||
"right_stick_x_axis": 0,
|
||||
"right_stick_y_axis": 0,
|
||||
"right_stick_center_pressed": 0,
|
||||
|
||||
"left_trigger_z_axis": 0,
|
||||
"left_bumper_pressed": 0,
|
||||
|
||||
"z_axis": 128,
|
||||
"right_bumper_pressed": 0,
|
||||
"throttle_axis": 128,
|
||||
|
||||
"dpad_x": 0,
|
||||
"dpad_y": 0,
|
||||
"hat_x_axis": 0,
|
||||
"hat_y_axis": 0,
|
||||
|
||||
"select_pressed": 0,
|
||||
"start_pressed": 0,
|
||||
"home_pressed": 0,
|
||||
"trigger_pressed": 0,
|
||||
"thumb_pressed": 0,
|
||||
"three_pressed": 0,
|
||||
"four_pressed": 0,
|
||||
"five_pressed": 0,
|
||||
"six_pressed": 0,
|
||||
|
||||
"a_pressed": 0,
|
||||
"b_pressed": 0,
|
||||
"x_pressed": 0,
|
||||
"y_pressed": 0
|
||||
"eleven_pressed": 0,
|
||||
"twelve_pressed": 0,
|
||||
"thirteen_pressed": 0,
|
||||
"fourteen_pressed": 0,
|
||||
"fifteen_pressed": 0,
|
||||
"sixteen_pressed": 0,
|
||||
}
|
||||
|
||||
self.raw_mapping_to_class_mapping = {
|
||||
"ABS_X": "left_stick_x_axis",
|
||||
"ABS_X": "x_axis",
|
||||
"ABS_Y": "y_axis",
|
||||
"BTN_THUMBL": "left_stick_center_pressed",
|
||||
|
||||
"ABS_RX": "right_stick_x_axis",
|
||||
"ABS_RY": "right_stick_y_axis",
|
||||
"BTN_THUMBR": "right_stick_center_pressed",
|
||||
|
||||
"ABS_Z": "left_trigger_z_axis",
|
||||
"BTN_TL": "left_bumper_pressed",
|
||||
|
||||
"ABS_RZ": "z_axis",
|
||||
"BTN_TR": "right_bumper_pressed",
|
||||
"ABS_THROTTLE": "throttle_axis",
|
||||
|
||||
"ABS_HAT0X": "dpad_x",
|
||||
"ABS_HAT0Y": "dpad_y",
|
||||
"ABS_HAT0X": "hat_x_axis",
|
||||
"ABS_HAT0Y": "hat_y_axis",
|
||||
|
||||
"BTN_SELECT": "select_pressed",
|
||||
"BTN_START": "start_pressed",
|
||||
"BTN_MODE": "home_pressed",
|
||||
"BTN_TRIGGER": "trigger_pressed",
|
||||
"BTN_THUMB": "thumb_pressed",
|
||||
"BTN_THUMB2": "three_pressed",
|
||||
"BTN_TOP": "four_pressed",
|
||||
"BTN_TOP2": "five_pressed",
|
||||
"BTN_PINKIE": "six_pressed",
|
||||
|
||||
"BTN_SOUTH": "a_pressed",
|
||||
"BTN_EAST": "b_pressed",
|
||||
"BTN_NORTH": "x_pressed",
|
||||
"BTN_WEST": "y_pressed"
|
||||
"BTN_BASE5": "eleven_pressed",
|
||||
"BTN_BASE6": "twelve_pressed",
|
||||
"BTN_BASE3": "thirteen_pressed",
|
||||
"BTN_BASE4": "fourteen_pressed",
|
||||
"BTN_BASE": "fifteen_pressed",
|
||||
"BTN_BASE2": "sixteen_pressed",
|
||||
}
|
||||
|
||||
self.ready = False
|
||||
@@ -107,7 +104,6 @@ class LogitechJoystick(QtCore.QThread):
|
||||
|
||||
def __setup_controller(self):
|
||||
for device in devices.gamepads:
|
||||
print device
|
||||
if device.name == GAME_CONTROLLER_NAME:
|
||||
self.gamepad = device
|
||||
|
||||
@@ -121,23 +117,27 @@ class LogitechJoystick(QtCore.QThread):
|
||||
for event in events:
|
||||
if event.code in self.raw_mapping_to_class_mapping:
|
||||
self.controller_states[self.raw_mapping_to_class_mapping[event.code]] = event.state
|
||||
|
||||
self.ready = True
|
||||
# print "Logitech: %s" % self.controller_states
|
||||
|
||||
|
||||
#####################################
|
||||
# Controller Class Definition
|
||||
#####################################
|
||||
class RoverDriveSender(QtCore.QThread):
|
||||
set_speed_limit__signal = QtCore.pyqtSignal(int)
|
||||
set_left_drive_output__signal = QtCore.pyqtSignal(int)
|
||||
set_right_drive_output__signal = QtCore.pyqtSignal(int)
|
||||
|
||||
def __init__(self, shared_objects):
|
||||
super(RoverDriveSender, self).__init__()
|
||||
|
||||
# ########## Reference to class init variables ##########
|
||||
self.shared_objects = shared_objects
|
||||
self.right_screen = self.shared_objects["screens"]["right_screen"]
|
||||
self.primary_video_display_label = self.right_screen.primary_video_label # type:QtWidgets.QLabel
|
||||
self.secondary_video_display_label = self.right_screen.secondary_video_label # type:QtWidgets.QLabel
|
||||
self.tertiary_video_display_label = self.right_screen.tertiary_video_label # type:QtWidgets.QLabel
|
||||
self.speed_limit_progress_bar = self.right_screen.speed_limit_progress_bar # type: QtWidgets.QProgressBar
|
||||
self.left_drive_progress_bar = self.right_screen.left_drive_progress_bar # type: QtWidgets.QProgressBar
|
||||
self.right_drive_progress_bar = self.right_screen.right_drive_progress_bar # type: QtWidgets.QProgressBar
|
||||
|
||||
# ########## Get the settings instance ##########
|
||||
self.settings = QtCore.QSettings()
|
||||
@@ -154,34 +154,82 @@ class RoverDriveSender(QtCore.QThread):
|
||||
# Publishers
|
||||
self.drive_command_publisher = rospy.Publisher(DEFAULT_DRIVE_COMMAND_TOPIC, DriveCommandMessage, queue_size=1)
|
||||
|
||||
self.wait_time = 1 / DRIVE_COMMAND_HERTZ
|
||||
self.wait_time = 1.0 / DRIVE_COMMAND_HERTZ
|
||||
|
||||
self.drive_paused = True
|
||||
|
||||
def run(self):
|
||||
while self.run_thread_flag:
|
||||
|
||||
start_time = time()
|
||||
|
||||
self.check_and_set_pause_state()
|
||||
self.__update_and_publish()
|
||||
|
||||
time_diff = time() - start_time
|
||||
|
||||
self.msleep(max(self.wait_time - time_diff, 0))
|
||||
self.msleep(max(int(self.wait_time - time_diff), 0))
|
||||
|
||||
def connect_signals_and_slots(self):
|
||||
pass
|
||||
self.set_speed_limit__signal.connect(self.speed_limit_progress_bar.setValue)
|
||||
self.set_left_drive_output__signal.connect(self.left_drive_progress_bar.setValue)
|
||||
self.set_right_drive_output__signal.connect(self.right_drive_progress_bar.setValue)
|
||||
|
||||
def check_and_set_pause_state(self):
|
||||
if self.joystick.controller_states["thumb_pressed"]:
|
||||
self.drive_paused = not self.drive_paused
|
||||
self.msleep(350)
|
||||
self.show_changed_pause_state()
|
||||
|
||||
def __update_and_publish(self):
|
||||
throttle_axis = max((255 - self.joystick.controller_states["throttle_axis"]) / 255.0, THROTTLE_MIN)
|
||||
|
||||
if self.drive_paused:
|
||||
drive_message = DriveCommandMessage()
|
||||
else:
|
||||
drive_message = self.get_drive_message(throttle_axis)
|
||||
|
||||
left_output = abs(drive_message.drive_twist.linear.x - drive_message.drive_twist.angular.z)
|
||||
right_output = abs(drive_message.drive_twist.linear.x + drive_message.drive_twist.angular.z)
|
||||
|
||||
self.set_speed_limit__signal.emit(throttle_axis * 100)
|
||||
self.set_left_drive_output__signal.emit(left_output * 100)
|
||||
self.set_right_drive_output__signal.emit(right_output * 100)
|
||||
|
||||
self.drive_command_publisher.publish(drive_message)
|
||||
|
||||
def get_drive_message(self, throttle_axis):
|
||||
drive_message = DriveCommandMessage()
|
||||
|
||||
drive_message.drive_twist.linear.x = -(self.joystick.controller_states["y_axis"] - 512) / 1024.0
|
||||
drive_message.drive_twist.angular.z = -(self.joystick.controller_states["z_axis"] - 128) / 255.0
|
||||
self.drive_command_publisher.publish(drive_message)
|
||||
# print self.joystick.controller_states["y_axis"], self.joystick.controller_states["z_axis"]
|
||||
y_axis = throttle_axis * (-(self.joystick.controller_states["y_axis"] - 512) / 512.0)
|
||||
z_axis = throttle_axis * (-(self.joystick.controller_states["z_axis"] - 128) / 128.0)
|
||||
x_axis = throttle_axis * (-(self.joystick.controller_states["x_axis"] - 512) / 512.0)
|
||||
|
||||
if abs(y_axis) < Y_AXIS_DEADBAND:
|
||||
y_axis = 0
|
||||
|
||||
if abs(x_axis) < X_AXIS_DEADBAND and y_axis == 0:
|
||||
twist = z_axis
|
||||
else:
|
||||
twist = x_axis if y_axis >= 0 else -x_axis
|
||||
|
||||
drive_message.drive_twist.linear.x = y_axis
|
||||
drive_message.drive_twist.angular.z = twist
|
||||
|
||||
return drive_message
|
||||
|
||||
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 show_changed_pause_state(self):
|
||||
if self.drive_paused:
|
||||
self.left_drive_progress_bar.setStyleSheet("background-color:darkred;")
|
||||
self.right_drive_progress_bar.setStyleSheet("background-color:darkred;")
|
||||
else:
|
||||
self.left_drive_progress_bar.setStyleSheet("background-color: transparent;")
|
||||
self.right_drive_progress_bar.setStyleSheet("background-color: transparent;")
|
||||
|
||||
def on_kill_threads_requested__slot(self):
|
||||
self.run_thread_flag = False
|
||||
|
||||
@@ -76,13 +76,13 @@ class RoverMapCoordinator(QtCore.QThread):
|
||||
RoverMap.OverlayImage(44.567161, -123.278432,
|
||||
self.google_maps_object.northwest,
|
||||
self.google_maps_object.southeast,
|
||||
self.google_maps_object.big_image[0],
|
||||
self.google_maps_object.big_image[1],
|
||||
self.google_maps_object.big_image.size[0],
|
||||
self.google_maps_object.big_image.size[1],
|
||||
1280, 720))
|
||||
|
||||
def _get_map_image(self):
|
||||
self.map_image = self.google_maps_object.display_image
|
||||
self.map_image.paste(self.overlay_image_object.display_image)
|
||||
# self.map_image.paste(self.overlay_image_object.display_image)
|
||||
# get overlay here
|
||||
qim = ImageQt(self.map_image)
|
||||
self.map_pixmap = QtGui.QPixmap.fromImage(qim)
|
||||
|
||||
@@ -9,20 +9,17 @@ import rospy
|
||||
|
||||
# Custom Imports
|
||||
import RoverVideoReceiver
|
||||
from rover_camera.msg import CameraControlMessage
|
||||
|
||||
#####################################
|
||||
# Global Variables
|
||||
#####################################
|
||||
CAMERA_TOPIC_PATH = "/cameras/"
|
||||
EXCLUDED_CAMERAS = ["zed"]
|
||||
#
|
||||
PRIMARY_LABEL_MAX = (640, 360)
|
||||
SECONDARY_LABEL_MAX = (256, 144)
|
||||
TERTIARY_LABEL_MAX = (256, 144)
|
||||
|
||||
# PRIMARY_LABEL_MAX = (1280, 720)
|
||||
# SECONDARY_LABEL_MAX = (640, 360)
|
||||
# TERTIARY_LABEL_MAX = (640, 360)
|
||||
PRIMARY_LABEL_MAX = (640, 360)
|
||||
SECONDARY_LABEL_MAX = (640, 360)
|
||||
TERTIARY_LABEL_MAX = (640, 360)
|
||||
|
||||
|
||||
#####################################
|
||||
@@ -58,26 +55,35 @@ class RoverVideoCoordinator(QtCore.QThread):
|
||||
self.valid_cameras = []
|
||||
self.disabled_cameras = []
|
||||
|
||||
reset_camera_message = CameraControlMessage()
|
||||
reset_camera_message.enable_small_broadcast = True
|
||||
# Reset default cameras
|
||||
rospy.Publisher("/cameras/chassis/camera_control", CameraControlMessage, queue_size=1).publish(reset_camera_message)
|
||||
rospy.Publisher("/cameras/undercarriage/camera_control", CameraControlMessage, queue_size=1).publish(reset_camera_message)
|
||||
rospy.Publisher("/cameras/main_navigation/camera_control", CameraControlMessage, queue_size=1).publish(reset_camera_message)
|
||||
rospy.Publisher("/cameras/end_effector/camera_control", CameraControlMessage, queue_size=1).publish(reset_camera_message)
|
||||
|
||||
self.msleep(3000)
|
||||
|
||||
# Setup cameras
|
||||
self.__get_cameras()
|
||||
self.__setup_video_threads()
|
||||
|
||||
self.primary_label_current_setting = 0
|
||||
self.secondary_label_current_setting = 0
|
||||
self.tertiary_label_current_setting = 0
|
||||
self.secondary_label_current_setting = min(self.primary_label_current_setting + 1, len(self.valid_cameras))
|
||||
self.tertiary_label_current_setting = min(self.secondary_label_current_setting + 1, len(self.valid_cameras))
|
||||
|
||||
self.primary_label_max_resolution = -1
|
||||
self.secondary_label_max_resolution = -1
|
||||
self.tertiary_label_max_resolution = -1
|
||||
|
||||
self.set_max_resolutions_flag = True
|
||||
|
||||
self.first_image_received = False
|
||||
|
||||
def run(self):
|
||||
self.logger.debug("Starting Video Coordinator Thread")
|
||||
|
||||
self.__set_max_resolutions() # Do this initially so we don't try to disable cameras before they're set up
|
||||
self.msleep(500)
|
||||
|
||||
while self.run_thread_flag:
|
||||
self.__set_max_resolutions()
|
||||
self.__toggle_background_cameras_if_needed()
|
||||
@@ -88,37 +94,26 @@ class RoverVideoCoordinator(QtCore.QThread):
|
||||
self.logger.debug("Stopping Video Coordinator Thread")
|
||||
|
||||
def __set_max_resolutions(self):
|
||||
self.primary_label_max_resolution = self.camera_threads[
|
||||
self.valid_cameras[self.primary_label_current_setting]].current_max_resolution
|
||||
self.secondary_label_max_resolution = self.camera_threads[
|
||||
self.valid_cameras[self.secondary_label_current_setting]].current_max_resolution
|
||||
self.tertiary_label_max_resolution = self.camera_threads[
|
||||
self.valid_cameras[self.tertiary_label_current_setting]].current_max_resolution
|
||||
if self.set_max_resolutions_flag:
|
||||
self.camera_threads[self.valid_cameras[self.primary_label_current_setting]].set_hard_max_resolution(PRIMARY_LABEL_MAX)
|
||||
|
||||
if self.primary_label_max_resolution != PRIMARY_LABEL_MAX:
|
||||
self.camera_threads[self.valid_cameras[self.primary_label_current_setting]].change_max_resolution_setting(
|
||||
PRIMARY_LABEL_MAX)
|
||||
if self.secondary_label_current_setting != self.primary_label_current_setting:
|
||||
self.camera_threads[self.valid_cameras[self.secondary_label_current_setting]].set_hard_max_resolution(SECONDARY_LABEL_MAX)
|
||||
|
||||
if self.secondary_label_max_resolution != SECONDARY_LABEL_MAX and self.secondary_label_current_setting != self.primary_label_current_setting:
|
||||
self.camera_threads[self.valid_cameras[self.secondary_label_current_setting]].change_max_resolution_setting(
|
||||
SECONDARY_LABEL_MAX)
|
||||
if self.tertiary_label_current_setting != self.primary_label_current_setting and self.tertiary_label_current_setting != self.secondary_label_current_setting:
|
||||
self.camera_threads[self.valid_cameras[self.tertiary_label_current_setting]].set_hard_max_resolution(SECONDARY_LABEL_MAX)
|
||||
|
||||
if self.tertiary_label_max_resolution != TERTIARY_LABEL_MAX and self.tertiary_label_current_setting != self.primary_label_current_setting:
|
||||
self.camera_threads[self.valid_cameras[self.tertiary_label_current_setting]].change_max_resolution_setting(
|
||||
TERTIARY_LABEL_MAX)
|
||||
self.set_max_resolutions_flag = False
|
||||
|
||||
def __toggle_background_cameras_if_needed(self):
|
||||
if self.first_image_received:
|
||||
enabled = list({self.primary_label_current_setting, self.secondary_label_current_setting,
|
||||
self.tertiary_label_current_setting})
|
||||
enabled = list({self.primary_label_current_setting, self.secondary_label_current_setting,
|
||||
self.tertiary_label_current_setting})
|
||||
|
||||
for camera_index, camera_name in enumerate(self.valid_cameras):
|
||||
if camera_index not in enabled and camera_index not in self.disabled_cameras:
|
||||
self.camera_threads[camera_name].toggle_video_display()
|
||||
self.disabled_cameras.append(camera_index)
|
||||
elif camera_index in enabled and camera_index in self.disabled_cameras:
|
||||
self.camera_threads[camera_name].toggle_video_display()
|
||||
self.disabled_cameras.remove(camera_index)
|
||||
for camera_index, camera_name in enumerate(self.valid_cameras):
|
||||
if camera_index not in enabled and camera_index not in self.disabled_cameras and self.camera_threads[camera_name].video_enabled:
|
||||
self.camera_threads[camera_name].toggle_video_display()
|
||||
elif camera_index in enabled and camera_index not in self.disabled_cameras and not self.camera_threads[camera_name].video_enabled:
|
||||
self.camera_threads[camera_name].toggle_video_display()
|
||||
|
||||
def __get_cameras(self):
|
||||
topics = rospy.get_published_topics(CAMERA_TOPIC_PATH)
|
||||
@@ -167,33 +162,54 @@ class RoverVideoCoordinator(QtCore.QThread):
|
||||
def __change_display_source_primary_mouse_press_event(self, event):
|
||||
if event.button() == QtCore.Qt.LeftButton:
|
||||
self.primary_label_current_setting = (self.primary_label_current_setting + 1) % len(self.valid_cameras)
|
||||
self.set_max_resolutions_flag = True
|
||||
elif event.button() == QtCore.Qt.RightButton:
|
||||
if self.primary_label_current_setting in self.disabled_cameras:
|
||||
self.disabled_cameras.remove(self.primary_label_current_setting)
|
||||
else:
|
||||
self.disabled_cameras.append(self.primary_label_current_setting)
|
||||
self.camera_threads[self.valid_cameras[self.primary_label_current_setting]].toggle_video_display()
|
||||
|
||||
def __change_display_source_secondary_mouse_press_event(self, event):
|
||||
if event.button() == QtCore.Qt.LeftButton:
|
||||
self.secondary_label_current_setting = (self.secondary_label_current_setting + 1) % len(self.valid_cameras)
|
||||
self.set_max_resolutions_flag = True
|
||||
elif event.button() == QtCore.Qt.RightButton:
|
||||
if self.secondary_label_current_setting in self.disabled_cameras:
|
||||
self.disabled_cameras.remove(self.secondary_label_current_setting)
|
||||
else:
|
||||
self.disabled_cameras.append(self.secondary_label_current_setting)
|
||||
self.camera_threads[self.valid_cameras[self.secondary_label_current_setting]].toggle_video_display()
|
||||
|
||||
def __change_display_source_tertiary_mouse_press_event(self, event):
|
||||
if event.button() == QtCore.Qt.LeftButton:
|
||||
self.tertiary_label_current_setting = (self.tertiary_label_current_setting + 1) % len(self.valid_cameras)
|
||||
self.set_max_resolutions_flag = True
|
||||
elif event.button() == QtCore.Qt.RightButton:
|
||||
if self.tertiary_label_current_setting in self.disabled_cameras:
|
||||
self.disabled_cameras.remove(self.tertiary_label_current_setting)
|
||||
else:
|
||||
self.disabled_cameras.append(self.tertiary_label_current_setting)
|
||||
self.camera_threads[self.valid_cameras[self.tertiary_label_current_setting]].toggle_video_display()
|
||||
|
||||
def pixmap_ready__slot(self, camera):
|
||||
if not self.first_image_received:
|
||||
self.first_image_received = True
|
||||
|
||||
if self.valid_cameras[self.primary_label_current_setting] == camera:
|
||||
self.primary_video_display_label.setPixmap(self.camera_threads[camera].pixmap_1280x720_image)
|
||||
try:
|
||||
self.primary_video_display_label.setPixmap(self.camera_threads[camera].pixmap_1280x720_image)
|
||||
except:
|
||||
pass
|
||||
|
||||
if self.valid_cameras[self.secondary_label_current_setting] == camera:
|
||||
self.secondary_video_display_label.setPixmap(self.camera_threads[camera].pixmap_640x360_image)
|
||||
try:
|
||||
self.secondary_video_display_label.setPixmap(self.camera_threads[camera].pixmap_640x360_image)
|
||||
except:
|
||||
pass
|
||||
|
||||
if self.valid_cameras[self.tertiary_label_current_setting] == camera:
|
||||
self.tertiary_video_display_label.setPixmap(self.camera_threads[camera].pixmap_640x360_image)
|
||||
try:
|
||||
self.tertiary_video_display_label.setPixmap(self.camera_threads[camera].pixmap_640x360_image)
|
||||
except:
|
||||
pass
|
||||
|
||||
def on_kill_threads_requested__slot(self):
|
||||
self.run_thread_flag = False
|
||||
|
||||
@@ -7,6 +7,7 @@ import logging
|
||||
import cv2
|
||||
import numpy as np
|
||||
import qimage2ndarray
|
||||
from time import time
|
||||
|
||||
import rospy
|
||||
import dynamic_reconfigure.client
|
||||
@@ -14,6 +15,7 @@ from cv_bridge import CvBridge
|
||||
from sensor_msgs.msg import CompressedImage
|
||||
|
||||
# Custom Imports
|
||||
from rover_camera.msg import CameraControlMessage
|
||||
|
||||
#####################################
|
||||
# Global Variables
|
||||
@@ -23,6 +25,11 @@ CAMERA_TOPIC_PATH = "/cameras/"
|
||||
QUALITY_MAX = 80
|
||||
QUALITY_MIN = 15
|
||||
|
||||
FRAMERATE_AVERAGING_TIME = 10 # seconds
|
||||
|
||||
MIN_FRAMERATE_BEFORE_ADJUST = 23
|
||||
MAX_FRAMERATE_BEFORE_ADJUST = 28
|
||||
|
||||
|
||||
#####################################
|
||||
# RoverVideoReceiver Class Definition
|
||||
@@ -30,6 +37,14 @@ QUALITY_MIN = 15
|
||||
class RoverVideoReceiver(QtCore.QThread):
|
||||
image_ready_signal = QtCore.pyqtSignal(str)
|
||||
|
||||
RESOLUTION_OPTIONS = [(256, 144), (640, 360), (1280, 720)]
|
||||
|
||||
RESOLUTION_MAPPINGS = {
|
||||
(1280, 720): None,
|
||||
(640, 360): None,
|
||||
(256, 144): None
|
||||
}
|
||||
|
||||
def __init__(self, camera_name):
|
||||
super(RoverVideoReceiver, self).__init__()
|
||||
|
||||
@@ -49,22 +64,35 @@ class RoverVideoReceiver(QtCore.QThread):
|
||||
self.camera_title_name = self.camera_name.replace("_", " ").title()
|
||||
|
||||
self.topic_base_path = CAMERA_TOPIC_PATH + self.camera_name
|
||||
self.camera_topics = {}
|
||||
|
||||
self.current_max_resolution = None
|
||||
|
||||
self.current_camera_settings = {
|
||||
"resolution": None,
|
||||
"quality_setting": QUALITY_MAX,
|
||||
|
||||
}
|
||||
|
||||
self.previous_camera_settings = self.current_camera_settings.copy()
|
||||
|
||||
self.temp_topic_path = CAMERA_TOPIC_PATH + self.camera_name + "/image_640x360/compressed"
|
||||
self.control_topic_path = self.topic_base_path + "/camera_control"
|
||||
|
||||
# Subscription variables
|
||||
self.video_subscriber = None # type: rospy.Subscriber
|
||||
self.video_subscribers = []
|
||||
|
||||
self.video_subscribers.append(rospy.Subscriber(self.topic_base_path + "/image_1280x720/compressed", CompressedImage, self.__image_data_received_callback))
|
||||
self.video_subscribers.append(rospy.Subscriber(self.topic_base_path + "/image_640x360/compressed", CompressedImage, self.__image_data_received_callback))
|
||||
self.video_subscribers.append(rospy.Subscriber(self.topic_base_path + "/image_256x144/compressed", CompressedImage, self.__image_data_received_callback))
|
||||
|
||||
# Publisher variables
|
||||
self.camera_control_publisher = rospy.Publisher(self.control_topic_path, CameraControlMessage, queue_size=1)
|
||||
|
||||
# Set up resolution mappings
|
||||
self.RESOLUTION_MAPPINGS[(1280, 720)] = CameraControlMessage()
|
||||
self.RESOLUTION_MAPPINGS[(640, 360)] = CameraControlMessage()
|
||||
self.RESOLUTION_MAPPINGS[(256, 144)] = CameraControlMessage()
|
||||
|
||||
self.RESOLUTION_MAPPINGS[(1280, 720)].enable_large_broadcast = True
|
||||
self.RESOLUTION_MAPPINGS[(640, 360)].enable_medium_broadcast = True
|
||||
self.RESOLUTION_MAPPINGS[(256, 144)].enable_small_broadcast = True
|
||||
|
||||
# Auto resolution adjustment variables
|
||||
self.current_resolution_index = 1
|
||||
self.last_resolution_index = self.current_resolution_index
|
||||
self.max_resolution_index = len(self.RESOLUTION_OPTIONS)
|
||||
|
||||
self.frame_count = 0
|
||||
self.last_framerate_time = time()
|
||||
self.resolution_just_adjusted = False
|
||||
|
||||
# Image variables
|
||||
self.raw_image = None
|
||||
@@ -87,17 +115,14 @@ class RoverVideoReceiver(QtCore.QThread):
|
||||
self.camera_name_opencv_1280x720_image = None
|
||||
self.camera_name_opencv_640x360_image = None
|
||||
|
||||
# ROS Dynamic Reconfigure Client
|
||||
self.reconfigure_clients = {}
|
||||
|
||||
# Initial class setup to make text images and get camera resolutions
|
||||
self.__create_camera_name_opencv_images()
|
||||
self.__get_camera_available_resolutions()
|
||||
#self.__setup_reconfigure_clients()
|
||||
|
||||
def run(self):
|
||||
self.logger.debug("Starting \"%s\" Camera Thread" % self.camera_title_name)
|
||||
|
||||
self.__enable_camera_resolution(self.RESOLUTION_OPTIONS[self.current_resolution_index])
|
||||
|
||||
while self.run_thread_flag:
|
||||
if self.video_enabled:
|
||||
self.__show_video_enabled()
|
||||
@@ -108,62 +133,43 @@ class RoverVideoReceiver(QtCore.QThread):
|
||||
|
||||
self.logger.debug("Stopping \"%s\" Camera Thread" % self.camera_title_name)
|
||||
|
||||
def __perform_quality_check_and_adjust(self):
|
||||
self.__set_jpeg_quality(self.current_camera_settings["quality_setting"])
|
||||
def __enable_camera_resolution(self, resolution):
|
||||
self.camera_control_publisher.publish(self.RESOLUTION_MAPPINGS[resolution])
|
||||
|
||||
def __set_jpeg_quality(self, quality_setting):
|
||||
self.reconfigure_clients[self.current_camera_settings["resolution"]].update_configuration({"jpeg_quality": quality_setting})
|
||||
def __check_framerate_and_adjust_resolution(self):
|
||||
time_diff = time() - self.last_framerate_time
|
||||
if time_diff > FRAMERATE_AVERAGING_TIME:
|
||||
current_fps = self.frame_count / time_diff
|
||||
|
||||
def __setup_reconfigure_clients(self):
|
||||
for resolution_group in self.camera_topics:
|
||||
image_topic_string = "image_%sx%s" % resolution_group
|
||||
full_topic = self.topic_base_path + "/" + image_topic_string + "/compressed"
|
||||
self.reconfigure_clients[resolution_group] = dynamic_reconfigure.client.Client(full_topic)
|
||||
if current_fps >= MAX_FRAMERATE_BEFORE_ADJUST:
|
||||
self.current_resolution_index = min(self.current_resolution_index + 1, self.max_resolution_index)
|
||||
elif current_fps <= MIN_FRAMERATE_BEFORE_ADJUST:
|
||||
self.current_resolution_index = max(self.current_resolution_index - 1, 0)
|
||||
|
||||
def __get_camera_available_resolutions(self):
|
||||
topics = rospy.get_published_topics(self.topic_base_path)
|
||||
if self.last_resolution_index != self.current_resolution_index:
|
||||
self.camera_control_publisher.publish(
|
||||
self.RESOLUTION_MAPPINGS[self.RESOLUTION_OPTIONS[self.current_resolution_index]])
|
||||
print "Setting %s to %s" % (self.camera_title_name, self.RESOLUTION_OPTIONS[self.current_resolution_index])
|
||||
self.last_resolution_index = self.current_resolution_index
|
||||
self.resolution_just_adjusted = True
|
||||
|
||||
resolution_options = []
|
||||
|
||||
for topics_group in topics:
|
||||
main_topic = topics_group[0]
|
||||
if "heartbeat" in main_topic:
|
||||
continue
|
||||
camera_name = main_topic.split("/")[3]
|
||||
resolution_options.append(camera_name)
|
||||
|
||||
resolution_options = list(set(resolution_options))
|
||||
|
||||
for resolution in resolution_options:
|
||||
# Creates a tuple in (width, height) format that we can use as the key
|
||||
group = int(resolution.split("image_")[1].split("x")[0]), int(resolution.split("image_")[1].split("x")[1])
|
||||
self.camera_topics[group] = self.topic_base_path + "/" + resolution + "/compressed"
|
||||
|
||||
def __update_camera_subscription_and_settings(self):
|
||||
if self.current_camera_settings["resolution"] != self.previous_camera_settings["resolution"]:
|
||||
|
||||
if self.video_subscriber:
|
||||
self.video_subscriber.unregister()
|
||||
new_topic = self.camera_topics[self.current_camera_settings["resolution"]]
|
||||
self.video_subscriber = rospy.Subscriber(new_topic, CompressedImage, self.__image_data_received_callback)
|
||||
|
||||
self.new_frame = False
|
||||
while not self.new_frame:
|
||||
self.msleep(10)
|
||||
|
||||
self.previous_camera_settings["resolution"] = self.current_camera_settings["resolution"]
|
||||
# print "%s: %s FPS" % (self.camera_title_name, current_fps)
|
||||
self.last_framerate_time = time()
|
||||
self.frame_count = 0
|
||||
|
||||
def __show_video_enabled(self):
|
||||
self.__update_camera_subscription_and_settings()
|
||||
if self.new_frame:
|
||||
self.__check_framerate_and_adjust_resolution()
|
||||
|
||||
if self.new_frame and self.current_camera_settings["resolution"]:
|
||||
# self.__perform_quality_check_and_adjust()
|
||||
try:
|
||||
opencv_image = self.bridge.compressed_imgmsg_to_cv2(self.raw_image, "rgb8")
|
||||
|
||||
opencv_image = self.bridge.compressed_imgmsg_to_cv2(self.raw_image, "rgb8")
|
||||
self.__create_final_pixmaps(opencv_image)
|
||||
|
||||
self.__create_final_pixmaps(opencv_image)
|
||||
self.image_ready_signal.emit(self.camera_name)
|
||||
except Exception, error:
|
||||
print "Failed with error:" + str(error)
|
||||
|
||||
self.image_ready_signal.emit(self.camera_name)
|
||||
self.new_frame = False
|
||||
|
||||
def __show_video_disabled(self):
|
||||
@@ -196,8 +202,14 @@ class RoverVideoReceiver(QtCore.QThread):
|
||||
|
||||
def __image_data_received_callback(self, raw_image):
|
||||
self.raw_image = raw_image
|
||||
self.frame_count += 1
|
||||
self.new_frame = True
|
||||
|
||||
if self.resolution_just_adjusted:
|
||||
self.frame_count = 0
|
||||
self.last_framerate_time = time()
|
||||
self.resolution_just_adjusted = False
|
||||
|
||||
def __create_camera_name_opencv_images(self):
|
||||
camera_name_text_width, camera_name_text_height = \
|
||||
cv2.getTextSize(self.camera_title_name, self.font, self.font_thickness, self.font_baseline)[0]
|
||||
@@ -224,20 +236,17 @@ class RoverVideoReceiver(QtCore.QThread):
|
||||
self.camera_name_opencv_640x360_image = \
|
||||
cv2.resize(camera_name_opencv_image, (camera_name_width_buffered / 2, camera_name_height_buffered / 2))
|
||||
|
||||
def change_max_resolution_setting(self, resolution_max):
|
||||
self.current_max_resolution = resolution_max
|
||||
self.current_camera_settings["resolution"] = resolution_max
|
||||
def set_hard_max_resolution(self, resolution):
|
||||
self.max_resolution_index = self.RESOLUTION_OPTIONS.index(resolution)
|
||||
|
||||
def toggle_video_display(self):
|
||||
if self.video_enabled:
|
||||
if self.video_subscriber:
|
||||
self.video_subscriber.unregister()
|
||||
self.new_frame = True
|
||||
self.video_enabled = False
|
||||
else:
|
||||
new_topic = self.camera_topics[self.current_camera_settings["resolution"]]
|
||||
self.video_subscriber = rospy.Subscriber(new_topic, CompressedImage, self.__image_data_received_callback)
|
||||
if not self.video_enabled:
|
||||
self.camera_control_publisher.publish(self.RESOLUTION_MAPPINGS[self.RESOLUTION_OPTIONS[self.current_resolution_index]])
|
||||
self.video_enabled = True
|
||||
self.new_frame = True
|
||||
else:
|
||||
self.camera_control_publisher.publish(CameraControlMessage())
|
||||
self.video_enabled = False
|
||||
|
||||
def connect_signals_and_slots(self):
|
||||
pass
|
||||
|
||||
Binary file not shown.
|
After Width: | Height: | Size: 144 KiB |
@@ -42,7 +42,16 @@
|
||||
<property name="sizeConstraint">
|
||||
<enum>QLayout::SetDefaultConstraint</enum>
|
||||
</property>
|
||||
<property name="margin">
|
||||
<property name="leftMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
@@ -75,9 +84,453 @@
|
||||
<height>720</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color:black;</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_44">
|
||||
<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">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_9">
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QLabel" name="label_44">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>22</pointsize>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Arm Joint Positions</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_6">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_10">
|
||||
<item>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_39">
|
||||
<item>
|
||||
<widget class="QLabel" name="label_45">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>14</pointsize>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Base Rotation</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QDial" name="dial_31">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>305</width>
|
||||
<height>185</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="minimum">
|
||||
<number>-180</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>180</number>
|
||||
</property>
|
||||
<property name="pageStep">
|
||||
<number>10</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="sliderPosition">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="tracking">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="invertedAppearance">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="invertedControls">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="wrapping">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="notchTarget">
|
||||
<double>90.000000000000000</double>
|
||||
</property>
|
||||
<property name="notchesVisible">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_40">
|
||||
<item>
|
||||
<widget class="QLabel" name="label_46">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>14</pointsize>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Shoulder Pitch</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QDial" name="dial_32">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>305</width>
|
||||
<height>185</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="minimum">
|
||||
<number>-180</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>180</number>
|
||||
</property>
|
||||
<property name="pageStep">
|
||||
<number>10</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="sliderPosition">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="tracking">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="invertedAppearance">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="invertedControls">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="wrapping">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="notchTarget">
|
||||
<double>90.000000000000000</double>
|
||||
</property>
|
||||
<property name="notchesVisible">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_11">
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_7">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_41">
|
||||
<item>
|
||||
<widget class="QLabel" name="label_47">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>14</pointsize>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Elbow Pitch</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QDial" name="dial_33">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>305</width>
|
||||
<height>185</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="minimum">
|
||||
<number>-180</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>180</number>
|
||||
</property>
|
||||
<property name="pageStep">
|
||||
<number>10</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="sliderPosition">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="tracking">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="invertedAppearance">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="invertedControls">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="wrapping">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="notchTarget">
|
||||
<double>90.000000000000000</double>
|
||||
</property>
|
||||
<property name="notchesVisible">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_8">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_12">
|
||||
<item>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_42">
|
||||
<item>
|
||||
<widget class="QLabel" name="label_48">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>14</pointsize>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>End Effector Pitch</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QDial" name="dial_34">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>305</width>
|
||||
<height>185</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="minimum">
|
||||
<number>-180</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>180</number>
|
||||
</property>
|
||||
<property name="pageStep">
|
||||
<number>10</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="sliderPosition">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="tracking">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="invertedAppearance">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="invertedControls">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="wrapping">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="notchTarget">
|
||||
<double>90.000000000000000</double>
|
||||
</property>
|
||||
<property name="notchesVisible">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QVBoxLayout" name="verticalLayout_43">
|
||||
<item>
|
||||
<widget class="QLabel" name="label_49">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>14</pointsize>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>End Effector Rotation</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QDial" name="dial_35">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>305</width>
|
||||
<height>185</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="minimum">
|
||||
<number>-180</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>180</number>
|
||||
</property>
|
||||
<property name="pageStep">
|
||||
<number>10</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="sliderPosition">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="tracking">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="invertedAppearance">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="invertedControls">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="wrapping">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="notchTarget">
|
||||
<double>90.000000000000000</double>
|
||||
</property>
|
||||
<property name="notchesVisible">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="verticalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>3</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="Line" name="line">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
@@ -108,26 +561,207 @@
|
||||
<height>360</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color:black;;</string>
|
||||
</property>
|
||||
<layout class="QGridLayout" name="gridLayout">
|
||||
<property name="margin">
|
||||
<property name="leftMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item row="0" column="0">
|
||||
<widget class="QLabel" name="compass_label">
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
<item row="0" column="1">
|
||||
<widget class="Line" name="line_2">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="0">
|
||||
<layout class="QVBoxLayout" name="verticalLayout_5">
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
<layout class="QGridLayout" name="gridLayout_2">
|
||||
<property name="leftMargin">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="current_heading_label">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>14</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>260°</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<spacer name="horizontalSpacer_2">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item row="0" column="0">
|
||||
<widget class="QLabel" name="label_8">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>17</pointsize>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Heading</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="2">
|
||||
<widget class="QLabel" name="label_10">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>17</pointsize>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Next Goal</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="2">
|
||||
<widget class="QLabel" name="next_goal_label">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>14</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>258°</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="verticalSpacer_6">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>40</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_7">
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_4">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="heading_compass_label">
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>275</width>
|
||||
<height>275</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>275</width>
|
||||
<height>275</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
<property name="scaledContents">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="horizontalSpacer_5">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="verticalSpacer_5">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>40</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</item>
|
||||
@@ -152,6 +786,21 @@
|
||||
</size>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout">
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="leftMargin">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QLabel" name="label">
|
||||
<property name="font">
|
||||
@@ -170,19 +819,51 @@
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="label_2">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>22</pointsize>
|
||||
</font>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout_2">
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>2.4 m/s</string>
|
||||
<item>
|
||||
<widget class="QLabel" name="label_2">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>22</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>0.0</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="label_7">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>22</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>m/s</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="verticalSpacer_3">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>40</height>
|
||||
</size>
|
||||
</property>
|
||||
</widget>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="label_3">
|
||||
@@ -202,13 +883,19 @@
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QProgressBar" name="progressBar">
|
||||
<widget class="QProgressBar" name="speed_limit_progress_bar">
|
||||
<property name="maximum">
|
||||
<number>100</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>50</number>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
<property name="textVisible">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
@@ -220,6 +907,19 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<spacer name="verticalSpacer_4">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>40</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="label_4">
|
||||
<property name="font">
|
||||
@@ -238,18 +938,88 @@
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QProgressBar" name="progressBar_3">
|
||||
<property name="value">
|
||||
<number>0</number>
|
||||
<layout class="QFormLayout" name="formLayout">
|
||||
<property name="horizontalSpacing">
|
||||
<number>6</number>
|
||||
</property>
|
||||
</widget>
|
||||
<item row="0" column="0">
|
||||
<widget class="QLabel" name="label_5">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string> Left</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="0" column="1">
|
||||
<widget class="QProgressBar" name="left_drive_progress_bar">
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color:darkred;</string>
|
||||
</property>
|
||||
<property name="minimum">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>100</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="textVisible">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="0">
|
||||
<widget class="QLabel" name="label_6">
|
||||
<property name="font">
|
||||
<font>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Right</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<widget class="QProgressBar" name="right_drive_progress_bar">
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color:darkred;</string>
|
||||
</property>
|
||||
<property name="minimum">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>100</number>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="textVisible">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QProgressBar" name="progressBar_2">
|
||||
<property name="value">
|
||||
<number>0</number>
|
||||
<spacer name="verticalSpacer_2">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Vertical</enum>
|
||||
</property>
|
||||
</widget>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>20</width>
|
||||
<height>40</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
|
||||
@@ -98,14 +98,14 @@ class GroundStation(QtCore.QObject):
|
||||
|
||||
# ##### Instantiate Threaded Classes ######
|
||||
self.__add_thread("Video Coordinator", RoverVideoCoordinator.RoverVideoCoordinator(self.shared_objects))
|
||||
self.__add_thread("Map Coordinator", RoverMapCoordinator.RoverMapCoordinator(self.shared_objects))
|
||||
# self.__add_thread("Map Coordinator", RoverMapCoordinator.RoverMapCoordinator(self.shared_objects))
|
||||
self.__add_thread("Rover Drive Sender", RoverDriveSender.RoverDriveSender(self.shared_objects))
|
||||
self.connect_signals_and_slots_signal.emit()
|
||||
self.__connect_signals_to_slots()
|
||||
self.start_threads_signal.emit()
|
||||
|
||||
compass_image = PIL.Image.open("Resources/Images/compass.png").resize((300, 300)) # PIL.Image
|
||||
self.shared_objects["screens"]["right_screen"].compass_label.setPixmap(QtGui.QPixmap.fromImage(ImageQt(compass_image)))
|
||||
self.shared_objects["screens"]["right_screen"].heading_compass_label.setPixmap(QtGui.QPixmap.fromImage(ImageQt(compass_image)))
|
||||
|
||||
def ___ros_master_running(self):
|
||||
checker = ROSMasterChecker.ROSMasterChecker()
|
||||
|
||||
Reference in New Issue
Block a user