PKU-MARL / DexterousHands

This is a library that provides dual dexterous hand manipulation tasks through Isaac Gym
https://pku-marl.github.io/DexterousHands/
Apache License 2.0
664 stars 83 forks source link

Issue with assets #13

Closed livermoreee closed 2 years ago

livermoreee commented 2 years ago

Hi, I am using the pot asset contained in this repo in writing my own environment: "mjcf/pot/mobility.urdf". However, I am having trouble in the reset phase.

in the initialization of environment

get root state tensor, useful for obtaining state information about the object

actor_root_state_tensor = self.gym.acquire_actor_root_state_tensor(self.sim)
self.root_state_tensor = gymtorch.wrap_tensor(actor_root_state_tensor)
get dof state tensor

_dof_states = self.gym.acquire_dof_state_tensor(self.sim)
self.dof_states = gymtorch.wrap_tensor(_dof_states)

self.gym.refresh_actor_root_state_tensor(self.sim)
self.gym.refresh_dof_state_tensor(self.sim)
self.saved_dof_states = self.dof_states.clone()
self.saved_root_state_tensor = self.root_state_tensor.clone()

and then when resetting:

self.gym.set_dof_state_tensor(self.sim, gymtorch.unwrap_tensor(self.saved_dof_states)) 
self.gym.set_actor_root_state_tensor(self.sim, gymtorch.unwrap_tensor(self.saved_root_state_tensor))

However, this leads to very weird physics/simulation errors in which all the pots suddenly fly around/glitching out upon reset. I verified that this is not a problem of my environment because everything loads correctly when I don’t reset things. But when I reset the tensors the environment just glitches crazily. Is there a reason why this might be happening?

As another test, I used another pot asset (the xml file): mjcf/pot/pot.xml, and the issue immediately disappears and everything works correctly. I am wondering what might be the difference between the mobility.urdf vs. pot.xml file, and why one of them leads to the glitch?

Thank you!

cypypccpy commented 2 years ago

Dear @livermoreee ,

Thanks for your sharing!

in the initialization of environment
get root state tensor, useful for obtaining state information about the object
...
and then when resetting:
...

This part of the code is really to ensure that there is no weird reset, so we save the state tensor at init and use it during reset.

However, this leads to very weird physics/simulation errors in which all the pots suddenly fly around/glitching out upon reset. I verified that this is not a problem of my environment because everything loads correctly when I don’t reset things. But when I reset the tensors the environment just glitches crazily. Is there a reason why this might be happening?

Can you tell me if you have changed anything on the source code? Because this bug did not appear when we used it, as follows:

https://user-images.githubusercontent.com/55881363/198131600-8ab6d58f-954d-48a8-b46a-5eb47a4acdb3.mp4

As another test, I used another pot asset (the xml file): mjcf/pot/pot.xml, and the issue immediately disappears and everything works correctly. I am wondering what might be the difference between the mobility.urdf vs. pot.xml file, and why one of them leads to the glitch?

This other pot is the first version we tried during the development phase. It is a hand-written mjcf object, not the same as the pot in our benchmark, so the reward shaping will be different from the source code, which has been abandoned.

Anyway, since Isaac Gym is still in development, empirically it will have kinds of issues, especially with the physics engine. I guess it may be a bug caused by collision, so you can try to modify the pot's init pos to make it a little higher from the table at the beginning and see if it can be solved.

Hope this can help you.

livermoreee commented 2 years ago

Thank you for the detailed reply! I wrote a short script that demonstrates the problem that I have been seeing. This script can be placed inside the bi-dexhands directory and directly run. Here I am initializing only a table and the pot to be dropped from 1 meter above the table, and reset the environment every 200 steps. By observing the resets, it seems like the pot sometimes falls straight through the table, and sometimes glitches out and even flies away. However, if the asset is replaced with pot.xml instead of mobility.urdf, the issue disappears. Could you help me take a look at what I might be doing wrong? Thank you!

from isaacgym import gymapi
from isaacgym import gymutil
from isaacgym import gymtorch
from isaacgym.torch_utils import *

import math
import numpy as np
import torch
import random
import time
gym = gymapi.acquire_gym()
device = 'cuda:0'

sim_params = gymapi.SimParams()
sim_params.up_axis = gymapi.UP_AXIS_Z
sim_params.gravity = gymapi.Vec3(0.0, 0.0, -9.8)
sim_params.dt = 1.0 / 60.0
sim_params.substeps = 2
sim_params.use_gpu_pipeline = True
sim_params.physx.solver_type = 1
sim_params.physx.num_position_iterations = 8
sim_params.physx.num_velocity_iterations = 1
sim_params.physx.rest_offset = 0.0
sim_params.physx.contact_offset = 0.001
sim_params.physx.friction_offset_threshold = 0.001
sim_params.physx.friction_correlation_distance = 0.0005
sim_params.physx.num_threads = 0
sim_params.physx.use_gpu = True

compute_device_id = 0
graphics_device_id = 0
physics_engine = gymapi.SIM_PHYSX
sim = gym.create_sim(compute_device_id, graphics_device_id, physics_engine, sim_params)

viewer = gym.create_viewer(sim, gymapi.CameraProperties())

asset_root = "../assets"

table_dims = gymapi.Vec3(0.6, 1.0, 0.4)
asset_options = gymapi.AssetOptions()
asset_options.fix_base_link = True
table_asset = gym.create_box(sim, table_dims.x, table_dims.y, table_dims.z, asset_options)

