mirror of
https://github.com/OSURoboticsClub/Rover_2017_2018.git
synced 2025-11-09 02:31:14 +00:00
Fixes to work with new controller and manipulate pitch.
Thanks Ben Signed-off-by: Prathyoosha Chaya <chayap@oregonstate.edu>
This commit is contained in:
@@ -13,8 +13,8 @@ from rover_control.msg import DriveCommandMessage, TowerPanTiltControlMessage
|
|||||||
#####################################
|
#####################################
|
||||||
# Global Variables
|
# Global Variables
|
||||||
#####################################
|
#####################################
|
||||||
GAME_CONTROLLER_NAME = "Microsoft X-Box One S pad"
|
#GAME_CONTROLLER_NAME = "Microsoft X-Box One S pad" <-- This was the actual xbox controller that Dylan had to buy at CIRC 2018
|
||||||
|
GAME_CONTROLLER_NAME = "PowerA Xbox One wired controller"
|
||||||
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"
|
||||||
DEFAULT_CHASSIS_PAN_TILT_COMMAND_TOPIC = "/rover_control/chassis/pan_tilt/control"
|
DEFAULT_CHASSIS_PAN_TILT_COMMAND_TOPIC = "/rover_control/chassis/pan_tilt/control"
|
||||||
|
|||||||
@@ -197,6 +197,8 @@ class EffectorsAndArmControlSender(QtCore.QThread):
|
|||||||
self.gripper_mode_wide_label = self.right_screen.gripper_mode_wide_label # type: QtWidgets.QLabel
|
self.gripper_mode_wide_label = self.right_screen.gripper_mode_wide_label # type: QtWidgets.QLabel
|
||||||
self.gripper_mode_scissor_label = self.right_screen.gripper_mode_scissor_label # type: QtWidgets.QLabel
|
self.gripper_mode_scissor_label = self.right_screen.gripper_mode_scissor_label # type: QtWidgets.QLabel
|
||||||
|
|
||||||
|
self.arm_speed_limit_slider = self.right_screen.arm_speed_limit_slider # type: QtWidgets.QSlider
|
||||||
|
|
||||||
# ########## Get the settings instance ##########
|
# ########## Get the settings instance ##########
|
||||||
self.settings = QtCore.QSettings()
|
self.settings = QtCore.QSettings()
|
||||||
|
|
||||||
@@ -373,30 +375,27 @@ class EffectorsAndArmControlSender(QtCore.QThread):
|
|||||||
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
|
speed_limit = self.arm_speed_limit_slider.value() / 100.0
|
||||||
|
|
||||||
left_trigger_ratio = left_trigger / 255.0
|
|
||||||
right_trigger_ratio = right_trigger / 255.0
|
|
||||||
|
|
||||||
if left_trigger > 0:
|
if left_trigger > 0:
|
||||||
should_publish_arm = True
|
should_publish_arm = True
|
||||||
arm_control_message.base = ((left_x_axis / THUMB_STICK_MAX) * BASE_SCALAR) * left_trigger_ratio
|
arm_control_message.base = ((left_x_axis / THUMB_STICK_MAX) * BASE_SCALAR) * speed_limit
|
||||||
arm_control_message.shoulder = ((left_y_axis / THUMB_STICK_MAX) * SHOULDER_SCALAR) * left_trigger_ratio
|
arm_control_message.shoulder = ((left_y_axis / THUMB_STICK_MAX) * SHOULDER_SCALAR) * speed_limit
|
||||||
arm_control_message.elbow = (-(right_y_axis / THUMB_STICK_MAX) * ELBOW_SCALAR) * left_trigger_ratio
|
arm_control_message.elbow = (-(right_y_axis / THUMB_STICK_MAX) * ELBOW_SCALAR) * speed_limit
|
||||||
arm_control_message.roll = (-(right_x_axis / THUMB_STICK_MAX) * ROLL_SCALAR) * left_trigger_ratio
|
arm_control_message.roll = (-(right_x_axis / THUMB_STICK_MAX) * ROLL_SCALAR) * speed_limit
|
||||||
|
|
||||||
elif right_trigger > 0:
|
elif right_trigger > 0:
|
||||||
should_publish_arm = True
|
should_publish_arm = True
|
||||||
should_publish_gripper = True
|
should_publish_gripper = True
|
||||||
|
|
||||||
arm_control_message.wrist_roll = ((left_x_axis / THUMB_STICK_MAX) * BASE_SCALAR) * right_trigger_ratio
|
arm_control_message.wrist_roll = ((left_x_axis / THUMB_STICK_MAX) * BASE_SCALAR) * speed_limit
|
||||||
|
|
||||||
# ##### FIXME #####
|
# ##### FIXME #####
|
||||||
# Remove this once the arm is fixed
|
# Remove this once the arm is fixed
|
||||||
# arm_control_message.wrist_pitch = (-(left_y_axis / THUMB_STICK_MAX) * WRIST_PITCH_SCALAR) * right_trigger_ratio
|
# arm_control_message.wrist_pitch = (-(left_y_axis / THUMB_STICK_MAX) * WRIST_PITCH_SCALAR) * speed_limit
|
||||||
# #################
|
# #################
|
||||||
|
|
||||||
gripper_control_message.gripper_position_relative = (-(right_y_axis / THUMB_STICK_MAX) * GRIPPER_MOVEMENT_SCALAR) * right_trigger_ratio
|
gripper_control_message.gripper_position_relative = (-(right_y_axis / THUMB_STICK_MAX) * GRIPPER_MOVEMENT_SCALAR)
|
||||||
|
|
||||||
if should_publish_arm:
|
if should_publish_arm:
|
||||||
self.relative_arm_control_publisher.publish(arm_control_message)
|
self.relative_arm_control_publisher.publish(arm_control_message)
|
||||||
|
|||||||
@@ -2217,7 +2217,7 @@ Position</string>
|
|||||||
<widget class="QLabel" name="label_9">
|
<widget class="QLabel" name="label_9">
|
||||||
<property name="font">
|
<property name="font">
|
||||||
<font>
|
<font>
|
||||||
<pointsize>14</pointsize>
|
<pointsize>12</pointsize>
|
||||||
<weight>75</weight>
|
<weight>75</weight>
|
||||||
<bold>true</bold>
|
<bold>true</bold>
|
||||||
</font>
|
</font>
|
||||||
@@ -2308,7 +2308,7 @@ Position</string>
|
|||||||
<widget class="QLabel" name="label_5">
|
<widget class="QLabel" name="label_5">
|
||||||
<property name="font">
|
<property name="font">
|
||||||
<font>
|
<font>
|
||||||
<pointsize>14</pointsize>
|
<pointsize>12</pointsize>
|
||||||
<weight>75</weight>
|
<weight>75</weight>
|
||||||
<bold>true</bold>
|
<bold>true</bold>
|
||||||
</font>
|
</font>
|
||||||
@@ -2378,13 +2378,13 @@ Position</string>
|
|||||||
<widget class="QLabel" name="label_3">
|
<widget class="QLabel" name="label_3">
|
||||||
<property name="font">
|
<property name="font">
|
||||||
<font>
|
<font>
|
||||||
<pointsize>14</pointsize>
|
<pointsize>12</pointsize>
|
||||||
<weight>75</weight>
|
<weight>75</weight>
|
||||||
<bold>true</bold>
|
<bold>true</bold>
|
||||||
</font>
|
</font>
|
||||||
</property>
|
</property>
|
||||||
<property name="text">
|
<property name="text">
|
||||||
<string>Speed Limit</string>
|
<string>Rover Speed Limit</string>
|
||||||
</property>
|
</property>
|
||||||
<property name="alignment">
|
<property name="alignment">
|
||||||
<set>Qt::AlignCenter</set>
|
<set>Qt::AlignCenter</set>
|
||||||
@@ -2419,11 +2419,71 @@ Position</string>
|
|||||||
</property>
|
</property>
|
||||||
</spacer>
|
</spacer>
|
||||||
</item>
|
</item>
|
||||||
|
<item>
|
||||||
|
<layout class="QVBoxLayout" name="verticalLayout_16">
|
||||||
|
<item>
|
||||||
|
<spacer name="verticalSpacer_8">
|
||||||
|
<property name="orientation">
|
||||||
|
<enum>Qt::Vertical</enum>
|
||||||
|
</property>
|
||||||
|
<property name="sizeHint" stdset="0">
|
||||||
|
<size>
|
||||||
|
<width>20</width>
|
||||||
|
<height>40</height>
|
||||||
|
</size>
|
||||||
|
</property>
|
||||||
|
</spacer>
|
||||||
|
</item>
|
||||||
|
<item>
|
||||||
|
<widget class="QLabel" name="label_11">
|
||||||
|
<property name="font">
|
||||||
|
<font>
|
||||||
|
<pointsize>12</pointsize>
|
||||||
|
<weight>75</weight>
|
||||||
|
<bold>true</bold>
|
||||||
|
</font>
|
||||||
|
</property>
|
||||||
|
<property name="text">
|
||||||
|
<string>Arm Speed Limit</string>
|
||||||
|
</property>
|
||||||
|
<property name="alignment">
|
||||||
|
<set>Qt::AlignCenter</set>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
<item>
|
||||||
|
<widget class="QSlider" name="arm_speed_limit_slider">
|
||||||
|
<property name="maximum">
|
||||||
|
<number>100</number>
|
||||||
|
</property>
|
||||||
|
<property name="value">
|
||||||
|
<number>50</number>
|
||||||
|
</property>
|
||||||
|
<property name="orientation">
|
||||||
|
<enum>Qt::Horizontal</enum>
|
||||||
|
</property>
|
||||||
|
</widget>
|
||||||
|
</item>
|
||||||
|
<item>
|
||||||
|
<spacer name="verticalSpacer_9">
|
||||||
|
<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>
|
<item>
|
||||||
<widget class="QLabel" name="label_6">
|
<widget class="QLabel" name="label_6">
|
||||||
<property name="font">
|
<property name="font">
|
||||||
<font>
|
<font>
|
||||||
<pointsize>14</pointsize>
|
<pointsize>12</pointsize>
|
||||||
<weight>75</weight>
|
<weight>75</weight>
|
||||||
<bold>true</bold>
|
<bold>true</bold>
|
||||||
</font>
|
</font>
|
||||||
@@ -2534,7 +2594,7 @@ Position</string>
|
|||||||
<widget class="QLabel" name="label_4">
|
<widget class="QLabel" name="label_4">
|
||||||
<property name="font">
|
<property name="font">
|
||||||
<font>
|
<font>
|
||||||
<pointsize>14</pointsize>
|
<pointsize>12</pointsize>
|
||||||
<weight>75</weight>
|
<weight>75</weight>
|
||||||
<bold>true</bold>
|
<bold>true</bold>
|
||||||
</font>
|
</font>
|
||||||
@@ -2578,7 +2638,13 @@ Position</string>
|
|||||||
<property name="minimumSize">
|
<property name="minimumSize">
|
||||||
<size>
|
<size>
|
||||||
<width>0</width>
|
<width>0</width>
|
||||||
<height>50</height>
|
<height>25</height>
|
||||||
|
</size>
|
||||||
|
</property>
|
||||||
|
<property name="maximumSize">
|
||||||
|
<size>
|
||||||
|
<width>16777215</width>
|
||||||
|
<height>25</height>
|
||||||
</size>
|
</size>
|
||||||
</property>
|
</property>
|
||||||
</widget>
|
</widget>
|
||||||
@@ -2611,7 +2677,13 @@ Position</string>
|
|||||||
<property name="minimumSize">
|
<property name="minimumSize">
|
||||||
<size>
|
<size>
|
||||||
<width>0</width>
|
<width>0</width>
|
||||||
<height>50</height>
|
<height>25</height>
|
||||||
|
</size>
|
||||||
|
</property>
|
||||||
|
<property name="maximumSize">
|
||||||
|
<size>
|
||||||
|
<width>16777215</width>
|
||||||
|
<height>25</height>
|
||||||
</size>
|
</size>
|
||||||
</property>
|
</property>
|
||||||
</widget>
|
</widget>
|
||||||
|
|||||||
@@ -3,7 +3,7 @@
|
|||||||
<!-- Start Undercarriage Camera -->
|
<!-- Start Undercarriage Camera -->
|
||||||
<node name="undercarriage" pkg="rover_camera" type="rover_camera" launch-prefix="taskset -c 1" respawn="true" output="screen">
|
<node name="undercarriage" pkg="rover_camera" type="rover_camera" launch-prefix="taskset -c 1" respawn="true" output="screen">
|
||||||
<param name="device_path" value="/dev/rover/camera_undercarriage"/>
|
<param name="device_path" value="/dev/rover/camera_undercarriage"/>
|
||||||
<param name="upside_down" value="true"/>
|
<!--<param name="upside_down" value="true"/>-->
|
||||||
</node>
|
</node>
|
||||||
|
|
||||||
<!--<!– Start Main Navigation Camera –>-->
|
<!--<!– Start Main Navigation Camera –>-->
|
||||||
|
|||||||
Reference in New Issue
Block a user