|
|
| import math |
| from isaacgym import gymapi |
| from isaacgym import gymutil |
| import numpy as np |
| from isaacgym.torch_utils import * |
| from termcolor import cprint |
| import argparse |
|
|
|
|
| |
| gym = gymapi.acquire_gym() |
|
|
| |
| sim_params = gymapi.SimParams() |
| sim_params.substeps = 2 |
| sim_params.dt = 1.0 / 60.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 = 4 |
| sim_params.physx.use_gpu = True |
|
|
| sim_params.use_gpu_pipeline = False |
| device_id = 1 |
| |
| sim = gym.create_sim(device_id, device_id, gymapi.SIM_PHYSX, sim_params) |
| if sim is None: |
| print("*** Failed to create sim") |
| quit() |
|
|
| |
| viewer = gym.create_viewer(sim, gymapi.CameraProperties()) |
| if viewer is None: |
| raise ValueError('*** Failed to create viewer') |
|
|
| |
| plane_params = gymapi.PlaneParams() |
| gym.add_ground(sim, gymapi.PlaneParams()) |
|
|
| |
| num_envs = 4 |
| spacing = 1.5 |
| env_lower = gymapi.Vec3(-spacing, 0.0, -spacing) |
| env_upper = gymapi.Vec3(spacing, 0.0, spacing) |
|
|
|
|
| asset_root = f"../assets/" |
| |
| |
| |
| |
| |
| |
| |
| asset_file = "pnd_adam_lite/adam_lite.urdf" |
|
|
| |
| asset_options = gymapi.AssetOptions() |
| asset_options.fix_base_link = True |
| asset_options.default_dof_drive_mode = gymapi.DOF_MODE_POS |
| asset_options.collapse_fixed_joints = False |
| asset_options.use_mesh_materials = False |
| |
| asset_options.vhacd_enabled = True |
| asset_options.vhacd_params = gymapi.VhacdParams() |
| asset_options.vhacd_params.resolution = 200000 |
|
|
| asset_options.flip_visual_attachments = True |
| |
|
|
| print("Loading asset '%s' from '%s'" % (asset_file, asset_root)) |
| robot_asset = gym.load_asset(sim, asset_root, asset_file, asset_options) |
|
|
| robot_link_dict = gym.get_asset_rigid_body_dict(robot_asset) |
| robot_dof_dict = gym.get_asset_dof_dict(robot_asset) |
| ordered_body_dict = {k: v for k, v in sorted(robot_link_dict.items(), key=lambda item: item[1])} |
| cprint(f'[HumanoidRobot] Full robot body dict. NumBody: {len(robot_link_dict.keys())}', 'blue') |
| for k, v in ordered_body_dict.items(): |
| cprint(f'\t {k} {v}', 'blue') |
|
|
| ordered_dof_dict = {k: v for k, v in sorted(robot_dof_dict.items(), key=lambda item: item[1])} |
| cprint(f'[HumanoidRobot] Full robot dof dict. DoF: {len(ordered_dof_dict.keys())}', 'green') |
| for k, v in ordered_dof_dict.items(): |
| cprint(f'\t {k} {v}', 'green') |
|
|
| |
| print("Body names: ", ordered_body_dict.keys()) |
| print("DoF names: ", ordered_dof_dict.keys()) |
|
|
| |
| initial_pose = gymapi.Transform() |
| initial_pose.p = gymapi.Vec3(0.0, 1.5, 0.0) |
| initial_pose.r = gymapi.Quat(-0.707107, 0.0, 0.0, 0.707107) |
| |
|
|
| env = gym.create_env(sim, env_lower, env_upper, 0) |
| robot = gym.create_actor(env, robot_asset, initial_pose, 'robot', 0, 1) |
|
|
|
|
| |
| props = gym.get_actor_dof_properties(env, robot) |
| props['driveMode'][:] = gymapi.DOF_MODE_POS |
| props['stiffness'][:] = 400.0 |
| props['damping'][:] = 40.0 |
| gym.set_actor_dof_properties(env, robot, props) |
|
|
|
|
| |
| cam_pos = gymapi.Vec3(8, 4, 1.5) |
| cam_target = gymapi.Vec3(0, 2, 1.5) |
| gym.viewer_camera_look_at(viewer, env, cam_pos, cam_target) |
|
|
| num_dofs = gym.get_actor_dof_count(env, robot) |
| initial_dof_positions = np.zeros(num_dofs, dtype=np.float32) |
| gym.set_actor_dof_position_targets(env, robot, initial_dof_positions) |
|
|
|
|
| |
| while not gym.query_viewer_has_closed(viewer): |
|
|
| |
| gym.simulate(sim) |
| gym.fetch_results(sim, True) |
|
|
| |
| gym.step_graphics(sim) |
| gym.draw_viewer(viewer, sim, True) |
|
|
| |
| gym.sync_frame_time(sim) |
|
|
|
|
|
|
| print('Done') |
|
|
| gym.destroy_viewer(viewer) |
| gym.destroy_sim(sim) |