Skip to content

Commit

Permalink
Merge pull request #137 from ARISE-Initiative/bug-fixes
Browse files Browse the repository at this point in the history
Greatly Improved Interfaces + Bug Fixes
  • Loading branch information
cremebrule authored Dec 18, 2020
2 parents 4562300 + 412038c commit e0982ca
Show file tree
Hide file tree
Showing 162 changed files with 7,658 additions and 7,386 deletions.
4 changes: 4 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,10 @@

[**[Homepage]**](https://robosuite.ai/)   [**[White Paper]**](https://arxiv.org/abs/2009.12293)   [**[Documentations]**](https://robosuite.ai/docs/overview.html)   [**[ARISE Initiative]**](https://github.com/ARISE-Initiative)

-------
## Latest Updates
[12/17/2020] **v1.1.0**: Refactored infrastructure and standardized model classes for much easier environment prototyping :wrench:

-------

**robosuite** is a simulation framework powered by the [MuJoCo](http://mujoco.org/) physics engine for robot learning. It also offers a suite of benchmark environments for reproducible research. The current release (v1.0) features manipulation tasks with feature supports of procedural generation, advanced controllers, teleoperation, etc. This project is part of the broader [Advancing Robot Intelligence through Simulated Environments (ARISE) Initiative](https://github.com/ARISE-Initiative), with the aim of lowering the barriers of entry for cutting-edge research at the intersection of AI and Robotics.
Expand Down
4 changes: 4 additions & 0 deletions docs/references.md
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,8 @@ A list of references of projects and papers that use **robosuite**. If you would
- [Long-Horizon Visual Planning with Goal-Conditioned Hierarchical Predictors](https://arxiv.org/abs/2006.13205). Karl Pertsch, Oleh Rybkin, Frederik Ebert, Chelsea Finn, Dinesh Jayaraman, Sergey Levine
- [Balance Between Efficient and Effective Learning: Dense2Sparse Reward Shaping for Robot Manipulation with Environment Uncertainty](https://arxiv.org/abs/2003.02740). Yongle Luo, Kun Dong, Lili Zhao, Zhiyong Sun, Chao Zhou, Bo Song
- [Hierarchical 6-DoF Grasping with Approaching Direction Selection](http://rllab.snu.ac.kr/publications/papers/2020_icra_gads.pdf). Yunho Choi, Hogun Kee, Kyungjae Lee, JaeGoo Choy, Junhong Min, Sohee Lee, and Songhwai Oh
- [Conservative Safety Critics for Exploration](https://arxiv.org/abs/2010.14497). Homanga Bharadhwaj, Aviral Kumar, Nicholas Rhinehart, Sergey Levine, Florian Shkurti, Animesh Garg
- [Deep Reinforcement Learning for Contact-Rich Skills Using Compliant Movement Primitives](https://arxiv.org/abs/2008.13223). Oren Spector, Miriam Zacksenhouse

## Imitation Learning and Batch (Offline) Reinforcement Learning

Expand All @@ -21,6 +23,8 @@ A list of references of projects and papers that use **robosuite**. If you would
- [To Follow or not to Follow: Selective Imitation Learning from Observations](https://arxiv.org/abs/1912.07670). Youngwoon Lee, Edward S. Hu, Zhengyu Yang, Joseph J. Lim
- [Learning Robot Skills with Temporal Variational Inference](https://arxiv.org/abs/2006.16232). Tanmay Shankar, Abhinav Gupta
- [Residual Learning from Demonstration](https://arxiv.org/abs/2008.07682). Todor Davchev, Kevin Sebastian Luck, Michael Burke, Franziska Meier, Stefan Schaal, Subramanian Ramamoorthy
- [Variational Imitation Learning with Diverse-quality Demonstrations](https://proceedings.icml.cc/static/paper_files/icml/2020/577-Paper.pdf). Voot Tangkaratt, Bo Han, Mohammad Emtiyaz Khan, Masashi Sugiyama
- [Transformers for One-Shot Visual Imitation](https://corlconf.github.io/paper_463/). Sudeep Dasari, Abhinav Gupta

## Benchmarks

Expand Down
21 changes: 11 additions & 10 deletions robosuite/__init__.py
Original file line number Diff line number Diff line change
@@ -1,21 +1,22 @@
from robosuite.environments.base import make

from robosuite.environments.lift import Lift
from robosuite.environments.stack import Stack
from robosuite.environments.nut_assembly import NutAssembly
from robosuite.environments.pick_place import PickPlace
from robosuite.environments.door import Door
from robosuite.environments.wipe import Wipe
from robosuite.environments.two_arm_lift import TwoArmLift
from robosuite.environments.two_arm_peg_in_hole import TwoArmPegInHole
from robosuite.environments.two_arm_handover import TwoArmHandover
# Manipulation environments
from robosuite.environments.manipulation.lift import Lift
from robosuite.environments.manipulation.stack import Stack
from robosuite.environments.manipulation.nut_assembly import NutAssembly
from robosuite.environments.manipulation.pick_place import PickPlace
from robosuite.environments.manipulation.door import Door
from robosuite.environments.manipulation.wipe import Wipe
from robosuite.environments.manipulation.two_arm_lift import TwoArmLift
from robosuite.environments.manipulation.two_arm_peg_in_hole import TwoArmPegInHole
from robosuite.environments.manipulation.two_arm_handover import TwoArmHandover

from robosuite.environments import ALL_ENVIRONMENTS
from robosuite.controllers import ALL_CONTROLLERS, load_controller_config
from robosuite.robots import ALL_ROBOTS
from robosuite.models.grippers import ALL_GRIPPERS

__version__ = "1.0.0"
__version__ = "1.1.0"
__logo__ = """
; / ,--.
["] ["] ,< |__**|
Expand Down
2 changes: 1 addition & 1 deletion robosuite/controllers/joint_pos.py
Original file line number Diff line number Diff line change
Expand Up @@ -120,7 +120,7 @@ def __init__(self,
self.output_min = self.nums2array(output_min, self.control_dim)

# limits
self.position_limits = qpos_limits
self.position_limits = np.array(qpos_limits) if qpos_limits is not None else qpos_limits

# kp kd
self.kp = self.nums2array(kp, self.control_dim)
Expand Down
2 changes: 1 addition & 1 deletion robosuite/controllers/joint_tor.py
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ def __init__(self,
self.output_min = self.nums2array(output_min, self.control_dim)

# limits (if not specified, set them to actuator limits by default)
self.torque_limits = torque_limits if torque_limits is not None else self.actuator_limits
self.torque_limits = np.array(torque_limits) if torque_limits is not None else self.actuator_limits

# control frequency
self.control_freq = policy_freq
Expand Down
2 changes: 1 addition & 1 deletion robosuite/controllers/joint_vel.py
Original file line number Diff line number Diff line change
Expand Up @@ -104,7 +104,7 @@ def __init__(self,
self.last_joint_vel = np.zeros(self.joint_dim)

# limits
self.velocity_limits = velocity_limits
self.velocity_limits = np.array(velocity_limits) if velocity_limits is not None else None

# control frequency
self.control_freq = policy_freq
Expand Down
11 changes: 9 additions & 2 deletions robosuite/controllers/osc.py
Original file line number Diff line number Diff line change
Expand Up @@ -176,8 +176,8 @@ def __init__(self,
self.control_dim += 6

# limits
self.position_limits = position_limits
self.orientation_limits = orientation_limits
self.position_limits = np.array(position_limits) if position_limits is not None else position_limits
self.orientation_limits = np.array(orientation_limits) if orientation_limits is not None else orientation_limits

# control frequency
self.control_freq = policy_freq
Expand Down Expand Up @@ -345,6 +345,13 @@ def run_controller(self):

return self.torques

def update_initial_joints(self, initial_joints):
# First, update from the superclass method
super().update_initial_joints(initial_joints)

# We also need to reset the goal in case the old goals were set to the initial confguration
self.reset_goal()

def reset_goal(self):
"""
Resets the goal to the current state of the robot
Expand Down
5 changes: 4 additions & 1 deletion robosuite/demos/demo_device_control.py
Original file line number Diff line number Diff line change
Expand Up @@ -100,6 +100,7 @@
import robosuite as suite
from robosuite import load_controller_config
from robosuite.utils.input_utils import input2action
from robosuite.wrappers import VisualizationWrapper



Expand Down Expand Up @@ -152,12 +153,14 @@
render_camera="agentview",
ignore_done=True,
use_camera_obs=False,
gripper_visualizations=True,
reward_shaping=True,
control_freq=20,
hard_reset=False,
)

# Wrap this environment in a visualization wrapper
env = VisualizationWrapper(env, indicator_configs=None)

# Setup printing options for numbers
np.set_printoptions(formatter={'float': lambda x: "{0:0.3f}".format(x)})

Expand Down
5 changes: 4 additions & 1 deletion robosuite/demos/demo_domain_randomization.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,11 +2,14 @@
Script to showcase domain randomization functionality.
"""

import numpy as np
import robosuite.utils.macros as macros
from robosuite.controllers import load_controller_config
from robosuite.utils.input_utils import *
from robosuite.wrappers import DomainRandomizationWrapper

# We'll use instance randomization so that entire geom groups are randomized together
macros.USING_INSTANCE_RANDOMIZATION = True

if __name__ == "__main__":

# Create dict to hold options that will be passed to env creation call
Expand Down
35 changes: 20 additions & 15 deletions robosuite/demos/demo_gripper_interaction.py
Original file line number Diff line number Diff line change
Expand Up @@ -29,16 +29,21 @@

# add a gripper
gripper = RethinkGripper()
# Create another body with a slider joint to which we'll add this gripper
gripper_body = ET.Element("body")
for body in gripper.worldbody:
gripper_body.append(body)
gripper_body.set("pos", "0 0 0.3")
gripper_body.set("quat", "0 0 1 0") # flip z
gripper_body.append(
new_joint(name="gripper_z_joint", type="slide", axis="0 0 1", damping="50")
)
world.merge(gripper, merge_body=False)
# Add all gripper bodies to this higher level body
for body in gripper.worldbody:
gripper_body.append(body)
# Merge the all of the gripper tags except its bodies
world.merge(gripper, merge_body=None)
# Manually add the higher level body we created
world.worldbody.append(gripper_body)
# Create a new actuator to control our slider joint
world.actuator.append(
new_actuator(
joint="gripper_z_joint", act_type="position", name="gripper_z", kp="500"
Expand All @@ -51,22 +56,19 @@
size=[0.02, 0.02, 0.02],
rgba=[1, 0, 0, 1],
friction=[1, 0.005, 0.0001]
).get_collision()
mujoco_object.append(new_joint(name="object_free_joint", type="free"))
).get_obj()
# Set the position of this object
mujoco_object.set("pos", "0 0 0.11")
geoms = mujoco_object.findall("./geom")
for geom in geoms:
if geom.get("contype"):
pass
geom.set("name", "object")
geom.set("density", "10000") # 1000 for water
# Add our object to the world body
world.worldbody.append(mujoco_object)

# add reference objects for x and y axes
x_ref = BoxObject(name="x_ref", size=[0.01, 0.01, 0.01], rgba=[0, 1, 0, 1]).get_visual()
x_ref = BoxObject(name="x_ref", size=[0.01, 0.01, 0.01], rgba=[0, 1, 0, 1], obj_type="visual",
joints=None).get_obj()
x_ref.set("pos", "0.2 0 0.105")
world.worldbody.append(x_ref)
y_ref = BoxObject(name="y_ref", size=[0.01, 0.01, 0.01], rgba=[0, 0, 1, 1]).get_visual()
y_ref = BoxObject(name="y_ref", size=[0.01, 0.01, 0.01], rgba=[0, 0, 1, 1], obj_type="visual",
joints=None).get_obj()
y_ref.set("pos", "0 0.2 0.105")
world.worldbody.append(y_ref)

Expand All @@ -83,6 +85,7 @@
sim.model.get_joint_qvel_addr(x) for x in gravity_corrected
]

# Set gripper parameters
gripper_z_id = sim.model.actuator_name2id("gripper_z")
gripper_z_low = 0.07
gripper_z_high = -0.02
Expand All @@ -102,11 +105,10 @@
step = 0
T = 500
while True:

if step % 100 == 0:
print("step: {}".format(step))

if step % 100 == 0:
# Get contact information
for contact in sim.data.contact[0 : sim.data.ncon]:

geom_name1 = sim.model.geom_id2name(contact.geom1)
Expand All @@ -119,6 +121,7 @@
print("friction: {}".format(contact.friction))
print("normal: {}".format(contact.frame[0:3]))

# Iterate through gripping trajectory
if step % T == 0:
plan = seq[int(step / T) % len(seq)]
gripper_z_is_low, gripper_is_closed = plan
Expand All @@ -128,6 +131,7 @@
)
)

# Control gripper
if gripper_z_is_low:
sim.data.ctrl[gripper_z_id] = gripper_z_low
else:
Expand All @@ -137,6 +141,7 @@
else:
sim.data.ctrl[gripper_jaw_ids] = gripper_open

# Step through sim
sim.step()
sim.data.qfrc_applied[_ref_joint_vel_indexes] = sim.data.qfrc_bias[
_ref_joint_vel_indexes
Expand Down
6 changes: 5 additions & 1 deletion robosuite/demos/demo_video_recording.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,12 @@
import imageio
import numpy as np

import robosuite.utils.macros as macros
from robosuite import make

# Set the image convention to opencv so that the images are automatically rendered "right side up" when using imageio
# (which uses opencv convention)
macros.IMAGE_CONVENTION = "opencv"

if __name__ == "__main__":

Expand Down Expand Up @@ -54,7 +58,7 @@

# dump a frame from every K frames
if i % args.skip_frame == 0:
frame = obs[args.camera + "_image"][::-1]
frame = obs[args.camera + "_image"]
writer.append_data(frame)
print("Saving frame #{}".format(i))

Expand Down
14 changes: 12 additions & 2 deletions robosuite/devices/spacemouse.py
Original file line number Diff line number Diff line change
Expand Up @@ -123,6 +123,10 @@ def __init__(self,
print("Manufacturer: %s" % self.device.get_manufacturer_string())
print("Product: %s" % self.device.get_product_string())

# 6-DOF variables
self.x, self.y, self.z = 0, 0, 0
self.roll, self.pitch, self.yaw = 0, 0, 0

self._display_controls()

self.single_click_and_hold = False
Expand Down Expand Up @@ -164,6 +168,13 @@ def _reset_internal_state(self):
Resets internal state of controller, except for the reset signal.
"""
self.rotation = np.array([[-1., 0., 0.], [0., 1., 0.], [0., 0., -1.]])
# Reset 6-DOF variables
self.x, self.y, self.z = 0, 0, 0
self.roll, self.pitch, self.yaw = 0, 0, 0
# Reset control
self._control = np.zeros(6)
# Reset grasp
self.single_click_and_hold = False

def start_control(self):
"""
Expand All @@ -183,7 +194,6 @@ def get_controller_state(self):
"""
dpos = self.control[:3] * 0.005 * self.pos_sensitivity
roll, pitch, yaw = self.control[3:] * 0.005 * self.rot_sensitivity
self.grasp = self.control_gripper

# convert RPY to an absolute orientation
drot1 = rotation_matrix(angle=-pitch, direction=[1., 0, 0], point=None)[:3, :3]
Expand All @@ -196,7 +206,7 @@ def get_controller_state(self):
dpos=dpos,
rotation=self.rotation,
raw_drotation=np.array([roll, pitch, yaw]),
grasp=self.grasp,
grasp=self.control_gripper,
reset=self._reset_state
)

Expand Down
Loading

0 comments on commit e0982ca

Please sign in to comment.