object_asset_file = "mjcf/pot/mobility.urdf"
object_asset_options = gymapi.AssetOptions()
object_asset_options.density = 1000
box_asset = gym.load_asset(sim, asset_root, object_asset_file, object_asset_options)

num_envs = 256
num_per_row = int(math.sqrt(num_envs))
spacing = 1.0
env_lower = gymapi.Vec3(-spacing, -spacing, 0.0)
env_upper = gymapi.Vec3(spacing, spacing, spacing)
print("Creating %d environments" % num_envs)

table_pose = gymapi.Transform()
table_pose.p = gymapi.Vec3(0.5, 0.0, 0.5 * table_dims.z)

box_pose = gymapi.Transform()

envs = []

# add ground plane
plane_params = gymapi.PlaneParams()
plane_params.normal = gymapi.Vec3(0, 0, 1)
gym.add_ground(sim, plane_params)

for i in range(num_envs):
    env = gym.create_env(sim, env_lower, env_upper, num_per_row)
    envs.append(env)

    table_handle = gym.create_actor(env, table_asset, table_pose, "table", i, 0)

    box_pose.p.x = table_pose.p.x + np.random.uniform(-0.2, 0.1)
    box_pose.p.y = table_pose.p.y + np.random.uniform(-0.3, 0.3)
    box_pose.p.z = table_dims.z + 1
    box_pose.r = gymapi.Quat.from_axis_angle(gymapi.Vec3(0, 0, 1), np.random.uniform(-math.pi, math.pi))
    box_handle = gym.create_actor(env, box_asset, box_pose, "box", i, 0)
    color = gymapi.Vec3(np.random.uniform(0, 1), np.random.uniform(0, 1), np.random.uniform(0, 1))
    gym.set_rigid_body_color(env, box_handle, 0, gymapi.MESH_VISUAL_AND_COLLISION, color)

cam_pos = gymapi.Vec3(4, 3, 2)
cam_target = gymapi.Vec3(-4, -3, 0)
middle_env = envs[num_envs // 2 + num_per_row // 2]
gym.viewer_camera_look_at(viewer, middle_env, cam_pos, cam_target)

gym.prepare_sim(sim)

actor_root_state_tensor = gym.acquire_actor_root_state_tensor(sim)
root_state_tensor = gymtorch.wrap_tensor(actor_root_state_tensor)

_dof_states = gym.acquire_dof_state_tensor(sim)
dof_states = gymtorch.wrap_tensor(_dof_states) # (self.num_envs * total DOF, 2)

_rb_states = gym.acquire_rigid_body_state_tensor(sim)
rb_states = gymtorch.wrap_tensor(_rb_states)

gym.refresh_actor_root_state_tensor(sim)
gym.refresh_dof_state_tensor(sim)
saved_dof_states = dof_states.clone()
saved_root_state_tensor = root_state_tensor.clone()

step = 0
while not gym.query_viewer_has_closed(viewer):

    if step % 200 == 0:
        gym.set_dof_state_tensor(sim, gymtorch.unwrap_tensor(saved_dof_states))
        gym.set_actor_root_state_tensor(sim, gymtorch.unwrap_tensor(saved_root_state_tensor))

    step += 1

    gym.simulate(sim)
    gym.fetch_results(sim, True)

    gym.refresh_dof_state_tensor(sim)
    gym.refresh_actor_root_state_tensor(sim)

    gym.step_graphics(sim)
    gym.draw_viewer(viewer, sim, False)
    gym.sync_frame_time(sim)

gym.destroy_viewer(viewer)
gym.destroy_sim(sim)
cypypccpy commented 2 years ago

Hi @livermoreee ,

Thank you for your detailed sharing! There is nothing wrong with the main part of your code, the problem is in the parameter of the physics engine.

After I modified it into:

sim_params.physx.solver_type = 1
sim_params.physx.num_position_iterations = 8
sim_params.physx.num_velocity_iterations = 0
sim_params.physx.rest_offset = 0.0
sim_params.physx.contact_offset = 0.001
sim_params.physx.friction_offset_threshold = 0.001
sim_params.physx.friction_correlation_distance = 0.0005
sim_params.physx.num_threads = 16
sim_params.physx.use_gpu = True

it could simulate normally, as follows:

https://user-images.githubusercontent.com/55881363/198270112-b5d95659-c4b6-48e0-88d7-b43e5a577b55.mp4

I only adjusted these two parameters:

sim_params.physx.num_velocity_iterations = 0
sim_params.physx.num_threads = 16

For why I modified sim_params.physx.num_threads, the official documentation of it is described as follows: image

Therefore, it can be set according to the number of CPUs you want to use, maybe the bigger the better.

For why I modified sim_params.physx.num_velocity_iterations, You can take a look at this post on the isaacgym official forum, it said: image

Therefore, in general, this parameter can be set to 0.

As for why pot.xml can be correct, I think it is because its model is relatively simple, so that the contact calculation is relatively simple, and it is not easy to cause physical bugs. To be honest, most of the bugs in Isaac Gym currently come from the physics engine, especially when it comes to collisions. Sometimes I also look for answers on the official forums I mentioned above, which are very helpful.

Hope this can help you.

livermoreee commented 2 years ago

That helped, thank you!