Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Standardizing End-Effector Frame Conventions for Robot-Gripper Compatibility #625

Open
wants to merge 5 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions robosuite/models/assets/grippers/bd_gripper.xml
Original file line number Diff line number Diff line change
Expand Up @@ -44,11 +44,11 @@
</default>

<worldbody>
<body name="right_gripper" pos="0 0 0" quat="1 0 0 0">
<body name="right_gripper" pos="0 0 -0.05" quat="0 0.707107 0 0.707107">
<site name="ft_frame" pos="0 0 0" size="0.01 0.01 0.01" rgba="1 0 0 1" type="sphere" group="1"/>
<inertial pos="0 0 0.0" quat="0.707107 0.707107 0 0" mass="0.3" diaginertia="0.09 0.07 0.05" />
<!-- This site was added for visualization. -->
<body name="eef" pos="0 0 0.0" quat="0.707 0. -0.707 0.">
<body name="eef" pos="0.2 0 0" quat="0.5 0.5 0.5 0.5">
<site name="grip_site" pos="0 0 0" size="0.01 0.01 0.01" rgba="0 0 1 0.5" type="sphere" group="1"/>
<site name="ee_x" pos="0.1 0 0" size="0.005 .1" quat="0.707105 0 0.707108 0 " rgba="1 0 0 0" type="cylinder" group="1"/>
<site name="ee_y" pos="0 0.1 0" size="0.005 .1" quat="0.707105 0.707108 0 0" rgba="0 1 0 0" type="cylinder" group="1"/>
Expand Down
6 changes: 3 additions & 3 deletions robosuite/models/assets/grippers/fourier_left_hand.xml
Original file line number Diff line number Diff line change
Expand Up @@ -65,16 +65,16 @@
</asset>

<worldbody>
<body name="left_hand" pos="0 0 0" quat="0.7071068 0.7071068 0 0">
<body name="left_hand" pos="0 0 0" quat="0.5 -0.5 0.5 -0.5">
<site name="ft_frame" pos="0 0 0" size="0.01 0.01 0.01" rgba="1 0 0 0" type="sphere" group="1"/>
<inertial diaginertia="0 0 0" mass="0" pos="0 0 0"/>
<body name="eef" pos="0 0 0" quat="0.707 0. -0.707 0.">
<body name="eef" pos="0 0 0" quat="0.707107 0.707107 0 0">
<site name="grip_site" pos="0 0 0" size="0.01 0.01 0.01" rgba="1 1 0 1" type="sphere" group="2"/>
<site name="ee_x" pos="0.1 0 0" size="0.005 .1" quat="0.707105 0 0.707108 0 " rgba="1 0 0 0" type="cylinder" group="1"/>
<site name="ee_y" pos="0 0.1 0" size="0.005 .1" quat="0.707105 0.707108 0 0" rgba="0 1 0 0" type="cylinder" group="1"/>
<site name="ee_z" pos="0 0 0.1" size="0.005 .1" quat="1 0 0 0" rgba="0 0 1 0" type="cylinder" group="1"/>
<!-- This site was added for visualization. -->
<site name="grip_site_cylinder" pos="0 0 0" quat="-0.5 -0.5 -0.5 0.5" size="0.005 0.5" rgba="0 1 0 0.3" type="cylinder" group="1"/>
<site name="grip_site_cylinder" pos="0 0 0" size="0.005 0.5" rgba="0 1 0 0.3" type="cylinder" group="1"/>
</body>

<!-- Palm -->
Expand Down
6 changes: 3 additions & 3 deletions robosuite/models/assets/grippers/fourier_right_hand.xml
Original file line number Diff line number Diff line change
Expand Up @@ -78,16 +78,16 @@
</asset>

