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

Added XArm7 #631

Open
wants to merge 3 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/controllers/composite/composite_controller.py
Original file line number Diff line number Diff line change
Expand Up @@ -200,7 +200,7 @@ def create_action_vector(self, action_dict):
A helper function that creates the action vector given a dictionary
"""
full_action_vector = np.zeros(self.action_limits[0].shape)
for (part_name, action_vector) in action_dict.items():
for part_name, action_vector in action_dict.items():
if part_name not in self._action_split_indexes:
ROBOSUITE_DEFAULT_LOGGER.debug(f"{part_name} is not specified in the action space")
continue
Expand Down Expand Up @@ -349,7 +349,7 @@ def action_limits(self):

def create_action_vector(self, action_dict: Dict[str, np.ndarray]) -> np.ndarray:
full_action_vector = np.zeros(self.action_limits[0].shape)
for (part_name, action_vector) in action_dict.items():
for part_name, action_vector in action_dict.items():
if part_name not in self._whole_body_controller_action_split_indexes:
ROBOSUITE_DEFAULT_LOGGER.debug(f"{part_name} is not specified in the action space")
continue
Expand Down
1 change: 1 addition & 0 deletions robosuite/controllers/parts/controller_factory.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
"""
Set of functions that streamline controller initialization process
"""

import json
import os
from copy import deepcopy
Expand Down
1 change: 1 addition & 0 deletions robosuite/demos/demo_gripper_selection.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@
This script shows you how to select gripper for an environment.
This is controlled by gripper_type keyword argument.
"""

import time

import numpy as np
Expand Down
1 change: 1 addition & 0 deletions robosuite/demos/demo_segmentation.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
"""
Play random actions in an environment and render a video that demonstrates segmentation.
"""

import argparse
import colorsys
import json
Expand Down
5 changes: 3 additions & 2 deletions robosuite/demos/demo_usd_export.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
""" Exports a USD file corresponding to the collected trajectory.
"""Exports a USD file corresponding to the collected trajectory.

The USD (Universal Scene Description) file format allows users to save
trajectories such that they can be rendered in external renderers such
Expand All @@ -8,8 +8,9 @@

