Skip to content

Commit

Permalink
Merge pull request moveit#16 from rethink-kmaroney/master
Browse files Browse the repository at this point in the history
Baxter 0.7.0 SDK Release Updates
  • Loading branch information
isucan committed Nov 20, 2013
2 parents 8ce30a2 + e981756 commit 52b4156
Show file tree
Hide file tree
Showing 3 changed files with 38 additions and 14 deletions.
24 changes: 24 additions & 0 deletions baxter/baxter_moveit_config/config/baxter.srdf
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
<joint name="left_w1" />
<joint name="left_w2" />
<joint name="left_hand" />
<joint name="left_gripper_base" />
<joint name="left_endpoint" />
</group>
<group name="right_arm">
Expand All @@ -29,16 +30,21 @@
<joint name="right_w1" />
<joint name="right_w2" />
<joint name="right_hand" />
<joint name="right_gripper_base" />
<joint name="right_endpoint" />
</group>
<group name="both_arms">
<group name="right_arm" />
<group name="left_arm" />
</group>
<group name="left_hand">
<link name="left_hand" />
<link name="left_gripper_base" />
<link name="left_gripper" />
</group>
<group name="right_hand">
<link name="right_hand" />
<link name="right_gripper_base" />
<link name="right_gripper" />
</group>
<!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'-->
Expand Down Expand Up @@ -119,6 +125,7 @@
<disable_collisions link1="left_gripper" link2="screen" reason="Never" />
<disable_collisions link1="left_gripper" link2="sonar_ring" reason="Never" />
<disable_collisions link1="left_gripper" link2="pedestal" reason="Never" />
<disable_collisions link1="left_hand" link2="left_gripper_base" reason="Adjacent" />
<disable_collisions link1="left_hand" link2="left_hand_camera" reason="Adjacent" />
<disable_collisions link1="left_hand" link2="left_hand_range" reason="Adjacent" />
<disable_collisions link1="left_hand" link2="left_lower_elbow" reason="Never" />
Expand All @@ -145,6 +152,7 @@
<disable_collisions link1="left_hand_range" link2="left_lower_forearm" reason="Never" />
<disable_collisions link1="left_hand_range" link2="left_upper_elbow_visual" reason="Never" />
<disable_collisions link1="left_hand_range" link2="left_upper_forearm" reason="Never" />
<disable_collisions link1="left_wrist" link2="left_gripper_base" reason="Never" />
<disable_collisions link1="left_wrist" link2="left_upper_forearm" reason="Never" />
<disable_collisions link1="left_wrist" link2="left_upper_forearm_visual" reason="Never" />
<disable_collisions link1="left_wrist" link2="pedestal" reason="Never" />
Expand Down Expand Up @@ -202,6 +210,7 @@
<disable_collisions link1="left_upper_forearm" link2="left_upper_forearm_visual" reason="Default" />
<disable_collisions link1="left_upper_forearm" link2="left_wrist" reason="Never" />
<disable_collisions link1="left_upper_forearm" link2="pedestal" reason="Never" />
<disable_collisions link1="left_upper_forearm_visual" link2="torso" reason="Never" />
<disable_collisions link1="left_upper_shoulder" link2="pedestal" reason="Never" />
<disable_collisions link1="left_upper_shoulder" link2="right_lower_elbow" reason="Never" />
<disable_collisions link1="left_upper_shoulder" link2="right_lower_shoulder" reason="Never" />
Expand All @@ -211,12 +220,24 @@
<disable_collisions link1="left_upper_shoulder" link2="screen" reason="Never" />
<disable_collisions link1="left_upper_shoulder" link2="sonar_ring" reason="Never" />
<disable_collisions link1="left_upper_shoulder" link2="torso" reason="Adjacent" />
<disable_collisions link1="pedestal" link2="right_gripper_base" reason="Default" />
<disable_collisions link1="pedestal" link2="right_hand_camera" reason="Default" />
<disable_collisions link1="pedestal" link2="right_hand_range" reason="Default" />
<disable_collisions link1="pedestal" link2="right_lower_elbow" reason="Default" />
<disable_collisions link1="pedestal" link2="right_lower_shoulder" reason="Never" />
<disable_collisions link1="pedestal" link2="right_upper_elbow" reason="Never" />
<disable_collisions link1="pedestal" link2="right_upper_forearm" reason="Never" />
<disable_collisions link1="pedestal" link2="right_upper_forearm_visual" reason="Default" />
<disable_collisions link1="pedestal" link2="right_upper_shoulder" reason="Never" />
<disable_collisions link1="pedestal" link2="left_gripper_base" reason="Default" />
<disable_collisions link1="pedestal" link2="left_hand_camera" reason="Default" />
<disable_collisions link1="pedestal" link2="left_hand_range" reason="Default" />
<disable_collisions link1="pedestal" link2="left_lower_elbow" reason="Default" />
<disable_collisions link1="pedestal" link2="left_lower_shoulder" reason="Never" />
<disable_collisions link1="pedestal" link2="left_upper_elbow" reason="Never" />
<disable_collisions link1="pedestal" link2="left_upper_forearm" reason="Never" />
<disable_collisions link1="pedestal" link2="left_upper_forearm_visual" reason="Default" />
<disable_collisions link1="pedestal" link2="left_upper_shoulder" reason="Never" />
<disable_collisions link1="pedestal" link2="screen" reason="Never" />
<disable_collisions link1="pedestal" link2="sonar_ring" reason="Never" />
<disable_collisions link1="pedestal" link2="torso" reason="Adjacent" />
Expand All @@ -233,6 +254,7 @@
<disable_collisions link1="right_gripper" link2="screen" reason="Never" />
<disable_collisions link1="right_gripper" link2="sonar_ring" reason="Never" />
<disable_collisions link1="right_gripper" link2="pedestal" reason="Never" />
<disable_collisions link1="right_hand" link2="right_gripper_base" reason="Adjacent" />
<disable_collisions link1="right_hand" link2="right_hand_camera" reason="Adjacent" />
<disable_collisions link1="right_hand" link2="right_hand_range" reason="Adjacent" />
<disable_collisions link1="right_hand" link2="right_lower_elbow" reason="Never" />
Expand All @@ -256,6 +278,7 @@
<disable_collisions link1="right_hand_range" link2="right_upper_elbow" reason="Never" />
<disable_collisions link1="right_hand_range" link2="right_upper_elbow_visual" reason="Never" />
<disable_collisions link1="right_hand_range" link2="right_upper_forearm" reason="Never" />
<disable_collisions link1="right_wrist" link2="right_gripper_base" reason="Never" />
<disable_collisions link1="right_wrist" link2="right_upper_forearm" reason="Never" />
<disable_collisions link1="right_wrist" link2="right_upper_forearm_visual" reason="Never" />
<disable_collisions link1="right_wrist" link2="pedestal" reason="Never" />
Expand Down Expand Up @@ -297,6 +320,7 @@
<disable_collisions link1="right_upper_elbow_visual" link2="pedestal" reason="Never" />
<disable_collisions link1="right_upper_forearm" link2="right_upper_forearm_visual" reason="Default" />
<disable_collisions link1="right_upper_forearm" link2="right_wrist" reason="Never" />
<disable_collisions link1="right_upper_forearm_visual" link2="torso" reason="Never" />
<disable_collisions link1="right_upper_shoulder" link2="screen" reason="Never" />
<disable_collisions link1="right_upper_shoulder" link2="sonar_ring" reason="Never" />
<disable_collisions link1="right_upper_shoulder" link2="torso" reason="Adjacent" />
Expand Down
4 changes: 2 additions & 2 deletions baxter/baxter_moveit_config/config/baxter_controllers.yaml
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
controller_list:
- name: /sdk/robot/limb/right
- name: /robot/limb/right
action_ns: follow_joint_trajectory
type: FollowJointTrajectory
default: true
Expand All @@ -11,7 +11,7 @@ controller_list:
- right_w0
- right_w1
- right_w2
- name: /sdk/robot/limb/left
- name: /robot/limb/left
action_ns: follow_joint_trajectory
type: FollowJointTrajectory
default: true
Expand Down
24 changes: 12 additions & 12 deletions baxter/baxter_moveit_config/config/joint_limits.yaml
Original file line number Diff line number Diff line change
@@ -1,32 +1,32 @@
joint_limits:
left_e0:
has_velocity_limits: true
max_velocity: 0.5
max_velocity: 0.27
has_acceleration_limits: true
max_acceleration: 0.5
left_e1:
has_velocity_limits: true
max_velocity: 0.5
max_velocity: 0.27
has_acceleration_limits: true
max_acceleration: 0.5
left_s0:
has_velocity_limits: true
max_velocity: 0.5
max_velocity: 0.27
has_acceleration_limits: true
max_acceleration: 0.5
left_s1:
has_velocity_limits: true
max_velocity: 0.5
max_velocity: 0.27
has_acceleration_limits: true
max_acceleration: 0.5
left_w0:
has_velocity_limits: true
max_velocity: 0.5
max_velocity: 0.3
has_acceleration_limits: true
max_acceleration: 0.5
left_w1:
has_velocity_limits: true
max_velocity: 0.5
max_velocity: 0.3
has_acceleration_limits: true
max_acceleration: 0.5
left_w2:
Expand All @@ -36,32 +36,32 @@ joint_limits:
max_acceleration: 0.5
right_e0:
has_velocity_limits: true
max_velocity: 0.5
max_velocity: 0.27
has_acceleration_limits: true
max_acceleration: 0.5
right_e1:
has_velocity_limits: true
max_velocity: 0.5
max_velocity: 0.27
has_acceleration_limits: true
max_acceleration: 0.5
right_s0:
has_velocity_limits: true
max_velocity: 0.5
max_velocity: 0.27
has_acceleration_limits: true
max_acceleration: 0.5
right_s1:
has_velocity_limits: true
max_velocity: 0.5
max_velocity: 0.27
has_acceleration_limits: true
max_acceleration: 0.5
right_w0:
has_velocity_limits: true
max_velocity: 0.5
max_velocity: 0.3
has_acceleration_limits: true
max_acceleration: 0.5
right_w1:
has_velocity_limits: true
max_velocity: 0.5
max_velocity: 0.3
has_acceleration_limits: true
max_acceleration: 0.5
right_w2:
Expand Down

0 comments on commit 52b4156

Please sign in to comment.