<worldbody>
<body name="right_hand" pos="0 0 0" quat="0.7071068 0.7071068 0 0">
<body name="right_hand" pos="0 0 0" quat="0.5 -0.5 -0.5 0.5">
<site name="ft_frame" pos="0 0 0" size="0.01 0.01 0.01" rgba="1 0 0 0" type="sphere" group="1"/>
<!-- <inertial diaginertia="0 0 0" mass="0" pos="0 0 0"/> -->
<body name="eef" pos="0 0 0" quat="0.707 0. -0.707 0.">
<body name="eef" pos="0 0 0" quat="0.707107 0.707107 0 0">
<site name="grip_site" pos="0 0 0" size="0.01 0.01 0.01" rgba="1 1 0 1" type="sphere" group="2"/>
<site name="ee_x" pos="0.1 0 0" size="0.005 .1" quat="0.707105 0 0.707108 0 " rgba="1 0 0 0" type="cylinder" group="1"/>
<site name="ee_y" pos="0 0.1 0" size="0.005 .1" quat="0.707105 0.707108 0 0" rgba="0 1 0 0" type="cylinder" group="1"/>
<site name="ee_z" pos="0 0 0.1" size="0.005 .1" quat="1 0 0 0" rgba="0 0 1 0" type="cylinder" group="1"/>
<!-- This site was added for visualization. -->
<site name="grip_site_cylinder" pos="0 0 0" quat="-0.5 -0.5 -0.5 0.5" size="0.005 0.5" rgba="0 1 0 0.3" type="cylinder" group="1"/>
<site name="grip_site_cylinder" pos="0 0 0" size="0.005 0.5" rgba="0 1 0 0.3" type="cylinder" group="1"/>
</body>

<!-- Palm -->
Expand Down
8 changes: 4 additions & 4 deletions robosuite/models/assets/grippers/inspire_left_hand.xml
Original file line number Diff line number Diff line change
Expand Up @@ -75,16 +75,16 @@
</asset>

<worldbody>
<body name="left_hand" pos="0 0 0" quat="0.7071068 0.7071068 0 0">
<body name="left_hand" pos="0 0 0" quat="0.5 -0.5 0.5 -0.5">
<site name="ft_frame" pos="0 0 0" size="0.01 0.01 0.01" rgba="1 0 0 0" type="sphere" group="1"/>
<inertial diaginertia="0 0 0" mass="0" pos="0 0 0"/>
<body name="eef" pos="0 0 0" quat="0.707 0. -0.707 0.">
<site name="grip_site" pos="0 0 0" size="0.01 0.01 0.01" rgba="1 1 0 1" type="sphere" group="2"/>
<body name="eef" pos="0 0 0" quat="0.707107 0.707107 0 0">
<site name="grip_site" pos="0 0 0" size="0.01 0.01 0.01" rgba="1 1 0 0" type="sphere" group="2"/>
<site name="ee_x" pos="0.1 0 0" size="0.005 .1" quat="0.707105 0 0.707108 0 " rgba="1 0 0 0" type="cylinder" group="1"/>
<site name="ee_y" pos="0 0.1 0" size="0.005 .1" quat="0.707105 0.707108 0 0" rgba="0 1 0 0" type="cylinder" group="1"/>
<site name="ee_z" pos="0 0 0.1" size="0.005 .1" quat="1 0 0 0" rgba="0 0 1 0" type="cylinder" group="1"/>
<!-- This site was added for visualization. -->
<site name="grip_site_cylinder" pos="0 0 0" quat="-0.5 -0.5 -0.5 0.5" size="0.005 0.5" rgba="0 1 0 0.3" type="cylinder" group="1"/>
<site name="grip_site_cylinder" pos="0 0 0" size="0.005 0.5" rgba="0 1 0 0.3" type="cylinder" group="1"/>
</body>


Expand Down
6 changes: 3 additions & 3 deletions robosuite/models/assets/grippers/inspire_right_hand.xml
Original file line number Diff line number Diff line change
Expand Up @@ -72,16 +72,16 @@
</asset>

