Skip to content

Commit

Permalink
Merge pull request #186 from Balint-H/env/bionic-bimanual
Browse files Browse the repository at this point in the history
Add MJCF for manip challenge
  • Loading branch information
vikashplus authored Jul 15, 2024
2 parents 92ec2f1 + 397a8f4 commit 9e2c6de
Show file tree
Hide file tree
Showing 13 changed files with 616 additions and 8 deletions.
7 changes: 7 additions & 0 deletions .gitmodules
Original file line number Diff line number Diff line change
Expand Up @@ -7,3 +7,10 @@
[submodule "myosuite/simhive/object_sim"]
path = myosuite/simhive/object_sim
url = https://github.com/vikashplus/object_sim.git
[submodule "myosuite/simhive/MPL_sim"]
path = myosuite/simhive/MPL_sim
url = https://github.com/vikashplus/MPL_sim.git
branch = myochallenge
[submodule "myosuite/simhive/YCB_sim"]
path = myosuite/simhive/YCB_sim
url = https://github.com/vikashplus/YCB_sim.git
42 changes: 42 additions & 0 deletions myosuite/agents/config/hydra_myochal_sb3_ppo_config.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
default:
- override hydra/output: local
- override hydra/launcher: local

env : 'myoChallengeBimanual-v0' #myosuite-v1 # placeholder name, not a real env
algorithm : PPO
seed : 123
n_env : 32
n_eval_env : 5

# PPO object
policy : 'MlpPolicy'
learning_rate : 0.0003
batch_size : 64
gamma : 0.99

# PPO.learn function
total_timesteps : 150000
log_interval : 10000

eval_freq : 1000000
restore_checkpoint_freq : 500000
save_freq : 10000000

policy_kwargs:
net_arch:
- pi: [256, 256]
vf: [256, 256]

# Algorithm hyperparameters : if alg requires additional params, can be specified here (or defaults will be used)
alg_hyper_params : {'device': 'cpu'}

clip_range: 0.2
ent_coeff: 0.001
n_epochs: 10
n_steps: 2048

job_name : ppo_sb3_${env}

hydra:
job:
name: ${env}
25 changes: 21 additions & 4 deletions myosuite/agents/sb3_job_script.py
Original file line number Diff line number Diff line change
Expand Up @@ -10,12 +10,14 @@
import os
import json
import time as timer
import myosuite
from stable_baselines3 import PPO, SAC
from stable_baselines3.common.callbacks import CheckpointCallback
from stable_baselines3.common.env_util import make_vec_env
from stable_baselines3.common.logger import configure
from stable_baselines3.common.vec_env import VecNormalize
import myosuite
import torch
from omegaconf import OmegaConf

import functools
from in_callbacks import InfoCallback, FallbackCheckpoint, SaveSuccesses, EvalCallback
Expand Down Expand Up @@ -45,19 +47,22 @@ def train_loop(job_data) -> None:
)

log = configure(f'results_{job_data.env}')

# Create the vectorized environment and normalize ob
env = make_vec_env(job_data.env, n_envs=job_data.n_env)
env = VecNormalize(env, norm_obs=True, norm_reward=False, clip_obs=10.)

eval_env = make_vec_env(job_data.env, n_envs=job_data.n_eval_env)
eval_env = VecNormalize(eval_env, norm_obs=True, norm_reward=False, clip_obs=10.)

algo = job_data.algorithm
if algo == 'PPO':
# Load activation function from config
policy_kwargs = OmegaConf.to_container(job_data.policy_kwargs, resolve=True)

model = PPO(job_data.policy, env, verbose=1,
learning_rate=job_data.learning_rate,
batch_size=job_data.batch_size,
policy_kwargs=policy_kwargs,
gamma=job_data.gamma, **job_data.alg_hyper_params)
elif algo == 'SAC':
model = SAC(job_data.policy, env,
Expand All @@ -67,8 +72,20 @@ def train_loop(job_data) -> None:
batch_size=job_data.batch_size,
tau=job_data.tau,
gamma=job_data.gamma, **job_data.alg_hyper_params)




if job_data.job_name =="checkpoint.pt":
foldername = os.path.join(os.path.dirname(os.path.realpath(__file__)), f"baseline_SB3/myoChal24/{job_data.env}")
file_path = os.path.join(foldername, job_data.job_name)
if os.path.isfile(file_path):
print("Loading weights from checkpoint")
model.policy.load_state_dict(torch.load(file_path))
else:
raise FileNotFoundError(f"No file found at the specified path: {file_path}. See https://github.com/MyoHub/myosuite/blob/dev/myosuite/agents/README.md to download one.")
else:
print("No checkpoint loaded, training starts.")

