Skip to content

Commit

Permalink
loading isaac gym model to mujoco
Browse files Browse the repository at this point in the history
  • Loading branch information
is2ac2 committed Jul 15, 2024
1 parent 72705d0 commit 0c2d2db
Show file tree
Hide file tree
Showing 9 changed files with 315 additions and 17 deletions.
2 changes: 1 addition & 1 deletion sim/deploy/config.py
100644 → 100755
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ class RobotConfig:
kds: np.ndarray
tau_limit: np.ndarray
robot_model_path: str
dt: float = 0.001
dt: float = 0.0001#0.001
phase_duration: float = 0.64
duration: float = 10.0
decimation: int = 10
Expand Down
7 changes: 5 additions & 2 deletions sim/deploy/policy.py
100644 → 100755
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,10 @@ def __init__(
self.hist_obs = deque()
for _ in range(frame_stack):
self.hist_obs.append(np.zeros([1, obs_size], dtype=np.double))
self.model = torch.jit.load(model_path)
# Load the model.
# Changed to load onto same device as other tensors
self.device = torch.device("cuda" if torch.cuda.is_available() else "cpu")
self.model = torch.load(model_path, map_location=self.device)
self.action = np.zeros((num_actions), dtype=np.double)

@abstractmethod
Expand Down Expand Up @@ -167,7 +170,7 @@ def next_action(
for i in range(self.cfg.frame_stack):
policy_input[0, i * self.cfg.num_single_obs : (i + 1) * self.cfg.num_single_obs] = self.hist_obs[i][0, :]

self.action[:] = self.model(torch.tensor(policy_input))[0].detach().numpy()
self.action[:] = self.model(torch.tensor(policy_input).to(self.device))[0].detach().cpu().numpy()

self.action = np.clip(self.action, -self.cfg.normalization.clip_actions, self.cfg.normalization.clip_actions)
return self.action
Expand Down
14 changes: 12 additions & 2 deletions sim/deploy/run.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
"""Basic sim2sim and sim2real deployment script.
<joint name="lfemurrx" pos="0 0 0" axis="1 0 0" range="-0.349066 2.79253" class="stiff_medium"/>
Run example:
mjpython sim/deploy/run.py --load_model sim/deploy/tests/walking_policy.pt --world MUJOCO
Expand All @@ -21,7 +22,7 @@
from isaacgym import gymapi
from sim.deploy.config import RobotConfig
from sim.env import stompy_mjcf_path
from sim.stompy.joints import StompyFixed
from sim.stompy_legs.joints import Stompy as StompyFixed


class Worlds(Enum):
Expand Down Expand Up @@ -62,11 +63,19 @@ class MujocoWorld(World):
def __init__(self, cfg: RobotConfig):
self.cfg = cfg
self.model = mujoco.MjModel.from_xml_path(str(self.cfg.robot_model_path))

self.model.opt.timestep = self.cfg.dt

# First step
self.data = mujoco.MjData(self.model)
self.data.qpos = self.model.keyframe("default").qpos

mujoco.mj_step(self.model, self.data)

#Set self.data initial state to the default standing position
#self.data.qpos = StompyFixed.default_standing()


def step(
self,
tau: np.ndarray = None,
Expand Down Expand Up @@ -109,6 +118,7 @@ def get_observation(self) -> Tuple[np.ndarray, np.ndarray, np.ndarray, np.ndarra
return dof_pos, dof_vel, orientation, ang_vel

def simulate(self, policy: SimPolicy) -> None:

with mujoco.viewer.launch_passive(self.model, self.data) as viewer:
for step in tqdm(range(int(cfg.duration / cfg.dt)), desc="Simulating..."):
# Get the world state
Expand Down Expand Up @@ -141,7 +151,7 @@ def __init__(self, cfg: RobotConfig):
delattr(args, "load_model")

# adapt
args.task = "legs_ppo"
args.task = "only_legs_ppo"
args.device = "cpu"
args.physics_engine = gymapi.SIM_PHYSX
args.num_envs = 1
Expand Down
Binary file added sim/deploy/tests/model_400_model_only.pt
Binary file not shown.
19 changes: 10 additions & 9 deletions sim/humanoid_gym/envs/only_legs_config.py
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ class asset(LeggedRobotCfg.asset):

termination_height = 0.23
default_feet_height = 0.0
terminate_after_contacts_on = ["link_leg_assembly_left_1_leg_part_1_2", "link_leg_assembly_right_1_leg_part_1_2"]
# terminate_after_contacts_on = ["link_leg_assembly_left_1_leg_part_1_2", "link_leg_assembly_right_1_leg_part_1_2"]

penalize_contacts_on = []
self_collisions = 0 # 1 to disable, 0 to enable...bitwise filter
Expand Down Expand Up @@ -104,7 +104,7 @@ class control(LeggedRobotCfg.control):
"hand": 200,
"torso": 200,
"hip": 250,
"ankle": 15,
"ankle": 200,
"knee": 350,
}
damping = {
Expand All @@ -118,9 +118,9 @@ class control(LeggedRobotCfg.control):
"knee": 10,
}
for k in stiffness:
stiffness[k]*= .01
damping[k] *= .01
action_scale = 0.5
stiffness[k]*= .00001
damping[k] *= .1
action_scale = 2500
# decimation: Number of control action updates @ sim DT per policy DT
decimation = 10 # 100hz

Expand All @@ -144,12 +144,13 @@ class physx(LeggedRobotCfg.sim.physx):
contact_collection = 2

class domain_rand:
randomize_friction = False
randomize_friction = True
friction_range = [0.1, 2.0]

randomize_base_mass = False
added_mass_range = [-1.0, 1.0]
push_robots = False
randomize_base_mass = True
# added_mass_range = [-1.0, 1.0]
added_mass_range = [-0.2, 0.2]
push_robots = True
push_interval_s = 4
max_push_vel_xy = 0.2
max_push_ang_vel = 0.4
Expand Down
1 change: 0 additions & 1 deletion sim/humanoid_gym/envs/only_legs_env.py
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,6 @@ def __init__(self, cfg: LeggedRobotCfg, sim_params, physics_engine, sim_device,
for name, joint in Stompy.legs.right.joints_motors():
joint_handle = self.gym.find_actor_dof_handle(env_handle, actor_handle, joint)
self.legs_joints["right_" + name] = joint_handle

self.compute_observations()

def _push_robots(self):
Expand Down
2 changes: 1 addition & 1 deletion sim/humanoid_gym/play.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,9 +7,9 @@

import cv2
import numpy as np
from isaacgym import gymapi
from tqdm import tqdm

from isaacgym import gymapi
from sim.logging import configure_logging

logger = logging.getLogger(__name__)
Expand Down
2 changes: 1 addition & 1 deletion sim/stompy_legs/robot_fixed.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -1260,4 +1260,4 @@
<parent link="link_right_foot_1_foot_1" />
<child link="link_right_foot_1_rubber_grip_3" />
</joint>
</robot>
</robot>
Loading

0 comments on commit 0c2d2db

Please sign in to comment.