| """ |
| Copyright (c) 2020, NVIDIA CORPORATION. All rights reserved. |
| |
| NVIDIA CORPORATION and its licensors retain all intellectual property |
| and proprietary rights in and to this software, related documentation |
| and any modifications thereto. Any use, reproduction, disclosure or |
| distribution of this software and related documentation without an express |
| license agreement from NVIDIA CORPORATION is strictly prohibited. |
| |
| |
| Convex decomposition example |
| """ |
|
|
| from isaacgym import gymapi |
| from isaacgym import gymutil |
|
|
| |
| gym = gymapi.acquire_gym() |
|
|
| |
| args = gymutil.parse_arguments(description="Convex decomposition example") |
|
|
| |
| sim_params = gymapi.SimParams() |
|
|
| sim_params.up_axis = gymapi.UP_AXIS_Z |
| sim_params.gravity = gymapi.Vec3(0.0, 0.0, -9.81) |
| 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 = 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: |
| raise Exception("Failed to create sim") |
|
|
| |
| viewer = gym.create_viewer(sim, gymapi.CameraProperties()) |
| if viewer is None: |
| raise Exception("Failed to create viewer") |
|
|
| |
| plane_params = gymapi.PlaneParams() |
| plane_params.normal = gymapi.Vec3(0, 0, 1) |
| gym.add_ground(sim, plane_params) |
|
|
| |
| num_envs = 4 |
| envs_per_row = 2 |
| spacing = 0.5 |
| env_lower = gymapi.Vec3(-spacing, 0.0, -spacing) |
| env_upper = gymapi.Vec3(spacing, spacing, spacing) |
|
|
| |
| initial_pose = gymapi.Transform() |
| initial_pose.p = gymapi.Vec3(0.0, 0.0, 0.2) |
|
|
| asset_root = "../../assets" |
| asset_options = gymapi.AssetOptions() |
|
|
| |
| asset_options.use_mesh_materials = True |
| asset_options.mesh_normal_mode = gymapi.COMPUTE_PER_VERTEX |
|
|
| |
| |
| asset_options.override_inertia = True |
| asset_options.override_com = True |
|
|
| |
| asset_options.vhacd_enabled = True |
| asset0 = gym.load_asset(sim, asset_root, "urdf/ycb/011_banana/011_banana.urdf", asset_options) |
|
|
| |
| asset_options.vhacd_enabled = True |
| asset_options.vhacd_params = gymapi.VhacdParams() |
| asset_options.vhacd_params.resolution = 300000 |
| asset1 = gym.load_asset(sim, asset_root, "urdf/ycb/025_mug/025_mug.urdf", asset_options) |
|
|
| |
| asset_options.vhacd_enabled = False |
| asset2 = gym.load_asset(sim, asset_root, "urdf/ycb/061_foam_brick/061_foam_brick.urdf", asset_options) |
|
|
| |
| asset_options.vhacd_enabled = True |
| asset_options.vhacd_params = gymapi.VhacdParams() |
| asset_options.vhacd_params.resolution = 500000 |
| asset3 = gym.load_asset(sim, asset_root, "urdf/ycb/010_potted_meat_can/010_potted_meat_can.urdf", asset_options) |
|
|
| |
| env = gym.create_env(sim, env_lower, env_upper, envs_per_row) |
| actor = gym.create_actor(env, asset0, initial_pose, 'actor', 0, 1) |
| env = gym.create_env(sim, env_lower, env_upper, envs_per_row) |
| actor = gym.create_actor(env, asset1, initial_pose, 'actor', 1, 1) |
| env = gym.create_env(sim, env_lower, env_upper, envs_per_row) |
| actor = gym.create_actor(env, asset2, initial_pose, 'actor', 2, 1) |
| env = gym.create_env(sim, env_lower, env_upper, envs_per_row) |
| actor = gym.create_actor(env, asset3, initial_pose, 'actor', 3, 1) |
|
|
| cam_pos = gymapi.Vec3(3, 0, 3) |
| cam_target = gymapi.Vec3(0, 0, 0) |
| gym.viewer_camera_look_at(viewer, None, cam_pos, cam_target) |
|
|
| |
| 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) |
|
|