Skip to content

Commit

Permalink
Merge pull request #132 from MyoHub/dev
Browse files Browse the repository at this point in the history
MyoChallenge'23 Release
  • Loading branch information
vikashplus authored Jan 11, 2024
2 parents 5f1aa16 + d5ba2a1 commit dbcb8bd
Show file tree
Hide file tree
Showing 9 changed files with 445 additions and 21 deletions.
2 changes: 1 addition & 1 deletion myosuite/agents/baseline_Reflex/ReflexCtrInterface.py
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ def __init__(self, init_dict=DEFAULT_INIT_POSE, dt=0.01, mode='3D', sim_time=2.0
curr_dir = os.getcwd()
register_env_variant(
env_id='myoLegDemo-v0',
variants={'model_path': curr_dir+'/../../simhive/myo_sim/myoleg/myoleg_v0.52(mj120).mjb',
variants={'model_path': curr_dir+'/../../simhive/myo_sim/leg/myolegs.xml',
'normalize_act':False},
variant_id='MyoLegReflex-v0',
silent=False
Expand Down
74 changes: 74 additions & 0 deletions myosuite/envs/myo/assets/arm/myoarm_relocate.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,74 @@
<mujoco model="MyoArm_v0.01">
<!-- =================================================
Copyright 2020 Vikash Kumar, Vittorio Caggiano, Guillaume Durandau
Model :: Myo Hand (MuJoCoV2.0)
Author :: Vikash Kumar ([email protected]), Vittorio Caggiano, Huawei Wang
source :: https://github.com/vikashplus
License :: Under Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. You may obtain a copy of the License at http://www.apache.org/licenses/LICENSE-2.0 Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License.
====================================================== -->

<include file="../../../../simhive/myo_sim/arm/assets/myoarm_assets.xml"/>
<include file="../../../../simhive/myo_sim/scene/myosuite_scene.xml"/>
<compiler meshdir='../../../../simhive/myo_sim/' texturedir='../../../../simhive/myo_sim/'/>

<asset>
<texture name="tabletop" type="2d" file="../furniture_sim/common/textures/stone1.png"/>
<material name="tabletop" texture="tabletop" rgba=".95 .95 .95 1"/>
<texture name="texwood" type="cube" file="../myo_sim/scene/floor0.png"/>
<material name="matwood" reflectance="0.01" texture="texwood" texuniform="false"/>
</asset>

<worldbody>

<!-- ======= MyoArm ======= -->
<geom name="body" type="mesh" mesh="body_norighthand" euler="0 0 3.14" contype="0" conaffinity="0"/>
<body name="full_body" pos="-.025 0.1 1.40">
<include file="../../../../simhive/myo_sim/arm/assets/myoarm_body.xml"/>
</body>

<!-- ======= Table ======= -->
<body name="table" pos="0 -.5 .85">
<geom name="table_top" type="box" size=".8 .5 .05" contype="1" conaffinity="1" material="tabletop"/>
<geom name="table_base" type="box" size=".35 .6 .45" pos="0 0 -.45" euler="0 0 1.57" contype="1" conaffinity="1" material="matwood"/>
</body>

<!-- ======= Object ======= -->
<body name="Object" pos="0 -.25 .95">
<joint name="OBJTx" pos="0 0 0" axis="1 0 0" limited="true" type="slide" range="-1.20 1.55" damping="0.001" />
<joint name="OBJTy" pos="0 0 0" axis="0 1 0" limited="true" type="slide" range="-1.10 1.20" damping="0.001" />
<joint name="OBJTz" pos="0 0 0" axis="0 0 1" limited="true" type="slide" range="-1.10 1.35" damping="0.001" />
<joint name="OBJRx" pos="0 0 0 " axis="1 0 0" limited="false" damping="0.001" />
<joint name="OBJRy" pos="0 0 0" axis="0 1 0" limited="false" damping="0.001" />
<joint name="OBJRz" pos="0 0 0" axis="0 0 1" limited="false" damping="0.001" />
<geom type="box" size="0.0284 0.0284 0.0284" euler="0.001 0.001 0.001" condim="4" rgba=".5 .2 .7 1" contype="1" conaffinity="1"/>
<geom type="box" size="0.00284 0.00284 0.00284" euler="0.001 0.001 0.001" condim="4" rgba=".5 .2 .7 1" contype="1" conaffinity="1"/> <!-- dummy geom for creating different objects-->
<geom type="box" size="0.00284 0.00284 0.00284" euler="0.001 0.001 0.001" condim="4" rgba=".5 .2 .7 1" contype="1" conaffinity="1"/> <!-- dummy geom for creating different objects-->
<site name="object_o" type="sphere" size="0.005" rgba="0.8 0.8 0.8 0.8" group="4" pos="0 0 0" />
<site name="object_x" type="sphere" size="0.005" rgba="0.8 0.2 0.2 0.8" group="4" pos="0.028 0 0" />
<site name="object_y" type="sphere" size="0.005" rgba="0.2 0.8 0.2 0.8" group="4" pos="0 .028 0" />
<site name="object_z" type="sphere" size="0.005" rgba="0.2 0.2 0.8 0.8" group="4" pos="0 0 .028" />
</body>

<!-- ======= BIN ======= -->
<body name="target" pos="0 -.25 0.9" euler="0.001 0.001 0.001" mocap="true">
<!-- <geom name="target_dice" type="box" size="0.026 0.026 0.026" contype="0" conaffinity="0" rgba='.1 1 .1 .3' group="2" /> -->
<geom name="base" type="box" size="0.10 0.10 0.10" pos="0.0 0.0 -.09" contype="1" conaffinity="1" group="2" material="matwood"/>
<geom name="wall0" type="box" size="0.10 0.01 0.10" pos="0 0.091 0.1" contype="1" conaffinity="1" group="2" material="matwood"/>
<geom name="wall1" type="box" size="0.01 0.10 0.10" pos="0.091 0 0.1" contype="1" conaffinity="1" group="2" material="matwood"/>
<geom name="wall2" type="box" size="0.10 0.01 0.10" pos="0 -.091 0.1" contype="1" conaffinity="1" group="2" material="matwood"/>
<geom name="wall3" type="box" size="0.01 0.10 0.10" pos="-.091 0 0.1" contype="1" conaffinity="1" group="2" material="matwood"/>

<site name="target_ball" type="sphere" size="0.045" rgba="0.2 1.7 0.2 0.1"/>
<site name="target_o" type="sphere" size="0.005" rgba="0.8 0.8 0.8 0.8" group="4" pos="0 0 0" />
<site name="target_x" type="sphere" size="0.005" rgba="0.8 0.2 0.2 0.8" group="4" pos="0.03 0 0" />
<site name="target_y" type="sphere" size="0.005" rgba="0.2 0.8 0.2 0.8" group="4" pos="0 .03 0" />
<site name="target_z" type="sphere" size="0.005" rgba="0.2 0.2 0.8 0.8" group="4" pos="0 0 .03" />
</body>

</worldbody>

<keyframe>
<key qpos='-0.022856 0.00967764 -0.00968029 0.10125 -0.00458344 0.20262 0.0828 -0.0168106 -0.2149 0.03876 0.168055 0.17281 -0.254074 -0.109975 1.11181 0.92689 0.106468 0 0.332 0.4114 -0.177165 -0.26182 0.18852 0.17017 0.447735 0.26707 0.28278 -0.010472 0.0168535 0.00701979 0.09139 -0.06545 0.243505 0.337765 0.23565 -0.101844 0.000607067 0.03142 -.2 0 -0.02 0 0 0'/>
<key qpos='-0.022856 0.01113 -0.08268 0.10125 -0.0494 0.16578 0.11868 -0.1932 -0.19648 0.03876 0.168055 0.17281 -0.254074 -0.109975 1.47485 1.28822 0.106468 -0.27489 0.332 0.4114 -0.177165 -0.26182 0.18852 0.17017 0.447735 0.26707 0.28278 -0.010472 0.0168535 0.00701979 0.09139 -0.06545 0.243505 0.337765 0.23565 -0.101844 0.000607067 0.03142 -0.2 0 -0.02 0 0 0'/>
</keyframe>
</mujoco>
57 changes: 57 additions & 0 deletions myosuite/envs/myo/assets/leg/myolegs_chasetag.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,57 @@
<?xml version="1.0" ?>
<mujoco model="MyoSuite's MyoQuad">
<!-- =================================================
Copyright 2023 MyoSuite
Model :: Myo Quad (MuJoCoV2.7)
Author :: Vikash Kumar ([email protected]), Vittorio Caggiano, Pierre Schumahchar, Chun Kwang Tan
source :: https://github.com/MyoHub/MyoSuite
License :: Under Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. You may obtain a copy of the License at http://www.apache.org/licenses/LICENSE-2.0 Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License.
====================================================== -©vk©-->

<include file="../../../../simhive/myo_sim/torso/assets/myotorsorigid_assets.xml"/>
<include file="../../../../simhive/myo_sim/leg/assets/myolegs_assets.xml"/>
<include file="../../../../simhive/myo_sim/scene/myosuite_quad.xml"/>
<compiler meshdir='../../../../simhive/myo_sim/' texturedir='../../../../simhive/myo_sim/'/>

<asset>
<hfield name="terrain" size="6 6 1 0.001" nrow="100" ncol="100"/>
<texture name="texmyo" type="cube" file="scene/myosuite_icon.png"/>
<material name="matmyo" texture="texmyo" rgba="1 1 1 1"/>
</asset>

<worldbody>
<geom name="terrain" type="hfield" hfield="terrain" pos="0 0 -0.005" material="matfloor" conaffinity="1" contype="1" rgba=".9 .9 .9 1"/>

<!-- <camera name="side_view" pos="-3 0 2.25" xyaxes="0 -1 0 1 0 2" mode="trackcom"/> -->


<!-- ======= Opponent ======= -->
<body name='opponent' pos="0 0 0" zaxis="0 0 1" mocap="true">
<light directional="false" diffuse=".25 .25 .25" specular="0.25 0.25 0.25" pos="0 -3 3" dir="0 1 -1" mode="trackcom"/>
<camera name="opponent_view" pos="4 0 2.75" xyaxes="0 1 0 -1 0 2" mode="trackcom"/>
<geom name="base" type="capsule" pos="0 0 0.15" euler="0 0 0" size="0.25 0.15" rgba=".11 .1 .1 1" group="2" contype="0" conaffinity="0"/>
<geom name="base_bar" type="cylinder" pos="0 0 0.8" euler="0 0 0" size="0.078 0.28" rgba=".7 .7 .7 1" group="2" contype="0" conaffinity="0"/>
<geom name="logo" type="sphere" pos="0 0 1.20" euler="1.57 0 0" size="0.25 0.02010" material="matmyo" group="2" contype="0" conaffinity="0"/>
<site name="opponent_indicator" size="0.3" pos="0 0 1.2" rgba="0 0 0 0"/>
</body>

<!-- ======= MyoAgent ======= -->
<site name="pelvis_target" size="0.02" pos="0 0 .92" group="4"/>
<body name="root" pos="0 0 1" euler="0 0 -1.57">
<light directional="false" diffuse=".25 .25 .25" specular="0.25 0.25 0.25" pos="3 0 2" dir="-1 0 -1" mode="trackcom"/>
<camera name="agent_view" pos="4 0 1.85" xyaxes="0 1 0 -1 0 2" mode="trackcom"/>
<site name="head" size="0.02" pos="0 0 1.80" group="4"/>
<include file="../../../../simhive/myo_sim/torso/assets/myotorsorigid_chain.xml"/>
<include file="../../../../simhive/myo_sim/leg/assets/myolegs_chain.xml"/>
<freejoint name="root"/>
</body>
</worldbody>

<keyframe>
<key qpos='0 0 .92 0.707388 0 0 -0.706825 0.161153 -0.0279385 -0.041886 0.00247908 0.00101098 0.461137 0.0275069 0.136817 0.334 -0.00117055 -0.000125295 -0.0302192 0.0395202 -0.194029 0.161153 -0.0279385 -0.041886 0.00247908 0.00101098 0.461137 0.0275069 0.136817 0.334 -0.00117055 -0.000125295 -0.0302192 0.0395202 -0.194029'/>
<key qpos='0 0 .9 0.707388 0 0 -0.706825 0.405648 -0.020957 -0.118677 0.0039054 0.00122326 0.7329 0.0102961 0.215496 0.40143 -0.006982 -0.02618 -0.03738 0.0080579 -0.87272 0.405648 -0.020957 -0.118677 0.0039054 0.00122326 0.7329 0.0102961 0.215496 0.40143 -0.006982 -0.02618 -0.03738 0.0080579 -0.87272'/>
<key qpos='0 0 1.0 0.707388 0 0 -0.706825 -0.2326 -0.0279385 -0.041886 0.00247908 0.00101098 1.227 0.0275069 0.136817 0.1672 -0.00117055 -0.000125295 -0.0302192 0.0395202 -0.194029 -0.1652 -0.0279385 -0.041886 0.00247908 0.0010198 0.0888 0.0275069 0.136817 -0.019 -0.00117055 -0.000125295 -0.0302192 0.0395202 -0.194029' qvel='0 -1.5 0 0 0 0 4.9066 0 0 0 0 -3.597 0 0 0.633 0 0 0 0 0 0.175 0 0 0 0 0.175 0 0 0.988 0 0 0 0 0'/>
<key qpos='0 0 1.0 0.707388 0 0 -0.706825 -0.1652 -0.0279385 -0.041886 0.00247908 0.00101098 0.0888 0.0275069 0.136817 -0.019 -0.00117055 -0.000125295 -0.0302192 0.0395202 -0.194029 -0.2326 -0.0279385 -0.041886 0.00247908 0.0010198 1.227 0.0275069 0.136817 0.1672 -0.00117055 -0.000125295 -0.0302192 0.0395202 -0.194029' qvel='0 -1.5 0 0 0 0 -0.576 0 0 0 0 0.175 0 0 0.988 0 0 0 0 0 4.9066 0 0 0 0 -3.597 0 0 0.633 0 0 0 0 0'/>
</keyframe>

</mujoco>
6 changes: 1 addition & 5 deletions myosuite/envs/myo/myobase/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -287,11 +287,7 @@ def register_env_with_variants(id, entry_point, max_episode_steps, kwargs):
# Gait Torso Reaching ==============================
from myosuite.physics.sim_scene import SimBackend
sim_backend = SimBackend.get_sim_backend()
if sim_backend == SimBackend.MUJOCO_PY:
leg_model='/../../../simhive/myo_sim/leg/myolegs_v0.54(mj210).mjb'
elif sim_backend == SimBackend.MUJOCO:
leg_model='/../../../simhive/myo_sim/leg/myolegs_v0.56(mj237).mjb'

leg_model='/../../../simhive/myo_sim/leg/myolegs.xml'

register_env_with_variants(id='myoLegStandRandom-v0',
entry_point='myosuite.envs.myo.myobase.walk_v0:ReachEnvV0',
Expand Down
8 changes: 8 additions & 0 deletions myosuite/envs/myo/myobase/walk_v0.py
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,10 @@ def _setup(self,
# Change the alpha value to make it transparent
self.sim.model.geom_rgba[geom_1_indices, 3] = 0

# move heightfield down if not used
self.sim.model.geom_rgba[self.sim.model.geom_name2id('terrain')][-1] = 0.0
self.sim.model.geom_pos[self.sim.model.geom_name2id('terrain')] = np.array([0, 0, -10])


def get_obs_dict(self, sim):
obs_dict = {}
Expand Down Expand Up @@ -208,6 +212,10 @@ def _setup(self,
self.init_qpos[:] = self.sim.model.key_qpos[0]
self.init_qvel[:] = 0.0

# move heightfield down if not used
self.sim.model.geom_rgba[self.sim.model.geom_name2id('terrain')][-1] = 0.0
self.sim.model.geom_pos[self.sim.model.geom_name2id('terrain')] = np.array([0, 0, -10])

def get_obs_dict(self, sim):
obs_dict = {}
obs_dict['t'] = np.array([sim.data.time])
Expand Down
55 changes: 51 additions & 4 deletions myosuite/envs/myo/myochallenge/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
entry_point='myosuite.envs.myo.myochallenge.relocate_v0:RelocateEnvV0',
max_episode_steps=150,
kwargs={
'model_path': curr_dir+'/../../../simhive/myo_sim/arm/myoarm_object_v0.16(mj237).mjb',
'model_path': curr_dir+'/../assets/arm/myoarm_relocate.xml',
'normalize_act': True,
'frame_skip': 5,
'pos_th': 0.1, # cover entire base of the receptacle
Expand All @@ -26,7 +26,7 @@
entry_point='myosuite.envs.myo.myochallenge.relocate_v0:RelocateEnvV0',
max_episode_steps=150,
kwargs={
'model_path': curr_dir+'/../../../simhive/myo_sim/arm/myoarm_object_v0.16(mj237).mjb',
'model_path': curr_dir+'/../assets/arm/myoarm_relocate.xml',
'normalize_act': True,
'frame_skip': 5,
'pos_th': 0.1, # cover entire base of the receptacle
Expand All @@ -41,13 +41,33 @@
}
)

# Register MyoChallenge Manipulation P2 Evals
register(id='myoChallengeRelocateP2eval-v0',
entry_point='myosuite.envs.myo.myochallenge.relocate_v0:RelocateEnvV0',
max_episode_steps=150,
kwargs={
'model_path': curr_dir + '/../assets/arm/myoarm_relocate.xml',
'normalize_act': True,
'frame_skip': 5,
'pos_th': 0.1, # cover entire base of the receptacle
'rot_th': np.inf, # ignore rotation errors
'qpos_noise_range':0.015, # jnt initialization range
'target_xyz_range': {'high':[0.4, -.1, 1.1], 'low':[-.5, -.5, .9]},
'target_rxryrz_range': {'high':[.3, .3, .3], 'low':[-.3, -.3, -.3]},
'obj_xyz_range': {'high':[0.15, -.10, 1.0], 'low':[-0.20, -.40, 1.0]},
'obj_geom_range': {'high':[.025, .025, .035], 'low':[.015, 0.015, 0.015]},
'obj_mass_range': {'high':0.300, 'low':0.050},# 50gms to 250 gms
'obj_friction_range': {'high':[1.2, 0.006, 0.00012], 'low':[0.8, 0.004, 0.00008]}
}
)


## MyoChallenge Locomotion P1
register(id='myoChallengeChaseTagP1-v0',
entry_point='myosuite.envs.myo.myochallenge.chasetag_v0:ChaseTagEnvV0',
max_episode_steps=2000,
kwargs={
'model_path': curr_dir+'/../../../simhive/myo_sim/leg/myolegs_chasetag_v0.11(mj237).mjb',
'model_path': curr_dir+'/../assets/leg/myolegs_chasetag.xml',
'normalize_act': True,
'win_distance': 0.5,
'min_spawn_distance': 2,
Expand All @@ -57,6 +77,7 @@
'hills_range': (0.0, 0.0),
'rough_range': (0.0, 0.0),
'relief_range': (0.0, 0.0),
'opponent_probabilities': (0.1, 0.45, 0.45),
}
)

Expand All @@ -66,7 +87,7 @@
entry_point='myosuite.envs.myo.myochallenge.chasetag_v0:ChaseTagEnvV0',
max_episode_steps=2000,
kwargs={
'model_path': curr_dir+'/../../../simhive/myo_sim/leg/myolegs_chasetag_v0.11(mj237).mjb',
'model_path': curr_dir+'/../assets/leg/myolegs_chasetag.xml',
'normalize_act': True,
'win_distance': 0.5,
'min_spawn_distance': 2,
Expand All @@ -76,9 +97,35 @@
'hills_range': (0.03, 0.23),
'rough_range': (0.05, 0.1),
'relief_range': (0.1, 0.3),
'repeller_opponent': False,
'chase_vel_range': (1.0, 1.0),
'random_vel_range': (-2, 2),
'opponent_probabilities': (0.1, 0.45, 0.45),
}
)

# Register MyoChallenge Locomotion P2 Evals
register(id='myoChallengeChaseTagP2eval-v0',
entry_point='myosuite.envs.myo.myochallenge.chasetag_v0:ChaseTagEnvV0',
max_episode_steps=2000,
kwargs={
'model_path': curr_dir+'/../assets/leg/myolegs_chasetag.xml',
'normalize_act': True,
'win_distance': 0.5,
'min_spawn_distance': 2,
'reset_type': 'random', # none, init, random
'terrain': 'random', # FLAT, random
'task_choice': 'random', # CHASE, EVADE, random
'hills_range': (0.03, 0.23),
'rough_range': (0.05, 0.1),
'relief_range': (0.1, 0.3),
'repeller_opponent': True,
'chase_vel_range': (1, 5),
'random_vel_range': (-2, 2),
'repeller_vel_range': (0.3, 1),
'opponent_probabilities': (0.1, 0.35, 0.35, 0.2),
}
)

# MyoChallenge 2022 envs ==============================================
# MyoChallenge Die: Trial env
Expand Down
Loading

0 comments on commit dbcb8bd

Please sign in to comment.