if IS_WnB_enabled:
callback = [WandbCallback(
model_save_path=f"models/{run.id}",
Expand Down
31 changes: 30 additions & 1 deletion myosuite/agents/train_myosuite.sh
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,8 @@ if [ "$1" == "myo" ] ; then
envs="myoFingerReachFixed-v0,myoFingerReachRandom-v0,myoFingerPoseFixed-v0,myoFingerPoseRandom-v0,myoElbowPose1D6MFixed-v0,myoElbowPose1D6MRandom-v0,myoHandPoseFixed-v0,myoHandPoseRandom-v0,myoHandReachFixed-v0,myoHandReachRandom-v0,myoHandKeyTurnFixed-v0,myoHandKeyTurnRandom-v0,myoHandObjHoldFixed-v0,myoHandObjHoldRandom-v0,myoHandPenTwirlFixed-v0,myoHandPenTwirlRandom-v0,myoHandBaodingFixed-v1,myoHandBaodingRandom-v1"
elif [ "$1" == "extra" ] ; then
envs="motorFingerReachFixed-v0,motorFingerReachRandom-v0,motorFingerPoseFixed-v0,motorFingerPoseRandom-v0,myoHandBaodingFixed4th-v1,myoHandBaodingFixed8th-v1"
elif [ "$1" == "myochal" ] ; then
envs="myoChallengeBimanual-v0"
else
echo "Unknown task suite"
exit 0
Expand All @@ -32,7 +34,11 @@ if [ "$3" == "mjrl" ] ; then
echo "NPG: ======="
echo "python hydra_mjrl_launcher.py --config-path config $config env=$envs"
elif [ "$3" == "sb3" ] ; then
config="--config-name hydra_myo_sb3_ppo_config.yaml $config"
if [ "$1" == "myochal" ] ; then
config="--config-name hydra_myochal_sb3_ppo_config.yaml $config"
else
config="--config-name hydra_myo_sb3_ppo_config.yaml $config"
fi
# Disp SB3 commands
echo "Stable-Baselines3: ======="
echo "python hydra_sb3_launcher.py --config-path config $config env=$envs"
Expand All @@ -41,6 +47,29 @@ else
exit 0
fi

if [ "$4" == 'baseline' ]; then
base_dir="baseline_SB3/myoChal24/${envs}"
filename="checkpoint.pt" # Specify the file name to save the checkpoint as

mkdir -p $base_dir

checkpoint_path="${base_dir}/${filename}"

model_url="https://drive.google.com/uc?export=download&id=1e7bj2Lrk50FU7nSRnIDg2JmYjGLBNChs"

# Use curl with -L to follow redirects and -o to specify output file
curl -L $model_url -o $checkpoint_path

if [ $? -eq 0 ]; then
echo "Download successful, checkpoint saved to $checkpoint_path."
config="$config checkpoint=$checkpoint_path job_name=$job_name"
else
echo "Download failed."
exit 1
fi
fi



#python hydra_sb3_launcher.py --config-path config --config-name hydra_myo_sb3_ppo_config.yaml env=myoHandPoseRandom-v0

Expand Down
88 changes: 88 additions & 0 deletions myosuite/envs/myo/assets/arm/myoarm_bionic_bimanual.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,88 @@
<mujoco model="MyoArm_Bimanual_MPL_v0.01">
<!-- =================================================
Copyright 2020 Vikash Kumar, Vittorio Caggiano, Guillaume Durandau
Model :: Myo Hand (MuJoCoV2.0)
Author :: Vikash Kumar ([email protected]), Vittorio Caggiano, Huawei Wang, Balint Hodossy
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/YCB_sim/includes/defaults_ycb.xml"/>
<include file="../../../../simhive/YCB_sim/includes/assets_009_gelatin_box.xml"/>

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

<include file='../../../../simhive/MPL_sim/assets/left_arm_assets.xml'/>
<include file='../../../../simhive/MPL_sim/assets/handL_assets.xml'/>

<compiler autolimits = "true" inertiafromgeom="auto" angle="radian" balanceinertia="true" boundmass="0.001" boundinertia=".0001" meshdir='../../../../simhive/myo_sim' texturedir='../../../../simhive/myo_sim/'/>
<option timestep="0.002">
<flag multiccd="enable"/>
</option>

<visual>
<global offwidth="1440" offheight="1080"/>
</visual>
<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"/>

<mesh file="../myo_sim/meshes/human_lowpoly_nohand.stl" name="body_nohand"/>

<texture type="2d" name="pillar_start" builtin="checker" mark="random" rgb1="0.4 0.4 0.4" rgb2="0.38 0.38 0.38"
markrgb="0.8 0.8 0.8" width="300" height="300" random="0.5"/>
<material name="pillar_start" texture="pillar_start" texuniform="true" texrepeat="5 5" reflectance="0.1"/>

<texture type="2d" name="pillar_goal" builtin="checker" mark="random" rgb1="0.45 0.45 0.45" rgb2="0.47 0.47 0.47"
markrgb="0.6 0.6 0.6" width="300" height="300" random="0.4"/>
<material name="pillar_goal" texture="pillar_goal" texuniform="true" texrepeat="5 5" reflectance="0.1"/>
</asset>


<worldbody>

<!-- ======= Human ======= -->
<geom name="body" type="mesh" mesh="body_nohand" 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>
<include file='../../../../simhive/MPL_sim/assets/left_arm_chain_myochallenge.xml'/>

<!-- ======= Object ======= -->
<body pos="-0.4 -0.2 1.2" euler="1.57 0 3.14" name="manip_object">
<freejoint/>
<include file="../../../../simhive/YCB_sim/includes/body_009_gelatin_box.xml"/>
<site name="touch_site" pos = "0 0 0.015" type="sphere" size="0.1" group="5" rgba="0.1 0.1 0.1 0.1"/>
</body>

<!-- ======= Start ======= -->
<body name="start" mocap="true" pos="-0.4 -0.25 1.05">
<geom type="cylinder" size="0.15 1.09" pos="0 0 -1.05" material="pillar_start" contype="1" conaffinity="1" solref="0.001 1" priority="2"/>
</body>

<!-- ======= Goal ======= -->
<body name="goal" mocap="true" pos="0.4 -0.25 1.05">
<geom type="cylinder" size="0.15 1.09" pos="0 0 -1.05" material="pillar_goal" contype="1" conaffinity="1" solref="0.001 1" priority="2"/>
</body>
</worldbody>

<keyframe>
<key qpos='0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0
0.494975 -0.23732 0.55978 1.26065 -0.2355 0.20447 -0.1456 0.5175 0.2987 0.5356 0.27248 0.13455 0.333625 0.4472 0.2415 0.757525 0.8304 0.4209 0.08625 0.357175 0.559 0.759 0.14835 0.74575 0 0.7314
-0.412997 -0.232224 1.10552 0.000796327 1.11022e-16 2.77556e-16 1'/>
<key qpos='0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0
0.494975 -1.07492 0.55978 1.26065 -0.2355 -0.08841 -0.208 0.5589 0.2987 0.5356 0.27248 0.276 0.4396 0.688 0.2415 0.22765 0.8304 0.4209 0.08625 0.357175 0.559 0 0.239775 0.286525 0 0.0345
-0.412997 -0.232224 1.10552 0.000796327 1.11022e-16 2.77556e-16 1'/>
<key qpos='-0.27804 0.11771 -0.11772 0.278047 -0.0564319 0.455158 0.204836 -0.204794 -0.455214 0.0564719 0.255888 1.14817 -0.255887 0.279129 0.844823 -0.0998497 0.248825 0.0328147 -0.31963 0.178287 0.122586 0.113854 0.156447 0.171211 0.0772555 0.0316704 0.14087 0.164449 0.0772084 0.0308998 0.126385 0.138577 0.0653656 0.0228821 0.117182 0.0890675 0.0301141 0.0205077 0.494975 -1.07492 0.55978 1.26065 -0.2355 -0.08841 -0.208 0.5589 0.2987 0.5356 0.27248 0.276 0.4396 0.688 0.2415 0.22765 0.8304 0.4209 0.08625 0.357175 0.559 0 0.239775 0.286525 0 0.0345
-0.400023 -0.200065 1.154 0.000477691 -0.000484427 -0.707107 0.707107'/>
<key qpos='-0.27804 0.11771 -0.11772 0.278047 -0.0564319 0.455158 0.204836 -0.204794 -0.455214 0.0564719 0.255888 1.14817 -0.255887 0.279129 0.844823 -0.0998497 0.248825 0.0328147 -0.31963 0.178287 0.122586 0.113854 0.156447 0.171211 0.0772555 0.0316704 0.14087 0.164449 0.0772084 0.0308998 0.126385 0.138577 0.0653656 0.0228821 0.117182 0.0890675 0.0301141 0.0205077 0.494975 0 0.23866 1.65267 1.57 0.11556 -0.4368 0.5589 0.25235 0.5356 0.27248 0.276 0.4396 0.688 0.2415 0.22765 0.8304 0.4209 0.08625 0.357175 0.559 0 0.239775 0.286525 0 0.0345 -0.400023 -0.200065 1.184 0.000477691 -0.000484427 -0.707107 0.707107'/>
</keyframe>
<sensor>
<touch site="touch_site"/>
</sensor>


</mujoco>
1 change: 1 addition & 0 deletions myosuite/envs/myo/assets/arm/myoarm_relocate.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
<compiler meshdir='../../../../simhive/myo_sim/' texturedir='../../../../simhive/myo_sim/'/>

<asset>
<mesh file="../myo_sim/meshes/human_lowpoly_norighthand.stl" name="body_norighthand"/>
<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"/>
Expand Down
14 changes: 14 additions & 0 deletions myosuite/envs/myo/myochallenge/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,20 @@ def register_env_with_variants(id, entry_point, max_episode_steps, kwargs):
silent=True
)

#MyoChallenge 2024 envs ===================
#MyoChallenge Manipulation P1

register_env_with_variants(id='myoChallengeBimanual-v0',
entry_point='myosuite.envs.myo.myochallenge.bimanual_v0:BimanualEnvV1',
max_episode_steps=250,
kwargs={
'model_path': curr_dir + '/../assets/arm/myoarm_bionic_bimanual.xml',
'normalize_act': True,
'frame_skip': 5,
}
)


# MyoChallenge 2023 envs ==============================================
# MyoChallenge Manipulation P1
register_env_with_variants(id='myoChallengeRelocateP1-v0',
Expand Down
Loading

0 comments on commit 9e2c6de

Please sign in to comment.