<worldbody>
<body name="right_hand" pos="0 0 0" quat="0.7071068 0.7071068 0 0">
<body name="right_hand" pos="0 0 0" quat="0.5 -0.5 -0.5 0.5">
<site name="ft_frame" pos="0 0 0" size="0.01 0.01 0.01" rgba="1 0 0 0" type="sphere" group="1"/>
<inertial diaginertia="0 0 0" mass="0" pos="0 0 0"/>
<body name="eef" pos="0 0 0" quat="0.707 0. -0.707 0.">
<body name="eef" pos="0 0 0" quat="0.707107 0.707107 0 0">
<site name="grip_site" pos="0 0 0" size="0.01 0.01 0.01" rgba="1 1 0 1" type="sphere" group="2"/>
<site name="ee_x" pos="0.1 0 0" size="0.005 .1" quat="0.707105 0 0.707108 0 " rgba="1 0 0 0" type="cylinder" group="1"/>
<site name="ee_y" pos="0 0.1 0" size="0.005 .1" quat="0.707105 0.707108 0 0" rgba="0 1 0 0" type="cylinder" group="1"/>
<site name="ee_z" pos="0 0 0.1" size="0.005 .1" quat="1 0 0 0" rgba="0 0 1 0" type="cylinder" group="1"/>
<!-- This site was added for visualization. -->
<site name="grip_site_cylinder" pos="0 0 0" quat="-0.5 -0.5 -0.5 0.5" size="0.005 0.5" rgba="0 1 0 0.3" type="cylinder" group="1"/>
<site name="grip_site_cylinder" pos="0 0 0" size="0.005 0.5" rgba="0 1 0 0.3" type="cylinder" group="1"/>
</body>


Expand Down
15 changes: 12 additions & 3 deletions robosuite/models/assets/robots/gr1/robot.xml
Original file line number Diff line number Diff line change
Expand Up @@ -139,9 +139,13 @@
<site name="r_wrist_site" pos="0 0 0" size="0.03 0.03 0.03" rgba="1 0 0 0" type="sphere" group="1" />
<inertial pos="0.0060733 0.0018907 -0.084578" quat="0.647336 -0.27161 -0.257721 0.6639" mass="0.53221" diaginertia="0.000319947 0.000196296 0.000182477" />
<joint name="r_wrist_pitch" pos="0 0 0" axis="0.0 1.0 0.0" range="-1.5 1.5" />
<body name="right_eef" pos="0 0 0" quat="-0.707107 0 0 0.707107">

<body name="right_eef" pos="0 0 0" quat="0 1 0 0">

<!-- These sites were added for visualization. -->
<site name="right_ee_x" pos="0.1 0 0" size="0.005 .1" quat="0.707105 0 0.707108 0 " rgba="1 0 0 0" type="cylinder" group="1"/>
<site name="right_ee_y" pos="0 0.1 0" size="0.005 .1" quat="0.707105 0.707108 0 0" rgba="0 1 0 0" type="cylinder" group="1"/>
<site name="right_ee_z" pos="0 0 0.1" size="0.005 .1" quat="1 0 0 0" rgba="0 0 1 0" type="cylinder" group="1"/>

<body name="right_mount" quat="0 0 1 0" />
<body name="right_hand_eef" pos="0 0 0" />
<camera mode="fixed" name="eye_in_right_hand" pos="-0.05 0.15 0.0" quat="0.965926 -0.258819 0.000000 0.000000" fovy="75" />
Expand Down Expand Up @@ -192,7 +196,12 @@
<joint name="l_wrist_pitch" pos="0 0 0" axis="0.0 1.0 0.0" range="-1.5 1.5" />
<site name="l_wrist_site" pos="0 0 0" size="0.03 0.03 0.03" rgba="1 0 0 0" type="sphere" group="1" />
<inertial pos="0.0071289 -0.0026192 -0.078567" quat="0.298548 0.646339 0.631172 0.307795" mass="0.5239" diaginertia="0.000345825 0.000211684 0.000195941" />
<body name="left_eef" pos="0 0 0" quat="0.707107 0 0 0.707107">
<body name="left_eef" pos="0 0 0" quat="0 1 0 0">
<!-- These sites were added for visualization. -->
<site name="left_ee_x" pos="0.1 0 0" size="0.005 .1" quat="0.707105 0 0.707108 0 " rgba="1 0 0 0" type="cylinder" group="1"/>
<site name="left_ee_y" pos="0 0.1 0" size="0.005 .1" quat="0.707105 0.707108 0 0" rgba="0 1 0 0" type="cylinder" group="1"/>
<site name="left_ee_z" pos="0 0 0.1" size="0.005 .1" quat="1 0 0 0" rgba="0 0 1 0" type="cylinder" group="1"/>

