I made code like this and a1 doesn’t appear when ‘fix_base_link = False’
except URDF problem.
I think there are some bugs in Isaac Gym.
from isaacgym import gymapi, gymutil, gymtorch
from math import sqrt, pi
import os
os.chdir("/home/minwoo/IsaacGym_Preview_3_Package/isaacgym/legged_gym/resources/robots")
# currentPath = os.getcwd()
# print("\ncurrentPath : {}\n".format(currentPath))
class AssetDesc:
def __init__(self, file_name, flip_visual_attachments=False,rotation=False):
self.file_name = file_name
self.flip_visual_attachments = flip_visual_attachments
self.rotation = rotation
asset_descriptors = [
AssetDesc("a1/urdf/a1.urdf", True),
AssetDesc("Quadruped_1/urdf/Quadruped_1.urdf", False)
]
#1. initialize gym
gym = gymapi.acquire_gym()
# parse arguments
args = gymutil.parse_arguments(description="Joint control Methods Example")
#2. create a simulator
sim_params = gymapi.SimParams()
sim_params.substeps = 2
sim_params.dt = 1.0 / 60.0
sim_params.gravity = gymapi.Vec3(0, -9.8, 0)
sim_params.physx.solver_type = 1
sim_params.physx.num_position_iterations = 4
sim_params.physx.num_velocity_iterations = 1
sim_params.physx.num_threads = args.num_threads
sim_params.physx.use_gpu = args.use_gpu
sim_params.use_gpu_pipeline = False
if args.use_gpu_pipeline:
print("WARNING: Forcing CPU pipeline.")
sim = gym.create_sim(args.compute_device_id, args.graphics_device_id, args.physics_engine, sim_params)
if sim is None:
print("*** Failed to create sim")
quit()
#8. create viewer using the default camera properties
viewer = gym.create_viewer(sim, gymapi.CameraProperties())
if viewer is None:
raise ValueError('*** Failed to create viewer')
#3. add ground plane
plane_params = gymapi.PlaneParams()
gym.add_ground(sim, gymapi.PlaneParams())
#4. Loading Assets
# add cartpole urdf asset
asset_root = "/home/minwoo/IsaacGym_Preview_3_Package/isaacgym/legged_gym/resources/robots/"
assets = []
for asset_desc in asset_descriptors:
asset_file = asset_desc.file_name
asset_options = gymapi.AssetOptions()
asset_options.fix_base_link = False
asset_options.flip_visual_attachments = asset_desc.flip_visual_attachments
asset_options.use_mesh_materials = True
print(f"Loading asset {asset_file} from {asset_root}")
assets.append(gym.load_asset(sim, asset_root, asset_file, asset_options))
#5. Environments and Actors
# set up the env grid
num_envs = 4
spacing = 2
env_lower = gymapi.Vec3(-spacing, 0.0, -spacing)
env_upper = gymapi.Vec3(spacing, 0.0, spacing)
# cache useful handles
envs = []
actor_handles = []
scale = 7
root2s = sqrt(2)**-1
for i, asset in enumerate(assets):
# create env
env = gym.create_env(sim, env_lower, env_upper, 1)
envs.append(env)
# add actor
pose = gymapi.Transform()
pose.p = gymapi.Vec3(0.0, 2, 0.0)
if i == 0 :
pose.r = gymapi.Quat(-root2s,0,0,root2s)
elif i == 1 :
pose.r = gymapi.Quat.from_euler_zyx(0,pi/2,pi/2)
actor_handle = gym.create_actor(env,asset,pose, "actor", i ,1)
actor_handles.append(actor_handle)
gym.set_actor_scale(env, actor_handle, scale)
# Configure DOF properties
# props = gym.get_actor_dof_properties(env0, cartpole0)
# props["driveMode"] = (gymapi.DOF_MODE_POS, gymapi.DOF_MODE_POS, gymapi.DOF_MODE_POS, gymapi.DOF_MODE_POS)
# props["stiffness"] = (5000.0, 5000.0, 5000.0, 5000.0)
# props["damping"] = (100.0, 100.0, 100.0, 100.0)
# gym.set_actor_dof_properties(env0, cartpole0, props)
#5. Look at the first env [Envs and Actors]
cam_pos = gymapi.Vec3(8, 4, 1.5)
cam_target = gymapi.Vec3(0, 2, 1.5)
gym.viewer_camera_look_at(viewer, None, cam_pos, cam_target)
#9. Tensor API Commanders
gym.prepare_sim(sim)
# Simulate
while not gym.query_viewer_has_closed(viewer):
# step the physics
gym.simulate(sim)
gym.fetch_results(sim, True)
# update the viewer
gym.step_graphics(sim)
gym.draw_viewer(viewer, sim, True)
gym.refresh_rigid_body_state_tensor(sim) # need to update the state tensors
gym.refresh_jacobian_tensors(sim) # need to update the state tensors
gym.refresh_mass_matrix_tensors(sim) # need to update the state tensors
# Nothing to be done for env 0
# Nothing to be done for env 1
# # Update env 2: reverse cart target velocity when bounds reached
# pos = gym.get_dof_position(env2, cart_dof_handle2)
# if pos >= 0.5:
# gym.set_dof_target_velocity(env2, cart_dof_handle2, -1.0)
# elif pos <= -0.5:
# gym.set_dof_target_velocity(env2, cart_dof_handle2, 1.0)
# # Update env 3: apply an effort to the pole to keep it upright
# pos = gym.get_dof_position(env3, pole_dof_handle3)
# gym.apply_dof_effort(env3, pole_dof_handle3, -pos * 50)
# Wait for dt to elapse in real time.
# This synchronizes the physics simulation with the rendering rate.
gym.sync_frame_time(sim)
print('Done')
gym.destroy_viewer(viewer)
gym.destroy_sim(sim)
btw thanks for your reply !