Skip to content

Commit

Permalink
seems to be working
Browse files Browse the repository at this point in the history
  • Loading branch information
codekansas committed Apr 1, 2024
1 parent 912e813 commit ceaacd3
Show file tree
Hide file tree
Showing 2 changed files with 63 additions and 19 deletions.
28 changes: 28 additions & 0 deletions sim/ref.py
Original file line number Diff line number Diff line change
Expand Up @@ -284,6 +284,34 @@
"transform_inverse",
]

dir_asset_options = [
"angular_damping",
"armature",
"collapse_fixed_joints",
"convex_decomposition_from_submeshes",
"default_dof_drive_mode",
"density",
"disable_gravity",
"enable_gyroscopic_forces",
"fix_base_link",
"flip_visual_attachments",
"linear_damping",
"max_angular_velocity",
"max_linear_velocity",
"mesh_normal_mode",
"min_particle_mass",
"override_com",
"override_inertia",
"replace_cylinder_with_capsule",
"slices_per_cylinder",
"tendon_limit_stiffness",
"thickness",
"use_mesh_materials",
"use_physx_armature",
"vhacd_enabled",
"vhacd_params",
]

dir_simparams = [
"dt",
"enable_actor_creation_warning",
Expand Down
54 changes: 35 additions & 19 deletions sim/scripts/drop_urdf.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
import logging
import time
from dataclasses import dataclass
from typing import Any
from typing import Any, Literal

from isaacgym import gymapi, gymutil

Expand Down Expand Up @@ -60,17 +60,17 @@ def load_gym() -> GymParams:

# Sets the simulation parameters.
sim_params = gymapi.SimParams()
sim_params.substeps = 2
sim_params.dt = 1.0 / 60.0
sim_params.substeps = 1
sim_params.dt = 0.005

sim_params.physx.solver_type = 1
sim_params.physx.num_position_iterations = 5
sim_params.physx.num_velocity_iterations = 5
sim_params.physx.contact_offset = 0.01
sim_params.physx.rest_offset = 0.0
sim_params.physx.bounce_threshold_velocity = 0.1
sim_params.physx.max_depenetration_velocity = 1.0
sim_params.physx.max_gpu_contact_pairs = 2**23
sim_params.physx.num_position_iterations = 4
sim_params.physx.num_velocity_iterations = 0
sim_params.physx.contact_offset = 0.02
sim_params.physx.rest_offset = 0.01
sim_params.physx.bounce_threshold_velocity = 1.0
sim_params.physx.max_depenetration_velocity = 0.5
sim_params.physx.max_gpu_contact_pairs = 2**24
sim_params.physx.default_buffer_size_multiplier = 5
sim_params.physx.contact_collection = gymapi.CC_ALL_SUBSTEPS

Expand Down Expand Up @@ -111,8 +111,9 @@ def load_gym() -> GymParams:
# Loads the robot asset.
asset_options = gymapi.AssetOptions()
asset_options.default_dof_drive_mode = DRIVE_MODE
asset_options.collapse_fixed_joints = True
asset_path = stompy_urdf_path()
robot_asset = gym.load_asset(sim, str(asset_path.parent), str(asset_path.name), asset_options)
robot_asset = gym.load_urdf(sim, str(asset_path.parent), str(asset_path.name), asset_options)

# Adds the robot to the environment.
initial_pose = gymapi.Transform()
Expand Down Expand Up @@ -142,12 +143,14 @@ def load_gym() -> GymParams:
)


def run_gym(gym: GymParams) -> None:
flag = False
def run_gym(gym: GymParams, mode: Literal["one_at_a_time", "all_at_once"] = "all_at_once") -> None:
joints = Stompy.all_joints()
last_time = time.time()
dof_ids = gym.gym.get_actor_dof_dict(gym.env, gym.robot)

joint_id = 0
effort = 10.0

while not gym.gym.query_viewer_has_closed(gym.viewer):
gym.gym.simulate(gym.sim)
gym.gym.fetch_results(gym.sim, True)
Expand All @@ -157,14 +160,27 @@ def run_gym(gym: GymParams) -> None:

# Every second, set the target effort for each joint to the reverse.
curr_time = time.time()
if curr_time - last_time > 1.0:
last_time = curr_time
effort = 10.0 if flag else -10.0
flag = not flag
for joint in joints:
joint_id = dof_ids[joint]

if mode == "one_at_a_time":
if curr_time - last_time > 0.25:
last_time = curr_time
gym.gym.apply_dof_effort(gym.env, joint_id, 0.0)
joint_id += 1
if joint_id >= len(joints):
effort = -effort
joint_id = 0
gym.gym.apply_dof_effort(gym.env, joint_id, effort)

elif mode == "all_at_once":
if curr_time - last_time > 1.0:
last_time = curr_time
effort = -effort
for joint_name in joints:
gym.gym.apply_dof_effort(gym.env, dof_ids[joint_name], effort)

else:
raise ValueError(f"Invalid mode: {mode}")

gym.gym.destroy_viewer(gym.viewer)
gym.gym.destroy_sim(gym.sim)

Expand Down

0 comments on commit ceaacd3

Please sign in to comment.