Browse Source

fix keyboard teleop for wrist

feature/pluggable_end_effector
Aaron Edsinger 3 years ago
parent
commit
5b1fc78d17
3 changed files with 27 additions and 19 deletions
  1. +1
    -1
      stretch_core/nodes/keyboard_teleop
  2. +25
    -17
      stretch_core/rviz/stretch_simple_test.rviz
  3. +1
    -1
      stretch_description/urdf/stretch_dex_wrist_beta.xacro

+ 1
- 1
stretch_core/nodes/keyboard_teleop View File

@ -105,7 +105,7 @@ class GetKeyboardCommands:
# dex joints # dex joints
if 'joint_wrist_pitch' in self.joints: if 'joint_wrist_pitch' in self.joints:
print('|{:^22}{:^21}|'.format('c PITCH FORWARD', 'v PITCH BACK'))
print('|{:^22}{:^21}|'.format('v PITCH FORWARD', 'c PITCH BACK'))
if 'joint_wrist_roll' in self.joints: if 'joint_wrist_roll' in self.joints:
print('|{:^22}{:^21}|'.format('o ROLL FORWARD', 'p ROLL BACK')) print('|{:^22}{:^21}|'.format('o ROLL FORWARD', 'p ROLL BACK'))

+ 25
- 17
stretch_core/rviz/stretch_simple_test.rviz View File

@ -8,7 +8,9 @@ Panels:
- /Status1 - /Status1
- /RobotModel1 - /RobotModel1
- /RobotModel1/Links1 - /RobotModel1/Links1
- /RobotModel1/Links1/link_arm_l01
- /RobotModel1/Links1/link_gripper_finger_left1 - /RobotModel1/Links1/link_gripper_finger_left1
- /RobotModel1/Links1/link_gripper_fingertip_right1
Splitter Ratio: 0.5 Splitter Ratio: 0.5
Tree Height: 1484 Tree Height: 1484
- Class: rviz/Selection - Class: rviz/Selection
@ -60,7 +62,7 @@ Visualization Manager:
Collision Enabled: false Collision Enabled: false
Enabled: true Enabled: true
Links: Links:
All Links Enabled: false
All Links Enabled: true
Expand Joint Details: false Expand Joint Details: false
Expand Link Details: false Expand Link Details: false
Expand Tree: false Expand Tree: false
@ -118,7 +120,7 @@ Visualization Manager:
Value: true Value: true
link_arm_l0: link_arm_l0:
Alpha: 1 Alpha: 1
Show Axes: false
Show Axes: true
Show Trail: false Show Trail: false
Value: true Value: true
link_arm_l1: link_arm_l1:
@ -166,15 +168,6 @@ Visualization Manager:
Show Axes: false Show Axes: false
Show Trail: false Show Trail: false
Value: true Value: true
link_grasp_center:
Alpha: 1
Show Axes: false
Show Trail: false
link_gripper:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_gripper_finger_left: link_gripper_finger_left:
Alpha: 1 Alpha: 1
Show Axes: false Show Axes: false
@ -192,7 +185,7 @@ Visualization Manager:
Value: true Value: true
link_gripper_fingertip_right: link_gripper_fingertip_right:
Alpha: 1 Alpha: 1
Show Axes: false
Show Axes: true
Show Trail: false Show Trail: false
Value: true Value: true
link_head: link_head:
@ -225,12 +218,22 @@ Visualization Manager:
Show Axes: false Show Axes: false
Show Trail: false Show Trail: false
Value: true Value: true
link_puller:
link_right_wheel:
Alpha: 1 Alpha: 1
Show Axes: false Show Axes: false
Show Trail: false Show Trail: false
Value: false
link_right_wheel:
Value: true
link_straight_gripper:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_wrist_pitch:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link_wrist_roll:
Alpha: 1 Alpha: 1
Show Axes: false Show Axes: false
Show Trail: false Show Trail: false
@ -240,6 +243,11 @@ Visualization Manager:
Show Axes: false Show Axes: false
Show Trail: false Show Trail: false
Value: true Value: true
link_wrist_yaw_bottom:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
respeaker_base: respeaker_base:
Alpha: 1 Alpha: 1
Show Axes: false Show Axes: false
@ -385,10 +393,10 @@ Visualization Manager:
Invert Z Axis: false Invert Z Axis: false
Name: Current View Name: Current View
Near Clip Distance: 0.009999999776482582 Near Clip Distance: 0.009999999776482582
Pitch: 0.8447968363761902
Pitch: 0.5397967100143433
Target Frame: <Fixed Frame> Target Frame: <Fixed Frame>
Value: Orbit (rviz) Value: Orbit (rviz)
Yaw: 5.8704514503479
Yaw: 5.230452060699463
Saved: ~ Saved: ~
Window Geometry: Window Geometry:
Displays: Displays:

+ 1
- 1
stretch_description/urdf/stretch_dex_wrist_beta.xacro View File

@ -108,7 +108,7 @@
link="link_wrist_pitch" /> link="link_wrist_pitch" />
<axis <axis
xyz="0 0 1" /> xyz="0 0 1" />
<limit effort="100" lower="-1.14" upper="3.14" velocity="1.0"/>
<limit effort="100" lower="-0.56" upper="1.56" velocity="1.0"/>
</joint> </joint>
<link <link
name="link_wrist_roll"> name="link_wrist_roll">

Loading…
Cancel
Save