Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Isaac to mujoco loading #29

Merged
merged 29 commits into from
Jul 17, 2024
Merged
Show file tree
Hide file tree
Changes from 26 commits
Commits
Show all changes
29 commits
Select commit Hold shift + click to select a range
85405f7
added stompyv2
nathanjzhao Jul 4, 2024
4ab2f4d
stompy_v2 fixes
is2ac2 Jul 4, 2024
815a901
removing torques values the model doesn't fly away
is2ac2 Jul 5, 2024
b0fc9e5
updated standing position and joint limits
is2ac2 Jul 9, 2024
cb8592b
initial params
is2ac2 Jul 9, 2024
80b9289
cleanup
is2ac2 Jul 9, 2024
e52ffaf
fighting mypy
is2ac2 Jul 9, 2024
c627bda
linting
is2ac2 Jul 9, 2024
9a25cbf
defeating mypy
is2ac2 Jul 9, 2024
bffbb58
fixes
is2ac2 Jul 10, 2024
5098bf1
final fixes
is2ac2 Jul 10, 2024
635a12c
more fixes
is2ac2 Jul 10, 2024
e5e9eec
more fixes
is2ac2 Jul 10, 2024
d346b62
linting
is2ac2 Jul 10, 2024
e2f9eb5
save the walking policy, small issues with knees
is2ac2 Jul 10, 2024
f8a1280
Merge branch 'master' of github.com:kscalelabs/sim into isaac/only_legs
is2ac2 Jul 10, 2024
54fbd28
linking latest humanoid-gym
is2ac2 Jul 11, 2024
d414cc3
setup working for mjcf
is2ac2 Jul 11, 2024
03bbe47
saving new modle with inertia, training works
is2ac2 Jul 11, 2024
440ebdc
saving model with inertia, training works
is2ac2 Jul 11, 2024
b1335a9
latest settings for making legs_only ppo realistic
is2ac2 Jul 13, 2024
b89bf62
cleanup / removing comments
is2ac2 Jul 13, 2024
72705d0
add hexmove settings and walking policy
is2ac2 Jul 13, 2024
0c2d2db
loading isaac gym model to mujoco
is2ac2 Jul 15, 2024
c7af392
Updated third party library
is2ac2 Jul 16, 2024
95ab213
linting
is2ac2 Jul 16, 2024
efa36d3
cleanup
is2ac2 Jul 17, 2024
8272d25
merge
is2ac2 Jul 17, 2024
c2f9b5f
merge conflicts
is2ac2 Jul 17, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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
budzianowski marked this conversation as resolved.
Show resolved Hide resolved
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.
budzianowski marked this conversation as resolved.
Show resolved Hide resolved
# 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
13 changes: 11 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 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,18 @@ 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()
budzianowski marked this conversation as resolved.
Show resolved Hide resolved

def step(
self,
tau: np.ndarray = None,
Expand Down Expand Up @@ -109,6 +117,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 +150,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.
Empty file added sim/hexmove/__init__.py
Empty file.
Loading
Loading