mirror of
https://github.com/OSURoboticsClub/Rover_2017_2018.git
synced 2025-11-08 18:21:15 +00:00
Control changes. Joystick and spacenav sucked. Switched to regular controllers. Added readout for xbox controller mode.
This commit is contained in:
@@ -13,7 +13,7 @@ from rover_control.msg import DriveCommandMessage, TowerPanTiltControlMessage
|
|||||||
#####################################
|
#####################################
|
||||||
# Global Variables
|
# Global Variables
|
||||||
#####################################
|
#####################################
|
||||||
GAME_CONTROLLER_NAME = "Logitech Logitech Extreme 3D Pro"
|
GAME_CONTROLLER_NAME = "Logitech Logitech Dual Action"
|
||||||
|
|
||||||
DEFAULT_DRIVE_COMMAND_TOPIC = "/rover_control/command_control/ground_station_drive"
|
DEFAULT_DRIVE_COMMAND_TOPIC = "/rover_control/command_control/ground_station_drive"
|
||||||
DEFAULT_TOWER_PAN_TILT_COMMAND_TOPIC = "/rover_control/tower/pan_tilt/control"
|
DEFAULT_TOWER_PAN_TILT_COMMAND_TOPIC = "/rover_control/tower/pan_tilt/control"
|
||||||
@@ -21,8 +21,10 @@ DEFAULT_CHASSIS_PAN_TILT_COMMAND_TOPIC = "/rover_control/chassis/pan_tilt/contro
|
|||||||
|
|
||||||
DRIVE_COMMAND_HERTZ = 20
|
DRIVE_COMMAND_HERTZ = 20
|
||||||
|
|
||||||
Y_AXIS_DEADBAND = 0.05
|
STICK_DEADBAND = 8
|
||||||
X_AXIS_DEADBAND = 0.05
|
|
||||||
|
STICK_MAX = 128.0
|
||||||
|
STICK_OFFSET = 127
|
||||||
|
|
||||||
THROTTLE_MIN = 0.05
|
THROTTLE_MIN = 0.05
|
||||||
|
|
||||||
@@ -56,51 +58,57 @@ class LogitechJoystick(QtCore.QThread):
|
|||||||
self.gamepad = None # type: GamePad
|
self.gamepad = None # type: GamePad
|
||||||
|
|
||||||
self.controller_states = {
|
self.controller_states = {
|
||||||
"x_axis": 512,
|
"left_x_axis": 127,
|
||||||
"y_axis": 512,
|
"left_y_axis": 127,
|
||||||
"z_axis": 128,
|
"right_x_axis": 127,
|
||||||
"throttle_axis": 128,
|
"right_y_axis": 127,
|
||||||
|
|
||||||
"hat_x_axis": 0,
|
"left_trigger": 0,
|
||||||
"hat_y_axis": 0,
|
"right_trigger": 0,
|
||||||
|
|
||||||
"trigger_pressed": 0,
|
"left_stick": 0,
|
||||||
"thumb_pressed": 0,
|
"right_right": 0,
|
||||||
"three_pressed": 0,
|
|
||||||
"four_pressed": 0,
|
|
||||||
"five_pressed": 0,
|
|
||||||
"six_pressed": 0,
|
|
||||||
|
|
||||||
"seven_pressed": 0,
|
"left_bumper": 0,
|
||||||
"eight_pressed": 0,
|
"right_bumper": 0,
|
||||||
"nine_pressed": 0,
|
|
||||||
"ten_pressed": 0,
|
"d_pad_x": 0,
|
||||||
"eleven_pressed": 0,
|
"d_pad_y": 0,
|
||||||
"twelve_pressed": 0,
|
|
||||||
|
"back": 0,
|
||||||
|
"start": 0,
|
||||||
|
|
||||||
|
"a": 0,
|
||||||
|
"x": 0,
|
||||||
|
"y": 0,
|
||||||
|
"b": 0,
|
||||||
}
|
}
|
||||||
|
|
||||||
self.raw_mapping_to_class_mapping = {
|
self.raw_mapping_to_class_mapping = {
|
||||||
"ABS_X": "x_axis",
|
"ABS_X": "left_x_axis",
|
||||||
"ABS_Y": "y_axis",
|
"ABS_Y": "left_y_axis",
|
||||||
"ABS_RZ": "z_axis",
|
"ABS_Z": "right_x_axis",
|
||||||
"ABS_THROTTLE": "throttle_axis",
|
"ABS_RZ": "right_y_axis",
|
||||||
|
|
||||||
"ABS_HAT0X": "hat_x_axis",
|
"BTN_BASE": "left_trigger",
|
||||||
"ABS_HAT0Y": "hat_y_axis",
|
"BTN_BASE2": "right_trigger",
|
||||||
|
|
||||||
"BTN_TRIGGER": "trigger_pressed",
|
"BTN_BASE5": "left_stick",
|
||||||
"BTN_THUMB": "thumb_pressed",
|
"BTN_BASE6": "right_right",
|
||||||
"BTN_THUMB2": "three_pressed",
|
|
||||||
"BTN_TOP": "four_pressed",
|
|
||||||
"BTN_TOP2": "five_pressed",
|
|
||||||
"BTN_PINKIE": "six_pressed",
|
|
||||||
|
|
||||||
"BTN_BASE": "seven_pressed",
|
"BTN_TOP2": "left_bumper",
|
||||||
"BTN_BASE2": "eight_pressed",
|
"BTN_PINKIE": "right_bumper",
|
||||||
"BTN_BASE3": "nine_pressed",
|
|
||||||
"BTN_BASE4": "ten_pressed",
|
"ABS_HAT0X": "d_pad_x",
|
||||||
"BTN_BASE5": "eleven_pressed",
|
"ABS_HAT0Y": "d_pad_y",
|
||||||
"BTN_BASE6": "twelve_pressed"
|
|
||||||
|
"BTN_BASE3": "back",
|
||||||
|
"BTN_BASE4": "start",
|
||||||
|
|
||||||
|
"BTN_THUMB": "a",
|
||||||
|
"BTN_TRIGGER": "x",
|
||||||
|
"BTN_TOP": "y",
|
||||||
|
"BTN_THUMB2": "b",
|
||||||
}
|
}
|
||||||
|
|
||||||
self.ready = False
|
self.ready = False
|
||||||
@@ -118,6 +126,7 @@ class LogitechJoystick(QtCore.QThread):
|
|||||||
|
|
||||||
def __setup_controller(self):
|
def __setup_controller(self):
|
||||||
for device in devices.gamepads:
|
for device in devices.gamepads:
|
||||||
|
# print device
|
||||||
if device.name == GAME_CONTROLLER_NAME:
|
if device.name == GAME_CONTROLLER_NAME:
|
||||||
self.gamepad = device
|
self.gamepad = device
|
||||||
|
|
||||||
@@ -129,7 +138,7 @@ class LogitechJoystick(QtCore.QThread):
|
|||||||
events = self.gamepad.read()
|
events = self.gamepad.read()
|
||||||
|
|
||||||
for event in events:
|
for event in events:
|
||||||
# print event.code
|
print event.code, event.state
|
||||||
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
|
||||||
|
|
||||||
@@ -139,7 +148,7 @@ class LogitechJoystick(QtCore.QThread):
|
|||||||
#####################################
|
#####################################
|
||||||
# Controller Class Definition
|
# Controller Class Definition
|
||||||
#####################################
|
#####################################
|
||||||
class JoystickControlSender(QtCore.QThread):
|
class LogitechControllerControlSender(QtCore.QThread):
|
||||||
set_speed_limit__signal = QtCore.pyqtSignal(int)
|
set_speed_limit__signal = QtCore.pyqtSignal(int)
|
||||||
set_left_drive_output__signal = QtCore.pyqtSignal(int)
|
set_left_drive_output__signal = QtCore.pyqtSignal(int)
|
||||||
set_right_drive_output__signal = QtCore.pyqtSignal(int)
|
set_right_drive_output__signal = QtCore.pyqtSignal(int)
|
||||||
@@ -149,7 +158,7 @@ class JoystickControlSender(QtCore.QThread):
|
|||||||
toggle_selected_gui_camera__signal = QtCore.pyqtSignal()
|
toggle_selected_gui_camera__signal = QtCore.pyqtSignal()
|
||||||
|
|
||||||
def __init__(self, shared_objects):
|
def __init__(self, shared_objects):
|
||||||
super(JoystickControlSender, self).__init__()
|
super(LogitechControllerControlSender, self).__init__()
|
||||||
|
|
||||||
# ########## Reference to class init variables ##########
|
# ########## Reference to class init variables ##########
|
||||||
self.shared_objects = shared_objects
|
self.shared_objects = shared_objects
|
||||||
@@ -215,7 +224,7 @@ class JoystickControlSender(QtCore.QThread):
|
|||||||
self.video_coordinator.pan_tilt_selection_changed__signal.connect(self.on_pan_tilt_selection_changed__slot)
|
self.video_coordinator.pan_tilt_selection_changed__signal.connect(self.on_pan_tilt_selection_changed__slot)
|
||||||
|
|
||||||
def check_and_set_pause_state(self):
|
def check_and_set_pause_state(self):
|
||||||
thumb_pressed = self.joystick.controller_states["thumb_pressed"]
|
thumb_pressed = self.joystick.controller_states["start"]
|
||||||
if thumb_pressed and (time() - self.last_pause_state_time) > PAUSE_STATE_CHANGE_TIME:
|
if thumb_pressed and (time() - self.last_pause_state_time) > PAUSE_STATE_CHANGE_TIME:
|
||||||
self.drive_paused = not self.drive_paused
|
self.drive_paused = not self.drive_paused
|
||||||
self.show_changed_pause_state()
|
self.show_changed_pause_state()
|
||||||
@@ -227,7 +236,8 @@ class JoystickControlSender(QtCore.QThread):
|
|||||||
self.publish_pan_tilt_control_commands()
|
self.publish_pan_tilt_control_commands()
|
||||||
|
|
||||||
def publish_drive_command(self):
|
def publish_drive_command(self):
|
||||||
throttle_axis = max((255 - self.joystick.controller_states["throttle_axis"]) / 255.0, THROTTLE_MIN)
|
throttle_axis = 1
|
||||||
|
# throttle_axis = max((255 - self.joystick.controller_states["throttle_axis"]) / 255.0, THROTTLE_MIN)
|
||||||
|
|
||||||
if self.drive_paused:
|
if self.drive_paused:
|
||||||
drive_message = DriveCommandMessage()
|
drive_message = DriveCommandMessage()
|
||||||
@@ -244,11 +254,11 @@ class JoystickControlSender(QtCore.QThread):
|
|||||||
self.drive_command_publisher.publish(drive_message)
|
self.drive_command_publisher.publish(drive_message)
|
||||||
|
|
||||||
def publish_camera_control_commands(self):
|
def publish_camera_control_commands(self):
|
||||||
trigger_pressed = self.joystick.controller_states["trigger_pressed"]
|
trigger_pressed = self.joystick.controller_states["y"]
|
||||||
three_pressed = self.joystick.controller_states["three_pressed"]
|
three_pressed = self.joystick.controller_states["left_bumper"]
|
||||||
four_pressed = self.joystick.controller_states["four_pressed"]
|
four_pressed = self.joystick.controller_states["right_bumper"]
|
||||||
five_pressed = self.joystick.controller_states["five_pressed"]
|
five_pressed = self.joystick.controller_states["left_trigger"]
|
||||||
six_pressed = self.joystick.controller_states["six_pressed"]
|
six_pressed = self.joystick.controller_states["right_trigger"]
|
||||||
|
|
||||||
if (five_pressed or six_pressed) and (time() - self.last_camera_change_time) > CAMERA_CHANGE_TIME:
|
if (five_pressed or six_pressed) and (time() - self.last_camera_change_time) > CAMERA_CHANGE_TIME:
|
||||||
change = -1 if five_pressed else 1
|
change = -1 if five_pressed else 1
|
||||||
@@ -265,9 +275,9 @@ class JoystickControlSender(QtCore.QThread):
|
|||||||
self.last_camera_toggle_time = time()
|
self.last_camera_toggle_time = time()
|
||||||
|
|
||||||
def publish_pan_tilt_control_commands(self):
|
def publish_pan_tilt_control_commands(self):
|
||||||
button_eight = self.joystick.controller_states["seven_pressed"]
|
button_eight = self.joystick.controller_states["a"]
|
||||||
hat_x = self.joystick.controller_states["hat_x_axis"]
|
hat_x = self.joystick.controller_states["d_pad_x"]
|
||||||
hat_y = self.joystick.controller_states["hat_y_axis"]
|
hat_y = self.joystick.controller_states["d_pad_y"]
|
||||||
|
|
||||||
if (hat_x == 0 and not self.last_hat_x_was_movement) and (
|
if (hat_x == 0 and not self.last_hat_x_was_movement) and (
|
||||||
hat_y == 0 and not self.last_hat_y_was_movement) and not button_eight:
|
hat_y == 0 and not self.last_hat_y_was_movement) and not button_eight:
|
||||||
@@ -294,20 +304,14 @@ class JoystickControlSender(QtCore.QThread):
|
|||||||
def get_drive_message(self, throttle_axis):
|
def get_drive_message(self, throttle_axis):
|
||||||
drive_message = DriveCommandMessage()
|
drive_message = DriveCommandMessage()
|
||||||
|
|
||||||
y_axis = throttle_axis * (-(self.joystick.controller_states["y_axis"] - 512) / 512.0)
|
left_y_axis = self.joystick.controller_states["left_y_axis"] if abs(self.joystick.controller_states["left_y_axis"]) > STICK_DEADBAND else 0
|
||||||
z_axis = throttle_axis * (-(self.joystick.controller_states["z_axis"] - 128) / 128.0)
|
right_y_axis = self.joystick.controller_states["right_y_axis"] if abs(self.joystick.controller_states["right_y_axis"]) > STICK_DEADBAND else 0
|
||||||
x_axis = throttle_axis * (-(self.joystick.controller_states["x_axis"] - 512) / 512.0)
|
|
||||||
|
|
||||||
if abs(y_axis) < Y_AXIS_DEADBAND:
|
left_y_axis = throttle_axis * (-(left_y_axis - STICK_OFFSET) / STICK_MAX)
|
||||||
y_axis = 0
|
right_y_axis = throttle_axis * (-(right_y_axis - STICK_OFFSET) / STICK_MAX)
|
||||||
|
|
||||||
if abs(x_axis) < X_AXIS_DEADBAND and y_axis == 0:
|
drive_message.drive_twist.linear.x = (left_y_axis + right_y_axis) / 2.0
|
||||||
twist = z_axis
|
drive_message.drive_twist.angular.z = (right_y_axis - left_y_axis) / 2.0
|
||||||
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
|
return drive_message
|
||||||
|
|
||||||
@@ -160,20 +160,7 @@ class SpaceNavControlSender(QtCore.QThread):
|
|||||||
elif self.current_control_mode == self.ARM_MODE:
|
elif self.current_control_mode == self.ARM_MODE:
|
||||||
pass
|
pass
|
||||||
|
|
||||||
def send_mining_commands(self):
|
|
||||||
linear_z = self.spnav_states["linear_z"]
|
|
||||||
angular_y = self.spnav_states["angular_y"]
|
|
||||||
|
|
||||||
message = MiningControlMessage()
|
|
||||||
|
|
||||||
message.lift_set_absolute = 1024
|
|
||||||
message.tilt_set_absolute = 1024
|
|
||||||
|
|
||||||
message.lift_set_relative = linear_z * MINING_LIFT_SCALAR if abs(linear_z) > Z_LINEAR_DEADBAND else 0
|
|
||||||
message.tilt_set_relative = angular_y * MINING_TILT_SCALAR if abs(angular_y) > Y_ANGULAR_DEADBAND else 0
|
|
||||||
message.cal_factor = -1
|
|
||||||
|
|
||||||
self.mining_control_publisher.publish(message)
|
|
||||||
# print self.spnav_states["linear_z"], self.spnav_states["angular_y"]
|
# print self.spnav_states["linear_z"], self.spnav_states["angular_y"]
|
||||||
|
|
||||||
def connect_signals_and_slots(self):
|
def connect_signals_and_slots(self):
|
||||||
|
|||||||
@@ -9,6 +9,7 @@ from time import time
|
|||||||
|
|
||||||
import rospy
|
import rospy
|
||||||
from rover_arm.msg import ArmControlMessage
|
from rover_arm.msg import ArmControlMessage
|
||||||
|
from rover_control.msg import MiningControlMessage
|
||||||
|
|
||||||
#####################################
|
#####################################
|
||||||
# Global Variables
|
# Global Variables
|
||||||
@@ -18,6 +19,7 @@ GAME_CONTROLLER_NAME = "Afterglow Gamepad for Xbox 360"
|
|||||||
DRIVE_COMMAND_HERTZ = 20
|
DRIVE_COMMAND_HERTZ = 20
|
||||||
|
|
||||||
RELATIVE_ARM_CONTROL_TOPIC = "/rover_arm/control/relative"
|
RELATIVE_ARM_CONTROL_TOPIC = "/rover_arm/control/relative"
|
||||||
|
MINING_CONTROL_TOPIC = "/rover_control/mining/control"
|
||||||
|
|
||||||
BASE_SCALAR = 0.003
|
BASE_SCALAR = 0.003
|
||||||
SHOULDER_SCALAR = 0.002
|
SHOULDER_SCALAR = 0.002
|
||||||
@@ -32,6 +34,15 @@ LEFT_Y_AXIS_DEADZONE = 1500
|
|||||||
RIGHT_X_AXIS_DEADZONE = 1500
|
RIGHT_X_AXIS_DEADZONE = 1500
|
||||||
RIGHT_Y_AXIS_DEADZONE = 1500
|
RIGHT_Y_AXIS_DEADZONE = 1500
|
||||||
|
|
||||||
|
THUMB_STICK_MAX = 32768.0
|
||||||
|
|
||||||
|
MINING_LIFT_SCALAR = 5
|
||||||
|
MINING_TILT_SCALAR = 5
|
||||||
|
|
||||||
|
|
||||||
|
COLOR_GREEN = "background-color:darkgreen; border: 1px solid black;"
|
||||||
|
COLOR_NONE = "border: 1px solid black;"
|
||||||
|
|
||||||
|
|
||||||
#####################################
|
#####################################
|
||||||
# Controller Class Definition
|
# Controller Class Definition
|
||||||
@@ -120,7 +131,7 @@ class XBOXController(QtCore.QThread):
|
|||||||
|
|
||||||
def __setup_controller(self):
|
def __setup_controller(self):
|
||||||
for device in devices.gamepads:
|
for device in devices.gamepads:
|
||||||
print device
|
# print device
|
||||||
if device.name == GAME_CONTROLLER_NAME:
|
if device.name == GAME_CONTROLLER_NAME:
|
||||||
self.gamepad = device
|
self.gamepad = device
|
||||||
|
|
||||||
@@ -146,15 +157,23 @@ class XBOXController(QtCore.QThread):
|
|||||||
#####################################
|
#####################################
|
||||||
# Controller Class Definition
|
# Controller Class Definition
|
||||||
#####################################
|
#####################################
|
||||||
class ControllerControlSender(QtCore.QThread):
|
class XBOXControllerControlSender(QtCore.QThread):
|
||||||
|
STATES = [
|
||||||
|
"ARM",
|
||||||
|
"MINING"
|
||||||
|
]
|
||||||
|
|
||||||
|
xbox_control_arm_stylesheet_update_ready__signal = QtCore.pyqtSignal(str)
|
||||||
|
xbox_control_mining_stylesheet_update_ready__signal = QtCore.pyqtSignal(str)
|
||||||
|
|
||||||
def __init__(self, shared_objects):
|
def __init__(self, shared_objects):
|
||||||
super(ControllerControlSender, self).__init__()
|
super(XBOXControllerControlSender, self).__init__()
|
||||||
|
|
||||||
# ########## Reference to class init variables ##########
|
# ########## Reference to class init variables ##########
|
||||||
self.shared_objects = shared_objects
|
self.shared_objects = shared_objects
|
||||||
self.video_coordinator = self.shared_objects["threaded_classes"]["Video Coordinator"]
|
self.left_screen = self.shared_objects["screens"]["left_screen"]
|
||||||
self.right_screen = self.shared_objects["screens"]["right_screen"]
|
self.xbox_mode_arm_label = self.left_screen.xbox_mode_arm_label # type: QtWidgets.QLabel
|
||||||
|
self.xbox_mode_mining_label = self.left_screen.xbox_mode_mining_label # type: QtWidgets.QLabel
|
||||||
|
|
||||||
# ########## Get the settings instance ##########
|
# ########## Get the settings instance ##########
|
||||||
self.settings = QtCore.QSettings()
|
self.settings = QtCore.QSettings()
|
||||||
@@ -173,6 +192,12 @@ class ControllerControlSender(QtCore.QThread):
|
|||||||
|
|
||||||
self.relative_arm_control_publisher = rospy.Publisher(RELATIVE_ARM_CONTROL_TOPIC, ArmControlMessage,
|
self.relative_arm_control_publisher = rospy.Publisher(RELATIVE_ARM_CONTROL_TOPIC, ArmControlMessage,
|
||||||
queue_size=1)
|
queue_size=1)
|
||||||
|
self.mining_control_publisher = rospy.Publisher(MINING_CONTROL_TOPIC, MiningControlMessage, queue_size=1)
|
||||||
|
|
||||||
|
self.current_state = self.STATES.index("ARM")
|
||||||
|
self.state_just_changed = False
|
||||||
|
|
||||||
|
self.last_xbox_button_state = 0
|
||||||
|
|
||||||
def run(self):
|
def run(self):
|
||||||
self.logger.debug("Starting Joystick Thread")
|
self.logger.debug("Starting Joystick Thread")
|
||||||
@@ -180,7 +205,12 @@ class ControllerControlSender(QtCore.QThread):
|
|||||||
while self.run_thread_flag:
|
while self.run_thread_flag:
|
||||||
start_time = time()
|
start_time = time()
|
||||||
|
|
||||||
self.process_and_send_arm_control()
|
self.change_control_state_if_needed()
|
||||||
|
|
||||||
|
if self.current_state == self.STATES.index("ARM"):
|
||||||
|
self.process_and_send_arm_control()
|
||||||
|
elif self.current_state == self.STATES.index("MINING"):
|
||||||
|
self.send_mining_commands()
|
||||||
|
|
||||||
time_diff = time() - start_time
|
time_diff = time() - start_time
|
||||||
|
|
||||||
@@ -189,9 +219,32 @@ class ControllerControlSender(QtCore.QThread):
|
|||||||
self.logger.debug("Stopping Joystick Thread")
|
self.logger.debug("Stopping Joystick Thread")
|
||||||
|
|
||||||
def connect_signals_and_slots(self):
|
def connect_signals_and_slots(self):
|
||||||
pass
|
self.xbox_control_arm_stylesheet_update_ready__signal.connect(self.xbox_mode_arm_label.setStyleSheet)
|
||||||
|
self.xbox_control_mining_stylesheet_update_ready__signal.connect(self.xbox_mode_mining_label.setStyleSheet)
|
||||||
|
|
||||||
|
def change_control_state_if_needed(self):
|
||||||
|
if self.state_just_changed:
|
||||||
|
self.xbox_control_arm_stylesheet_update_ready__signal.emit(COLOR_NONE)
|
||||||
|
self.xbox_control_mining_stylesheet_update_ready__signal.emit(COLOR_GREEN)
|
||||||
|
self.state_just_changed = False
|
||||||
|
|
||||||
|
xbox_state = self.controller.controller_states["xbox_button"]
|
||||||
|
|
||||||
|
if self.last_xbox_button_state == 0 and xbox_state == 1:
|
||||||
|
self.current_state += 1
|
||||||
|
self.current_state = self.current_state % len(self.STATES)
|
||||||
|
self.state_just_changed = True
|
||||||
|
self.last_xbox_button_state = 1
|
||||||
|
|
||||||
|
elif self.last_xbox_button_state == 1 and xbox_state == 0:
|
||||||
|
self.last_xbox_button_state = 0
|
||||||
|
|
||||||
def process_and_send_arm_control(self):
|
def process_and_send_arm_control(self):
|
||||||
|
if self.state_just_changed:
|
||||||
|
self.xbox_control_arm_stylesheet_update_ready__signal.emit(COLOR_GREEN)
|
||||||
|
self.xbox_control_mining_stylesheet_update_ready__signal.emit(COLOR_NONE)
|
||||||
|
self.state_just_changed = False
|
||||||
|
|
||||||
message = ArmControlMessage()
|
message = ArmControlMessage()
|
||||||
|
|
||||||
should_publish = False
|
should_publish = False
|
||||||
@@ -200,13 +253,13 @@ class ControllerControlSender(QtCore.QThread):
|
|||||||
right_trigger = self.controller.controller_states["right_trigger"]
|
right_trigger = self.controller.controller_states["right_trigger"]
|
||||||
|
|
||||||
left_x_axis = self.controller.controller_states["left_x_axis"] if abs(self.controller.controller_states[
|
left_x_axis = self.controller.controller_states["left_x_axis"] if abs(self.controller.controller_states[
|
||||||
"left_x_axis"]) > LEFT_X_AXIS_DEADZONE else 0
|
"left_x_axis"]) > LEFT_X_AXIS_DEADZONE else 0
|
||||||
left_y_axis = self.controller.controller_states["left_y_axis"] if abs(self.controller.controller_states[
|
left_y_axis = self.controller.controller_states["left_y_axis"] if abs(self.controller.controller_states[
|
||||||
"left_y_axis"]) > LEFT_Y_AXIS_DEADZONE else 0
|
"left_y_axis"]) > LEFT_Y_AXIS_DEADZONE else 0
|
||||||
right_y_axis = self.controller.controller_states["right_y_axis"] if abs(self.controller.controller_states[
|
right_y_axis = self.controller.controller_states["right_y_axis"] if abs(self.controller.controller_states[
|
||||||
"right_y_axis"]) > RIGHT_Y_AXIS_DEADZONE else 0
|
"right_y_axis"]) > RIGHT_Y_AXIS_DEADZONE else 0
|
||||||
right_x_axis = self.controller.controller_states["right_x_axis"] if abs(self.controller.controller_states[
|
right_x_axis = self.controller.controller_states["right_x_axis"] if abs(self.controller.controller_states[
|
||||||
"right_x_axis"]) > RIGHT_X_AXIS_DEADZONE else 0
|
"right_x_axis"]) > RIGHT_X_AXIS_DEADZONE else 0
|
||||||
|
|
||||||
# print left_x_axis, ":", left_y_axis, ":", right_x_axis, ":", right_y_axis
|
# print left_x_axis, ":", left_y_axis, ":", right_x_axis, ":", right_y_axis
|
||||||
|
|
||||||
@@ -215,19 +268,38 @@ class ControllerControlSender(QtCore.QThread):
|
|||||||
|
|
||||||
if left_trigger > 25:
|
if left_trigger > 25:
|
||||||
should_publish = True
|
should_publish = True
|
||||||
message.base = ((left_x_axis / 32768.0) * BASE_SCALAR) * left_trigger_ratio
|
message.base = ((left_x_axis / THUMB_STICK_MAX) * BASE_SCALAR) * left_trigger_ratio
|
||||||
message.shoulder = (-(left_y_axis / 32768.0) * SHOULDER_SCALAR) * left_trigger_ratio
|
message.shoulder = ((left_y_axis / THUMB_STICK_MAX) * SHOULDER_SCALAR) * left_trigger_ratio
|
||||||
message.elbow = ((right_y_axis / 32768.0) * ELBOW_SCALAR) * left_trigger_ratio
|
message.elbow = (-(right_y_axis / THUMB_STICK_MAX) * ELBOW_SCALAR) * left_trigger_ratio
|
||||||
message.roll = (-(right_x_axis / 32768.0) * ROLL_SCALAR) * left_trigger_ratio
|
message.roll = (-(right_x_axis / THUMB_STICK_MAX) * ROLL_SCALAR) * left_trigger_ratio
|
||||||
|
|
||||||
elif right_trigger > 25:
|
elif right_trigger > 25:
|
||||||
should_publish = True
|
should_publish = True
|
||||||
message.wrist_roll = ((right_x_axis / 32768.0) * WRIST_ROLL_SCALAR) * right_trigger_ratio
|
message.wrist_roll = ((right_x_axis / THUMB_STICK_MAX) * WRIST_ROLL_SCALAR) * right_trigger_ratio
|
||||||
message.wrist_pitch = ((left_y_axis / 32768.0) * WRIST_PITCH_SCALAR) * right_trigger_ratio
|
message.wrist_pitch = (-(left_y_axis / THUMB_STICK_MAX) * WRIST_PITCH_SCALAR) * right_trigger_ratio
|
||||||
|
|
||||||
if should_publish:
|
if should_publish:
|
||||||
self.relative_arm_control_publisher.publish(message)
|
self.relative_arm_control_publisher.publish(message)
|
||||||
|
|
||||||
|
def send_mining_commands(self):
|
||||||
|
|
||||||
|
left_y_axis = self.controller.controller_states["left_y_axis"] if abs(self.controller.controller_states["left_y_axis"]) > LEFT_Y_AXIS_DEADZONE else 0
|
||||||
|
right_y_axis = self.controller.controller_states["right_y_axis"] if abs(self.controller.controller_states[
|
||||||
|
"right_y_axis"]) > RIGHT_Y_AXIS_DEADZONE else 0
|
||||||
|
|
||||||
|
if left_y_axis or right_y_axis:
|
||||||
|
|
||||||
|
message = MiningControlMessage()
|
||||||
|
|
||||||
|
message.lift_set_absolute = 1024
|
||||||
|
message.tilt_set_absolute = 1024
|
||||||
|
|
||||||
|
message.lift_set_relative = (-(left_y_axis / THUMB_STICK_MAX) * MINING_LIFT_SCALAR)
|
||||||
|
message.tilt_set_relative = ((right_y_axis / THUMB_STICK_MAX) * MINING_TILT_SCALAR)
|
||||||
|
message.cal_factor = -1
|
||||||
|
|
||||||
|
self.mining_control_publisher.publish(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)
|
||||||
@@ -2574,13 +2574,13 @@ N/A</string>
|
|||||||
</property>
|
</property>
|
||||||
<property name="minimumSize">
|
<property name="minimumSize">
|
||||||
<size>
|
<size>
|
||||||
<width>640</width>
|
<width>470</width>
|
||||||
<height>360</height>
|
<height>360</height>
|
||||||
</size>
|
</size>
|
||||||
</property>
|
</property>
|
||||||
<property name="maximumSize">
|
<property name="maximumSize">
|
||||||
<size>
|
<size>
|
||||||
<width>640</width>
|
<width>470</width>
|
||||||
<height>360</height>
|
<height>360</height>
|
||||||
</size>
|
</size>
|
||||||
</property>
|
</property>
|
||||||
@@ -3170,6 +3170,170 @@ N/A</string>
|
|||||||
</layout>
|
</layout>
|
||||||
</widget>
|
</widget>
|
||||||
</item>
|
</item>
|
||||||
|
<item>
|
||||||
|
<spacer name="horizontalSpacer_16">
|
||||||
|
<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="Line" name="line_9">
|
||||||
|
<property name="orientation">
|
||||||
|
<enum>Qt::Vertical</enum>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
<item>
|
||||||
|
<spacer name="horizontalSpacer_17">
|
||||||
|
<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_18">
|
||||||
|
<property name="spacing">
|
||||||
|
<number>6</number>
|
||||||
|
</property>
|
||||||
|
<item>
|
||||||
|
<widget class="QLabel" name="label_34">
|
||||||
|
<property name="font">
|
||||||
|
<font>
|
||||||
|
<pointsize>12</pointsize>
|
||||||
|
<weight>75</weight>
|
||||||
|
<bold>true</bold>
|
||||||
|
</font>
|
||||||
|
</property>
|
||||||
|
<property name="text">
|
||||||
|
<string>Xbox Mode</string>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
<item>
|
||||||
|
<layout class="QHBoxLayout" name="horizontalLayout_16">
|
||||||
|
<property name="spacing">
|
||||||
|
<number>0</number>
|
||||||
|
</property>
|
||||||
|
<item>
|
||||||
|
<widget class="QLabel" name="xbox_mode_arm_label">
|
||||||
|
<property name="minimumSize">
|
||||||
|
<size>
|
||||||
|
<width>120</width>
|
||||||
|
<height>120</height>
|
||||||
|
</size>
|
||||||
|
</property>
|
||||||
|
<property name="maximumSize">
|
||||||
|
<size>
|
||||||
|
<width>120</width>
|
||||||
|
<height>120</height>
|
||||||
|
</size>
|
||||||
|
</property>
|
||||||
|
<property name="styleSheet">
|
||||||
|
<string notr="true">background-color:darkgreen; border: 1px solid black;</string>
|
||||||
|
</property>
|
||||||
|
<property name="text">
|
||||||
|
<string>Arm</string>
|
||||||
|
</property>
|
||||||
|
<property name="alignment">
|
||||||
|
<set>Qt::AlignCenter</set>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
</layout>
|
||||||
|
</item>
|
||||||
|
<item>
|
||||||
|
<layout class="QHBoxLayout" name="horizontalLayout_17">
|
||||||
|
<property name="spacing">
|
||||||
|
<number>0</number>
|
||||||
|
</property>
|
||||||
|
<item>
|
||||||
|
<widget class="QLabel" name="xbox_mode_mining_label">
|
||||||
|
<property name="minimumSize">
|
||||||
|
<size>
|
||||||
|
<width>120</width>
|
||||||
|
<height>120</height>
|
||||||
|
</size>
|
||||||
|
</property>
|
||||||
|
<property name="maximumSize">
|
||||||
|
<size>
|
||||||
|
<width>120</width>
|
||||||
|
<height>120</height>
|
||||||
|
</size>
|
||||||
|
</property>
|
||||||
|
<property name="styleSheet">
|
||||||
|
<string notr="true">border: 1px solid black;</string>
|
||||||
|
</property>
|
||||||
|
<property name="text">
|
||||||
|
<string>Mining</string>
|
||||||
|
</property>
|
||||||
|
<property name="alignment">
|
||||||
|
<set>Qt::AlignCenter</set>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
</layout>
|
||||||
|
</item>
|
||||||
|
<item>
|
||||||
|
<spacer name="verticalSpacer_7">
|
||||||
|
<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>
|
||||||
|
<item>
|
||||||
|
<spacer name="horizontalSpacer_18">
|
||||||
|
<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="Line" name="line_10">
|
||||||
|
<property name="orientation">
|
||||||
|
<enum>Qt::Vertical</enum>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
<item>
|
||||||
|
<spacer name="horizontalSpacer_15">
|
||||||
|
<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>
|
<item>
|
||||||
<widget class="QWidget" name="widget_3" native="true">
|
<widget class="QWidget" name="widget_3" native="true">
|
||||||
<property name="sizePolicy">
|
<property name="sizePolicy">
|
||||||
|
|||||||
@@ -15,15 +15,14 @@ import Framework.StartupSystems.ROSMasterChecker as ROSMasterChecker
|
|||||||
import Framework.LoggingSystems.Logger as Logger
|
import Framework.LoggingSystems.Logger as Logger
|
||||||
import Framework.VideoSystems.RoverVideoCoordinator as RoverVideoCoordinator
|
import Framework.VideoSystems.RoverVideoCoordinator as RoverVideoCoordinator
|
||||||
import Framework.MapSystems.RoverMapCoordinator as RoverMapCoordinator
|
import Framework.MapSystems.RoverMapCoordinator as RoverMapCoordinator
|
||||||
import Framework.InputSystems.JoystickControlSender as JoystickControlSender
|
import Framework.InputSystems.LogitechControllerControlSender as JoystickControlSender
|
||||||
import Framework.InputSystems.ControllerControlSender as ControllerControlSender
|
import Framework.InputSystems.XBOXControllerControlSender as ControllerControlSender
|
||||||
import Framework.NavigationSystems.SpeedAndHeadingIndication as SpeedAndHeading
|
import Framework.NavigationSystems.SpeedAndHeadingIndication as SpeedAndHeading
|
||||||
import Framework.NavigationSystems.WaypointsCoordinator as WaypointsCoordinator
|
import Framework.NavigationSystems.WaypointsCoordinator as WaypointsCoordinator
|
||||||
import Framework.ArmSystems.ArmIndication as ArmIndication
|
import Framework.ArmSystems.ArmIndication as ArmIndication
|
||||||
import Framework.StatusSystems.StatusCore as StatusCore
|
import Framework.StatusSystems.StatusCore as StatusCore
|
||||||
import Framework.StatusSystems.UbiquitiStatusCore as UbiquitiStatusCore
|
import Framework.StatusSystems.UbiquitiStatusCore as UbiquitiStatusCore
|
||||||
import Framework.SettingsSystems.UbiquitiRadioSettings as UbiquitiRadioSettings
|
import Framework.SettingsSystems.UbiquitiRadioSettings as UbiquitiRadioSettings
|
||||||
import Framework.InputSystems.SpaceNavControlSender as SpaceNavControlSender
|
|
||||||
import Framework.MiscSystems.MiningCore as MiningCore
|
import Framework.MiscSystems.MiningCore as MiningCore
|
||||||
import Framework.MiscSystems.BashConsoleCore as BashConsoleCore
|
import Framework.MiscSystems.BashConsoleCore as BashConsoleCore
|
||||||
import Framework.MiscSystems.MiscArmCore as MiscArmCore
|
import Framework.MiscSystems.MiscArmCore as MiscArmCore
|
||||||
@@ -112,14 +111,13 @@ 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("Joystick Sender", JoystickControlSender.JoystickControlSender(self.shared_objects))
|
self.__add_thread("Joystick Sender", JoystickControlSender.LogitechControllerControlSender(self.shared_objects))
|
||||||
self.__add_thread("Controller Sender", ControllerControlSender.ControllerControlSender(self.shared_objects))
|
self.__add_thread("Controller Sender", ControllerControlSender.XBOXControllerControlSender(self.shared_objects))
|
||||||
self.__add_thread("Speed and Heading", SpeedAndHeading.SpeedAndHeadingIndication(self.shared_objects))
|
self.__add_thread("Speed and Heading", SpeedAndHeading.SpeedAndHeadingIndication(self.shared_objects))
|
||||||
self.__add_thread("Rover Status", StatusCore.SensorCore(self.shared_objects))
|
self.__add_thread("Rover Status", StatusCore.SensorCore(self.shared_objects))
|
||||||
self.__add_thread("Ubiquiti Status", UbiquitiStatusCore.UbiquitiStatus(self.shared_objects))
|
self.__add_thread("Ubiquiti Status", UbiquitiStatusCore.UbiquitiStatus(self.shared_objects))
|
||||||
self.__add_thread("Ubiquiti Radio Settings", UbiquitiRadioSettings.UbiquitiRadioSettings(self.shared_objects))
|
self.__add_thread("Ubiquiti Radio Settings", UbiquitiRadioSettings.UbiquitiRadioSettings(self.shared_objects))
|
||||||
self.__add_thread("Waypoints Coordinator", WaypointsCoordinator.WaypointsCoordinator(self.shared_objects))
|
self.__add_thread("Waypoints Coordinator", WaypointsCoordinator.WaypointsCoordinator(self.shared_objects))
|
||||||
self.__add_thread("Spacenav Sender", SpaceNavControlSender.SpaceNavControlSender(self.shared_objects))
|
|
||||||
self.__add_thread("Bash Console", BashConsoleCore.BashConsole(self.shared_objects))
|
self.__add_thread("Bash Console", BashConsoleCore.BashConsole(self.shared_objects))
|
||||||
self.__add_thread("Misc Arm", MiscArmCore.MiscArm(self.shared_objects))
|
self.__add_thread("Misc Arm", MiscArmCore.MiscArm(self.shared_objects))
|
||||||
self.__add_thread("RDF", RDFCore.RDF(self.shared_objects))
|
self.__add_thread("RDF", RDFCore.RDF(self.shared_objects))
|
||||||
|
|||||||
@@ -9,7 +9,7 @@
|
|||||||
[{name: "/rover_control/command_control/ground_station_drive", compress: true, rate: 15.0},
|
[{name: "/rover_control/command_control/ground_station_drive", compress: true, rate: 15.0},
|
||||||
{name: "/rover_control/tower/pan_tilt/control", compress: true, rate: 30.0},
|
{name: "/rover_control/tower/pan_tilt/control", compress: true, rate: 30.0},
|
||||||
{name: "/rover_control/chassis/pan_tilt/control", compress: true, rate: 30.0},
|
{name: "/rover_control/chassis/pan_tilt/control", compress: true, rate: 30.0},
|
||||||
{name: "/rover_control/mining/control", compress: true, rate: 15.0},
|
{name: "/rover_control/mining/control", compress: true, rate: 30.0},
|
||||||
{name: "/rover_arm/control/relative", compress: true, rate: 30.0}]
|
{name: "/rover_arm/control/relative", compress: true, rate: 30.0}]
|
||||||
</rosparam>
|
</rosparam>
|
||||||
</node>
|
</node>
|
||||||
|
|||||||
Reference in New Issue
Block a user