Finished re-write of ground station videoreceiver and videocoordinator to handle new nimbo udp sending, and working auto quality adjustmentgit status!

This commit is contained in:
2018-03-07 00:01:50 -08:00
parent 381eccf4b3
commit 69c4cc6c71
6 changed files with 173 additions and 131 deletions

View File

@@ -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 3
sleep 1
export DISPLAY=:0
python ground_station.py

View File

@@ -9,18 +9,15 @@ 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)
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})
for camera_index, camera_name in enumerate(self.valid_cameras):
if camera_index not in enabled and camera_index not in self.disabled_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()
self.disabled_cameras.append(camera_index)
elif camera_index in enabled and camera_index in self.disabled_cameras:
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()
self.disabled_cameras.remove(camera_index)
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:
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:
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:
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

View File

@@ -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 and self.current_camera_settings["resolution"]:
# self.__perform_quality_check_and_adjust()
if self.new_frame:
self.__check_framerate_and_adjust_resolution()
try:
opencv_image = self.bridge.compressed_imgmsg_to_cv2(self.raw_image, "rgb8")
self.__create_final_pixmaps(opencv_image)
self.image_ready_signal.emit(self.camera_name)
except Exception, error:
print "Failed with error:" + str(error)
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

View File

@@ -2,12 +2,25 @@
<group ns="sender_transports">
<arg name="target" default="192.168.1.10" />
<node name="ground_staion_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_port" value="17020" />
<rosparam param="topics">
[{name: "/rover_control/command_control/ground_station_drive", compress: true, rate: 15.0}]
</rosparam>
</node>
<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_port" value="17021" />
<rosparam param="topics">
[
{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}
]
</rosparam>
</node>
</group>
</launch>

View File

@@ -3,5 +3,9 @@
<node name="ground_station_drive_command" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">
<param name="port" value="17020" />
</node>
<node name="ground_station_tcp_topics" pkg="nimbro_topic_transport" type="tcp_receiver" output="screen">
<param name="port" value="17021" />
</node>
</group>
</launch>

View File

@@ -6,7 +6,7 @@
<param name="destination_addr" value="$(arg target)" />
<param name="destination_port" value="17001" />
<rosparam param="topics">
[{name: "/cameras/chassis/image_1280x720/compressed", compress: false, rate: 30.0}]
[{name: "/cameras/chassis/image_1280x720/compressed", compress: false, rate: 0.0}]
</rosparam>
</node>
@@ -14,7 +14,7 @@
<param name="destination_addr" value="$(arg target)" />
<param name="destination_port" value="17002" />
<rosparam param="topics">
[{name: "/cameras/undercarriage/image_1280x720/compressed", compress: false, rate: 30.0}]
[{name: "/cameras/undercarriage/image_1280x720/compressed", compress: false, rate: 0.0}]
</rosparam>
</node>
@@ -22,7 +22,7 @@
<param name="destination_addr" value="$(arg target)" />
<param name="destination_port" value="17003" />
<rosparam param="topics">
[{name: "/cameras/main_navigation/image_1280x720/compressed", compress: false, rate: 30.0}]
[{name: "/cameras/main_navigation/image_1280x720/compressed", compress: false, rate: 0.0}]
</rosparam>
</node>
@@ -30,7 +30,7 @@
<param name="destination_addr" value="$(arg target)" />
<param name="destination_port" value="17004" />
<rosparam param="topics">
[{name: "/cameras/end_effector/image_1280x720/compressed", compress: false, rate: 30.0}]
[{name: "/cameras/end_effector/image_1280x720/compressed", compress: false, rate: 0.0}]
</rosparam>
</node>
@@ -38,7 +38,7 @@
<param name="destination_addr" value="$(arg target)" />
<param name="destination_port" value="17005" />
<rosparam param="topics">
[{name: "/cameras/chassis/image_640x360/compressed", compress: false, rate: 30.0}]
[{name: "/cameras/chassis/image_640x360/compressed", compress: false, rate: 0.0}]
</rosparam>
</node>
@@ -46,7 +46,7 @@
<param name="destination_addr" value="$(arg target)" />
<param name="destination_port" value="17006" />
<rosparam param="topics">
[{name: "/cameras/undercarriage/image_640x360/compressed", compress: false, rate: 30.0}]
[{name: "/cameras/undercarriage/image_640x360/compressed", compress: false, rate: 0.0}]
</rosparam>
</node>
@@ -54,7 +54,7 @@
<param name="destination_addr" value="$(arg target)" />
<param name="destination_port" value="17007" />
<rosparam param="topics">
[{name: "/cameras/main_navigation/image_640x360/compressed", compress: false, rate: 30.0}]
[{name: "/cameras/main_navigation/image_640x360/compressed", compress: false, rate: 0.0}]
</rosparam>
</node>
@@ -62,7 +62,7 @@
<param name="destination_addr" value="$(arg target)" />
<param name="destination_port" value="17008" />
<rosparam param="topics">
[{name: "/cameras/end_effector/image_640x360/compressed", compress: false, rate: 30.0}]
[{name: "/cameras/end_effector/image_640x360/compressed", compress: false, rate: 0.0}]
</rosparam>
</node>
@@ -70,7 +70,7 @@
<param name="destination_addr" value="$(arg target)" />
<param name="destination_port" value="17009" />
<rosparam param="topics">
[{name: "/cameras/chassis/image_256x144/compressed", compress: false, rate: 30.0}]
[{name: "/cameras/chassis/image_256x144/compressed", compress: false, rate: 0.0}]
</rosparam>
</node>
@@ -78,7 +78,7 @@
<param name="destination_addr" value="$(arg target)" />
<param name="destination_port" value="17010" />
<rosparam param="topics">
[{name: "/cameras/undercarriage/image_256x144/compressed", compress: false, rate: 30.0}]
[{name: "/cameras/undercarriage/image_256x144/compressed", compress: false, rate: 0.0}]
</rosparam>
</node>
@@ -86,7 +86,7 @@
<param name="destination_addr" value="$(arg target)" />
<param name="destination_port" value="17011" />
<rosparam param="topics">
[{name: "/cameras/main_navigation/image_256x144/compressed", compress: false, rate: 30.0}]
[{name: "/cameras/main_navigation/image_256x144/compressed", compress: false, rate: 0.0}]
</rosparam>
</node>
@@ -94,7 +94,7 @@
<param name="destination_addr" value="$(arg target)" />
<param name="destination_port" value="17012" />
<rosparam param="topics">
[{name: "/cameras/end_effector/image_256x144/compressed", compress: false, rate: 30.0}]
[{name: "/cameras/end_effector/image_256x144/compressed", compress: false, rate: 0.0}]
</rosparam>
</node>
</group>