Skip to content

Commit

Permalink
Merge pull request #214 from elladyr/dev
Browse files Browse the repository at this point in the history
MyoChallenge Locomotion metrics
  • Loading branch information
Vittorio-Caggiano authored Sep 7, 2024
2 parents 5c8bb0e + 93d4667 commit a9cb246
Show file tree
Hide file tree
Showing 7 changed files with 202 additions and 12 deletions.
8 changes: 6 additions & 2 deletions .github/workflows/python-app.yml
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,7 @@ jobs:
# if: ${{ runner.os == 'macOS' }}
# run: |
# brew install --cask xquartz
# brew install hdf5
# brew install hdf5
# export CPATH="/opt/homebrew/include/"
# export HDF5_DIR=/opt/homebrew/
# pip3 install h5py --only-binary h5py
Expand All @@ -97,9 +97,13 @@ jobs:
if: ${{ runner.os == 'Linux' }}
run: python3 -m mujoco.render_test

- name: Run Test environment
- name: Test myoapi
run: |
conda activate $CONDA_DEFAULT_ENV
python3 -m myosuite.tests.test_myoapi
- name: Run Test environment
run: |
python3 -m myosuite.tests.test_myo
- name: Install ffmpeg
Expand Down
9 changes: 6 additions & 3 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ Test your installation using the following command (this will return also a list
``` bash
python -m myosuite.tests.test_myo
```


You can also visualize the environments with random controls using the command below:
``` bash
Expand All @@ -57,7 +57,10 @@ python -m myosuite.utils.examine_env --env_name myoElbowPose1D6MRandom-v0
mjpython -m myosuite.utils.examine_env --env_name myoElbowPose1D6MRandom-v0
```


It is possible to take advantage of the latest MyoSkeleton. Once added (follow the instructions prompted by `python -m myosuite_init`), run:
``` bash
python -m myosuite.utils.examine_sim -s myosuite/simhive/myo_model/myoskeleton/myoskeleton.xml
```

## Examples
It is possible to create and interface with MyoSuite environments just like any other OpenAI gym environments. For example, to use the `myoElbowPose1D6MRandom-v0` environment, it is possible simply to run: [![Open In Colab](https://colab.research.google.com/assets/colab-badge.svg)](https://colab.research.google.com/drive/1zFuNLsrmx42vT4oV8RbnEWtkSJ1xajEo)
Expand All @@ -74,7 +77,7 @@ for _ in range(1000):
env.close()
```

You can find our [tutorials](https://github.com/myohub/myosuite/tree/main/docs/source/tutorials#tutorials) on the general features and the **ICRA2023 Colab Tutorial** [![Open In Colab](https://colab.research.google.com/assets/colab-badge.svg)](https://colab.research.google.com/drive/1KGqZgSYgKXF-vaYC33GR9llDsIW9Rp-q) **ICRA2024 Colab Tutorial** [![Open In Colab](https://colab.research.google.com/assets/colab-badge.svg)](https://colab.research.google.com/drive/1JwxE7o6Z3bqCT4ewELacJ-Z1SV8xFhKK#scrollTo=QDppGIzHB9Zu)
You can find our [tutorials](https://github.com/myohub/myosuite/tree/main/docs/source/tutorials#tutorials) on the general features and the **ICRA2023 Colab Tutorial** [![Open In Colab](https://colab.research.google.com/assets/colab-badge.svg)](https://colab.research.google.com/drive/1KGqZgSYgKXF-vaYC33GR9llDsIW9Rp-q) **ICRA2024 Colab Tutorial** [![Open In Colab](https://colab.research.google.com/assets/colab-badge.svg)](https://colab.research.google.com/drive/1JwxE7o6Z3bqCT4ewELacJ-Z1SV8xFhKK#scrollTo=QDppGIzHB9Zu)
on how to load MyoSuite models/tasks, train them, and visualize their outcome. Also, you can find [baselines](https://github.com/myohub/myosuite/tree/main/myosuite/agents) to test some pre-trained policies.


Expand Down
44 changes: 41 additions & 3 deletions myosuite/envs/myo/myochallenge/run_track_v0.py
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,11 @@ class RunTrack(WalkEnvV0):
OSL_PARAM_LIST = []
OSL_PARAM_SELECT = 0

# Joint dict
pain_jnt = ['hip_adduction_l', 'hip_adduction_r', 'hip_flexion_l', 'hip_flexion_r', 'hip_rotation_l', 'hip_rotation_r',
'knee_angle_l', 'knee_angle_l_rotation2', 'knee_angle_l_rotation3',
'mtp_angle_l', 'ankle_angle_l', 'subtalar_angle_l']

def __init__(self, model_path, obsd_model_path=None, seed=None, **kwargs):
# This flag needs to be here to prevent the simulation from starting in a done state
# Before setting the key_frames, the model and opponent will be in the cartesian position,
Expand Down Expand Up @@ -82,13 +87,15 @@ def _setup(self,
real_width=1,
distance_thr = 10,
init_pose_path=None,
remap_required=False,
**kwargs,
):

self.startFlag = False
# Terrain type
self.terrain_type = TrackTypes.FLAT.value

self.remap_required = remap_required
# Env initialization with data
if init_pose_path is not None:
file_path = os.path.join(init_pose_path)
Expand Down Expand Up @@ -173,7 +180,9 @@ def get_reward_dict(self, obs_dict):
DEFAULT_RWD_KEYS_AND_WEIGHTS dict, or when registering the environment
with gym.register in myochallenge/__init__.py
"""
act_mag = np.linalg.norm(self.obs_dict['act'], axis=-1)/self.sim.model.na if self.sim.model.na !=0 else 0
# act_mag = np.linalg.norm(self.obs_dict['act'], axis=-1)/self.sim.model.na if self.sim.model.na !=0 else 0
act_mag = np.mean( np.square(self.obs_dict['act']) ) if self.sim.model.na !=0 else 0
pain = self.get_pain()

# The task is entirely defined by these 3 lines
score = self.get_score()
Expand All @@ -186,6 +195,7 @@ def get_reward_dict(self, obs_dict):

# Optional Keys
('act_reg', act_mag.squeeze()),
('pain', pain),
# Must keys
('sparse', score),
('solved', win_cdt),
Expand All @@ -199,10 +209,16 @@ def get_metrics(self, paths):
Evaluate paths and report metrics
"""
# average sucess over entire env horizon
times = np.mean([np.round(p['env_infos']['obs_dict']['time'][-1], 5) for p in paths])
score = np.mean([np.sum(p['env_infos']['rwd_dict']['sparse']) for p in paths])
effort = np.mean([np.sum(p['env_infos']['rwd_dict']['act_reg']) for p in paths])
pain = np.mean([np.sum(p['env_infos']['rwd_dict']['pain']) for p in paths])

metrics = {
'score': score,
'score': score, # Distance travelled
'Time': times,
'effort': effort,
'pain': pain,
}
return metrics

Expand Down Expand Up @@ -395,6 +411,15 @@ def get_score(self):
score = (y_pos - 15) / (- 15 - 15)
return score.squeeze()

def get_pain(self):
if not self.startFlag:
return -1

pain_score = 0
for joint in self.pain_jnt:
pain_score += np.clip(np.abs(self.get_limitfrc(joint).squeeze()), -1000, 1000)
return pain_score / len(self.pain_jnt)

def _get_muscle_lengthRange(self):
return self.sim.model.actuator_lengthrange.copy()

Expand Down Expand Up @@ -449,6 +474,14 @@ def _get_fallen_condition(self):
else:
return 0

def get_limitfrc(self, joint_name):
non_joint_limit_efc_idxs = np.where(self.sim.data.efc_type != self.sim.lib.mjtConstraint.mjCNSTR_LIMIT_JOINT)[0]
only_jnt_lim_efc_force = self.sim.data.efc_force.copy()
only_jnt_lim_efc_force[non_joint_limit_efc_idxs] = 0.0
joint_force = np.zeros((self.sim.model.nv,))
self.sim.lib.mj_mulJacTVec(self.sim.model._model, self.sim.data._data, joint_force, only_jnt_lim_efc_force)
return joint_force[self.sim.model.joint(joint_name).dofadr]

def get_internal_qpos(self):
temp_qpos = self.sim.data.qpos.copy()
to_remove = [self.sim.model.joint('osl_knee_angle_r').qposadr[0].copy(), self.sim.model.joint('osl_ankle_angle_r').qposadr[0].copy()]
Expand Down Expand Up @@ -637,6 +670,11 @@ def _prepareActions(self, mus_actions):
Only considers the 54 muscles of the OSLMyoleg model
"""

if self.remap_required:
if np.any( (mus_actions < -1) | (mus_actions > 1) ):
raise ValueError("Input value should be between -1 and 1")
mus_actions = (mus_actions + 1) / 2

full_actions = np.zeros(self.sim.model.nu,)
full_actions[0:self.sim.model.na] = mus_actions[0:self.sim.model.na].copy()

Expand All @@ -659,6 +697,6 @@ def get_osl_sens(self):
osl_sens_data['knee_vel'] = self.sim.data.joint('osl_knee_angle_r').qvel[0].copy()
osl_sens_data['ankle_angle'] = self.sim.data.joint('osl_ankle_angle_r').qpos[0].copy()
osl_sens_data['ankle_vel'] = self.sim.data.joint('osl_ankle_angle_r').qvel[0].copy()
osl_sens_data['load'] = self.sim.data.sensor('r_socket_load').data[1].copy() # Only vertical
osl_sens_data['load'] = -1*self.sim.data.sensor('r_osl_load').data[1].copy() # Only vertical

return osl_sens_data
25 changes: 25 additions & 0 deletions myosuite/tests/test_myoapi.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@

from pathlib import Path
from unittest.mock import patch

from myosuite_init import fetch_simhive

my_file = Path("/path/to/file")

@patch('builtins.input', side_effect=['no'])
def test_no_myoapi(mock_input):
print("mock_input", mock_input.side_effect)
fetch_simhive()
assert not Path("myosuite/simhive/myo_model/myoskeleton/myoskeleton.xml").exists()

@patch('builtins.input', side_effect=['yes'])
def test_yes_myoapi(mock_input):
print("mock_input", mock_input.side_effect)
fetch_simhive()
assert Path("myosuite/simhive/myo_model/myoskeleton/myoskeleton.xml").exists()

test_no_myoapi()
test_yes_myoapi()



2 changes: 1 addition & 1 deletion myosuite/version.py
Original file line number Diff line number Diff line change
@@ -1 +1 @@
__version_tuple__ = (2, 5, 0)
__version_tuple__ = (2, 7, 0)
113 changes: 113 additions & 0 deletions myosuite_init.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,113 @@
import os
import shutil
from os.path import expanduser

import git

curr_dir = os.path.dirname(os.path.abspath(__file__))
simhive_path = os.path.join(curr_dir, 'myosuite', 'simhive')


# from myosuite.utils.import_utils import fetch_git

def fetch_git(repo_url, commit_hash, clone_directory, clone_path=None):
"""
fetch git repo using provided details
"""
if clone_path is None:
clone_path = os.path.join(expanduser("~"), ".myosuite")
clone_directory = os.path.join(clone_path, clone_directory)

try:
# Create the clone directory if it doesn't exist
os.makedirs(clone_directory, exist_ok=True)

# Clone the repository to the specified path
if not os.path.exists(os.path.join(clone_directory,'.git')):
repo = git.Repo.clone_from(repo_url, clone_directory)
print(f"{repo_url} cloned at {clone_directory}")
else:
repo = git.Repo(clone_directory)
origin = repo.remote('origin')
origin.fetch()

# Check out the specific commit if not already
current_commit_hash = repo.head.commit.hexsha
if current_commit_hash != commit_hash:
repo.git.checkout(commit_hash)
print(f"{repo_url}@{commit_hash} fetched at {clone_directory}")
except git.GitCommandError as e:
print(f"Error: {e}")

return clone_directory


def clean_simhive():
"""
Remove cached simhive if it exists
"""
print("MyoSuite:> Clearing SimHive ...")
api_path = os.path.join(simhive_path, 'myo_model')
if os.path.exists(api_path):
shutil.rmtree(api_path)
else:
print("MyoSuite:> SimHive/myo_model directory does not exist.")
print("MyoSuite:> SimHive cleared")


def accept_license():
prompt = """
A permissive license for non-commercial scientific research is available.
You can review the license at: https://github.com/myolab/myo_model/blob/main/LICENSE
Do you accept the terms of the license? (yes/no):
"""
response = input(prompt).strip().lower()

if response == 'yes':
print("Thank you for accepting the license. You may proceed.")
return True
elif response == 'no':
print("You have rejected the license terms. Exiting...")
return False
else:
print("Invalid input. Please enter 'yes' or 'no'.")
return accept_license() # Recursively prompt again for valid input


def fetch_simhive():
"""
fetch a copy of simhive
"""
print("MyoSuite:> Initializing...")

# Mark the SimHive version (ToDo: Remove this when commits hashes are auto fetched from submodules)
__version__ = "2.5.0"

# Inform user about API
if accept_license():
# Proceed with the rest of the code
print("MyoSuite:> License accepted. Proceeding initialization ...")
else:
# Exit or handle the rejection case
print("MyoSuite:> License rejected. Exiting")
return

# Fetch SimHive
print("MyoSuite:> Downloading simulation assets (upto ~100MBs)")
fetch_git(repo_url="https://github.com/myolab/myo_model.git",
commit_hash="619b1a876113e91a302b9baeaad6c2341e12ac81",
clone_directory="myo_model",
clone_path=simhive_path)


# mark successful creation of simhive
filename = os.path.join(simhive_path, "simhive-version")
with open(filename, 'w') as file:
file.write(__version__)

print("MyoSuite:> Successfully Initialized.")


if __name__ == "__main__":
fetch_simhive()
13 changes: 10 additions & 3 deletions setup.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,8 @@
import os
import sys
import re
from setuptools import setup, find_packages
import sys

from setuptools import find_packages, setup

if sys.version_info.major != 3:
print("This Python is only compatible with Python 3, but you are running "
Expand Down Expand Up @@ -52,8 +53,14 @@ def package_files(directory):
"Topic :: Scientific/Engineering :: Artificial Intelligence ",
"Operating System :: OS Independent",
],
package_data={'': mjc_models_files},
package_data={'': mjc_models_files+['../myosuite_init.py']},
packages=find_packages(exclude=("myosuite.agents")),
python_requires=">=3.8",
install_requires=fetch_requirements(),
entry_points={
'console_scripts': [
'myoapi_init = myosuite_init:fetch_simhive',
'myoapi_clean = myosuite_init:clean_simhive',
],
},
)

0 comments on commit a9cb246

Please sign in to comment.