Skip to content

Commit

Permalink
Remapped controller
Browse files Browse the repository at this point in the history
  • Loading branch information
AydenBravender committed Jan 21, 2025
1 parent eb9b3d4 commit d28a593
Show file tree
Hide file tree
Showing 2 changed files with 11 additions and 8 deletions.
6 changes: 3 additions & 3 deletions kipp_arm/src/moveit_spear/config/moveit_servo_config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,10 @@
command_in_type: "unitless" # "unitless"> in the range [-1:1], as if from joystick. "speed_units"> cmds are in m/s and rad/s
scale:
# Scale parameters are only used if command_in_type=="unitless"
linear: 0.2 # Max linear velocity. Unit is [m/s]. Only used for Cartesian commands.
rotational: 8.0 # Max angular velocity. Unit is [rad/s]. Only used for Cartesian commands.
linear: 1.5 # Max linear velocity. Unit is [m/s]. Only used for Cartesian commands.
rotational: 0.9 # Max angular velocity. Unit is [rad/s]. Only used for Cartesian commands.
# Max joint angular/linear velocity. Only used for joint commands on joint_command_in_topic.
joint: 0.9
joint: 1.5

# Optionally override Servo's internal velocity scaling when near singularity or collision (0.0 = use internal velocity scaling)
# override_velocity_scaling_factor = 0.0 # valid range [0.0:1.0]
Expand Down
13 changes: 8 additions & 5 deletions kipp_arm/src/teleop/teleop/moded_joy_arm.py
Original file line number Diff line number Diff line change
Expand Up @@ -124,10 +124,10 @@ def ConvertJoyToCommand(self):
eef_open_msg.data = self.joystick_msg.axes[RIGHT_BUMPER]
self.publisher_.publish(eef_open_msg)

if self.joystick_msg.buttons[RIGHT_TRIGGER]:
if self.joystick_msg.buttons[LEFT_BUMPER]:
i += 1
eef_close_msg = Float32()
eef_close_msg.data = -self.joystick_msg.axes[RIGHT_TRIGGER]
eef_close_msg.data = -self.joystick_msg.axes[LEFT_BUMPER]
self.publisher_.publish(eef_close_msg)

if i > 0:
Expand All @@ -145,9 +145,10 @@ def publish_twist_command(self):
self.twist_msg.header.stamp = self.get_clock().now().to_msg()
self.twist_msg.header.frame_id = "base_link"

lin_x_left_bumper = (self.joystick_msg.buttons[LEFT_BUMPER])
lin_x_left_trigger = -0.5 * (self.joystick_msg.axes[LEFT_TRIGGER]+1)
lin_x = lin_x_left_bumper + lin_x_left_trigger
lin_x_right_trigger = -0.5 * (self.joystick_msg.axes[RIGHT_TRIGGER]+1)
self.get_logger().info(f"RIGHT {lin_x_right_trigger}")
lin_x_left_trigger = 0.5 * (self.joystick_msg.axes[LEFT_TRIGGER]+1)
lin_x = lin_x_right_trigger + lin_x_left_trigger

if abs(lin_x) > deadband_threshold or abs(self.joystick_msg.axes[LEFT_STICK_Y]) > deadband_threshold or abs(self.joystick_msg.axes[LEFT_STICK_X]) > deadband_threshold:
self.twist_msg.twist.linear.z = -self.joystick_msg.axes[LEFT_STICK_Y]
Expand All @@ -172,6 +173,8 @@ def publish_joint_command(self):

def JoystickMsg(self, msg):
self.joystick_msg = msg
self.get_logger().info(f"Joystick Axes Values: {msg.axes}")
self.get_logger().info(f"Joystick Button Values: {msg.buttons}")

def main(args=None):
rclpy.init(args=args)
Expand Down

0 comments on commit d28a593

Please sign in to comment.