mirror of
https://github.com/OSURoboticsClub/Rover_2017_2018.git
synced 2025-11-08 18:21:15 +00:00
Fixed some gui elements. Added pause / speed control to remote drive.
This commit is contained in:
@@ -19,6 +19,11 @@ DEFAULT_DRIVE_COMMAND_TOPIC = "/rover_control/command_control/ground_station_dri
|
|||||||
|
|
||||||
DRIVE_COMMAND_HERTZ = 15
|
DRIVE_COMMAND_HERTZ = 15
|
||||||
|
|
||||||
|
Y_AXIS_DEADBAND = 0.015
|
||||||
|
X_AXIS_DEADBAND = 0.025
|
||||||
|
|
||||||
|
THROTTLE_MIN = 0.05
|
||||||
|
|
||||||
|
|
||||||
#####################################
|
#####################################
|
||||||
# Controller Class Definition
|
# Controller Class Definition
|
||||||
@@ -37,59 +42,51 @@ class LogitechJoystick(QtCore.QThread):
|
|||||||
self.gamepad = None # type: GamePad
|
self.gamepad = None # type: GamePad
|
||||||
|
|
||||||
self.controller_states = {
|
self.controller_states = {
|
||||||
"left_stick_x_axis": 0,
|
"x_axis": 512,
|
||||||
"y_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,
|
"z_axis": 128,
|
||||||
"right_bumper_pressed": 0,
|
"throttle_axis": 128,
|
||||||
|
|
||||||
"dpad_x": 0,
|
"hat_x_axis": 0,
|
||||||
"dpad_y": 0,
|
"hat_y_axis": 0,
|
||||||
|
|
||||||
"select_pressed": 0,
|
"trigger_pressed": 0,
|
||||||
"start_pressed": 0,
|
"thumb_pressed": 0,
|
||||||
"home_pressed": 0,
|
"three_pressed": 0,
|
||||||
|
"four_pressed": 0,
|
||||||
|
"five_pressed": 0,
|
||||||
|
"six_pressed": 0,
|
||||||
|
|
||||||
"a_pressed": 0,
|
"eleven_pressed": 0,
|
||||||
"b_pressed": 0,
|
"twelve_pressed": 0,
|
||||||
"x_pressed": 0,
|
"thirteen_pressed": 0,
|
||||||
"y_pressed": 0
|
"fourteen_pressed": 0,
|
||||||
|
"fifteen_pressed": 0,
|
||||||
|
"sixteen_pressed": 0,
|
||||||
}
|
}
|
||||||
|
|
||||||
self.raw_mapping_to_class_mapping = {
|
self.raw_mapping_to_class_mapping = {
|
||||||
"ABS_X": "left_stick_x_axis",
|
"ABS_X": "x_axis",
|
||||||
"ABS_Y": "y_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",
|
"ABS_RZ": "z_axis",
|
||||||
"BTN_TR": "right_bumper_pressed",
|
"ABS_THROTTLE": "throttle_axis",
|
||||||
|
|
||||||
"ABS_HAT0X": "dpad_x",
|
"ABS_HAT0X": "hat_x_axis",
|
||||||
"ABS_HAT0Y": "dpad_y",
|
"ABS_HAT0Y": "hat_y_axis",
|
||||||
|
|
||||||
"BTN_SELECT": "select_pressed",
|
"BTN_TRIGGER": "trigger_pressed",
|
||||||
"BTN_START": "start_pressed",
|
"BTN_THUMB": "thumb_pressed",
|
||||||
"BTN_MODE": "home_pressed",
|
"BTN_THUMB2": "three_pressed",
|
||||||
|
"BTN_TOP": "four_pressed",
|
||||||
|
"BTN_TOP2": "five_pressed",
|
||||||
|
"BTN_PINKIE": "six_pressed",
|
||||||
|
|
||||||
"BTN_SOUTH": "a_pressed",
|
"BTN_BASE5": "eleven_pressed",
|
||||||
"BTN_EAST": "b_pressed",
|
"BTN_BASE6": "twelve_pressed",
|
||||||
"BTN_NORTH": "x_pressed",
|
"BTN_BASE3": "thirteen_pressed",
|
||||||
"BTN_WEST": "y_pressed"
|
"BTN_BASE4": "fourteen_pressed",
|
||||||
|
"BTN_BASE": "fifteen_pressed",
|
||||||
|
"BTN_BASE2": "sixteen_pressed",
|
||||||
}
|
}
|
||||||
|
|
||||||
self.ready = False
|
self.ready = False
|
||||||
@@ -121,23 +118,27 @@ class LogitechJoystick(QtCore.QThread):
|
|||||||
for event in events:
|
for event in events:
|
||||||
if event.code in self.raw_mapping_to_class_mapping:
|
if event.code in self.raw_mapping_to_class_mapping:
|
||||||
self.controller_states[self.raw_mapping_to_class_mapping[event.code]] = event.state
|
self.controller_states[self.raw_mapping_to_class_mapping[event.code]] = event.state
|
||||||
|
|
||||||
self.ready = True
|
self.ready = True
|
||||||
# print "Logitech: %s" % self.controller_states
|
|
||||||
|
|
||||||
|
|
||||||
#####################################
|
#####################################
|
||||||
# Controller Class Definition
|
# Controller Class Definition
|
||||||
#####################################
|
#####################################
|
||||||
class RoverDriveSender(QtCore.QThread):
|
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):
|
def __init__(self, shared_objects):
|
||||||
super(RoverDriveSender, self).__init__()
|
super(RoverDriveSender, self).__init__()
|
||||||
|
|
||||||
# ########## Reference to class init variables ##########
|
# ########## Reference to class init variables ##########
|
||||||
self.shared_objects = shared_objects
|
self.shared_objects = shared_objects
|
||||||
self.right_screen = self.shared_objects["screens"]["right_screen"]
|
self.right_screen = self.shared_objects["screens"]["right_screen"]
|
||||||
self.primary_video_display_label = self.right_screen.primary_video_label # type:QtWidgets.QLabel
|
self.speed_limit_progress_bar = self.right_screen.speed_limit_progress_bar # type: QtWidgets.QProgressBar
|
||||||
self.secondary_video_display_label = self.right_screen.secondary_video_label # type:QtWidgets.QLabel
|
self.left_drive_progress_bar = self.right_screen.left_drive_progress_bar # type: QtWidgets.QProgressBar
|
||||||
self.tertiary_video_display_label = self.right_screen.tertiary_video_label # type:QtWidgets.QLabel
|
self.right_drive_progress_bar = self.right_screen.right_drive_progress_bar # type: QtWidgets.QProgressBar
|
||||||
|
|
||||||
# ########## Get the settings instance ##########
|
# ########## Get the settings instance ##########
|
||||||
self.settings = QtCore.QSettings()
|
self.settings = QtCore.QSettings()
|
||||||
@@ -154,34 +155,82 @@ class RoverDriveSender(QtCore.QThread):
|
|||||||
# Publishers
|
# Publishers
|
||||||
self.drive_command_publisher = rospy.Publisher(DEFAULT_DRIVE_COMMAND_TOPIC, DriveCommandMessage, queue_size=1)
|
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):
|
def run(self):
|
||||||
while self.run_thread_flag:
|
while self.run_thread_flag:
|
||||||
|
|
||||||
start_time = time()
|
start_time = time()
|
||||||
|
|
||||||
|
self.check_and_set_pause_state()
|
||||||
self.__update_and_publish()
|
self.__update_and_publish()
|
||||||
|
|
||||||
time_diff = time() - start_time
|
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):
|
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):
|
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 = DriveCommandMessage()
|
||||||
|
|
||||||
drive_message.drive_twist.linear.x = -(self.joystick.controller_states["y_axis"] - 512) / 1024.0
|
y_axis = throttle_axis * (-(self.joystick.controller_states["y_axis"] - 512) / 512.0)
|
||||||
drive_message.drive_twist.angular.z = -(self.joystick.controller_states["z_axis"] - 128) / 255.0
|
z_axis = throttle_axis * (-(self.joystick.controller_states["z_axis"] - 128) / 128.0)
|
||||||
self.drive_command_publisher.publish(drive_message)
|
x_axis = throttle_axis * (-(self.joystick.controller_states["x_axis"] - 512) / 512.0)
|
||||||
# print self.joystick.controller_states["y_axis"], self.joystick.controller_states["z_axis"]
|
|
||||||
|
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):
|
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)
|
||||||
kill_signal.connect(self.on_kill_threads_requested__slot)
|
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):
|
def on_kill_threads_requested__slot(self):
|
||||||
self.run_thread_flag = False
|
self.run_thread_flag = False
|
||||||
|
|||||||
@@ -76,13 +76,13 @@ class RoverMapCoordinator(QtCore.QThread):
|
|||||||
RoverMap.OverlayImage(44.567161, -123.278432,
|
RoverMap.OverlayImage(44.567161, -123.278432,
|
||||||
self.google_maps_object.northwest,
|
self.google_maps_object.northwest,
|
||||||
self.google_maps_object.southeast,
|
self.google_maps_object.southeast,
|
||||||
self.google_maps_object.big_image[0],
|
self.google_maps_object.big_image.size[0],
|
||||||
self.google_maps_object.big_image[1],
|
self.google_maps_object.big_image.size[1],
|
||||||
1280, 720))
|
1280, 720))
|
||||||
|
|
||||||
def _get_map_image(self):
|
def _get_map_image(self):
|
||||||
self.map_image = self.google_maps_object.display_image
|
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
|
# get overlay here
|
||||||
qim = ImageQt(self.map_image)
|
qim = ImageQt(self.map_image)
|
||||||
self.map_pixmap = QtGui.QPixmap.fromImage(qim)
|
self.map_pixmap = QtGui.QPixmap.fromImage(qim)
|
||||||
|
|||||||
@@ -42,7 +42,16 @@
|
|||||||
<property name="sizeConstraint">
|
<property name="sizeConstraint">
|
||||||
<enum>QLayout::SetDefaultConstraint</enum>
|
<enum>QLayout::SetDefaultConstraint</enum>
|
||||||
</property>
|
</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>
|
<number>0</number>
|
||||||
</property>
|
</property>
|
||||||
<item>
|
<item>
|
||||||
@@ -75,9 +84,425 @@
|
|||||||
<height>720</height>
|
<height>720</height>
|
||||||
</size>
|
</size>
|
||||||
</property>
|
</property>
|
||||||
<property name="styleSheet">
|
<layout class="QVBoxLayout" name="verticalLayout_44">
|
||||||
<string notr="true">background-color:black;</string>
|
<item>
|
||||||
</property>
|
<layout class="QHBoxLayout" name="horizontalLayout_9">
|
||||||
|
<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>
|
||||||
|
</layout>
|
||||||
</widget>
|
</widget>
|
||||||
</item>
|
</item>
|
||||||
<item>
|
<item>
|
||||||
@@ -108,25 +533,134 @@
|
|||||||
<height>360</height>
|
<height>360</height>
|
||||||
</size>
|
</size>
|
||||||
</property>
|
</property>
|
||||||
<property name="styleSheet">
|
|
||||||
<string notr="true">background-color:black;;</string>
|
|
||||||
</property>
|
|
||||||
<layout class="QGridLayout" name="gridLayout">
|
<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>
|
<number>0</number>
|
||||||
</property>
|
</property>
|
||||||
<property name="spacing">
|
<property name="spacing">
|
||||||
<number>0</number>
|
<number>0</number>
|
||||||
</property>
|
</property>
|
||||||
<item row="0" column="0">
|
<item row="0" column="0">
|
||||||
<widget class="QLabel" name="compass_label">
|
<layout class="QVBoxLayout" name="verticalLayout_5">
|
||||||
<property name="text">
|
<property name="spacing">
|
||||||
<string/>
|
<number>0</number>
|
||||||
</property>
|
</property>
|
||||||
<property name="alignment">
|
<item>
|
||||||
<set>Qt::AlignCenter</set>
|
<layout class="QGridLayout" name="gridLayout_2">
|
||||||
</property>
|
<property name="leftMargin">
|
||||||
</widget>
|
<number>6</number>
|
||||||
|
</property>
|
||||||
|
<property name="rightMargin">
|
||||||
|
<number>6</number>
|
||||||
|
</property>
|
||||||
|
<property name="spacing">
|
||||||
|
<number>0</number>
|
||||||
|
</property>
|
||||||
|
<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="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>
|
||||||
|
<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="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>
|
||||||
|
</layout>
|
||||||
|
</item>
|
||||||
|
<item>
|
||||||
|
<widget class="QLabel" name="compass_label">
|
||||||
|
<property name="minimumSize">
|
||||||
|
<size>
|
||||||
|
<width>275</width>
|
||||||
|
<height>275</height>
|
||||||
|
</size>
|
||||||
|
</property>
|
||||||
|
<property name="text">
|
||||||
|
<string/>
|
||||||
|
</property>
|
||||||
|
<property name="alignment">
|
||||||
|
<set>Qt::AlignCenter</set>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
</layout>
|
||||||
</item>
|
</item>
|
||||||
</layout>
|
</layout>
|
||||||
</widget>
|
</widget>
|
||||||
@@ -152,6 +686,21 @@
|
|||||||
</size>
|
</size>
|
||||||
</property>
|
</property>
|
||||||
<layout class="QVBoxLayout" name="verticalLayout">
|
<layout class="QVBoxLayout" name="verticalLayout">
|
||||||
|
<property name="spacing">
|
||||||
|
<number>6</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>
|
<item>
|
||||||
<widget class="QLabel" name="label">
|
<widget class="QLabel" name="label">
|
||||||
<property name="font">
|
<property name="font">
|
||||||
@@ -170,19 +719,35 @@
|
|||||||
</widget>
|
</widget>
|
||||||
</item>
|
</item>
|
||||||
<item>
|
<item>
|
||||||
<widget class="QLabel" name="label_2">
|
<layout class="QHBoxLayout" name="horizontalLayout_2">
|
||||||
<property name="font">
|
<item>
|
||||||
<font>
|
<widget class="QLabel" name="label_2">
|
||||||
<pointsize>22</pointsize>
|
<property name="font">
|
||||||
</font>
|
<font>
|
||||||
</property>
|
<pointsize>22</pointsize>
|
||||||
<property name="text">
|
</font>
|
||||||
<string>2.4 m/s</string>
|
</property>
|
||||||
</property>
|
<property name="text">
|
||||||
<property name="alignment">
|
<string>0.0</string>
|
||||||
<set>Qt::AlignCenter</set>
|
</property>
|
||||||
</property>
|
<property name="alignment">
|
||||||
</widget>
|
<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>
|
||||||
<item>
|
<item>
|
||||||
<widget class="QLabel" name="label_3">
|
<widget class="QLabel" name="label_3">
|
||||||
@@ -202,13 +767,19 @@
|
|||||||
</widget>
|
</widget>
|
||||||
</item>
|
</item>
|
||||||
<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">
|
<property name="value">
|
||||||
<number>50</number>
|
<number>50</number>
|
||||||
</property>
|
</property>
|
||||||
<property name="alignment">
|
<property name="alignment">
|
||||||
<set>Qt::AlignCenter</set>
|
<set>Qt::AlignCenter</set>
|
||||||
</property>
|
</property>
|
||||||
|
<property name="textVisible">
|
||||||
|
<bool>true</bool>
|
||||||
|
</property>
|
||||||
<property name="orientation">
|
<property name="orientation">
|
||||||
<enum>Qt::Horizontal</enum>
|
<enum>Qt::Horizontal</enum>
|
||||||
</property>
|
</property>
|
||||||
@@ -238,18 +809,72 @@
|
|||||||
</widget>
|
</widget>
|
||||||
</item>
|
</item>
|
||||||
<item>
|
<item>
|
||||||
<widget class="QProgressBar" name="progressBar_3">
|
<layout class="QFormLayout" name="formLayout">
|
||||||
<property name="value">
|
<item row="0" column="0">
|
||||||
<number>0</number>
|
<widget class="QLabel" name="label_5">
|
||||||
</property>
|
<property name="font">
|
||||||
</widget>
|
<font>
|
||||||
</item>
|
<weight>75</weight>
|
||||||
<item>
|
<bold>true</bold>
|
||||||
<widget class="QProgressBar" name="progressBar_2">
|
</font>
|
||||||
<property name="value">
|
</property>
|
||||||
<number>0</number>
|
<property name="text">
|
||||||
</property>
|
<string> Left</string>
|
||||||
</widget>
|
</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>
|
||||||
</layout>
|
</layout>
|
||||||
</widget>
|
</widget>
|
||||||
|
|||||||
@@ -98,7 +98,7 @@ class GroundStation(QtCore.QObject):
|
|||||||
|
|
||||||
# ##### Instantiate Threaded Classes ######
|
# ##### Instantiate Threaded Classes ######
|
||||||
self.__add_thread("Video Coordinator", RoverVideoCoordinator.RoverVideoCoordinator(self.shared_objects))
|
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.__add_thread("Rover Drive Sender", RoverDriveSender.RoverDriveSender(self.shared_objects))
|
||||||
self.connect_signals_and_slots_signal.emit()
|
self.connect_signals_and_slots_signal.emit()
|
||||||
self.__connect_signals_to_slots()
|
self.__connect_signals_to_slots()
|
||||||
|
|||||||
@@ -117,7 +117,6 @@ class DriveCoordinator(object):
|
|||||||
self.left_bogie_publisher.publish(left_drive)
|
self.left_bogie_publisher.publish(left_drive)
|
||||||
self.right_bogie_publisher.publish(right_drive)
|
self.right_bogie_publisher.publish(right_drive)
|
||||||
|
|
||||||
|
|
||||||
def iris_drive_command_callback(self, drive_command):
|
def iris_drive_command_callback(self, drive_command):
|
||||||
self.drive_commands["iris"] = drive_command
|
self.drive_commands["iris"] = drive_command
|
||||||
return
|
return
|
||||||
|
|||||||
@@ -118,6 +118,7 @@ class IrisController(object):
|
|||||||
|
|
||||||
def read_registers(self):
|
def read_registers(self):
|
||||||
self.registers = self.iris.read_registers(0, len(MODBUS_REGISTERS))
|
self.registers = self.iris.read_registers(0, len(MODBUS_REGISTERS))
|
||||||
|
# print self.registers
|
||||||
|
|
||||||
def broadcast_drive_if_current_mode(self):
|
def broadcast_drive_if_current_mode(self):
|
||||||
if self.registers[MODBUS_REGISTERS[REGISTER_STATE_MAPPING["DRIVE_VS_ARM"]]] < SBUS_VALUES["SBUS_MID"]:
|
if self.registers[MODBUS_REGISTERS[REGISTER_STATE_MAPPING["DRIVE_VS_ARM"]]] < SBUS_VALUES["SBUS_MID"]:
|
||||||
|
|||||||
Reference in New Issue
Block a user