mirror of
https://github.com/OSURoboticsClub/Rover_2017_2018.git
synced 2025-11-08 18:21:15 +00:00
Switched to a new controller and renamed control system files to a better naming convention
This commit is contained in:
@@ -13,7 +13,7 @@ from rover_control.msg import DriveCommandMessage, TowerPanTiltControlMessage
|
||||
#####################################
|
||||
# Global Variables
|
||||
#####################################
|
||||
GAME_CONTROLLER_NAME = "Logitech Logitech Dual Action"
|
||||
GAME_CONTROLLER_NAME = "Microsoft X-Box One S pad"
|
||||
|
||||
DEFAULT_DRIVE_COMMAND_TOPIC = "/rover_control/command_control/ground_station_drive"
|
||||
DEFAULT_TOWER_PAN_TILT_COMMAND_TOPIC = "/rover_control/tower/pan_tilt/control"
|
||||
@@ -21,10 +21,10 @@ DEFAULT_CHASSIS_PAN_TILT_COMMAND_TOPIC = "/rover_control/chassis/pan_tilt/contro
|
||||
|
||||
DRIVE_COMMAND_HERTZ = 20
|
||||
|
||||
STICK_DEADBAND = 8
|
||||
STICK_DEADBAND = 3500
|
||||
|
||||
STICK_MAX = 128.0
|
||||
STICK_OFFSET = 127
|
||||
STICK_MAX = 32768.0
|
||||
STICK_OFFSET = 0
|
||||
|
||||
THROTTLE_MIN = 0.05
|
||||
|
||||
@@ -58,10 +58,10 @@ class LogitechJoystick(QtCore.QThread):
|
||||
self.gamepad = None # type: GamePad
|
||||
|
||||
self.controller_states = {
|
||||
"left_x_axis": 127,
|
||||
"left_y_axis": 127,
|
||||
"right_x_axis": 127,
|
||||
"right_y_axis": 127,
|
||||
"left_x_axis": 0,
|
||||
"left_y_axis": 0,
|
||||
"right_x_axis": 0,
|
||||
"right_y_axis": 0,
|
||||
|
||||
"left_trigger": 0,
|
||||
"right_trigger": 0,
|
||||
@@ -87,28 +87,28 @@ class LogitechJoystick(QtCore.QThread):
|
||||
self.raw_mapping_to_class_mapping = {
|
||||
"ABS_X": "left_x_axis",
|
||||
"ABS_Y": "left_y_axis",
|
||||
"ABS_Z": "right_x_axis",
|
||||
"ABS_RZ": "right_y_axis",
|
||||
"ABS_RX": "right_x_axis",
|
||||
"ABS_RY": "right_y_axis",
|
||||
|
||||
"BTN_BASE": "left_trigger",
|
||||
"BTN_BASE2": "right_trigger",
|
||||
"ABS_Z": "left_trigger",
|
||||
"ABS_RZ": "right_trigger",
|
||||
|
||||
"BTN_BASE5": "left_stick",
|
||||
"BTN_BASE6": "right_right",
|
||||
"BTN_THUMBL": "left_stick",
|
||||
"BTN_THUMBR": "right_right",
|
||||
|
||||
"BTN_TOP2": "left_bumper",
|
||||
"BTN_PINKIE": "right_bumper",
|
||||
"BTN_TL": "left_bumper",
|
||||
"BTN_TR": "right_bumper",
|
||||
|
||||
"ABS_HAT0X": "d_pad_x",
|
||||
"ABS_HAT0Y": "d_pad_y",
|
||||
|
||||
"BTN_BASE3": "back",
|
||||
"BTN_BASE4": "start",
|
||||
"BTN_SELECT": "back",
|
||||
"BTN_START": "start",
|
||||
|
||||
"BTN_THUMB": "a",
|
||||
"BTN_TRIGGER": "x",
|
||||
"BTN_TOP": "y",
|
||||
"BTN_THUMB2": "b",
|
||||
"BTN_SOUTH": "a",
|
||||
"BTN_NORTH": "x",
|
||||
"BTN_WEST": "y",
|
||||
"BTN_EAST": "b",
|
||||
}
|
||||
|
||||
self.ready = False
|
||||
@@ -148,7 +148,7 @@ class LogitechJoystick(QtCore.QThread):
|
||||
#####################################
|
||||
# Controller Class Definition
|
||||
#####################################
|
||||
class LogitechControllerControlSender(QtCore.QThread):
|
||||
class DriveAndCameraControlSender(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)
|
||||
@@ -158,7 +158,7 @@ class LogitechControllerControlSender(QtCore.QThread):
|
||||
toggle_selected_gui_camera__signal = QtCore.pyqtSignal()
|
||||
|
||||
def __init__(self, shared_objects):
|
||||
super(LogitechControllerControlSender, self).__init__()
|
||||
super(DriveAndCameraControlSender, self).__init__()
|
||||
|
||||
# ########## Reference to class init variables ##########
|
||||
self.shared_objects = shared_objects
|
||||
@@ -159,7 +159,7 @@ class XBOXController(QtCore.QThread):
|
||||
#####################################
|
||||
# Controller Class Definition
|
||||
#####################################
|
||||
class XBOXControllerControlSender(QtCore.QThread):
|
||||
class EffectorsAndArmControlSender(QtCore.QThread):
|
||||
xbox_control_arm_stylesheet_update_ready__signal = QtCore.pyqtSignal(str)
|
||||
xbox_control_mining_stylesheet_update_ready__signal = QtCore.pyqtSignal(str)
|
||||
|
||||
@@ -183,7 +183,7 @@ class XBOXControllerControlSender(QtCore.QThread):
|
||||
PINCH_MODE_ABSOLUTE_SET_POSITION = 57740
|
||||
|
||||
def __init__(self, shared_objects):
|
||||
super(XBOXControllerControlSender, self).__init__()
|
||||
super(EffectorsAndArmControlSender, self).__init__()
|
||||
|
||||
# ########## Reference to class init variables ##########
|
||||
self.shared_objects = shared_objects
|
||||
@@ -390,7 +390,11 @@ class XBOXControllerControlSender(QtCore.QThread):
|
||||
should_publish_gripper = True
|
||||
|
||||
arm_control_message.wrist_roll = ((left_x_axis / THUMB_STICK_MAX) * BASE_SCALAR) * right_trigger_ratio
|
||||
arm_control_message.wrist_pitch = (-(left_y_axis / THUMB_STICK_MAX) * WRIST_PITCH_SCALAR) * right_trigger_ratio
|
||||
|
||||
# ##### FIXME #####
|
||||
# Remove this once the arm is fixed
|
||||
# arm_control_message.wrist_pitch = (-(left_y_axis / THUMB_STICK_MAX) * WRIST_PITCH_SCALAR) * right_trigger_ratio
|
||||
# #################
|
||||
|
||||
gripper_control_message.gripper_position_relative = (-(right_y_axis / THUMB_STICK_MAX) * GRIPPER_MOVEMENT_SCALAR) * right_trigger_ratio
|
||||
|
||||
@@ -67,6 +67,12 @@ class MiscArm(QtCore.QThread):
|
||||
self.arm_controls_stow_arm_button = self.left_screen.arm_controls_stow_arm_button # type:QtWidgets.QPushButton
|
||||
self.arm_controls_unstow_arm_button = self.left_screen.arm_controls_unstow_arm_button # type:QtWidgets.QPushButton
|
||||
|
||||
# ##### FIXME #####
|
||||
# Remove these once the arm is fixed
|
||||
self.arm_controls_stow_arm_button.setEnabled(False)
|
||||
self.arm_controls_unstow_arm_button.setEnabled(False)
|
||||
# #################
|
||||
|
||||
self.arm_controls_calibration_button = self.left_screen.arm_controls_calibration_button # type:QtWidgets.QPushButton
|
||||
self.arm_controls_clear_faults_button = self.left_screen.arm_controls_clear_faults_button # type:QtWidgets.QPushButton
|
||||
self.arm_controls_reset_motor_drivers_button = self.left_screen.arm_controls_reset_motor_drivers_button # type:QtWidgets.QPushButton
|
||||
|
||||
@@ -15,8 +15,8 @@ import Framework.StartupSystems.ROSMasterChecker as ROSMasterChecker
|
||||
import Framework.LoggingSystems.Logger as Logger
|
||||
import Framework.VideoSystems.RoverVideoCoordinator as RoverVideoCoordinator
|
||||
import Framework.MapSystems.RoverMapCoordinator as RoverMapCoordinator
|
||||
import Framework.InputSystems.LogitechControllerControlSender as JoystickControlSender
|
||||
import Framework.InputSystems.XBOXControllerControlSender as ControllerControlSender
|
||||
import Framework.ControlSystems.DriveAndCameraControlSender as JoystickControlSender
|
||||
import Framework.ControlSystems.EffectorsAndArmControlSender as ControllerControlSender
|
||||
import Framework.NavigationSystems.SpeedAndHeadingIndication as SpeedAndHeading
|
||||
import Framework.NavigationSystems.WaypointsCoordinator as WaypointsCoordinator
|
||||
import Framework.ArmSystems.ArmIndication as ArmIndication
|
||||
@@ -111,8 +111,8 @@ class GroundStation(QtCore.QObject):
|
||||
# ##### Instantiate Threaded Classes ######
|
||||
self.__add_thread("Video Coordinator", RoverVideoCoordinator.RoverVideoCoordinator(self.shared_objects))
|
||||
self.__add_thread("Map Coordinator", RoverMapCoordinator.RoverMapCoordinator(self.shared_objects))
|
||||
self.__add_thread("Joystick Sender", JoystickControlSender.LogitechControllerControlSender(self.shared_objects))
|
||||
self.__add_thread("Controller Sender", ControllerControlSender.XBOXControllerControlSender(self.shared_objects))
|
||||
self.__add_thread("Joystick Sender", JoystickControlSender.DriveAndCameraControlSender(self.shared_objects))
|
||||
self.__add_thread("Controller Sender", ControllerControlSender.EffectorsAndArmControlSender(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("Ubiquiti Status", UbiquitiStatusCore.UbiquitiStatus(self.shared_objects))
|
||||
|
||||
@@ -39,7 +39,7 @@
|
||||
<!--<param name="port" value="/dev/rover/ttyARM"/>-->
|
||||
</node>
|
||||
|
||||
<node name="scale" pkg="rover_control" type="emergency_scale.py" respawn="true" output="screen">
|
||||
</node>
|
||||
<!--<node name="scale" pkg="rover_control" type="emergency_scale.py" respawn="true" output="screen">-->
|
||||
<!--</node>-->
|
||||
</group>
|
||||
</launch>
|
||||
|
||||
Reference in New Issue
Block a user