***IMPORTANT***: If you are using mujoco version 3.1.1, please make sure
that you also have numpy < 2 installed in your environment. Failure to do
so may result in incorrect renderings.
so may result in incorrect renderings.
"""

import argparse

import mujoco
Expand Down
2 changes: 1 addition & 1 deletion robosuite/devices/device.py
Original file line number Diff line number Diff line change
Expand Up @@ -166,7 +166,7 @@ def input2action(self, mirror_actions=False) -> Optional[Dict]:
ac_dict[f"{active_arm}_gripper"] = np.array([grasp] * gripper_dof)

# clip actions between -1 and 1
for (k, v) in ac_dict.items():
for k, v in ac_dict.items():
if "abs" not in k:
ac_dict[k] = np.clip(v, -1, 1)

Expand Down
2 changes: 1 addition & 1 deletion robosuite/environments/robot_env.py
Original file line number Diff line number Diff line change
Expand Up @@ -345,7 +345,7 @@ def _setup_observables(self):
# Create sensor information
sensors = []
names = []
for (cam_name, cam_w, cam_h, cam_d, cam_segs) in zip(
for cam_name, cam_w, cam_h, cam_d, cam_segs in zip(
self.camera_names,
self.camera_widths,
self.camera_heights,
Expand Down
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
138 changes: 138 additions & 0 deletions robosuite/models/assets/grippers/xarm7_gripper.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,138 @@
<mujoco model="xarm7 hand">
<compiler angle="radian" autolimits="true"/>

<option integrator="implicitfast"/>

<asset>
<material name="white" rgba="1 1 1 1"/>
<material name="black" rgba="0.149 0.149 0.149 1"/>

<mesh name="base_link" file="meshes/xarm7_gripper/base_link.stl"/>
<mesh name="left_outer_knuckle" file="meshes/xarm7_gripper/left_outer_knuckle.stl"/>
<mesh name="left_finger" file="meshes/xarm7_gripper/left_finger.stl"/>
<mesh name="left_inner_knuckle" file="meshes/xarm7_gripper/left_inner_knuckle.stl"/>
<mesh name="right_outer_knuckle" file="meshes/xarm7_gripper/right_outer_knuckle.stl"/>
<mesh name="right_finger" file="meshes/xarm7_gripper/right_finger.stl"/>
<mesh name="right_inner_knuckle" file="meshes/xarm7_gripper/right_inner_knuckle.stl"/>
</asset>

<default>
<default class="xarm7_hand" group="1">
<geom type="mesh" material="black" group="1"/>
<joint range="0 0.85" axis="1 0 0" armature="0.1" frictionloss="1"/>
<site size="0.001" rgba="1 0 0 1" group="4"/>
<general biastype="affine" forcerange="-50 50" ctrlrange="0 255" gainprm="0.333" biasprm="0 -100 -10"/>
</default>
<default class="spring_link">
<joint stiffness="0.05" springref="2.62" damping="0.00125"/>
</default>
<default class="driver">
<joint armature="0.005" damping="0.1" solreflimit="0.005 1"/>
</default>
<default class="follower">
<joint solreflimit="0.005 1"/>
</default>
<default class="visual">
<geom type="mesh" contype="0" conaffinity="0" group="1"/>
</default>
<default class="collision">
<geom type="mesh" group="0"/>
</default>
<default class="pad_box1">
<geom type="box" friction="0.7" solimp="0.95 0.99 0.001" solref="0.004 1" mass="0" priority="1" size="0.015 0.002 0.0095" rgba="0.0 0.1 0.7 1"/>
</default>
<default class="pad_box2">
<geom type="box" friction="0.6" solimp="0.95 0.99 0.001" solref="0.004 1" mass="0" priority="1" size="0.015 0.002 0.0095" rgba="0.0 0.5 0.5 1"/>
</default>
</default>

<worldbody>
<body name="xarm_gripper_base_link">
<inertial pos="-0.00065489 -0.0018497 0.048028" quat="0.997403 -0.0717512 -0.0061836 0.000477479" mass="0.54156"
diaginertia="0.000471093 0.000332307 0.000254799"/>
<geom class="xarm7_hand" mesh="base_link" material="white"/>
<body name="left_outer_knuckle" pos="0 0.035 0.059098">
<inertial pos="0 0.021559 0.015181" quat="0.47789 0.87842 0 0" mass="0.033618"
diaginertia="1.9111e-05 1.79089e-05 1.90167e-06"/>
<joint name="left_driver_joint" axis="1 0 0" frictionloss="1" class="driver"/>
<geom class="xarm7_hand" material="black" mesh="left_outer_knuckle"/>
<body name="left_finger" pos="0 0.035465 0.042039">
<inertial pos="0 -0.016413 0.029258" quat="0.697634 0.115353 -0.115353 0.697634" mass="0.048304"
diaginertia="1.88037e-05 1.7493e-05 3.56792e-06"/>
<joint name="left_finger_joint" axis="-1 0 0" armature="0.1" frictionloss="1" class="follower"/>
<geom class="visual" material="black" mesh="left_finger"/>
<geom class="pad_box1" name="left_finger_pad_1" pos="0 -0.024003 0.032"/>
<geom class="pad_box2" name="left_finger_pad_2" pos="0 -0.024003 0.050"/>
</body>
</body>
<body name="left_inner_knuckle" pos="0 0.02 0.074098">
<inertial pos="1.86601e-06 0.0220468 0.0261335" quat="0.664139 -0.242732 0.242713 0.664146" mass="0.0230126"
diaginertia="8.34216e-06 6.0949e-06 2.75601e-06"/>
<joint name="left_inner_knuckle_joint" axis="1 0 0" armature="0.1" frictionloss="1" class="spring_link"/>
<geom class="xarm7_hand" material="black" mesh="left_inner_knuckle"/>
</body>
<body name="right_outer_knuckle" pos="0 -0.035 0.059098">
<inertial pos="0 -0.021559 0.015181" quat="0.87842 0.47789 0 0" mass="0.033618"
diaginertia="1.9111e-05 1.79089e-05 1.90167e-06"/>
<joint name="right_driver_joint" axis="-1 0 0" frictionloss="1" class="driver"/>
<geom class="xarm7_hand" material="black" mesh="right_outer_knuckle"/>
<body name="right_finger" pos="0 -0.035465 0.042039">
<inertial pos="0 0.016413 0.029258" quat="0.697634 -0.115356 0.115356 0.697634" mass="0.048304"
diaginertia="1.88038e-05 1.7493e-05 3.56779e-06"/>
<joint name="right_finger_joint" axis="1 0 0" armature="0.1" frictionloss="1" class="follower"/>
<geom class="visual" material="black" mesh="right_finger"/>
<geom class="pad_box1" name="right_finger_pad_1" pos="0 0.024003 0.032"/>
<geom class="pad_box2" name="right_finger_pad_2" pos="0 0.024003 0.050"/>
<site name="ft_frame" pos="0 0 0" size="0.01 0.01 0.01" rgba="1 0 0 1" type="sphere" group="1"/>
</body>
</body>
<body name="right_inner_knuckle" pos="0 -0.02 0.074098">
<inertial pos="1.866e-06 -0.022047 0.026133" quat="0.66415 0.242702 -0.242721 0.664144" mass="0.023013"
diaginertia="8.34209e-06 6.0949e-06 2.75601e-06"/>
<joint name="right_inner_knuckle_joint" axis="-1 0 0" armature="0.1" frictionloss="1" class="spring_link"/>
<geom class="xarm7_hand" material="black" mesh="right_inner_knuckle"/>
</body>
<body name="eef" pos="0 0 0.097" quat="1 0 0 0">
<site name="grip_site" pos="0 0 0.05" size="0.01 0.01 0.01" rgba="1 0 0 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"/>
<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" size="0.005 10" rgba="0 1 0 0.3" type="cylinder" group="1"/>
</body>
</body>
</worldbody>

<sensor>
<force name="force_ee" site="ft_frame"/>
<torque name="torque_ee" site="ft_frame"/>
</sensor>

<contact>
<exclude body1="right_inner_knuckle" body2="right_outer_knuckle"/>
<exclude body1="right_inner_knuckle" body2="right_finger"/>
<exclude body1="left_inner_knuckle" body2="left_outer_knuckle"/>
<exclude body1="left_inner_knuckle" body2="left_finger"/>
<exclude body1="left_inner_knuckle" body2="xarm_gripper_base_link"/>
<exclude body1="right_inner_knuckle" body2="xarm_gripper_base_link"/>
<exclude body1="left_outer_knuckle" body2="xarm_gripper_base_link"/>
<exclude body1="right_outer_knuckle" body2="xarm_gripper_base_link"/>
</contact>

<tendon>
<fixed name="split">
<joint joint="right_driver_joint" coef="0.5"/>
<joint joint="left_driver_joint" coef="0.5"/>
</fixed>
</tendon>

<equality>
<connect anchor="0 0.015 0.015" body1="right_finger" body2="right_inner_knuckle" solref="0.005 1"/>
<connect anchor="0 -0.015 0.015" body1="left_finger" body2="left_inner_knuckle" solref="0.005 1"/>
<joint joint1="left_driver_joint" joint2="right_driver_joint" polycoef="0 1 0 0 0" solref="0.005 1"/>
</equality>

<actuator>
<general class="xarm7_hand" name="fingers_actuator" tendon="split"/>
</actuator>
</mujoco>
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
Diff not rendered.
102 changes: 102 additions & 0 deletions robosuite/models/assets/robots/xarm7/robot.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,102 @@
<mujoco model="xarm7">
<compiler angle="radian" autolimits="true"/>

<option integrator="implicitfast"/>

<asset>
<material name="white" rgba="1 1 1 1"/>
<material name="gray" rgba="0.753 0.753 0.753 1"/>
<material name="black" rgba="0.149 0.149 0.149 1"/>

<mesh name="link_base" file="meshes/link_base.stl"/>
<mesh name="link1" file="meshes/link1.stl"/>
<mesh name="link2" file="meshes/link2.stl"/>
<mesh name="link3" file="meshes/link3.stl"/>
<mesh name="link4" file="meshes/link4.stl"/>
<mesh name="link5" file="meshes/link5.stl"/>
<mesh name="link6" file="meshes/link6.stl"/>
<mesh name="link7" file="meshes/link7.stl"/>
<mesh name="end_tool" file="meshes/end_tool.stl"/>
</asset>
<worldbody>
<body name="base" pos="0 0 0">
<!-- robot view -->
<camera mode="fixed" name="robotview" pos="1.0 0 0.4" quat="0.653 0.271 0.271 0.653"/>
<!-- <inertial diaginertia="0 0 0" mass="0" pos="0 0 0"/> -->
<!-- mount attached here -->

<inertial pos="-0.021131 -0.0016302 0.056488" quat="0.696843 0.20176 0.10388 0.680376" mass="0.88556"
diaginertia="0.00382023 0.00335282 0.00167725"/>
<geom mesh="link_base" type="mesh" material="white" group="1"/>
<body name="link1" pos="0 0 0.267">
<site name="right_center" pos="0 0 0" size="0.01" rgba="1 0.3 0.3 1" group="2"/>
<inertial pos="-0.0002 0.02905 -0.01233" quat="0.978953 -0.202769 -0.00441617 -0.0227264" mass="2.382"
diaginertia="0.00569127 0.00533384 0.00293865"/>
<joint name="joint1" axis="0 0 1" range="-6.28319 6.28319" frictionloss="1" damping="0.1"/>
<geom mesh="link1" type="mesh" material="white" group="1"/>
<body name="link2" quat="1 -1 0 0">
<inertial pos="0.00022 -0.12856 0.01735" quat="0.50198 0.86483 -0.00778841 0.00483285" mass="1.869"
diaginertia="0.00959898 0.00937717 0.00201315"/>
<joint name="joint2" axis="0 0 1" frictionloss="1" range="-2.059 2.0944" damping="0.1"/>
<geom mesh="link2" type="mesh" material="white" group="1"/>
<body name="link3" pos="0 -0.293 0" quat="1 1 0 0">
<inertial pos="0.0466 -0.02463 -0.00768" quat="0.913819 0.289775 0.281481 -0.0416455" mass="1.6383"
diaginertia="0.00351721 0.00294089 0.00195868"/>
<joint name="joint3" axis="0 0 1" range="-6.28319 6.28319" frictionloss="1" damping="0.1"/>
<geom mesh="link3" type="mesh" material="white" group="1"/>
<body name="link4" pos="0.0525 0 0" quat="1 1 0 0">
<inertial pos="0.07047 -0.11575 0.012" quat="0.422108 0.852026 -0.126025 0.282832" mass="1.7269"
diaginertia="0.00657137 0.00647948 0.00186763"/>
<joint name="joint4" axis="0 0 1" frictionloss="1" range="-0.19198 3.927" damping="0.1"/>
<geom mesh="link4" type="mesh" material="white" group="1"/>
<body name="link5" pos="0.0775 -0.3425 0" quat="1 1 0 0">
<inertial pos="-0.00032 0.01604 -0.026" quat="0.999311 -0.0304457 0.000577067 0.0212082" mass="1.3203"
diaginertia="0.00534729 0.00499076 0.0013489"/>
<joint name="joint5" axis="0 0 1" range="-6.28319 6.28319" frictionloss="1" damping="0.1"/>
<geom mesh="link5" type="mesh" material="white" group="1"/>
<body name="link6" quat="1 1 0 0">
<inertial pos="0.06469 0.03278 0.02141" quat="-0.217672 0.772419 0.16258 0.574069" mass="1.325"
diaginertia="0.00245421 0.00221646 0.00107273"/>
<joint name="joint6" axis="0 0 1" frictionloss="1" range="-1.69297 3.14159" damping="0.01"/>
<geom mesh="link6" type="mesh" material="white" group="1"/>
<body name="link7" pos="0.076 0.097 0" quat="1 -1 0 0">
<inertial pos="0 -0.00677 -0.01098" quat="0.487612 0.512088 -0.512088 0.487612" mass="0.17"
diaginertia="0.000132176 9.3e-05 5.85236e-05"/>
<joint name="joint7" axis="0 0 1" range="-6.28319 6.28319" frictionloss="1" damping="0.01"/>
<!-- <geom material="gray" mesh="end_tool"/> -->

<body name="right_hand" pos="0.0 0.0 -0.027" quat="0 0 0 1">
<!-- This sites were added for visualization. They are all standardized between models-->
<!-- Position mimics the gripper attachment point (right_hand) -->
<!-- Y-axis should be perpendicular to grasping motion, and Z-axis should point out of the robot eef -->

<!-- Values here must be tuned manually -->
<site name="ee" pos="0 0 0" size="0.01 0.01 0.01" rgba="0 0 1 1" type="sphere" group="1"/>
<site name="ee_x" pos="0 0 0" size="0.005 .1" quat="0.707105 0.707108 0 0 " rgba="1 0 0 0" type="cylinder" />
<site name="ee_z" pos="0 0 0" size="0.005 .1" quat="0.707105 0 0 0.707108" rgba="0 0 1 0" type="cylinder" />
<site name="ee_y" pos="0 0 0" size="0.005 .1" quat="0.707105 0 0.707108 0 " rgba="0 1 0 0" type="cylinder" />
<!-- 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 -->
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</worldbody>

<actuator>
<!-- Physical limits of the actuator. -->
<motor ctrllimited="true" ctrlrange="-80.0 80.0" joint="joint1" name="torq_j1"/>
<motor ctrllimited="true" ctrlrange="-80.0 80.0" joint="joint2" name="torq_j2"/>
<motor ctrllimited="true" ctrlrange="-80.0 80.0" joint="joint3" name="torq_j3"/>
<motor ctrllimited="true" ctrlrange="-80.0 80.0" joint="joint4" name="torq_j4"/>
<motor ctrllimited="true" ctrlrange="-80.0 80.0" joint="joint5" name="torq_j5"/>
<motor ctrllimited="true" ctrlrange="-80.0 80.0" joint="joint6" name="torq_j6"/>
<motor ctrllimited="true" ctrlrange="-80.0 80.0" joint="joint7" name="torq_j7"/>
</actuator>
</mujoco>
1 change: 1 addition & 0 deletions robosuite/models/bases/floating_legged_base.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
"""
Rethink's Generic Mount (Officially used on Sawyer).
"""

import numpy as np

from robosuite.models.bases.mobile_base_model import MobileBaseModel
Expand Down
1 change: 1 addition & 0 deletions robosuite/models/bases/leg_base_model.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
"""
Defines the base class of all mobile bases
"""

from xml.etree import ElementTree as ET

import numpy as np
Expand Down
1 change: 1 addition & 0 deletions robosuite/models/bases/no_actuation_base.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
"""
Rethink's Generic Mount (Officially used on Sawyer).
"""

import numpy as np

from robosuite.models.bases.mobile_base_model import MobileBaseModel
Expand Down
1 change: 1 addition & 0 deletions robosuite/models/bases/null_mobile_base.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
"""
Rethink's Generic Mount (Officially used on Sawyer).
"""

import numpy as np

from robosuite.models.bases.mobile_base_model import MobileBaseModel
Expand Down
1 change: 1 addition & 0 deletions robosuite/models/bases/null_mount.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
"""
Rethink's Generic Mount (Officially used on Sawyer).
"""

import numpy as np

from robosuite.models.bases.mount_model import MountModel
Expand Down
1 change: 1 addition & 0 deletions robosuite/models/bases/omron_mobile_base.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
"""
Omron LD-60 Mobile Base.
"""

import numpy as np

from robosuite.models.bases.mobile_base_model import MobileBaseModel
Expand Down
1 change: 1 addition & 0 deletions robosuite/models/bases/rethink_minimal_mount.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
"""
Rethink's Alternative Mount (Officially used on Baxter).
"""

import numpy as np

from robosuite.models.bases.mount_model import MountModel
Expand Down
1 change: 1 addition & 0 deletions robosuite/models/bases/rethink_mount.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
"""
Rethink's Generic Mount (Officially used on Sawyer).
"""

import numpy as np

from robosuite.models.bases.mount_model import MountModel
Expand Down
1 change: 1 addition & 0 deletions robosuite/models/bases/robot_base_model.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
"""
Defines the base class of all mounts
"""

from typing import Dict, List

import numpy as np
Expand Down
Loading