mirror of
https://github.com/OSURoboticsClub/Rover_2017_2018.git
synced 2025-11-08 10:11:14 +00:00
Minor changes to rdf and a low res mode for video.
This commit is contained in:
15
software/firmware/freq_testing/freq_testing.ino
Normal file
15
software/firmware/freq_testing/freq_testing.ino
Normal file
@@ -0,0 +1,15 @@
|
|||||||
|
float freq = 1.5;
|
||||||
|
int pin = 13;
|
||||||
|
// convert freq to mills
|
||||||
|
float mills = (1/freq)*1000;
|
||||||
|
|
||||||
|
void setup(){
|
||||||
|
pinMode(pin, OUTPUT);
|
||||||
|
}
|
||||||
|
|
||||||
|
void loop(){
|
||||||
|
digitalWrite(pin,LOW);
|
||||||
|
delay(mills);
|
||||||
|
digitalWrite(pin, HIGH);
|
||||||
|
delay(mills);
|
||||||
|
}
|
||||||
@@ -22,6 +22,9 @@ enum HARDWARE {
|
|||||||
MOTOR_TILT_EN = 33,
|
MOTOR_TILT_EN = 33,
|
||||||
MOTOR_TILT_FB = A11,
|
MOTOR_TILT_FB = A11,
|
||||||
|
|
||||||
|
CAMERA_CONTROL = 0,
|
||||||
|
CAMERA_VIDEO_EN = 1,
|
||||||
|
|
||||||
LED_13 = 13,
|
LED_13 = 13,
|
||||||
|
|
||||||
LED_RED = 20,
|
LED_RED = 20,
|
||||||
@@ -119,6 +122,10 @@ void setup_hardware() {
|
|||||||
pinMode(HARDWARE::MOTOR_TILT_CS, INPUT);
|
pinMode(HARDWARE::MOTOR_TILT_CS, INPUT);
|
||||||
pinMode(HARDWARE::MOTOR_TILT_FB, INPUT);
|
pinMode(HARDWARE::MOTOR_TILT_FB, INPUT);
|
||||||
|
|
||||||
|
|
||||||
|
pinMode(HARDWARE::CAMERA_CONTROL, OUTPUT);
|
||||||
|
pinMode(HARDWARE::CAMERA_VIDEO_EN, OUTPUT);
|
||||||
|
|
||||||
pinMode(HARDWARE::LED_13, OUTPUT);
|
pinMode(HARDWARE::LED_13, OUTPUT);
|
||||||
pinMode(HARDWARE::LED_RED, OUTPUT);
|
pinMode(HARDWARE::LED_RED, OUTPUT);
|
||||||
pinMode(HARDWARE::LED_BLUE, OUTPUT);
|
pinMode(HARDWARE::LED_BLUE, OUTPUT);
|
||||||
@@ -132,6 +139,8 @@ void setup_hardware() {
|
|||||||
digitalWrite(HARDWARE::MOTOR_LIFT_EN, HIGH);
|
digitalWrite(HARDWARE::MOTOR_LIFT_EN, HIGH);
|
||||||
digitalWrite(HARDWARE::MOTOR_TILT_EN, HIGH);
|
digitalWrite(HARDWARE::MOTOR_TILT_EN, HIGH);
|
||||||
|
|
||||||
|
digitalWrite(HARDWARE::CAMERA_VIDEO_EN, HIGH);
|
||||||
|
|
||||||
// Change motor PWM frequency so it's not in the audible range
|
// Change motor PWM frequency so it's not in the audible range
|
||||||
analogWriteFrequency(HARDWARE::MOTOR_LIFT_PWM, 25000);
|
analogWriteFrequency(HARDWARE::MOTOR_LIFT_PWM, 25000);
|
||||||
analogWriteFrequency(HARDWARE::MOTOR_TILT_PWM, 25000);
|
analogWriteFrequency(HARDWARE::MOTOR_TILT_PWM, 25000);
|
||||||
|
|||||||
@@ -14,9 +14,9 @@ import paramiko
|
|||||||
#####################################
|
#####################################
|
||||||
THREAD_HERTZ = 5
|
THREAD_HERTZ = 5
|
||||||
|
|
||||||
IP = "192.168.1.127"
|
IP = "192.168.1.10"
|
||||||
USER = "caperren"
|
USER = "nvidia"
|
||||||
PASS = "ult1m2t3!"
|
PASS = "nvidia"
|
||||||
|
|
||||||
|
|
||||||
#####################################
|
#####################################
|
||||||
@@ -81,6 +81,8 @@ class BashConsole(QtCore.QThread):
|
|||||||
self.ssh_client.connect(IP, username=USER, password=PASS, compress=True)
|
self.ssh_client.connect(IP, username=USER, password=PASS, compress=True)
|
||||||
except:
|
except:
|
||||||
print "No connection"
|
print "No connection"
|
||||||
|
if not self.run_thread_flag:
|
||||||
|
return
|
||||||
self.ssh_client = None
|
self.ssh_client = None
|
||||||
self.msleep(1000)
|
self.msleep(1000)
|
||||||
|
|
||||||
|
|||||||
@@ -20,6 +20,13 @@ RDF_DATA_TOPIC = "/rover_science/rdf/data"
|
|||||||
THREAD_HERTZ = 5
|
THREAD_HERTZ = 5
|
||||||
|
|
||||||
|
|
||||||
|
COLOR_GREEN = "background-color:darkgreen;"
|
||||||
|
COLOR_RED = "background-color:darkred;"
|
||||||
|
|
||||||
|
|
||||||
|
ALLOWED_RDF_VARIANCE = 0.15
|
||||||
|
|
||||||
|
|
||||||
#####################################
|
#####################################
|
||||||
# UbiquitiRadioSettings Class Definition
|
# UbiquitiRadioSettings Class Definition
|
||||||
#####################################
|
#####################################
|
||||||
@@ -28,6 +35,9 @@ class RDF(QtCore.QThread):
|
|||||||
rssi_lcd_number_update_ready__signal = QtCore.pyqtSignal(int)
|
rssi_lcd_number_update_ready__signal = QtCore.pyqtSignal(int)
|
||||||
beacon_lcd_number_update_ready__signal = QtCore.pyqtSignal(float)
|
beacon_lcd_number_update_ready__signal = QtCore.pyqtSignal(float)
|
||||||
|
|
||||||
|
beacon_valid_text_change_ready__signal = QtCore.pyqtSignal(str)
|
||||||
|
beacon_valid_stylesheet_change_ready__signal = QtCore.pyqtSignal(str)
|
||||||
|
|
||||||
def __init__(self, shared_objects):
|
def __init__(self, shared_objects):
|
||||||
super(RDF, self).__init__()
|
super(RDF, self).__init__()
|
||||||
|
|
||||||
@@ -37,6 +47,7 @@ class RDF(QtCore.QThread):
|
|||||||
|
|
||||||
self.rssi_lcdnumber = self.left_screen.rssi_lcdnumber # type:QtWidgets.QLCDNumber
|
self.rssi_lcdnumber = self.left_screen.rssi_lcdnumber # type:QtWidgets.QLCDNumber
|
||||||
self.beacon_frequency_lcd_number = self.left_screen.beacon_frequency_lcd_number # type:QtWidgets.QLCDNumber
|
self.beacon_frequency_lcd_number = self.left_screen.beacon_frequency_lcd_number # type:QtWidgets.QLCDNumber
|
||||||
|
self.beacon_frequency_valid_label = self.left_screen.beacon_frequency_valid_label # type:QtWidgets.QLCDNumber
|
||||||
|
|
||||||
# ########## Get the settings instance ##########
|
# ########## Get the settings instance ##########
|
||||||
self.settings = QtCore.QSettings()
|
self.settings = QtCore.QSettings()
|
||||||
@@ -58,6 +69,9 @@ class RDF(QtCore.QThread):
|
|||||||
self.raw_data_timestamps = numpy.array([])
|
self.raw_data_timestamps = numpy.array([])
|
||||||
self.data_window_size = 200
|
self.data_window_size = 200
|
||||||
|
|
||||||
|
self.previous_frequencies = []
|
||||||
|
self.num_previous_frequencies = 3
|
||||||
|
|
||||||
def run(self):
|
def run(self):
|
||||||
self.logger.debug("Starting RDF Thread")
|
self.logger.debug("Starting RDF Thread")
|
||||||
|
|
||||||
@@ -92,9 +106,30 @@ class RDF(QtCore.QThread):
|
|||||||
|
|
||||||
max_index = numpy.argmax(numpy.abs(yf))
|
max_index = numpy.argmax(numpy.abs(yf))
|
||||||
freq = xf[max_index]
|
freq = xf[max_index]
|
||||||
|
|
||||||
|
if len(self.previous_frequencies) == self.num_previous_frequencies:
|
||||||
|
del self.previous_frequencies[0]
|
||||||
|
|
||||||
|
self.previous_frequencies.append(freq)
|
||||||
|
|
||||||
|
if len(self.previous_frequencies) == self.num_previous_frequencies:
|
||||||
|
variance_too_large = False
|
||||||
|
|
||||||
|
if abs(self.previous_frequencies[0] - self.previous_frequencies[1]) > ALLOWED_RDF_VARIANCE:
|
||||||
|
variance_too_large = True
|
||||||
|
|
||||||
|
if abs(self.previous_frequencies[0] - self.previous_frequencies[2]) > ALLOWED_RDF_VARIANCE:
|
||||||
|
variance_too_large = True
|
||||||
|
|
||||||
|
if abs(self.previous_frequencies[1] - self.previous_frequencies[2]) > ALLOWED_RDF_VARIANCE:
|
||||||
|
variance_too_large = True
|
||||||
|
|
||||||
|
self.beacon_valid_stylesheet_change_ready__signal.emit(COLOR_GREEN if not variance_too_large else COLOR_RED)
|
||||||
|
self.beacon_valid_text_change_ready__signal.emit("Yes" if not variance_too_large else "No")
|
||||||
|
|
||||||
self.beacon_lcd_number_update_ready__signal.emit(freq)
|
self.beacon_lcd_number_update_ready__signal.emit(freq)
|
||||||
except:
|
except Exception, e:
|
||||||
pass
|
print e
|
||||||
|
|
||||||
self.raw_data = numpy.array([])
|
self.raw_data = numpy.array([])
|
||||||
self.raw_data_timestamps = numpy.array([])
|
self.raw_data_timestamps = numpy.array([])
|
||||||
@@ -119,6 +154,9 @@ class RDF(QtCore.QThread):
|
|||||||
self.rssi_lcd_number_update_ready__signal.connect(self.rssi_lcdnumber.display)
|
self.rssi_lcd_number_update_ready__signal.connect(self.rssi_lcdnumber.display)
|
||||||
self.beacon_lcd_number_update_ready__signal.connect(self.beacon_frequency_lcd_number.display)
|
self.beacon_lcd_number_update_ready__signal.connect(self.beacon_frequency_lcd_number.display)
|
||||||
|
|
||||||
|
self.beacon_valid_text_change_ready__signal.connect(self.beacon_frequency_valid_label.setText)
|
||||||
|
self.beacon_valid_stylesheet_change_ready__signal.connect(self.beacon_frequency_valid_label.setStyleSheet)
|
||||||
|
|
||||||
def setup_signals(self, start_signal, signals_and_slots_signal, kill_signal):
|
def setup_signals(self, start_signal, signals_and_slots_signal, kill_signal):
|
||||||
start_signal.connect(self.start)
|
start_signal.connect(self.start)
|
||||||
signals_and_slots_signal.connect(self.connect_signals_and_slots)
|
signals_and_slots_signal.connect(self.connect_signals_and_slots)
|
||||||
|
|||||||
@@ -22,11 +22,16 @@ PRIMARY_LABEL_MAX = (640, 360)
|
|||||||
SECONDARY_LABEL_MAX = (640, 360)
|
SECONDARY_LABEL_MAX = (640, 360)
|
||||||
TERTIARY_LABEL_MAX = (640, 360)
|
TERTIARY_LABEL_MAX = (640, 360)
|
||||||
|
|
||||||
|
LOW_RES = (256, 144)
|
||||||
|
|
||||||
GUI_SELECTION_CHANGE_TIMEOUT = 3 # Seconds
|
GUI_SELECTION_CHANGE_TIMEOUT = 3 # Seconds
|
||||||
|
|
||||||
STYLESHEET_SELECTED = "border: 2px solid orange; background-color:black;"
|
STYLESHEET_SELECTED = "border: 2px solid orange; background-color:black;"
|
||||||
STYLESHEET_UNSELECTED = "background-color:black;"
|
STYLESHEET_UNSELECTED = "background-color:black;"
|
||||||
|
|
||||||
|
COLOR_GREEN = "background-color: darkgreen;"
|
||||||
|
COLOR_RED = "background-color: darkred;"
|
||||||
|
|
||||||
|
|
||||||
#####################################
|
#####################################
|
||||||
# RoverVideoCoordinator Class Definition
|
# RoverVideoCoordinator Class Definition
|
||||||
@@ -38,6 +43,9 @@ class RoverVideoCoordinator(QtCore.QThread):
|
|||||||
|
|
||||||
pan_tilt_selection_changed__signal = QtCore.pyqtSignal(str)
|
pan_tilt_selection_changed__signal = QtCore.pyqtSignal(str)
|
||||||
|
|
||||||
|
low_res_button_text_update_ready__signal = QtCore.pyqtSignal(str)
|
||||||
|
low_res_button_stylesheet_update_ready__signal = QtCore.pyqtSignal(str)
|
||||||
|
|
||||||
def __init__(self, shared_objects):
|
def __init__(self, shared_objects):
|
||||||
super(RoverVideoCoordinator, self).__init__()
|
super(RoverVideoCoordinator, self).__init__()
|
||||||
|
|
||||||
@@ -48,6 +56,8 @@ class RoverVideoCoordinator(QtCore.QThread):
|
|||||||
self.secondary_video_display_label = self.right_screen.secondary_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.tertiary_video_display_label = self.right_screen.tertiary_video_label # type:QtWidgets.QLabel
|
||||||
|
|
||||||
|
self.low_res_mode_button = self.right_screen.low_res_mode_button # type: QtWidgets.QLabel
|
||||||
|
|
||||||
self.index_to_label_element = {
|
self.index_to_label_element = {
|
||||||
0: self.primary_video_display_label,
|
0: self.primary_video_display_label,
|
||||||
1: self.secondary_video_display_label,
|
1: self.secondary_video_display_label,
|
||||||
@@ -107,6 +117,8 @@ class RoverVideoCoordinator(QtCore.QThread):
|
|||||||
|
|
||||||
self.first_image_received = False
|
self.first_image_received = False
|
||||||
|
|
||||||
|
self.in_low_res_mode = False
|
||||||
|
|
||||||
def run(self):
|
def run(self):
|
||||||
self.logger.debug("Starting Video Coordinator Thread")
|
self.logger.debug("Starting Video Coordinator Thread")
|
||||||
|
|
||||||
@@ -140,13 +152,17 @@ class RoverVideoCoordinator(QtCore.QThread):
|
|||||||
|
|
||||||
def __set_max_resolutions(self):
|
def __set_max_resolutions(self):
|
||||||
if self.set_max_resolutions_flag:
|
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.in_low_res_mode:
|
||||||
|
for camera in self.camera_threads:
|
||||||
|
self.camera_threads[camera].set_hard_max_resolution(LOW_RES)
|
||||||
|
else:
|
||||||
|
self.camera_threads[self.valid_cameras[self.primary_label_current_setting]].set_hard_max_resolution(PRIMARY_LABEL_MAX)
|
||||||
|
|
||||||
if self.secondary_label_current_setting != self.primary_label_current_setting:
|
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)
|
self.camera_threads[self.valid_cameras[self.secondary_label_current_setting]].set_hard_max_resolution(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:
|
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)
|
self.camera_threads[self.valid_cameras[self.tertiary_label_current_setting]].set_hard_max_resolution(SECONDARY_LABEL_MAX)
|
||||||
|
|
||||||
self.set_max_resolutions_flag = False
|
self.set_max_resolutions_flag = False
|
||||||
|
|
||||||
@@ -242,6 +258,10 @@ class RoverVideoCoordinator(QtCore.QThread):
|
|||||||
self.shared_objects["threaded_classes"]["Joystick Sender"].toggle_selected_gui_camera__signal.connect(
|
self.shared_objects["threaded_classes"]["Joystick Sender"].toggle_selected_gui_camera__signal.connect(
|
||||||
self.on_gui_selected_camera_toggled)
|
self.on_gui_selected_camera_toggled)
|
||||||
|
|
||||||
|
self.low_res_mode_button.clicked.connect(self.on_low_res_button_clicked__slot)
|
||||||
|
self.low_res_button_text_update_ready__signal.connect(self.low_res_mode_button.setText)
|
||||||
|
self.low_res_button_stylesheet_update_ready__signal.connect(self.low_res_mode_button.setStyleSheet)
|
||||||
|
|
||||||
self.update_element_stylesheet__signal.connect(self.__on_gui_element_stylesheet_update__slot)
|
self.update_element_stylesheet__signal.connect(self.__on_gui_element_stylesheet_update__slot)
|
||||||
|
|
||||||
def setup_signals(self, start_signal, signals_and_slots_signal, kill_signal):
|
def setup_signals(self, start_signal, signals_and_slots_signal, kill_signal):
|
||||||
@@ -353,5 +373,19 @@ class RoverVideoCoordinator(QtCore.QThread):
|
|||||||
|
|
||||||
self.update_element_stylesheet__signal.emit()
|
self.update_element_stylesheet__signal.emit()
|
||||||
|
|
||||||
|
def on_low_res_button_clicked__slot(self):
|
||||||
|
if self.low_res_mode_button.text() == "ENABLED":
|
||||||
|
self.in_low_res_mode = False
|
||||||
|
self.set_max_resolutions_flag = True
|
||||||
|
|
||||||
|
self.low_res_button_text_update_ready__signal.emit("DISABLED")
|
||||||
|
self.low_res_button_stylesheet_update_ready__signal.emit(COLOR_GREEN)
|
||||||
|
else:
|
||||||
|
self.in_low_res_mode = False
|
||||||
|
self.set_max_resolutions_flag = True
|
||||||
|
|
||||||
|
self.low_res_button_text_update_ready__signal.emit("ENABLED")
|
||||||
|
self.low_res_button_stylesheet_update_ready__signal.emit(COLOR_RED)
|
||||||
|
|
||||||
def on_kill_threads_requested__slot(self):
|
def on_kill_threads_requested__slot(self):
|
||||||
self.run_thread_flag = False
|
self.run_thread_flag = False
|
||||||
|
|||||||
@@ -146,6 +146,8 @@ class RoverVideoReceiver(QtCore.QThread):
|
|||||||
self.current_resolution_index = min(self.current_resolution_index + 1, self.max_resolution_index)
|
self.current_resolution_index = min(self.current_resolution_index + 1, self.max_resolution_index)
|
||||||
elif current_fps <= MIN_FRAMERATE_BEFORE_ADJUST:
|
elif current_fps <= MIN_FRAMERATE_BEFORE_ADJUST:
|
||||||
self.current_resolution_index = max(self.current_resolution_index - 1, 0)
|
self.current_resolution_index = max(self.current_resolution_index - 1, 0)
|
||||||
|
else:
|
||||||
|
self.current_resolution_index = min(self.current_resolution_index, self.max_resolution_index)
|
||||||
|
|
||||||
if self.last_resolution_index != self.current_resolution_index:
|
if self.last_resolution_index != self.current_resolution_index:
|
||||||
self.camera_control_publisher.publish(
|
self.camera_control_publisher.publish(
|
||||||
|
|||||||
@@ -1390,14 +1390,14 @@ N/A</string>
|
|||||||
</size>
|
</size>
|
||||||
</property>
|
</property>
|
||||||
<property name="currentIndex">
|
<property name="currentIndex">
|
||||||
<number>0</number>
|
<number>1</number>
|
||||||
</property>
|
</property>
|
||||||
<widget class="QWidget" name="tab_5">
|
<widget class="QWidget" name="tab_5">
|
||||||
<attribute name="title">
|
<attribute name="title">
|
||||||
<string>RDF</string>
|
<string>RDF</string>
|
||||||
</attribute>
|
</attribute>
|
||||||
<layout class="QGridLayout" name="gridLayout_16">
|
<layout class="QGridLayout" name="gridLayout_16">
|
||||||
<item row="1" column="0">
|
<item row="2" column="0">
|
||||||
<spacer name="verticalSpacer_6">
|
<spacer name="verticalSpacer_6">
|
||||||
<property name="orientation">
|
<property name="orientation">
|
||||||
<enum>Qt::Vertical</enum>
|
<enum>Qt::Vertical</enum>
|
||||||
@@ -1441,7 +1441,27 @@ N/A</string>
|
|||||||
</layout>
|
</layout>
|
||||||
</item>
|
</item>
|
||||||
<item>
|
<item>
|
||||||
<layout class="QVBoxLayout" name="verticalLayout_22">
|
<layout class="QVBoxLayout" name="verticalLayout_22"/>
|
||||||
|
</item>
|
||||||
|
</layout>
|
||||||
|
</item>
|
||||||
|
<item row="0" column="1">
|
||||||
|
<spacer name="horizontalSpacer_19">
|
||||||
|
<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="1" column="0">
|
||||||
|
<layout class="QHBoxLayout" name="horizontalLayout_20">
|
||||||
|
<item>
|
||||||
|
<layout class="QVBoxLayout" name="verticalLayout_23">
|
||||||
<item>
|
<item>
|
||||||
<widget class="QLabel" name="label_32">
|
<widget class="QLabel" name="label_32">
|
||||||
<property name="font">
|
<property name="font">
|
||||||
@@ -1468,21 +1488,57 @@ N/A</string>
|
|||||||
</item>
|
</item>
|
||||||
</layout>
|
</layout>
|
||||||
</item>
|
</item>
|
||||||
|
<item>
|
||||||
|
<widget class="Line" name="line_12">
|
||||||
|
<property name="orientation">
|
||||||
|
<enum>Qt::Vertical</enum>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
<item>
|
||||||
|
<layout class="QVBoxLayout" name="verticalLayout_24">
|
||||||
|
<item>
|
||||||
|
<widget class="QLabel" name="label_33">
|
||||||
|
<property name="font">
|
||||||
|
<font>
|
||||||
|
<pointsize>16</pointsize>
|
||||||
|
<weight>75</weight>
|
||||||
|
<bold>true</bold>
|
||||||
|
</font>
|
||||||
|
</property>
|
||||||
|
<property name="text">
|
||||||
|
<string>Frequency Valid</string>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
<item>
|
||||||
|
<widget class="QLabel" name="beacon_frequency_valid_label">
|
||||||
|
<property name="minimumSize">
|
||||||
|
<size>
|
||||||
|
<width>0</width>
|
||||||
|
<height>150</height>
|
||||||
|
</size>
|
||||||
|
</property>
|
||||||
|
<property name="font">
|
||||||
|
<font>
|
||||||
|
<pointsize>24</pointsize>
|
||||||
|
</font>
|
||||||
|
</property>
|
||||||
|
<property name="styleSheet">
|
||||||
|
<string notr="true">background-color:darkred;</string>
|
||||||
|
</property>
|
||||||
|
<property name="text">
|
||||||
|
<string>No</string>
|
||||||
|
</property>
|
||||||
|
<property name="alignment">
|
||||||
|
<set>Qt::AlignCenter</set>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
</layout>
|
||||||
|
</item>
|
||||||
</layout>
|
</layout>
|
||||||
</item>
|
</item>
|
||||||
<item row="0" column="1">
|
|
||||||
<spacer name="horizontalSpacer_19">
|
|
||||||
<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>
|
</layout>
|
||||||
</widget>
|
</widget>
|
||||||
<widget class="QWidget" name="tab_4">
|
<widget class="QWidget" name="tab_4">
|
||||||
@@ -1527,6 +1583,9 @@ N/A</string>
|
|||||||
<layout class="QGridLayout" name="gridLayout_13">
|
<layout class="QGridLayout" name="gridLayout_13">
|
||||||
<item row="3" column="0">
|
<item row="3" column="0">
|
||||||
<widget class="QPushButton" name="arm_control_upright_zeroed_button">
|
<widget class="QPushButton" name="arm_control_upright_zeroed_button">
|
||||||
|
<property name="styleSheet">
|
||||||
|
<string notr="true">background-color: darkred;</string>
|
||||||
|
</property>
|
||||||
<property name="text">
|
<property name="text">
|
||||||
<string>Upright Zeroed</string>
|
<string>Upright Zeroed</string>
|
||||||
</property>
|
</property>
|
||||||
@@ -1534,6 +1593,9 @@ N/A</string>
|
|||||||
</item>
|
</item>
|
||||||
<item row="0" column="0">
|
<item row="0" column="0">
|
||||||
<widget class="QPushButton" name="arm_controls_stow_arm_button">
|
<widget class="QPushButton" name="arm_controls_stow_arm_button">
|
||||||
|
<property name="styleSheet">
|
||||||
|
<string notr="true">background-color: darkred;</string>
|
||||||
|
</property>
|
||||||
<property name="text">
|
<property name="text">
|
||||||
<string>Stow Arm</string>
|
<string>Stow Arm</string>
|
||||||
</property>
|
</property>
|
||||||
@@ -1541,6 +1603,9 @@ N/A</string>
|
|||||||
</item>
|
</item>
|
||||||
<item row="1" column="0">
|
<item row="1" column="0">
|
||||||
<widget class="QPushButton" name="arm_controls_unstow_arm_button">
|
<widget class="QPushButton" name="arm_controls_unstow_arm_button">
|
||||||
|
<property name="styleSheet">
|
||||||
|
<string notr="true">background-color: darkred;</string>
|
||||||
|
</property>
|
||||||
<property name="text">
|
<property name="text">
|
||||||
<string>Unstow Arm</string>
|
<string>Unstow Arm</string>
|
||||||
</property>
|
</property>
|
||||||
|
|||||||
@@ -975,6 +975,9 @@ Position</string>
|
|||||||
<bold>false</bold>
|
<bold>false</bold>
|
||||||
</font>
|
</font>
|
||||||
</property>
|
</property>
|
||||||
|
<property name="styleSheet">
|
||||||
|
<string notr="true">color:red;</string>
|
||||||
|
</property>
|
||||||
<property name="text">
|
<property name="text">
|
||||||
<string/>
|
<string/>
|
||||||
</property>
|
</property>
|
||||||
@@ -1083,6 +1086,9 @@ Position</string>
|
|||||||
<bold>false</bold>
|
<bold>false</bold>
|
||||||
</font>
|
</font>
|
||||||
</property>
|
</property>
|
||||||
|
<property name="styleSheet">
|
||||||
|
<string notr="true">color:red;</string>
|
||||||
|
</property>
|
||||||
<property name="text">
|
<property name="text">
|
||||||
<string/>
|
<string/>
|
||||||
</property>
|
</property>
|
||||||
@@ -1191,6 +1197,9 @@ Position</string>
|
|||||||
<bold>false</bold>
|
<bold>false</bold>
|
||||||
</font>
|
</font>
|
||||||
</property>
|
</property>
|
||||||
|
<property name="styleSheet">
|
||||||
|
<string notr="true">color:red;</string>
|
||||||
|
</property>
|
||||||
<property name="text">
|
<property name="text">
|
||||||
<string/>
|
<string/>
|
||||||
</property>
|
</property>
|
||||||
@@ -2158,11 +2167,84 @@ Position</string>
|
|||||||
</property>
|
</property>
|
||||||
<item>
|
<item>
|
||||||
<layout class="QVBoxLayout" name="verticalLayout_9">
|
<layout class="QVBoxLayout" name="verticalLayout_9">
|
||||||
|
<item>
|
||||||
|
<widget class="QLabel" name="label_9">
|
||||||
|
<property name="font">
|
||||||
|
<font>
|
||||||
|
<pointsize>14</pointsize>
|
||||||
|
<weight>75</weight>
|
||||||
|
<bold>true</bold>
|
||||||
|
</font>
|
||||||
|
</property>
|
||||||
|
<property name="text">
|
||||||
|
<string>Low Res Mode</string>
|
||||||
|
</property>
|
||||||
|
<property name="alignment">
|
||||||
|
<set>Qt::AlignCenter</set>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
<item>
|
||||||
|
<layout class="QHBoxLayout" name="horizontalLayout_5">
|
||||||
|
<property name="bottomMargin">
|
||||||
|
<number>6</number>
|
||||||
|
</property>
|
||||||
|
<item>
|
||||||
|
<spacer name="horizontalSpacer">
|
||||||
|
<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="QPushButton" name="low_res_mode_button">
|
||||||
|
<property name="styleSheet">
|
||||||
|
<string notr="true">background-color:darkgreen</string>
|
||||||
|
</property>
|
||||||
|
<property name="text">
|
||||||
|
<string>DISABLED</string>
|
||||||
|
</property>
|
||||||
|
<property name="checkable">
|
||||||
|
<bool>false</bool>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
<item>
|
||||||
|
<spacer name="horizontalSpacer_3">
|
||||||
|
<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>
|
||||||
|
<widget class="Line" name="line_3">
|
||||||
|
<property name="orientation">
|
||||||
|
<enum>Qt::Horizontal</enum>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
<item>
|
<item>
|
||||||
<layout class="QVBoxLayout" name="verticalLayout_10">
|
<layout class="QVBoxLayout" name="verticalLayout_10">
|
||||||
<property name="spacing">
|
<property name="spacing">
|
||||||
<number>0</number>
|
<number>0</number>
|
||||||
</property>
|
</property>
|
||||||
|
<property name="topMargin">
|
||||||
|
<number>6</number>
|
||||||
|
</property>
|
||||||
<item>
|
<item>
|
||||||
<layout class="QHBoxLayout" name="horizontalLayout_2">
|
<layout class="QHBoxLayout" name="horizontalLayout_2">
|
||||||
<property name="leftMargin">
|
<property name="leftMargin">
|
||||||
|
|||||||
@@ -35,6 +35,8 @@
|
|||||||
|
|
||||||
<node name="chassis_pan_tilt" pkg="rover_control" type="chassis_pan_tilt_control.py" respawn="true" output="screen"/>
|
<node name="chassis_pan_tilt" pkg="rover_control" type="chassis_pan_tilt_control.py" respawn="true" output="screen"/>
|
||||||
|
|
||||||
<node name="effectors" pkg="rover_control" type="effectors_control.py" respawn="true" output="screen"/>
|
<!--<node name="effectors" pkg="rover_control" type="effectors_control.py" respawn="true" output="screen">-->
|
||||||
|
<!--<param name="port" value="/dev/rover/ttyARM"/>-->
|
||||||
|
<!--</node>-->
|
||||||
</group>
|
</group>
|
||||||
</launch>
|
</launch>
|
||||||
|
|||||||
Reference in New Issue
Block a user