<site name="left_eef_site" pos="0 0 0" size="0.01" rgba="1 0.3 0.3 1" group="2" />
<body name="left_mount" quat="0 0 1 0" />
<body name="left_hand_eefd" pos="0 0 0" />
Expand Down
4 changes: 4 additions & 0 deletions robosuite/models/assets/robots/panda/robot.xml
Original file line number Diff line number Diff line change
Expand Up @@ -220,6 +220,10 @@
<geom type="mesh" group="0" mesh="link7" name="link7_collision"/>
<body name="right_hand" pos="0 0 0.1065" quat="0.924 0 0 -0.383">
<inertial pos="0 0 0" mass="0.5" diaginertia="0.05 0.05 0.05"/>
<!-- These sites were added for visualization. -->
<site name="ee_x" pos="0.1 0 0" size="0.005 .1" quat="0.707105 0 0.707108 0 " rgba="1 0 0 0" type="cylinder" group="1"/>
<site name="ee_y" pos="0 0.1 0" size="0.005 .1" quat="0.707105 0.707108 0 0" rgba="0 1 0 0" type="cylinder" group="1"/>
<site name="ee_z" pos="0 0 0.1" size="0.005 .1" quat="1 0 0 0" rgba="0 0 1 0" type="cylinder" group="1"/>
<!-- This camera points out from the eef. -->
<camera mode="fixed" name="eye_in_hand" pos="0.05 0 0" quat="0 0.707108 0.707108 0" fovy="75"/>
<!-- to add gripper -->
Expand Down
6 changes: 5 additions & 1 deletion robosuite/models/assets/robots/spot_arm/robot.xml
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,11 @@
diaginertia="0.00176281 0.00168181 0.000767414"/>
<joint name="arm_wr1" axis="1 0 0" range="-2.87979 2.87979"/>
<!--Start of right_hand-->
<body name="right_hand" pos="0.0 0.0 0.0" quat="1 0 0 0">
<body name="right_hand" pos="0.05 0.0 0.0" quat="0 0.707107 0 0.707107">
<!-- These sites are used for visualization only -->
<site name="ee_x" pos="0.1 0 0" size="0.005 .1" quat="0.707105 0 0.707108 0 " rgba="1 0 0 0" type="cylinder" group="1"/>
<site name="ee_y" pos="0 0.1 0" size="0.005 .1" quat="0.707105 0.707108 0 0" rgba="0 1 0 0" type="cylinder" group="1"/>
<site name="ee_z" pos="0 0 0.1" size="0.005 .1" quat="1 0 0 0" rgba="0 0 1 0" type="cylinder" group="1"/>
<camera mode="fixed" name="right_eye_in_hand" pos="0.05 0 0" quat="0.5 0.5 -0.5 -0.5" fovy="75"/>
</body>
</body>
Expand Down
24 changes: 12 additions & 12 deletions robosuite/models/robots/compositional.py
Original file line number Diff line number Diff line change
Expand Up @@ -81,24 +81,24 @@ class PandaDexRH(Panda):
def default_gripper(self):
return {"right": "InspireRightHand"}

@property
def gripper_mount_pos_offset(self):
return {"right": [0.0, 0.0, 0.0]}
# @property
# def gripper_mount_pos_offset(self):
# return {"right": [0.0, 0.0, 0.0]}

@property
def gripper_mount_quat_offset(self):
return {"right": [-0.5, 0.5, 0.5, -0.5]}
# @property
# def gripper_mount_quat_offset(self):
# return {"right": [0.5, -0.5, -0.5, 0.5]}


class PandaDexLH(Panda):
@property
def default_gripper(self):
return {"right": "InspireLeftHand"}

@property
def gripper_mount_pos_offset(self):
return {"right": [0.0, 0.0, 0.0]}
# @property
# def gripper_mount_pos_offset(self):
# return {"right": [0.0, 0.0, 0.0]}

@property
def gripper_mount_quat_offset(self):
return {"right": [0.5, -0.5, 0.5, -0.5]}
# @property
# def gripper_mount_quat_offset(self):
# return {"right": [0.5, -0.5, 0.5, -0.5]}
Loading