From 01bec92fd24b1625dcdf4d50b115d9b1eb0a09dd Mon Sep 17 00:00:00 2001 From: alberthli Date: Wed, 8 Nov 2023 21:21:34 -0800 Subject: [PATCH 01/79] [dirty] redo of kinematics/dynamics testing --- tests/test_kin_dyn.py | 65 +++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 65 insertions(+) create mode 100644 tests/test_kin_dyn.py diff --git a/tests/test_kin_dyn.py b/tests/test_kin_dyn.py new file mode 100644 index 00000000..b3bd2c9f --- /dev/null +++ b/tests/test_kin_dyn.py @@ -0,0 +1,65 @@ +import mujoco as mj +import numpy as np +import pinocchio as pin +from mujoco import mjx + +from ambersim import ROOT +from ambersim.utils.io_utils import load_mjx_model_and_data_from_file + + +def test_fk(): + """Tests forward kinematics.""" + urdf_path = ROOT + "/models/barrett_hand/bh280.urdf" + + # from ambersim.utils.io_utils import load_mj_model_from_file + + # mj_model = load_mj_model_from_file(urdf_path, force_float=True) + + # mjx + # floating base state convention: (translation[x, y, z], quat[w, x, y, z]) + mjx_model, mjx_data = load_mjx_model_and_data_from_file(urdf_path, force_float=True) + qpos_new = mjx_data.qpos.at[7:].set(0.5) # set all non-quat states to 0.5 + data_new = mjx_data.replace(qpos=qpos_new) + data_post_kin = mjx.kinematics(mjx_model, data_new) + xpos_mjx_post_kin = data_post_kin.xpos + print(xpos_mjx_post_kin) + + # pinocchio + # floating base state convention: (translation[x, y, z], quat[x, y, z, w]) + pin_model = pin.buildModelFromUrdf(urdf_path) + pin_model.addJoint(0, pin.JointModelFreeFlyer(), pin.SE3.Identity(), "freejoint") + pin_data = pin_model.createData() + breakpoint() + qpos_quat_xyzw = np.roll(np.array(qpos_new)[3:7], -1, axis=0) + pin_qpos = np.concatenate((np.array(qpos_new)[7:], np.array(qpos_new)[:7])) + pin_qpos[-4:] = qpos_quat_xyzw + pin.forwardKinematics(pin_model, pin_data, pin_qpos) + pin.updateFramePlacements(pin_model, pin_data) + for oMi in pin_data.oMi: + print(oMi.translation) + breakpoint() + + # # mjx + # # floating base state convention: (translation[x, y, z], quat[w, x, y, z]) + # mjx_model, mjx_data = load_mjx_model_and_data_from_file(urdf_path, force_float=False) + # qpos_new = mjx_data.qpos.at[:].set(0.5) + # data_new = mjx_data.replace(qpos=qpos_new) + # data_post_kin = mjx.kinematics(mjx_model, data_new) + # xpos_mjx_post_kin = data_post_kin.xpos + + # # pinocchio + # # floating base state convention: (translation[x, y, z], quat[x, y, z, w]) + # pin_model = pin.buildModelFromUrdf(urdf_path) + # pin_data = pin_model.createData() + # pin_qpos = np.array(qpos_new) + # pin.forwardKinematics(pin_model, pin_data, pin_qpos) + # pin.updateFramePlacements(pin_model, pin_data) + # breakpoint() + + +def test_fd(): + """Tests forward dynamics.""" + + +def test_id(): + """Tests inverse dynamics.""" From 5001a6b09c6aedde27362267ea3bb6f943f54bdb Mon Sep 17 00:00:00 2001 From: alberthli Date: Wed, 8 Nov 2023 22:27:45 -0800 Subject: [PATCH 02/79] wrote forward kinematics test by comparing to pinocchio --- tests/test_kin_dyn.py | 102 ++++++++++++++++++++++++------------------ 1 file changed, 59 insertions(+), 43 deletions(-) diff --git a/tests/test_kin_dyn.py b/tests/test_kin_dyn.py index b3bd2c9f..540e8043 100644 --- a/tests/test_kin_dyn.py +++ b/tests/test_kin_dyn.py @@ -1,60 +1,76 @@ +import jax.numpy as jnp import mujoco as mj import numpy as np import pinocchio as pin +import pytest from mujoco import mjx from ambersim import ROOT -from ambersim.utils.io_utils import load_mjx_model_and_data_from_file +from ambersim.utils.introspection_utils import get_joint_names +from ambersim.utils.io_utils import load_mj_model_from_file, mj_to_mjx_model_and_data -def test_fk(): - """Tests forward kinematics.""" +@pytest.fixture +def shared_variables(): + """Configuration method for global variables.""" + # run all tests on the barrett hand urdf_path = ROOT + "/models/barrett_hand/bh280.urdf" - # from ambersim.utils.io_utils import load_mj_model_from_file + # loading mjx models + mj_model = load_mj_model_from_file(urdf_path, force_float=True) + mjx_model, mjx_data = mj_to_mjx_model_and_data(mj_model) + mj_joint_names = get_joint_names(mj_model) - # mj_model = load_mj_model_from_file(urdf_path, force_float=True) - - # mjx - # floating base state convention: (translation[x, y, z], quat[w, x, y, z]) - mjx_model, mjx_data = load_mjx_model_and_data_from_file(urdf_path, force_float=True) - qpos_new = mjx_data.qpos.at[7:].set(0.5) # set all non-quat states to 0.5 - data_new = mjx_data.replace(qpos=qpos_new) - data_post_kin = mjx.kinematics(mjx_model, data_new) - xpos_mjx_post_kin = data_post_kin.xpos - print(xpos_mjx_post_kin) - - # pinocchio - # floating base state convention: (translation[x, y, z], quat[x, y, z, w]) + # loading pinocchio models pin_model = pin.buildModelFromUrdf(urdf_path) pin_model.addJoint(0, pin.JointModelFreeFlyer(), pin.SE3.Identity(), "freejoint") pin_data = pin_model.createData() - breakpoint() - qpos_quat_xyzw = np.roll(np.array(qpos_new)[3:7], -1, axis=0) - pin_qpos = np.concatenate((np.array(qpos_new)[7:], np.array(qpos_new)[:7])) - pin_qpos[-4:] = qpos_quat_xyzw - pin.forwardKinematics(pin_model, pin_data, pin_qpos) - pin.updateFramePlacements(pin_model, pin_data) - for oMi in pin_data.oMi: - print(oMi.translation) - breakpoint() - - # # mjx - # # floating base state convention: (translation[x, y, z], quat[w, x, y, z]) - # mjx_model, mjx_data = load_mjx_model_and_data_from_file(urdf_path, force_float=False) - # qpos_new = mjx_data.qpos.at[:].set(0.5) - # data_new = mjx_data.replace(qpos=qpos_new) - # data_post_kin = mjx.kinematics(mjx_model, data_new) - # xpos_mjx_post_kin = data_post_kin.xpos - - # # pinocchio - # # floating base state convention: (translation[x, y, z], quat[x, y, z, w]) - # pin_model = pin.buildModelFromUrdf(urdf_path) - # pin_data = pin_model.createData() - # pin_qpos = np.array(qpos_new) - # pin.forwardKinematics(pin_model, pin_data, pin_qpos) - # pin.updateFramePlacements(pin_model, pin_data) - # breakpoint() + pin_joint_names = list(pin_model.names) + + # setting dummy positions + _qpos_mj = [] + for mjjn in mj_joint_names: + if mjjn != "freejoint": + _qpos_mj.append([0.5]) # arbitrary + else: + # floating base state convention: (translation[x, y, z], quat[w, x, y, z]) + _qpos_mj.append([0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0]) + + _qpos_pin = [] + for pjn in pin_joint_names: + if pjn not in ["freejoint", "universe"]: + _qpos_pin.append([0.5]) # arbitrary + elif pjn != "universe": + # floating base state convention: (translation[x, y, z], quat[x, y, z, w]) + _qpos_pin.append([0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0]) + + qpos_mj = jnp.array(np.concatenate(_qpos_mj)) + qpos_pin = np.concatenate(_qpos_pin) + + # return shared variables + return mjx_model, mjx_data, mj_joint_names, pin_model, pin_data, pin_joint_names, qpos_mj, qpos_pin + + +def test_fk(shared_variables): + """Tests forward kinematics. + + Checks against pinocchio. The two main bookkeeping things are (1) the joint names and (2) the different quaternion convention. + """ + # loading global variables + mjx_model, mjx_data, mj_joint_names, pin_model, pin_data, pin_joint_names, qpos_mj, qpos_pin = shared_variables + + # running FK test + mjx_data = mjx.kinematics(mjx_model, mjx_data.replace(qpos=qpos_mj)) + pin.forwardKinematics(pin_model, pin_data, qpos_pin) + + for i, mjjn in enumerate(mj_joint_names): + j = pin_joint_names.index(mjjn) + assert np.allclose( + np.array(mjx_data.xanchor[i, :]), + np.array(pin_data.oMi[j].translation), + rtol=1e-6, + atol=1e-6, # loosen atol a bit + ) def test_fd(): From 0d1b3b779ad3eac70d5c1e2f676265242ddeedec Mon Sep 17 00:00:00 2001 From: alberthli Date: Thu, 9 Nov 2023 15:38:48 -0800 Subject: [PATCH 03/79] [dirty] pinocchio utils + refined FK test --- ambersim/utils/introspection_utils.py | 5 + ambersim/utils/pin_utils.py | 158 ++++++++++++++++++++++++++ tests/test_kin_dyn.py | 128 ++++++++++++++++----- 3 files changed, 261 insertions(+), 30 deletions(-) create mode 100644 ambersim/utils/pin_utils.py diff --git a/ambersim/utils/introspection_utils.py b/ambersim/utils/introspection_utils.py index 549b3e14..6b65064d 100644 --- a/ambersim/utils/introspection_utils.py +++ b/ambersim/utils/introspection_utils.py @@ -3,6 +3,11 @@ import mujoco as mj +def get_body_names(model: mj.MjModel) -> List[str]: + """Returns a list of all geom names in a mujoco (NOT mjx) model.""" + return [mj.mj_id2name(model, mj.mjtObj.mjOBJ_BODY, i) for i in range(model.nbody)] + + def get_geom_names(model: mj.MjModel) -> List[str]: """Returns a list of all geom names in a mujoco (NOT mjx) model.""" return [mj.mj_id2name(model, mj.mjtObj.mjOBJ_GEOM, i) for i in range(model.ngeom)] diff --git a/ambersim/utils/pin_utils.py b/ambersim/utils/pin_utils.py new file mode 100644 index 00000000..2fdb8023 --- /dev/null +++ b/ambersim/utils/pin_utils.py @@ -0,0 +1,158 @@ +from typing import List, Tuple + +import jax +import mujoco as mj +import numpy as np +import pinocchio as pin +from mujoco import mjx +from mujoco.mjx._src.scan import _q_jointid + +from ambersim.utils.introspection_utils import get_joint_names + +"""Utils for converting quantities between mujoco/mjx and pinocchio.""" + + +def get_joint_orders( + mj_model: mj.MjModel, + pin_model: pin.Model, +) -> Tuple[List[int], List[int]]: + """Computes the mapping from joint orders in mujoco and pinocchio. + + Pinocchio maintains one extra joint relative to mujoco (the "universe" joint). + The outputs satisfy the following two tests: + + assert [mj_joint_names[i] if i is not None else "universe" for i in mj2pin] == pin_joint_names + assert [pin_joint_names[i] for i in pin2mj if i is not None] == mj_joint_names + + Args: + mj_model: The MuJoCo model. + pin_model: The Pinocchio model. + + Returns: + pin2mj: The mapping from pinocchio joint order to mujoco joint order. + mj2pin: The mapping from mujoco joint order to pinocchio joint order. + """ + mj_joint_names = get_joint_names(mj_model) + pin_joint_names = list(pin_model.names) + + mj2pin = [mj_joint_names.index(a) if a in mj_joint_names else None for a in pin_joint_names] + pin2mj = [pin_joint_names.index(a) if a in pin_joint_names else None for a in mj_joint_names] + + return mj2pin, pin2mj + + +def mjx_xanchor_to_pin(mj2pin: List[int], mjx_data: mjx.Data) -> np.ndarray: + """Converts the mujoco joint anchor positions to pinocchio joint placements. + + Args: + mj2pin: The mapping from mujoco joint order to pinocchio joint order. + mjx_data: The mujoco data. + + Returns: + xanchor_pin: The pinocchio joint placements. + """ + xanchors = np.array(mjx_data.xanchor) + _xanchor_pin = [] + for mj_idx in mj2pin: + if mj_idx is not None: + _xanchor_pin.append(xanchors[mj_idx, :]) + else: + _xanchor_pin.append(np.zeros(3)) + return np.stack(_xanchor_pin) + + +def pin_xanchor_to_mjx(pin2mj: List[int], pin_data: pin.Data) -> np.ndarray: + """Converts the pinocchio joint placements to mujoco joint anchor positions. + + Args: + pin2mj: The mapping from pinocchio joint order to mujoco joint order. + pin_data: The pinocchio data. + + Returns: + xanchor_mj: The mujoco joint anchor positions. + """ + _xanchor_mj = [] + for pin_idx in pin2mj: + if pin_idx is not None: + _xanchor_mj.append(pin_data.oMi[pin_idx].translation) + else: + _xanchor_mj.append(np.zeros(3)) + return np.stack(_xanchor_mj) + + +def mjx_qpos_to_pin(qpos_mjx: jax.Array, mjx_model: mjx.Model, mj2pin: List[int]) -> np.ndarray: + """Converts the mujoco joint positions to pinocchio joint positions. + + Args: + qpos_mjx: The mjx joint positions. + mjx_model: The mjx model. + mj2pin: The mapping from mujoco joint order to pinocchio joint order. + + Returns: + qpos_pin: The pinocchio joint positions. + """ + qpos_mjx = np.array(qpos_mjx) + _qpos_pin = [] + jnt_types = mjx_model.jnt_type + for mj_idx in mj2pin: + # ignore Nones + if mj_idx is None: + continue + + # check how to append based on joint type + jnt_type = jnt_types[mj_idx] + startidx = mjx_model.jnt_qposadr[mj_idx] + + if jnt_type == 0: # FREE, 7-dimensional + _qpos_pin.append(qpos_mjx[startidx : startidx + 3]) + quat_wxyz = qpos_mjx[startidx + 3 : startidx + 7] + quat_xyzw = np.concatenate((quat_wxyz[1:], quat_wxyz[:1])) + _qpos_pin.append(quat_xyzw) + elif jnt_type == 1: # BALL, 4-dimensional + quat_wxyz = qpos_mjx[startidx : startidx + 4] + quat_xyzw = np.concatenate((quat_wxyz[1:], quat_wxyz[:1])) + _qpos_pin.append(quat_xyzw) + elif jnt_type == 2: # SLIDE, 3-dimensional + _qpos_pin.append(qpos_mjx[startidx : startidx + 3]) + else: # HINGE, 1-dimensional + _qpos_pin.append(qpos_mjx[startidx : startidx + 1]) + + return np.concatenate(_qpos_pin) + + +def mjx_qvel_to_pin(qvel_mjx: jax.Array, mjx_model: mjx.Model, mj2pin: List[int]) -> np.ndarray: + """Converts the mujoco joint velocities to pinocchio joint velocities. + + Notice that there is one less coordinate for rotational velocities compared to quaternion coordinates. + + Args: + qvel_mjx: The mjx joint velocities. + mjx_model: The mjx model. + mj2pin: The mapping from mujoco joint order to pinocchio joint order. + + Returns: + qvel_pin: The pinocchio joint velocities. + """ + qvel_mjx = np.array(qvel_mjx) + _qvel_pin = [] + jnt_types = mjx_model.jnt_type + for mj_idx in mj2pin: + # ignore Nones + if mj_idx is None: + continue + + # check how to append based on joint type + jnt_type = jnt_types[mj_idx] + startidx = mjx_model.jnt_dofadr[mj_idx] + + if jnt_type == 0: # FREE, 6-dimensional + _qvel_pin.append(qvel_mjx[startidx : startidx + 3]) + _qvel_pin.append(qvel_mjx[startidx + 3 : startidx + 6]) + elif jnt_type == 1: # BALL, 3-dimensional + _qvel_pin.append(qvel_mjx[startidx : startidx + 3]) + elif jnt_type == 2: # SLIDE, 1-dimensional + _qvel_pin.append(qvel_mjx[startidx : startidx + 1]) + else: # HINGE, 1-dimensional + _qvel_pin.append(qvel_mjx[startidx : startidx + 1]) + + return np.concatenate(_qvel_pin) diff --git a/tests/test_kin_dyn.py b/tests/test_kin_dyn.py index 540e8043..802c50bf 100644 --- a/tests/test_kin_dyn.py +++ b/tests/test_kin_dyn.py @@ -8,6 +8,23 @@ from ambersim import ROOT from ambersim.utils.introspection_utils import get_joint_names from ambersim.utils.io_utils import load_mj_model_from_file, mj_to_mjx_model_and_data +from ambersim.utils.pin_utils import ( + get_joint_orders, + mjx_qpos_to_pin, + mjx_qvel_to_pin, + mjx_xanchor_to_pin, + pin_xanchor_to_mjx, +) + +""" +The tests here check the mjx calculations against pinocchio (and also demonstrate how to use the kin/dyn funcs +independently of environments). The two main bookkeeping things are (1) the joint names and (2) the different +quaternion convention. + +TODO(ahl): +* test correctness of batched data +* use more convincing nonzero values for dynamics tests +""" @pytest.fixture @@ -27,55 +44,106 @@ def shared_variables(): pin_data = pin_model.createData() pin_joint_names = list(pin_model.names) + # relating mujoco and pinocchio joint orders + mj2pin, pin2mj = get_joint_orders(mj_model, pin_model) + # setting dummy positions _qpos_mj = [] for mjjn in mj_joint_names: if mjjn != "freejoint": - _qpos_mj.append([0.5]) # arbitrary + _qpos_mj.append([np.random.randn()]) # arbitrary else: # floating base state convention: (translation[x, y, z], quat[w, x, y, z]) - _qpos_mj.append([0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0]) - - _qpos_pin = [] - for pjn in pin_joint_names: - if pjn not in ["freejoint", "universe"]: - _qpos_pin.append([0.5]) # arbitrary - elif pjn != "universe": - # floating base state convention: (translation[x, y, z], quat[x, y, z, w]) - _qpos_pin.append([0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0]) + # TODO(ahl): also randomize rotation + _qpos_mj.append([np.random.randn(), np.random.randn(), np.random.randn(), 1.0, 0.0, 0.0, 0.0]) + qpos_mjx = jnp.array(np.concatenate(_qpos_mj)) + qpos_pin = mjx_qpos_to_pin(qpos_mjx, mjx_model, mj2pin) # accounts for potentially different joint ordering - qpos_mj = jnp.array(np.concatenate(_qpos_mj)) - qpos_pin = np.concatenate(_qpos_pin) + # setting dummy velocities + # qvel_mjx = jnp.array(np.random.randn(mjx_model.nv)) + # qvel_pin = mjx_qvel_to_pin(qvel_mjx, mjx_model, mj2pin) # accounts for potentially different joint ordering # return shared variables - return mjx_model, mjx_data, mj_joint_names, pin_model, pin_data, pin_joint_names, qpos_mj, qpos_pin + return ( + mj_model, + mjx_model, + mjx_data, + mj_joint_names, + pin_model, + pin_data, + pin_joint_names, + qpos_mjx, + qpos_pin, + mj2pin, + pin2mj, + ) + + +def test_joint_orders(shared_variables): + """Tests joint ordering.""" + mj_model = shared_variables[0] + mj_joint_names = shared_variables[3] + pin_model = shared_variables[4] + pin_joint_names = shared_variables[6] + mj2pin, pin2mj = get_joint_orders(mj_model, pin_model) + assert [mj_joint_names[i] if i is not None else "universe" for i in mj2pin] == pin_joint_names + assert [pin_joint_names[i] for i in pin2mj if i is not None] == mj_joint_names def test_fk(shared_variables): - """Tests forward kinematics. - - Checks against pinocchio. The two main bookkeeping things are (1) the joint names and (2) the different quaternion convention. - """ + """Tests forward kinematics. Also implicitly tests conversion functions between mjx and pin.""" # loading global variables - mjx_model, mjx_data, mj_joint_names, pin_model, pin_data, pin_joint_names, qpos_mj, qpos_pin = shared_variables + ( + mj_model, + mjx_model, + mjx_data, + mj_joint_names, + pin_model, + pin_data, + pin_joint_names, + qpos_mjx, + qpos_pin, + mj2pin, + pin2mj, + ) = shared_variables # running FK test - mjx_data = mjx.kinematics(mjx_model, mjx_data.replace(qpos=qpos_mj)) + mjx_data = mjx.kinematics(mjx_model, mjx_data.replace(qpos=qpos_mjx)) pin.forwardKinematics(pin_model, pin_data, qpos_pin) - for i, mjjn in enumerate(mj_joint_names): - j = pin_joint_names.index(mjjn) + # testing in one direction (mjx coords -> pin) + xanchors_pin = mjx_xanchor_to_pin(mj2pin, mjx_data) + for i, x in enumerate(xanchors_pin): assert np.allclose( - np.array(mjx_data.xanchor[i, :]), - np.array(pin_data.oMi[j].translation), + np.array(x), + np.array(pin_data.oMi[i].translation), rtol=1e-6, atol=1e-6, # loosen atol a bit ) - -def test_fd(): - """Tests forward dynamics.""" - - -def test_id(): - """Tests inverse dynamics.""" + # testing other direction (pin coords -> mjx) + xanchors_mjx = mjx_data.xanchor + xanchors_mjx_converted = pin_xanchor_to_mjx(pin2mj, pin_data) + for i, xanchor_mjx in enumerate(xanchors_mjx): + if mj2pin[i] is not None: + assert np.allclose( + np.array(xanchor_mjx), + np.array(xanchors_mjx_converted[i, :]), + rtol=1e-6, + atol=1e-6, # loosen atol a bit + ) + + +# def test_fd(shared_variables): +# """Tests forward dynamics.""" +# # mj_model, mjx_model, mjx_data, mj_joint_names, pin_model, pin_data, pin_joint_names, qpos_mjx, qpos_pin, mj2pin, pin2mj = shared_variables + +# # # running FD test +# # +# # dv_mjx = np.array(mjx_data.qacc) + +# # M = pin.crba(pin_model, pin_data, qpos_pin)mjx_data = mjx.forward(mjx_model, mjx_data.replace(qpos=qpos_mjx)) +# # qvel_pin = np.zeros(pin_model.nv) # [TODO] make this more exotic +# # zero_accel = np.zeros(pin_model.nv) +# # tau0 = pin.rnea(pin_model, pin_data, qpos_pin, qvel_pin, zero_accel) +# # # [TODO] add applied forces tau to pinocchio and mjx for the test, check about gravity From 7bcace7817d824976ce909308e3451cb17f6cca9 Mon Sep 17 00:00:00 2001 From: alberthli Date: Thu, 9 Nov 2023 16:51:38 -0800 Subject: [PATCH 04/79] added functionality that parses actuators from URDF and ensures that they are present in the XML --- ambersim/utils/conversion_utils.py | 15 +++--- ambersim/utils/io_utils.py | 81 +++++++++++++++++++++++++++--- 2 files changed, 79 insertions(+), 17 deletions(-) diff --git a/ambersim/utils/conversion_utils.py b/ambersim/utils/conversion_utils.py index d83b7384..ffa9e9b5 100644 --- a/ambersim/utils/conversion_utils.py +++ b/ambersim/utils/conversion_utils.py @@ -8,7 +8,7 @@ from ambersim.utils._internal_utils import _check_filepath -def save_model_xml(filepath: Union[str, Path], output_name: Optional[str] = None) -> None: +def save_model_xml(filepath: Union[str, Path], output_path: Optional[Union[str, Path]] = None) -> None: """Loads a model and saves it to a mujoco-compliant XML. Will save the file to the directory where this util is called. Note that you should add a mujoco tag to URDF files @@ -17,21 +17,18 @@ def save_model_xml(filepath: Union[str, Path], output_name: Optional[str] = None Args: filepath: A path to a URDF or MJCF file. This can be global, local, or with respect to the repository root. - output_name: The output name of the model. + output_path: The output path of the model. """ try: # loading model and saving XML filepath = _check_filepath(filepath) _model = mj.MjModel.from_xml_path(filepath) - if output_name is None: - output_name = filepath.split("/")[-1].split(".")[0] - else: - output_name = output_name.split(".")[0] # strip any extensions - mj.mj_saveLastXML(f"{output_name}.xml", _model) + if output_path is None: + output_path = filepath.split("/")[-1].split(".")[0] + ".xml" + mj.mj_saveLastXML(output_path, _model) # reporting save path for clarity - output_path = Path.cwd() / Path(str(output_name) + ".xml") - print(f"XML file saved to {output_path}!") + print(f"XML file saved to {str(output_path)}!") except ValueError as e: print(e) print( diff --git a/ambersim/utils/io_utils.py b/ambersim/utils/io_utils.py index 38cef0cc..acbc0dbb 100644 --- a/ambersim/utils/io_utils.py +++ b/ambersim/utils/io_utils.py @@ -6,6 +6,7 @@ import numpy as np import trimesh from dm_control import mjcf +from lxml import etree from mujoco import mjx from ambersim import ROOT @@ -13,6 +14,62 @@ from ambersim.utils.conversion_utils import save_model_xml +def _add_actuators(urdf_filepath: Union[str, Path], xml_filepath: Union[str, Path]) -> None: + """Takes a URDF and a corresponding XML derived from it and adds actuators to the XML. + + This util is necessary because mujoco doesn't automatically add actuators. We assume that transmissions are defined + for all actuated DOFs in the URDF. The supplied xml is directly modified. + + Args: + urdf_filepath: A path to a URDF file. + xml_filepath: A path to an XML file. + """ + # parsing URDF + # the recover=True keyword parses even after encountering invalid namespaces + # this is useful when, e.g., we have drake:declare_convex, which is not a valid namespace + with open(urdf_filepath, "r") as f: + urdf_tree = etree.XML(f.read(), etree.XMLParser(remove_blank_text=True, recover=True)) + + # parsing XML + with open(xml_filepath, "r") as f: + xml_tree = etree.XML(f.read(), etree.XMLParser(remove_blank_text=True)) + + # checking whether the XML has an actuator section already + if xml_tree.find("actuator") is None: + actuator = etree.Element("actuator") + xml_tree.append(actuator) + + # getting transmission info from URDF and loading it into the XML + actuators = xml_tree.find("actuator") + for transmission in urdf_tree.findall("transmission"): + joint_name = transmission.find("joint").get("name") + joint = urdf_tree.find(f"joint[@name='{joint_name}']") + limit = joint.find("limit").get("effort") + + if actuators.find(f"motor[@joint='{joint_name}']") is None: + if limit is not None: + etree.SubElement( + actuators, + "motor", + name=joint_name + "_actuator", + ctrllimited="true", + ctrlrange=f"-{limit} {limit}", + joint=joint_name, + ) + else: + etree.SubElement( + actuators, + "motor", + name=joint_name + "_actuator", + ctrllimited="false", + joint=joint_name, + ) + + # resaving the XML + with open(xml_filepath, "wb") as f: + f.write(etree.tostring(xml_tree, pretty_print=True)) + + def _modify_robot_float_base(filepath: Union[str, Path]) -> mj.MjModel: """Modifies a robot to have a floating base if it doesn't already.""" # loading current robot @@ -50,6 +107,9 @@ def load_mj_model_from_file( Returns: mj_model: A mujoco model. + + Raises: + NotImplementedError: if the file extension is not in [".urdf", ".xml"] """ # TODO(ahl): once we allow installing mujoco from source, update this to allow the Newton solver + update default if isinstance(solver, str): @@ -61,17 +121,22 @@ def load_mj_model_from_file( assert solver in [mj.mjtSolver.mjSOL_CG] filepath = _check_filepath(filepath) + is_urdf = str(filepath).split(".")[-1] == "urdf" + is_xml = str(filepath).split(".")[-1] == "xml" - # loading the model and data. check whether freejoint is added forcibly + # loading the model and data. check whether to forcibly add a freejoint if force_float: - # check that the file is an XML. if not, save as xml temporarily - if str(filepath).split(".")[-1] != "xml": - output_name = "/".join(str(filepath).split("/")[:-1]) + "/_temp_xml_model.xml" - save_model_xml(filepath, output_name=output_name) - mj_model = _modify_robot_float_base(output_name) - Path.unlink(output_name) - else: + # check file extension and process accordingly + if is_urdf: + output_path = "/".join(str(filepath).split("/")[:-1]) + "/_temp_xml_model.xml" + save_model_xml(filepath, output_path=output_path) + _add_actuators(filepath, output_path) + mj_model = _modify_robot_float_base(output_path) + Path.unlink(output_path) + elif is_xml: mj_model = _modify_robot_float_base(filepath) + else: + raise NotImplementedError else: mj_model = mj.MjModel.from_xml_path(filepath) From c4582e4a27fa4fb645ce0ea0f130ebdc8d72cac5 Mon Sep 17 00:00:00 2001 From: alberthli Date: Thu, 9 Nov 2023 17:08:48 -0800 Subject: [PATCH 05/79] added test for actuator loading --- ambersim/utils/io_utils.py | 32 +++++++++++++++++++------------- tests/test_model_io.py | 14 ++++++++++++++ 2 files changed, 33 insertions(+), 13 deletions(-) diff --git a/ambersim/utils/io_utils.py b/ambersim/utils/io_utils.py index acbc0dbb..df8f60ec 100644 --- a/ambersim/utils/io_utils.py +++ b/ambersim/utils/io_utils.py @@ -124,21 +124,27 @@ def load_mj_model_from_file( is_urdf = str(filepath).split(".")[-1] == "urdf" is_xml = str(filepath).split(".")[-1] == "xml" - # loading the model and data. check whether to forcibly add a freejoint + # treating URDFs and XMLs differently + temp_output_path = False + if is_urdf: + output_path = "/".join(str(filepath).split("/")[:-1]) + "/_temp_xml_model.xml" + save_model_xml(filepath, output_path=output_path) + _add_actuators(filepath, output_path) + temp_output_path = True + elif is_xml: + output_path = filepath + else: + raise NotImplementedError + + # checking whether to force float if force_float: - # check file extension and process accordingly - if is_urdf: - output_path = "/".join(str(filepath).split("/")[:-1]) + "/_temp_xml_model.xml" - save_model_xml(filepath, output_path=output_path) - _add_actuators(filepath, output_path) - mj_model = _modify_robot_float_base(output_path) - Path.unlink(output_path) - elif is_xml: - mj_model = _modify_robot_float_base(filepath) - else: - raise NotImplementedError + mj_model = _modify_robot_float_base(output_path) else: - mj_model = mj.MjModel.from_xml_path(filepath) + mj_model = mj.MjModel.from_xml_path(output_path) + + # deleting temp file + if temp_output_path: + Path.unlink(output_path) # setting solver options mj_model.opt.solver = solver diff --git a/tests/test_model_io.py b/tests/test_model_io.py index 4d084904..1736033a 100644 --- a/tests/test_model_io.py +++ b/tests/test_model_io.py @@ -5,6 +5,7 @@ import numpy as np import trimesh from dm_control import mjcf +from lxml import etree from mujoco import mjx from ambersim import ROOT @@ -56,6 +57,19 @@ def test_save_xml(): Path.unlink("pendulum.xml") # deleting test file +def test_actuators(): + """Tests that actuators are added correctly when converting from URDF to XML.""" + for urdf_filepath in Path(ROOT + "/models").rglob("*.urdf"): + # loading the URDF and checking the number of transmissions it has + with open(urdf_filepath, "r") as f: + urdf_tree = etree.XML(f.read(), etree.XMLParser(remove_blank_text=True, recover=True)) + num_actuators = len(urdf_tree.findall("transmission")) + + # checking that the same file loaded into mjx has the same number of actuators + mjx_model, _ = load_mjx_model_and_data_from_file(urdf_filepath) + assert mjx_model.nu == num_actuators + + def test_force_float(): """Tests the functionality of forcing models to have a floating base.""" # case 1: model's first body has a joint, add a freejoint with dummy body From 9b69372f469fad6625c841371136ae0746eb2776 Mon Sep 17 00:00:00 2001 From: alberthli Date: Thu, 9 Nov 2023 17:13:18 -0800 Subject: [PATCH 06/79] added some guidance in the README about model loading --- README.md | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/README.md b/README.md index 42b0a16f..3b27a887 100644 --- a/README.md +++ b/README.md @@ -33,6 +33,12 @@ pre-commit autoupdate pre-commit install ``` +## Custom Models +We have implemented some custom utils for model parsing, but they aren't complete/perfect. Here are some guidelines for when you want to use this codebase for a custom project: +* it's OK to just use URDFs and use our utils for loading them into `mjx` if you don't care too much about collision filtering or mujoco-specific elements like lights, sites, etc. +* if you decide to use URDFs instead of converting the model description into an `xml`, then you should add a `` tag with some specific settings to the top of your URDF. See the examples in this repo as guidance. +* if you decide to convert the URDF to an XML, then we have some custom utils for helping with the initial conversion, but if you want to add a lot of mujoco-specific elements, those need to be done by hand. + ## Development Details ### Abridged Dev Guidelines From 9037cd959292431de1867252a3fcbf3197f3513c Mon Sep 17 00:00:00 2001 From: alberthli Date: Thu, 9 Nov 2023 17:49:07 -0800 Subject: [PATCH 07/79] update README with info about transmission tag --- README.md | 1 + 1 file changed, 1 insertion(+) diff --git a/README.md b/README.md index 3b27a887..c437e89f 100644 --- a/README.md +++ b/README.md @@ -37,6 +37,7 @@ pre-commit install We have implemented some custom utils for model parsing, but they aren't complete/perfect. Here are some guidelines for when you want to use this codebase for a custom project: * it's OK to just use URDFs and use our utils for loading them into `mjx` if you don't care too much about collision filtering or mujoco-specific elements like lights, sites, etc. * if you decide to use URDFs instead of converting the model description into an `xml`, then you should add a `` tag with some specific settings to the top of your URDF. See the examples in this repo as guidance. + * you should also make sure that your actuated joints have `` blocks associated with them, as this is what our parser looks for to add actuators to the mujoco model. * if you decide to convert the URDF to an XML, then we have some custom utils for helping with the initial conversion, but if you want to add a lot of mujoco-specific elements, those need to be done by hand. ## Development Details From 909b6a2d724190b1019e04b7a2b51fcff58edea4 Mon Sep 17 00:00:00 2001 From: alberthli Date: Thu, 9 Nov 2023 22:10:35 -0800 Subject: [PATCH 08/79] initial bash script and README update --- README.md | 37 ++++++++++++++++++++++++------------- install.sh | 43 +++++++++++++++++++++++++++++++++++++++++++ 2 files changed, 67 insertions(+), 13 deletions(-) create mode 100755 install.sh diff --git a/README.md b/README.md index 42b0a16f..45d49bad 100644 --- a/README.md +++ b/README.md @@ -5,33 +5,44 @@ This repository houses tools built on the GPU-accelerated simulation capabilitie * massively-parallelized simulation. ## Quickstart - -### Non-developers Create a conda environment with Cuda 11.8 support: ``` conda env create -n -f environment.yml conda activate ``` -To locally install this package, clone the repository and in the repo root, run +Install the project. Note the two different options depending on whether you want to develop on the repo or not. ``` +# OPTION 1: NON-DEVELOPERS pip install . --default-timeout=100 future --find-links https://storage.googleapis.com/jax-releases/jax_cuda_releases.html --find-links https://download.pytorch.org/whl/cu118 -``` -### Developers -Create a conda environment with Cuda 11.8 support: -``` -conda env create -n -f environment.yml -conda activate -``` -Install the project with the editable flag and development dependencies: -``` +# OPTION 2: DEVELOPERS pip install -e .[all] --default-timeout=100 future --find-links https://storage.googleapis.com/jax-releases/jax_cuda_releases.html --find-links https://download.pytorch.org/whl/cu118 ``` -Then, install pre-commit hooks by running the following in the repo root: +For developers, install pre-commit hooks by running the following in the repo root: ``` pre-commit autoupdate pre-commit install ``` +To install the latest and greatest version of `mujoco` from source, ensure that your system has the right build dependencies: +``` +sudo apt-get update -y +sudo apt-get install -y \ + libgl1-mesa-dev \ + libxinerama-dev \ + libxcursor-dev \ + libxrandr-dev \ + libxi-dev \ + ninja-build +``` +Then, run the installation `bash` script, which will update `mujoco` to the latest version built from source: +``` +sudo chmod +x install.sh +./install.sh +``` +If the following line of code runs without error, then the installation was successful: +``` +python -c "import mujoco" +``` ## Development Details diff --git a/install.sh b/install.sh new file mode 100755 index 00000000..aad0a8b9 --- /dev/null +++ b/install.sh @@ -0,0 +1,43 @@ +#!/bin/bash +# instructions are taken from two places: +# (1) https://mujoco.readthedocs.io/en/latest/programming/#building-from-source +# (2) https://mujoco.readthedocs.io/en/latest/python.html#building-from-source + +set -e + +# Check if CMake and a compiler are installed +if ! command -v cmake &> /dev/null; then + echo "CMake is not installed. Please install CMake before proceeding." + exit 1 +fi + +if ! command -v g++ &> /dev/null; then + echo "C++ compiler is not available. Please install a C++ compiler before proceeding." + exit 1 +fi + +# Clone the Mujoco repo to the directory above where this script is located +# If it exists already, then just git pull new changes +script_dir="$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd)" +mujoco_dir="$script_dir/../mujoco" +if [ -d "$mujoco_dir" ]; then + echo "Mujoco exists already - running git pull to update it!" + (cd "$mujoco_dir" && git pull origin main) +else + git clone https://github.com/google-deepmind/mujoco.git "$mujoco_dir" +fi + +# Configure and build +cd "$mujoco_dir" +cmake . +cmake --build . + +# Install Mujoco +cmake . -DCMAKE_INSTALL_PREFIX="./mujoco_install" +cmake --install . + +# Generate source distribution required for Python bindings +cd "$mujoco_dir/python" +./make_sdist.sh +tar_path=$(find "$mujoco_dir/python/dist" -name 'mujoco-*.tar.gz' 2>/dev/null) +MUJOCO_PATH="$mujoco_dir/mujoco_install" MUJOCO_PLUGIN_PATH="$mujoco_dir/plugin" pip install "$tar_path" From 7635df2d7f31f78dfee28683acb1d57b27c560bb Mon Sep 17 00:00:00 2001 From: alberthli Date: Thu, 9 Nov 2023 22:49:57 -0800 Subject: [PATCH 09/79] update CI workflow and consolidate installation into one command (+system-wide dependency instructions for building from source) --- .github/workflows/code_checks.yml | 4 +- .pre-commit-config.yaml | 2 +- README.md | 31 +++++------ install.sh | 88 ++++++++++++++++++++----------- 4 files changed, 74 insertions(+), 51 deletions(-) diff --git a/.github/workflows/code_checks.yml b/.github/workflows/code_checks.yml index 84d7dea4..e8495cc5 100644 --- a/.github/workflows/code_checks.yml +++ b/.github/workflows/code_checks.yml @@ -26,8 +26,8 @@ jobs: restore-keys: | ${{ runner.os }}-pip- - name: Install dependencies - run: | - pip install --upgrade --upgrade-strategy eager -e .[all] --find-links https://storage.googleapis.com/jax-releases/jax_cuda_releases.html --find-links https://download.pytorch.org/whl/cu118 + working-directory: ${{ github.workspace }} + run: bash ./install.sh -d -s - name: Run black run: black --check . - name: Run flake8 diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 1ccced3e..1f4b1b80 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -15,7 +15,7 @@ repos: # code format according to black - repo: https://github.com/ambv/black - rev: 23.10.1 + rev: 23.11.0 hooks: - id: black diff --git a/README.md b/README.md index 45d49bad..31d8ba35 100644 --- a/README.md +++ b/README.md @@ -5,26 +5,24 @@ This repository houses tools built on the GPU-accelerated simulation capabilitie * massively-parallelized simulation. ## Quickstart -Create a conda environment with Cuda 11.8 support: +Create and activate a conda environment with Cuda 11.8 support: ``` conda env create -n -f environment.yml conda activate ``` -Install the project. Note the two different options depending on whether you want to develop on the repo or not. -``` -# OPTION 1: NON-DEVELOPERS -pip install . --default-timeout=100 future --find-links https://storage.googleapis.com/jax-releases/jax_cuda_releases.html --find-links https://download.pytorch.org/whl/cu118 -# OPTION 2: DEVELOPERS -pip install -e .[all] --default-timeout=100 future --find-links https://storage.googleapis.com/jax-releases/jax_cuda_releases.html --find-links https://download.pytorch.org/whl/cu118 -``` -For developers, install pre-commit hooks by running the following in the repo root: +Installation of this package is done via a `bash` script. There are two flags for configuring the installation: +* `-d` controls whether to use the heavier _development_ dependencies, which include linting and testing dependencies; +* `-s` controls whether to install the most recent `mujoco` installation from source. We recommend doing this, since the development version usually has important fixes. + +For non-developers: ``` -pre-commit autoupdate -pre-commit install +./install.sh -s ``` -To install the latest and greatest version of `mujoco` from source, ensure that your system has the right build dependencies: + +For developers: ``` +# important dependencies for building mujoco from source sudo apt-get update -y sudo apt-get install -y \ libgl1-mesa-dev \ @@ -33,12 +31,11 @@ sudo apt-get install -y \ libxrandr-dev \ libxi-dev \ ninja-build + +# install mujoco from source with development options +./install.sh -s -d ``` -Then, run the installation `bash` script, which will update `mujoco` to the latest version built from source: -``` -sudo chmod +x install.sh -./install.sh -``` + If the following line of code runs without error, then the installation was successful: ``` python -c "import mujoco" diff --git a/install.sh b/install.sh index aad0a8b9..592a77b6 100755 --- a/install.sh +++ b/install.sh @@ -1,43 +1,69 @@ #!/bin/bash -# instructions are taken from two places: +# instructions for installing from source are taken from two places: # (1) https://mujoco.readthedocs.io/en/latest/programming/#building-from-source # (2) https://mujoco.readthedocs.io/en/latest/python.html#building-from-source set -e -# Check if CMake and a compiler are installed -if ! command -v cmake &> /dev/null; then - echo "CMake is not installed. Please install CMake before proceeding." - exit 1 -fi - -if ! command -v g++ &> /dev/null; then - echo "C++ compiler is not available. Please install a C++ compiler before proceeding." - exit 1 -fi +dev=false +source=false +while getopts ds flag +do + case "${flag}" in + d) dev=true;; + s) source=true;; + esac +done -# Clone the Mujoco repo to the directory above where this script is located -# If it exists already, then just git pull new changes -script_dir="$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd)" -mujoco_dir="$script_dir/../mujoco" -if [ -d "$mujoco_dir" ]; then - echo "Mujoco exists already - running git pull to update it!" - (cd "$mujoco_dir" && git pull origin main) +# Install regular or development dependencies +if [ "$dev" = true ] ; then + echo "[NOTE] Installing development dependencies..." + pip install --upgrade --upgrade-strategy eager -e .[all] --find-links https://storage.googleapis.com/jax-releases/jax_cuda_releases.html --find-links https://download.pytorch.org/whl/cu118 + pre-commit autoupdate + pre-commit install else - git clone https://github.com/google-deepmind/mujoco.git "$mujoco_dir" + echo "[NOTE] Installing non-developer dependencies..." + pip install --upgrade --upgrade-strategy -e . --default-timeout=100 future --find-links https://storage.googleapis.com/jax-releases/jax_cuda_releases.html --find-links https://download.pytorch.org/whl/cu118 fi -# Configure and build -cd "$mujoco_dir" -cmake . -cmake --build . +# Checking whether to install mujoco from source +if [[ "$source" = true ]] ; then + echo -e "\n[NOTE] Installing mujoco from source..." + + # Check if CMake and a compiler are installed + if ! command -v cmake &> /dev/null; then + echo "CMake is not installed. Please install CMake before proceeding." + exit 1 + fi -# Install Mujoco -cmake . -DCMAKE_INSTALL_PREFIX="./mujoco_install" -cmake --install . + if ! command -v g++ &> /dev/null; then + echo "C++ compiler is not available. Please install a C++ compiler before proceeding." + exit 1 + fi -# Generate source distribution required for Python bindings -cd "$mujoco_dir/python" -./make_sdist.sh -tar_path=$(find "$mujoco_dir/python/dist" -name 'mujoco-*.tar.gz' 2>/dev/null) -MUJOCO_PATH="$mujoco_dir/mujoco_install" MUJOCO_PLUGIN_PATH="$mujoco_dir/plugin" pip install "$tar_path" + # Clone the Mujoco repo to the directory above where this script is located + # If it exists already, then just git pull new changes + script_dir="$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd)" + mujoco_dir="$script_dir/../mujoco" + if [ -d "$mujoco_dir" ]; then + echo "Mujoco exists already - running git pull to update it!" + (cd "$mujoco_dir" && git pull origin main) + else + git clone https://github.com/google-deepmind/mujoco.git "$mujoco_dir" + fi + + # Configure and build + cd "$mujoco_dir" + cmake . + cmake --build . + + # Install Mujoco + cmake . -DCMAKE_INSTALL_PREFIX="./mujoco_install" + cmake --install . + + # Generate source distribution required for Python bindings + cd "$mujoco_dir/python" + ./make_sdist.sh + tar_path=$(find "$mujoco_dir/python/dist" -name 'mujoco-*.tar.gz' 2>/dev/null) + MUJOCO_PATH="$mujoco_dir/mujoco_install" MUJOCO_PLUGIN_PATH="$mujoco_dir/plugin" pip install "$tar_path" +fi From 18d2ccf99c001871a42acc7d55114ef763b1ac1a Mon Sep 17 00:00:00 2001 From: alberthli Date: Thu, 9 Nov 2023 22:57:21 -0800 Subject: [PATCH 10/79] add apt dependencies to CI workflow + minor README update --- .github/workflows/code_checks.yml | 12 +++++++++++- README.md | 6 +++--- 2 files changed, 14 insertions(+), 4 deletions(-) diff --git a/.github/workflows/code_checks.yml b/.github/workflows/code_checks.yml index e8495cc5..5233b7e8 100644 --- a/.github/workflows/code_checks.yml +++ b/.github/workflows/code_checks.yml @@ -27,7 +27,17 @@ jobs: ${{ runner.os }}-pip- - name: Install dependencies working-directory: ${{ github.workspace }} - run: bash ./install.sh -d -s + run: | + sudo apt-get update -y + sudo apt-get install -y \ + libgl1-mesa-dev \ + libxinerama-dev \ + libxcursor-dev \ + libxrandr-dev \ + libxi-dev \ + ninja-build + python -m pip install --upgrade pip + bash ./install.sh -d -s - name: Run black run: black --check . - name: Run flake8 diff --git a/README.md b/README.md index 31d8ba35..a7554b39 100644 --- a/README.md +++ b/README.md @@ -4,8 +4,8 @@ This repository houses tools built on the GPU-accelerated simulation capabilitie * shared interfaces for control architectures, and * massively-parallelized simulation. -## Quickstart -Create and activate a conda environment with Cuda 11.8 support: +## Installation +Clone this repository and run the following commands in the repository root to create and activate a conda environment with Cuda 11.8 support: ``` conda env create -n -f environment.yml conda activate @@ -36,7 +36,7 @@ sudo apt-get install -y \ ./install.sh -s -d ``` -If the following line of code runs without error, then the installation was successful: +If the following line of code runs without error, then the installation of `mujoco` from source was successful: ``` python -c "import mujoco" ``` From a91b10da30f0bdad59d56705e365ab61bc3d2918 Mon Sep 17 00:00:00 2001 From: alberthli Date: Thu, 9 Nov 2023 23:13:09 -0800 Subject: [PATCH 11/79] edit workflow to add conda environment --- .github/workflows/code_checks.yml | 14 ++++++++++---- README.md | 4 ++-- 2 files changed, 12 insertions(+), 6 deletions(-) diff --git a/.github/workflows/code_checks.yml b/.github/workflows/code_checks.yml index 5233b7e8..b3e748f0 100644 --- a/.github/workflows/code_checks.yml +++ b/.github/workflows/code_checks.yml @@ -14,11 +14,17 @@ jobs: runs-on: ubuntu-latest steps: - - uses: actions/checkout@v4 - - name: Set up Python 3.11.5 - uses: actions/setup-python@v4 + - uses: conda-incubator/setup-miniconda@v2 with: - python-version: '3.11.5' + miniconda-version: "latest" + channels: conda-forge, defaults + use-only-tar-bz2: true + auto-update-conda: true + auto-activate-base: true + activate-environment: ambersim + python-version: 3.11 + environment-file: ${{ github.workspace }}/environment.yml + - uses: actions/checkout@v4 - uses: actions/cache@v3 with: path: ~/.cache/pip diff --git a/README.md b/README.md index a7554b39..6880ad30 100644 --- a/README.md +++ b/README.md @@ -13,7 +13,7 @@ conda activate Installation of this package is done via a `bash` script. There are two flags for configuring the installation: * `-d` controls whether to use the heavier _development_ dependencies, which include linting and testing dependencies; -* `-s` controls whether to install the most recent `mujoco` installation from source. We recommend doing this, since the development version usually has important fixes. +* `-s` controls whether to install the most recent `mujoco` version from source. We recommend doing this, since the development version usually has important bugfixes. For non-developers: ``` @@ -57,7 +57,7 @@ Python dependencies are specified using a `pyproject.toml` file. Non-python depe Major versioning decisions: * `python=3.11.5`. `torch`, `jax`, and `mujoco` all support it and there are major reported speed improvements over `python` 3.10. -* `cuda==11.8`. Both `torch` and `jax` support `cuda12`; however, they annoyingly support different minor versions which makes them incompatible in the same environment [https://github.com/google/jax/issues/18032](#18032). Once this is resolved, we will upgrade to `cuda-12.2` or later. It seems most likely that `torch` will support `cuda-12.3` once they do upgrade, since that is the most recent release. +* `cuda==11.8`. Both `torch` and `jax` support `cuda12`; however, they annoyingly support different minor versions which makes them [incompatible in the same environment](https://github.com/google/jax/issues/18032). Once this is resolved, we will upgrade to `cuda-12.2` or later. It seems most likely that `torch` will support `cuda-12.3` once they do upgrade, since that is the most recent release. ### Tooling We use various tools to ensure code quality. From 59d24e8d1abd1411efe4cfc742e3f656e3139715 Mon Sep 17 00:00:00 2001 From: alberthli Date: Thu, 9 Nov 2023 23:15:06 -0800 Subject: [PATCH 12/79] try changing a path in the workflow --- .github/workflows/code_checks.yml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/code_checks.yml b/.github/workflows/code_checks.yml index b3e748f0..ea17761d 100644 --- a/.github/workflows/code_checks.yml +++ b/.github/workflows/code_checks.yml @@ -23,7 +23,7 @@ jobs: auto-activate-base: true activate-environment: ambersim python-version: 3.11 - environment-file: ${{ github.workspace }}/environment.yml + environment-file: ${{ github.workspace }}/../environment.yml - uses: actions/checkout@v4 - uses: actions/cache@v3 with: @@ -32,7 +32,7 @@ jobs: restore-keys: | ${{ runner.os }}-pip- - name: Install dependencies - working-directory: ${{ github.workspace }} + working-directory: ${{ github.workspace }}/.. run: | sudo apt-get update -y sudo apt-get install -y \ From b85fb9cb1920f652e156a0bcb7f4f541e6d20365 Mon Sep 17 00:00:00 2001 From: alberthli Date: Thu, 9 Nov 2023 23:16:33 -0800 Subject: [PATCH 13/79] I have no idea how paths work in github workflows... --- .github/workflows/code_checks.yml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/code_checks.yml b/.github/workflows/code_checks.yml index ea17761d..86e5b791 100644 --- a/.github/workflows/code_checks.yml +++ b/.github/workflows/code_checks.yml @@ -23,7 +23,7 @@ jobs: auto-activate-base: true activate-environment: ambersim python-version: 3.11 - environment-file: ${{ github.workspace }}/../environment.yml + environment-file: environment.yml - uses: actions/checkout@v4 - uses: actions/cache@v3 with: @@ -32,7 +32,7 @@ jobs: restore-keys: | ${{ runner.os }}-pip- - name: Install dependencies - working-directory: ${{ github.workspace }}/.. + working-directory: ${{ github.workspace }} run: | sudo apt-get update -y sudo apt-get install -y \ From 4d84eeb1f75f9f9fe8a0d2fbfcc8fdace84194b5 Mon Sep 17 00:00:00 2001 From: alberthli Date: Thu, 9 Nov 2023 23:21:07 -0800 Subject: [PATCH 14/79] change order of steps in workflow --- .github/workflows/code_checks.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/code_checks.yml b/.github/workflows/code_checks.yml index 86e5b791..d7b7f071 100644 --- a/.github/workflows/code_checks.yml +++ b/.github/workflows/code_checks.yml @@ -14,6 +14,7 @@ jobs: runs-on: ubuntu-latest steps: + - uses: actions/checkout@v4 - uses: conda-incubator/setup-miniconda@v2 with: miniconda-version: "latest" @@ -24,7 +25,6 @@ jobs: activate-environment: ambersim python-version: 3.11 environment-file: environment.yml - - uses: actions/checkout@v4 - uses: actions/cache@v3 with: path: ~/.cache/pip From c85cfa3e0a13434a4e3a45c052b02b9d7e664909 Mon Sep 17 00:00:00 2001 From: alberthli Date: Thu, 9 Nov 2023 23:37:05 -0800 Subject: [PATCH 15/79] update CI with disk space freeing action + cache conda env --- .github/workflows/code_checks.yml | 29 ++++++++++++++++++++++++----- 1 file changed, 24 insertions(+), 5 deletions(-) diff --git a/.github/workflows/code_checks.yml b/.github/workflows/code_checks.yml index d7b7f071..d4e43690 100644 --- a/.github/workflows/code_checks.yml +++ b/.github/workflows/code_checks.yml @@ -15,14 +15,33 @@ jobs: steps: - uses: actions/checkout@v4 + - name: Free Up GitHub Actions Ubuntu Runner Disk Space 🔧 + uses: jlumbroso/free-disk-space@main + with: + # This might remove tools that are actually needed, if set to "true" but frees about 6 GB + tool-cache: true + + # All of these default to true, but feel free to set to "false" if necessary for your workflow + android: true + dotnet: true + haskell: true + large-packages: true + swap-storage: true + - name: Cache conda + uses: actions/cache@v3 + env: + CACHE_NUMBER: 0 + with: + path: ${{ env.CONDA }}/envs + key: + ${{ runner.os }}-conda-${{ env.CACHE_NUMBER }}-${{ + hashFiles('environment.yml') }} - uses: conda-incubator/setup-miniconda@v2 with: - miniconda-version: "latest" - channels: conda-forge, defaults - use-only-tar-bz2: true - auto-update-conda: true - auto-activate-base: true + miniforge-variant: Mambaforge + miniforge-version: latest activate-environment: ambersim + use-mamba: true python-version: 3.11 environment-file: environment.yml - uses: actions/cache@v3 From caa4cc3dfbb729dceb5e24083ef95fbdb197eb78 Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 00:01:46 -0800 Subject: [PATCH 16/79] add shell specification to actions so conda is activated correctly in all steps + temporarily test script --- .github/workflows/code_checks.yml | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/.github/workflows/code_checks.yml b/.github/workflows/code_checks.yml index d4e43690..a22d2ffe 100644 --- a/.github/workflows/code_checks.yml +++ b/.github/workflows/code_checks.yml @@ -42,7 +42,6 @@ jobs: miniforge-version: latest activate-environment: ambersim use-mamba: true - python-version: 3.11 environment-file: environment.yml - uses: actions/cache@v3 with: @@ -52,6 +51,7 @@ jobs: ${{ runner.os }}-pip- - name: Install dependencies working-directory: ${{ github.workspace }} + shell: bash -l {0} run: | sudo apt-get update -y sudo apt-get install -y \ @@ -64,14 +64,18 @@ jobs: python -m pip install --upgrade pip bash ./install.sh -d -s - name: Run black + shell: bash -l {0} run: black --check . - name: Run flake8 + shell: bash -l {0} run: | # stop the build if there are Python syntax errors or undefined names flake8 . --count --select=E9,F63,F7,F82 --show-source --statistics - name: Run pyright + shell: bash -l {0} run: | pyright - name: Test with pytest + shell: bash -l {0} run: | pytest \ No newline at end of file From 313089977bf307ba8049b212b5af9fe51c3253cd Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 00:35:11 -0800 Subject: [PATCH 17/79] check workflow caching + add more processors to cmake commands --- install.sh | 1 + 1 file changed, 1 insertion(+) diff --git a/install.sh b/install.sh index 592a77b6..a3f445d2 100755 --- a/install.sh +++ b/install.sh @@ -53,6 +53,7 @@ if [[ "$source" = true ]] ; then fi # Configure and build + export MAKEFLAGS="-j$(nproc)" # allow the max number of processors when building cd "$mujoco_dir" cmake . cmake --build . From 397f42ce496a86fe84fe6310ed5f1d887408cf87 Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 00:36:55 -0800 Subject: [PATCH 18/79] remove less space from test system to reduce workflow runtime --- .github/workflows/code_checks.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/code_checks.yml b/.github/workflows/code_checks.yml index a22d2ffe..cc6262a8 100644 --- a/.github/workflows/code_checks.yml +++ b/.github/workflows/code_checks.yml @@ -19,7 +19,7 @@ jobs: uses: jlumbroso/free-disk-space@main with: # This might remove tools that are actually needed, if set to "true" but frees about 6 GB - tool-cache: true + tool-cache: false # All of these default to true, but feel free to set to "false" if necessary for your workflow android: true From 051551ba581d31305dd1ad69f402cd92c4e87d7b Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 10:30:20 -0800 Subject: [PATCH 19/79] update workflow config to only run when PRs are marked 'ready for review' + update README with more guidelines --- .github/workflows/code_checks.yml | 1 + README.md | 1 + 2 files changed, 2 insertions(+) diff --git a/.github/workflows/code_checks.yml b/.github/workflows/code_checks.yml index cc6262a8..e9e6c773 100644 --- a/.github/workflows/code_checks.yml +++ b/.github/workflows/code_checks.yml @@ -4,6 +4,7 @@ on: push: branches: [main] pull_request: + types: [ready_for_review] branches: [main] permissions: diff --git a/README.md b/README.md index 6880ad30..6b3efbd5 100644 --- a/README.md +++ b/README.md @@ -46,6 +46,7 @@ python -c "import mujoco" ### Abridged Dev Guidelines Development on this code will be controlled via code review. To facilitate this, please follow these guidelines: * keep your pull requests small so that it's practical to human review them; +* try to create _draft pull requests_ instead of regular ones and request reviews from relevant people only when ready - our CI runs only when a pull request is marked "ready for review," so this saves a lot of unnecessary CI runs; * write tests as you go (and if you are reviewing, suggest missing tests); * write docstrings for public classes and methods, even if it's just a one-liner; * before committing, make sure you locally pass all tests by running `pytest` in the repo root; From 3c771654398dbb40f729c2962695b4aa7218e9a8 Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 11:00:45 -0800 Subject: [PATCH 20/79] updated to allow newton solver to be default if mujoco version is greater than 3.0.0 --- ambersim/utils/io_utils.py | 34 +++++++++++++++++++++++++--------- 1 file changed, 25 insertions(+), 9 deletions(-) diff --git a/ambersim/utils/io_utils.py b/ambersim/utils/io_utils.py index 38cef0cc..2f045ac9 100644 --- a/ambersim/utils/io_utils.py +++ b/ambersim/utils/io_utils.py @@ -7,6 +7,7 @@ import trimesh from dm_control import mjcf from mujoco import mjx +from packaging import version from ambersim import ROOT from ambersim.utils._internal_utils import _check_filepath @@ -35,7 +36,7 @@ def _modify_robot_float_base(filepath: Union[str, Path]) -> mj.MjModel: def load_mj_model_from_file( filepath: Union[str, Path], force_float: bool = False, - solver: Union[str, mj.mjtSolver] = mj.mjtSolver.mjSOL_CG, + solver: Optional[Union[str, mj.mjtSolver]] = None, iterations: Optional[int] = None, ls_iterations: Optional[int] = None, ) -> mj.MjModel: @@ -51,14 +52,29 @@ def load_mj_model_from_file( Returns: mj_model: A mujoco model. """ - # TODO(ahl): once we allow installing mujoco from source, update this to allow the Newton solver + update default - if isinstance(solver, str): - if solver.lower() == "cg": - solver = mj.mjtSolver.SOL_CG - else: - raise ValueError("Solver must be one of: ['cg']!") - elif isinstance(solver, mj.mjtSolver): - assert solver in [mj.mjtSolver.mjSOL_CG] + # allow different solver specifications depending on mujoco version + if version.parse(mj.__version__) < version.parse("3.0.1"): + if solver is None: + solver = mj.mjtSolver.mjSOL_CG + elif isinstance(solver, str): + if solver.lower() == "cg": + solver = mj.mjtSolver.mjSOL_CG + else: + raise ValueError("Solver must be one of: ['cg']!") + elif isinstance(solver, mj.mjtSolver): + assert solver in [mj.mjtSolver.mjSOL_CG] + else: + if solver is None: + solver = mj.mjtSolver.mjSOL_NEWTON + elif isinstance(solver, str): + if solver.lower() == "newton": + solver = mj.mjtSolver.mjSOL_NEWTON + elif solver.lower() == "cg": + solver = mj.mjtSolver.mjSOL_CG + else: + raise ValueError("Solver must be one of: ['cg', 'newton']!") + elif isinstance(solver, mj.mjtSolver): + assert solver in [mj.mjtSolver.mjSOL_CG, mj.mjtSolver.mjSOL_NEWTON] filepath = _check_filepath(filepath) From 422d51ecbf0843991a257599e8571dbff6f4fc33 Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 11:01:59 -0800 Subject: [PATCH 21/79] bugfix: install mjx from source in addition to mujoco --- install.sh | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/install.sh b/install.sh index a3f445d2..5c153c04 100755 --- a/install.sh +++ b/install.sh @@ -66,5 +66,9 @@ if [[ "$source" = true ]] ; then cd "$mujoco_dir/python" ./make_sdist.sh tar_path=$(find "$mujoco_dir/python/dist" -name 'mujoco-*.tar.gz' 2>/dev/null) + + # Installing mujoco and mjx from source MUJOCO_PATH="$mujoco_dir/mujoco_install" MUJOCO_PLUGIN_PATH="$mujoco_dir/plugin" pip install "$tar_path" + cd "$mujoco_dir/mjx" + pip install . fi From 2bd687511e015d83df4c542667bdf725024b3f58 Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 11:06:08 -0800 Subject: [PATCH 22/79] minor update to README --- README.md | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index 6b3efbd5..ec294bc1 100644 --- a/README.md +++ b/README.md @@ -38,7 +38,12 @@ sudo apt-get install -y \ If the following line of code runs without error, then the installation of `mujoco` from source was successful: ``` -python -c "import mujoco" +python -c "import mujoco; from mujoco import mjx" +``` +Further, you can examine the latest minor version using `pip`: +``` +pip show mujoco +pip show mujoco-mjx ``` ## Development Details From e51ef10c91de67b64474d76d021166ba37886aed Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 13:20:23 -0800 Subject: [PATCH 23/79] split up installation script into two: one specifically for installing mujoco from source --- install.sh | 44 +---------------------- install_mj_source.sh | 86 ++++++++++++++++++++++++++++++++++++++++++++ 2 files changed, 87 insertions(+), 43 deletions(-) create mode 100755 install_mj_source.sh diff --git a/install.sh b/install.sh index 5c153c04..c297f336 100755 --- a/install.sh +++ b/install.sh @@ -28,47 +28,5 @@ fi # Checking whether to install mujoco from source if [[ "$source" = true ]] ; then - echo -e "\n[NOTE] Installing mujoco from source..." - - # Check if CMake and a compiler are installed - if ! command -v cmake &> /dev/null; then - echo "CMake is not installed. Please install CMake before proceeding." - exit 1 - fi - - if ! command -v g++ &> /dev/null; then - echo "C++ compiler is not available. Please install a C++ compiler before proceeding." - exit 1 - fi - - # Clone the Mujoco repo to the directory above where this script is located - # If it exists already, then just git pull new changes - script_dir="$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd)" - mujoco_dir="$script_dir/../mujoco" - if [ -d "$mujoco_dir" ]; then - echo "Mujoco exists already - running git pull to update it!" - (cd "$mujoco_dir" && git pull origin main) - else - git clone https://github.com/google-deepmind/mujoco.git "$mujoco_dir" - fi - - # Configure and build - export MAKEFLAGS="-j$(nproc)" # allow the max number of processors when building - cd "$mujoco_dir" - cmake . - cmake --build . - - # Install Mujoco - cmake . -DCMAKE_INSTALL_PREFIX="./mujoco_install" - cmake --install . - - # Generate source distribution required for Python bindings - cd "$mujoco_dir/python" - ./make_sdist.sh - tar_path=$(find "$mujoco_dir/python/dist" -name 'mujoco-*.tar.gz' 2>/dev/null) - - # Installing mujoco and mjx from source - MUJOCO_PATH="$mujoco_dir/mujoco_install" MUJOCO_PLUGIN_PATH="$mujoco_dir/plugin" pip install "$tar_path" - cd "$mujoco_dir/mjx" - pip install . + bash install_mj_source.sh fi diff --git a/install_mj_source.sh b/install_mj_source.sh new file mode 100755 index 00000000..8250ae15 --- /dev/null +++ b/install_mj_source.sh @@ -0,0 +1,86 @@ +#!/bin/bash +echo -e "\n[NOTE] Installing mujoco from source..." + +# the script directory and mujoco directory +script_dir="$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd)" +mujoco_dir="$script_dir/../mujoco" + +# check whether we already have the most recent release cached to save build time +LATEST_GIT_HASH=$(git ls-remote https://github.com/google-deepmind/mujoco HEAD | awk '{ print $1}') +if [ -d "$mujoco_dir/python/dist" ]; then + tar_path=$(find "$mujoco_dir/python/dist" -name "mujoco-*${LATEST_GIT_HASH}.tar.gz" 2>/dev/null) + whl_path=$(find "$mujoco_dir/python/dist" -name "mujoco-*.whl" 2>/dev/null) + if [ -f "$tar_path" ]; then + echo -e "[NOTE] Found cached mujoco tar.gz file..." + # if wheel exists, install from wheel + if [ -f "$whl_path" ]; then + echo -e "[NOTE] Wheel found! Installing from wheel..." + cd "$mujoco_dir/python/dist" + + # [Nov 10, 2023] we install with --no-deps because this would upgrade numpy to a version incompatible with cmeel-boost 1.82.0 + MUJOCO_PATH="$mujoco_dir/mujoco_install" MUJOCO_PLUGIN_PATH="$mujoco_dir/plugin" pip install --no-deps --force-reinstall "$whl_path" + cd "$mujoco_dir/mjx" + pip install --no-deps --force-reinstall . + exit 0 + else + echo -e "[NOTE] No wheel found! Building it and installing..." + cd "$mujoco_dir/python/dist" + MUJOCO_PATH="$mujoco_dir/mujoco_install" MUJOCO_PLUGIN_PATH="$mujoco_dir/plugin" pip wheel -w $(dirname "whl_path") "$tar_path" + + # [Nov 10, 2023] we install with --no-deps because this would upgrade numpy to a version incompatible with cmeel-boost 1.82.0 + MUJOCO_PATH="$mujoco_dir/mujoco_install" MUJOCO_PLUGIN_PATH="$mujoco_dir/plugin" pip install --no-deps --force-reinstall "$whl_path" + cd "$mujoco_dir/mjx" + pip install --no-deps --force-reinstall . + exit 0 + fi + fi +fi + +# Check if CMake and a compiler are installed +if ! command -v cmake &> /dev/null; then + echo "CMake is not installed. Please install CMake before proceeding." + exit 1 +fi + +if ! command -v g++ &> /dev/null; then + echo "C++ compiler is not available. Please install a C++ compiler before proceeding." + exit 1 +fi + +# Clone the Mujoco repo to the directory above where this script is located +# If it exists already, then just git pull new changes +if [ -d "$mujoco_dir" ]; then + echo "Mujoco exists already - running git pull to update it!" + (cd "$mujoco_dir" && git pull origin main) +else + git clone https://github.com/google-deepmind/mujoco.git "$mujoco_dir" +fi + +# Configure and build +export MAKEFLAGS="-j$(nproc)" # allow the max number of processors when building +cd "$mujoco_dir" +SAVED_GIT_HASH=$(git rev-parse HEAD) # getting the git hash +cmake . +cmake --build . + +# Install Mujoco +cmake . -DCMAKE_INSTALL_PREFIX="./mujoco_install" +cmake --install . + +# Generate source distribution required for Python bindings +cd "$mujoco_dir/python" +./make_sdist.sh +tar_path=$(find "$mujoco_dir/python/dist" -name 'mujoco-*.tar.gz' 2>/dev/null) + +# Renaming the tar file to append the commit hash +old_name=$(basename "$tar_path") +old_prefix="${old_name%%.tar.gz}" +new_prefix="${old_prefix}-${SAVED_GIT_HASH}" +new_name="${new_prefix}.tar.gz" +new_tar_path="$(dirname "$tar_path")/$new_name" +mv "$tar_path" "$new_tar_path" # renames the tar file to have the git hash in it + +# Installing mujoco and mjx from source +MUJOCO_PATH="$mujoco_dir/mujoco_install" MUJOCO_PLUGIN_PATH="$mujoco_dir/plugin" pip install --upgrade "$new_tar_path" +cd "$mujoco_dir/mjx" +pip install --upgrade . \ No newline at end of file From bed2d1d4a51f26df2a87dd764df84ae385619329 Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 13:40:38 -0800 Subject: [PATCH 24/79] first stab at saving out a built wheel as an artifact --- .github/workflows/mujoco_nightly.yml | 48 ++++++++++++++++++++++++++++ 1 file changed, 48 insertions(+) create mode 100644 .github/workflows/mujoco_nightly.yml diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml new file mode 100644 index 00000000..b5bddf44 --- /dev/null +++ b/.github/workflows/mujoco_nightly.yml @@ -0,0 +1,48 @@ +name: Build Nightly MuJoCo Release + +on: + schedule: + - cron: "0 5 * * *" # runs at 5AM every day + +jobs: + build-and-package: + runs-on: ubuntu-latest + + steps: + - name: Checkout code + uses: actions/checkout@v4 + - name: Free Up GitHub Actions Ubuntu Runner Disk Space 🔧 + uses: jlumbroso/free-disk-space@main + with: + # This might remove tools that are actually needed, if set to "true" but frees about 6 GB + tool-cache: false + + # All of these default to true, but feel free to set to "false" if necessary for your workflow + android: true + dotnet: true + haskell: true + large-packages: true + swap-storage: true + - uses: conda-incubator/setup-miniconda@v2 + with: + miniforge-variant: Mambaforge + miniforge-version: latest + activate-environment: ambersim + use-mamba: true + environment-file: environment.yml + - name: Create and Store Wheel + shell: bash -l {0} + run: | + # Installs mujoco from source + run ./install_mj_source.sh + + # Store the package as an artifact + # the below path is known from the mujoco installation script + whl_path=$(find $PWD/../mujoco/python/dist -name "mujoco-*.whl") + echo "::set-output name=file_path::$whl_path" + id: package + - name: Upload artifact + uses: actions/upload-artifact@v2 + with: + name: ${{ steps.package.outputs.file_path }} + path: ${{ steps.package.outputs.file_path }} \ No newline at end of file From e7910b72cc6fe960f47842ce29bfc2014faeaad3 Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 13:50:36 -0800 Subject: [PATCH 25/79] add workflow_dispatch to allow manually triggering the workflow --- .github/workflows/mujoco_nightly.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml index b5bddf44..ead45488 100644 --- a/.github/workflows/mujoco_nightly.yml +++ b/.github/workflows/mujoco_nightly.yml @@ -3,6 +3,7 @@ name: Build Nightly MuJoCo Release on: schedule: - cron: "0 5 * * *" # runs at 5AM every day + workflow_dispatch: jobs: build-and-package: From e44fab96e5b72a5c227bc9660f88d9a6e932bf81 Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 13:53:28 -0800 Subject: [PATCH 26/79] add input for specifying branch --- .github/workflows/mujoco_nightly.yml | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml index ead45488..7416b546 100644 --- a/.github/workflows/mujoco_nightly.yml +++ b/.github/workflows/mujoco_nightly.yml @@ -4,7 +4,11 @@ on: schedule: - cron: "0 5 * * *" # runs at 5AM every day workflow_dispatch: - + inputs: + branch: + description: 'The branch to run the workflow on' + required: true + default: '' jobs: build-and-package: runs-on: ubuntu-latest From 0d1352436b24f5aa5ed9792ea885f410ba6112be Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 13:55:41 -0800 Subject: [PATCH 27/79] change to ready_for_review --- .github/workflows/mujoco_nightly.yml | 10 ++++------ 1 file changed, 4 insertions(+), 6 deletions(-) diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml index 7416b546..edc722eb 100644 --- a/.github/workflows/mujoco_nightly.yml +++ b/.github/workflows/mujoco_nightly.yml @@ -3,12 +3,10 @@ name: Build Nightly MuJoCo Release on: schedule: - cron: "0 5 * * *" # runs at 5AM every day - workflow_dispatch: - inputs: - branch: - description: 'The branch to run the workflow on' - required: true - default: '' + pull_request: + types: [ready_for_review] + branches: [main] + jobs: build-and-package: runs-on: ubuntu-latest From 4334596155c12168ac64a26751eb7443a81a72cd Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 14:56:11 -0800 Subject: [PATCH 28/79] fix run command --- .github/workflows/mujoco_nightly.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml index edc722eb..ff857da5 100644 --- a/.github/workflows/mujoco_nightly.yml +++ b/.github/workflows/mujoco_nightly.yml @@ -37,7 +37,7 @@ jobs: shell: bash -l {0} run: | # Installs mujoco from source - run ./install_mj_source.sh + ./install_mj_source.sh # Store the package as an artifact # the below path is known from the mujoco installation script From 5c1125224ee08d9f99de173ac2489a9cdd8768d9 Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 15:26:22 -0800 Subject: [PATCH 29/79] minor updates to workflow and mj source script to hopefully resolve install errors in workflow --- .github/workflows/mujoco_nightly.yml | 18 ++++++++++++++++++ install_mj_source.sh | 6 ++++-- 2 files changed, 22 insertions(+), 2 deletions(-) diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml index ff857da5..b869fb53 100644 --- a/.github/workflows/mujoco_nightly.yml +++ b/.github/workflows/mujoco_nightly.yml @@ -26,6 +26,15 @@ jobs: haskell: true large-packages: true swap-storage: true + - name: Cache conda + uses: actions/cache@v3 + env: + CACHE_NUMBER: 0 + with: + path: ${{ env.CONDA }}/envs + key: + ${{ runner.os }}-conda-${{ env.CACHE_NUMBER }}-${{ + hashFiles('environment.yml') }} - uses: conda-incubator/setup-miniconda@v2 with: miniforge-variant: Mambaforge @@ -37,6 +46,15 @@ jobs: shell: bash -l {0} run: | # Installs mujoco from source + sudo apt-get update -y + sudo apt-get install -y \ + libgl1-mesa-dev \ + libxinerama-dev \ + libxcursor-dev \ + libxrandr-dev \ + libxi-dev \ + ninja-build + python -m pip install --upgrade pip ./install_mj_source.sh # Store the package as an artifact diff --git a/install_mj_source.sh b/install_mj_source.sh index 8250ae15..63e07950 100755 --- a/install_mj_source.sh +++ b/install_mj_source.sh @@ -71,6 +71,7 @@ cmake --install . cd "$mujoco_dir/python" ./make_sdist.sh tar_path=$(find "$mujoco_dir/python/dist" -name 'mujoco-*.tar.gz' 2>/dev/null) +whl_path=$(find "$mujoco_dir/python/dist" -name "mujoco-*.whl" 2>/dev/null) # Renaming the tar file to append the commit hash old_name=$(basename "$tar_path") @@ -81,6 +82,7 @@ new_tar_path="$(dirname "$tar_path")/$new_name" mv "$tar_path" "$new_tar_path" # renames the tar file to have the git hash in it # Installing mujoco and mjx from source -MUJOCO_PATH="$mujoco_dir/mujoco_install" MUJOCO_PLUGIN_PATH="$mujoco_dir/plugin" pip install --upgrade "$new_tar_path" +MUJOCO_PATH="$mujoco_dir/mujoco_install" MUJOCO_PLUGIN_PATH="$mujoco_dir/plugin" pip wheel -w $(dirname "whl_path") "$tar_path" +MUJOCO_PATH="$mujoco_dir/mujoco_install" MUJOCO_PLUGIN_PATH="$mujoco_dir/plugin" pip install --no-deps --force-reinstall "$whl_path" cd "$mujoco_dir/mjx" -pip install --upgrade . \ No newline at end of file +pip install --no-deps --force-reinstall . \ No newline at end of file From 8cb731175ede35c67fdae55c0c8b20e6e59be926 Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 15:58:05 -0800 Subject: [PATCH 30/79] fixed minor bug with tar/wheel path --- .github/workflows/mujoco_nightly.yml | 8 ++++---- install_mj_source.sh | 8 +++++--- 2 files changed, 9 insertions(+), 7 deletions(-) diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml index b869fb53..fd2de483 100644 --- a/.github/workflows/mujoco_nightly.yml +++ b/.github/workflows/mujoco_nightly.yml @@ -60,10 +60,10 @@ jobs: # Store the package as an artifact # the below path is known from the mujoco installation script whl_path=$(find $PWD/../mujoco/python/dist -name "mujoco-*.whl") - echo "::set-output name=file_path::$whl_path" + echo "file_path={$whl_path}" >> $GITHUB_ENV id: package - name: Upload artifact - uses: actions/upload-artifact@v2 + uses: actions/upload-artifact@v3 with: - name: ${{ steps.package.outputs.file_path }} - path: ${{ steps.package.outputs.file_path }} \ No newline at end of file + name: mujoco_wheel + path: ${{ env.file_path }} \ No newline at end of file diff --git a/install_mj_source.sh b/install_mj_source.sh index 63e07950..09744f84 100755 --- a/install_mj_source.sh +++ b/install_mj_source.sh @@ -71,7 +71,6 @@ cmake --install . cd "$mujoco_dir/python" ./make_sdist.sh tar_path=$(find "$mujoco_dir/python/dist" -name 'mujoco-*.tar.gz' 2>/dev/null) -whl_path=$(find "$mujoco_dir/python/dist" -name "mujoco-*.whl" 2>/dev/null) # Renaming the tar file to append the commit hash old_name=$(basename "$tar_path") @@ -81,8 +80,11 @@ new_name="${new_prefix}.tar.gz" new_tar_path="$(dirname "$tar_path")/$new_name" mv "$tar_path" "$new_tar_path" # renames the tar file to have the git hash in it -# Installing mujoco and mjx from source -MUJOCO_PATH="$mujoco_dir/mujoco_install" MUJOCO_PLUGIN_PATH="$mujoco_dir/plugin" pip wheel -w $(dirname "whl_path") "$tar_path" +# manually building wheel so we can cache it +MUJOCO_PATH="$mujoco_dir/mujoco_install" MUJOCO_PLUGIN_PATH="$mujoco_dir/plugin" pip wheel -w $(dirname "new_tar_path") "$new_tar_path" + +# installing mujoco from wheel and then finally mjx +whl_path=$(find "$mujoco_dir/python/dist" -name "mujoco-*.whl" 2>/dev/null) MUJOCO_PATH="$mujoco_dir/mujoco_install" MUJOCO_PLUGIN_PATH="$mujoco_dir/plugin" pip install --no-deps --force-reinstall "$whl_path" cd "$mujoco_dir/mjx" pip install --no-deps --force-reinstall . \ No newline at end of file From c650518c263ca5c015acf8299b40ee69f959b09b Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 16:34:55 -0800 Subject: [PATCH 31/79] fixed bug where wheel wasn't saved to right directory --- .github/workflows/mujoco_nightly.yml | 3 ++- install_mj_source.sh | 1 + 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml index fd2de483..e989788d 100644 --- a/.github/workflows/mujoco_nightly.yml +++ b/.github/workflows/mujoco_nightly.yml @@ -60,9 +60,10 @@ jobs: # Store the package as an artifact # the below path is known from the mujoco installation script whl_path=$(find $PWD/../mujoco/python/dist -name "mujoco-*.whl") - echo "file_path={$whl_path}" >> $GITHUB_ENV + echo "file_path=$whl_path" >> $GITHUB_ENV id: package - name: Upload artifact + shell: bash -l {0} uses: actions/upload-artifact@v3 with: name: mujoco_wheel diff --git a/install_mj_source.sh b/install_mj_source.sh index 09744f84..c6ebdb35 100755 --- a/install_mj_source.sh +++ b/install_mj_source.sh @@ -81,6 +81,7 @@ new_tar_path="$(dirname "$tar_path")/$new_name" mv "$tar_path" "$new_tar_path" # renames the tar file to have the git hash in it # manually building wheel so we can cache it +cd "$mujoco_dir/python/dist" MUJOCO_PATH="$mujoco_dir/mujoco_install" MUJOCO_PLUGIN_PATH="$mujoco_dir/plugin" pip wheel -w $(dirname "new_tar_path") "$new_tar_path" # installing mujoco from wheel and then finally mjx From cf190f55ddad2537313a28e12e21dc27cbedc700 Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 16:38:27 -0800 Subject: [PATCH 32/79] bug in workflow preventing it from running --- .github/workflows/mujoco_nightly.yml | 1 - 1 file changed, 1 deletion(-) diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml index e989788d..5ab86d10 100644 --- a/.github/workflows/mujoco_nightly.yml +++ b/.github/workflows/mujoco_nightly.yml @@ -63,7 +63,6 @@ jobs: echo "file_path=$whl_path" >> $GITHUB_ENV id: package - name: Upload artifact - shell: bash -l {0} uses: actions/upload-artifact@v3 with: name: mujoco_wheel From 90b9e42f8debdbba0e7c3b53a38a9c71c8f820d3 Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 16:55:02 -0800 Subject: [PATCH 33/79] hopefully fixed conda env caching and artifact relative path error --- .github/workflows/mujoco_nightly.yml | 26 ++++++++++++++++++-------- 1 file changed, 18 insertions(+), 8 deletions(-) diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml index 5ab86d10..631a237e 100644 --- a/.github/workflows/mujoco_nightly.yml +++ b/.github/workflows/mujoco_nightly.yml @@ -26,6 +26,16 @@ jobs: haskell: true large-packages: true swap-storage: true + + # for caching the conda env + # see: https://github.com/conda-incubator/setup-miniconda#caching-environments + - name: Setup Mambaforge + uses: conda-incubator/setup-miniconda@v2 + with: + miniforge-variant: Mambaforge + miniforge-version: latest + activate-environment: anaconda-client-env + use-mamba: true - name: Cache conda uses: actions/cache@v3 env: @@ -35,13 +45,12 @@ jobs: key: ${{ runner.os }}-conda-${{ env.CACHE_NUMBER }}-${{ hashFiles('environment.yml') }} - - uses: conda-incubator/setup-miniconda@v2 - with: - miniforge-variant: Mambaforge - miniforge-version: latest - activate-environment: ambersim - use-mamba: true - environment-file: environment.yml + - name: Update environment + run: + mamba env update -n ambersim -f environment.yml + if: steps.cache.outputs.cache-hit != 'true' + + # mujoco build + install - name: Create and Store Wheel shell: bash -l {0} run: | @@ -60,8 +69,9 @@ jobs: # Store the package as an artifact # the below path is known from the mujoco installation script whl_path=$(find $PWD/../mujoco/python/dist -name "mujoco-*.whl") - echo "file_path=$whl_path" >> $GITHUB_ENV + echo "file_path=$(realpath $whl_path)" >> $GITHUB_ENV id: package + - name: Upload artifact uses: actions/upload-artifact@v3 with: From 8148ac911ca9af2c2af154397c1c5397c93a32c4 Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 17:16:06 -0800 Subject: [PATCH 34/79] test whether artifact is retrieved correctly for code checks --- .github/workflows/code_checks.yml | 45 +++++-------------------------- 1 file changed, 7 insertions(+), 38 deletions(-) diff --git a/.github/workflows/code_checks.yml b/.github/workflows/code_checks.yml index e9e6c773..e848f944 100644 --- a/.github/workflows/code_checks.yml +++ b/.github/workflows/code_checks.yml @@ -4,7 +4,6 @@ on: push: branches: [main] pull_request: - types: [ready_for_review] branches: [main] permissions: @@ -16,54 +15,24 @@ jobs: steps: - uses: actions/checkout@v4 - - name: Free Up GitHub Actions Ubuntu Runner Disk Space 🔧 - uses: jlumbroso/free-disk-space@main - with: - # This might remove tools that are actually needed, if set to "true" but frees about 6 GB - tool-cache: false - - # All of these default to true, but feel free to set to "false" if necessary for your workflow - android: true - dotnet: true - haskell: true - large-packages: true - swap-storage: true - - name: Cache conda - uses: actions/cache@v3 - env: - CACHE_NUMBER: 0 - with: - path: ${{ env.CONDA }}/envs - key: - ${{ runner.os }}-conda-${{ env.CACHE_NUMBER }}-${{ - hashFiles('environment.yml') }} - - uses: conda-incubator/setup-miniconda@v2 - with: - miniforge-variant: Mambaforge - miniforge-version: latest - activate-environment: ambersim - use-mamba: true - environment-file: environment.yml - uses: actions/cache@v3 with: path: ~/.cache/pip key: ${{ runner.os }}-${{ hashFiles('pyproject.toml') }} restore-keys: | ${{ runner.os }}-pip- + - name: Download Cached MuJoCo Artifact + uses: actions/download-artifact@v2 + with: + name: mujoco_wheel + path: ${{ github.workspace }} - name: Install dependencies working-directory: ${{ github.workspace }} shell: bash -l {0} run: | - sudo apt-get update -y - sudo apt-get install -y \ - libgl1-mesa-dev \ - libxinerama-dev \ - libxcursor-dev \ - libxrandr-dev \ - libxi-dev \ - ninja-build python -m pip install --upgrade pip - bash ./install.sh -d -s + bash ./install.sh -d + pip install --no-deps --force-reinstall mujoco-*.whl - name: Run black shell: bash -l {0} run: black --check . From 436288a08b4640d3ad08af237f64709827ff7eb4 Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 17:22:30 -0800 Subject: [PATCH 35/79] try to trigger test workflow --- .github/workflows/code_checks.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/workflows/code_checks.yml b/.github/workflows/code_checks.yml index e848f944..e5aa9bf9 100644 --- a/.github/workflows/code_checks.yml +++ b/.github/workflows/code_checks.yml @@ -1,5 +1,6 @@ name: Code Checks +# run on push to PRs to main on: push: branches: [main] From a14773f6c315407a400bcdff1073563e6d3f931b Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 17:27:03 -0800 Subject: [PATCH 36/79] try to fix weird bug where workflow doesn't run --- .github/workflows/code_checks.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/code_checks.yml b/.github/workflows/code_checks.yml index e5aa9bf9..58fff27e 100644 --- a/.github/workflows/code_checks.yml +++ b/.github/workflows/code_checks.yml @@ -1,10 +1,10 @@ name: Code Checks -# run on push to PRs to main on: push: branches: [main] pull_request: + types: [ready_for_review] branches: [main] permissions: From 876f9e3642f4fd794173a307ca076736b3cb24a9 Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 17:48:05 -0800 Subject: [PATCH 37/79] some changes to workflows to try to find the cached artifact correctly --- .github/workflows/code_checks.yml | 8 +++++--- .github/workflows/mujoco_nightly.yml | 6 ++---- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/.github/workflows/code_checks.yml b/.github/workflows/code_checks.yml index 58fff27e..9a2976c6 100644 --- a/.github/workflows/code_checks.yml +++ b/.github/workflows/code_checks.yml @@ -4,7 +4,6 @@ on: push: branches: [main] pull_request: - types: [ready_for_review] branches: [main] permissions: @@ -22,9 +21,12 @@ jobs: key: ${{ runner.os }}-${{ hashFiles('pyproject.toml') }} restore-keys: | ${{ runner.os }}-pip- - - name: Download Cached MuJoCo Artifact - uses: actions/download-artifact@v2 + - name: Download artifact + id: download-artifact + uses: dawidd6/action-download-artifact@v2 with: + workflow: mujoco_nightly.yml + workflow_conclusion: success name: mujoco_wheel path: ${{ github.workspace }} - name: Install dependencies diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml index 631a237e..1ee5608c 100644 --- a/.github/workflows/mujoco_nightly.yml +++ b/.github/workflows/mujoco_nightly.yml @@ -3,9 +3,6 @@ name: Build Nightly MuJoCo Release on: schedule: - cron: "0 5 * * *" # runs at 5AM every day - pull_request: - types: [ready_for_review] - branches: [main] jobs: build-and-package: @@ -76,4 +73,5 @@ jobs: uses: actions/upload-artifact@v3 with: name: mujoco_wheel - path: ${{ env.file_path }} \ No newline at end of file + path: ${{ env.file_path }} + retention-days: 7 \ No newline at end of file From 1cbf7b91641f5a1857fa556a6a862d98b96a2793 Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 17:58:33 -0800 Subject: [PATCH 38/79] bugfix: forgot to cache mjx wheel as well --- .github/workflows/code_checks.yml | 10 +++++++++- .github/workflows/mujoco_nightly.yml | 20 ++++++++++++++++---- install_mj_source.sh | 1 + 3 files changed, 26 insertions(+), 5 deletions(-) diff --git a/.github/workflows/code_checks.yml b/.github/workflows/code_checks.yml index 9a2976c6..3d2e00a0 100644 --- a/.github/workflows/code_checks.yml +++ b/.github/workflows/code_checks.yml @@ -21,7 +21,7 @@ jobs: key: ${{ runner.os }}-${{ hashFiles('pyproject.toml') }} restore-keys: | ${{ runner.os }}-pip- - - name: Download artifact + - name: Download mujoco artifact id: download-artifact uses: dawidd6/action-download-artifact@v2 with: @@ -29,6 +29,14 @@ jobs: workflow_conclusion: success name: mujoco_wheel path: ${{ github.workspace }} + - name: Download mjx artifact + id: download-artifact + uses: dawidd6/action-download-artifact@v2 + with: + workflow: mujoco_nightly.yml + workflow_conclusion: success + name: mjx_wheel + path: ${{ github.workspace }} - name: Install dependencies working-directory: ${{ github.workspace }} shell: bash -l {0} diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml index 1ee5608c..a3ee4050 100644 --- a/.github/workflows/mujoco_nightly.yml +++ b/.github/workflows/mujoco_nightly.yml @@ -3,6 +3,9 @@ name: Build Nightly MuJoCo Release on: schedule: - cron: "0 5 * * *" # runs at 5AM every day + push: + pull_request: + branches: [main] jobs: build-and-package: @@ -65,13 +68,22 @@ jobs: # Store the package as an artifact # the below path is known from the mujoco installation script - whl_path=$(find $PWD/../mujoco/python/dist -name "mujoco-*.whl") - echo "file_path=$(realpath $whl_path)" >> $GITHUB_ENV + mujoco_whl_path=$(find $PWD/../mujoco/python/dist -name "mujoco-*.whl") + mjx_whl_path=$(find $PWD/../mujoco/mjx -name "mujoco-*.whl") + echo "mujoco_path=$(realpath $mujoco_whl_path)" >> $GITHUB_ENV + echo "mjx_path=$(realpath $mjx_whl_path)" >> $GITHUB_ENV id: package - - name: Upload artifact + - name: Upload mujoco artifact uses: actions/upload-artifact@v3 with: name: mujoco_wheel - path: ${{ env.file_path }} + path: ${{ env.mujoco_path }} + retention-days: 7 + + - name: Upload mjx artifact + uses: actions/upload-artifact@v3 + with: + name: mjx_wheel + path: ${{ env.mjx_path }} retention-days: 7 \ No newline at end of file diff --git a/install_mj_source.sh b/install_mj_source.sh index c6ebdb35..e4170acc 100755 --- a/install_mj_source.sh +++ b/install_mj_source.sh @@ -88,4 +88,5 @@ MUJOCO_PATH="$mujoco_dir/mujoco_install" MUJOCO_PLUGIN_PATH="$mujoco_dir/plugin" whl_path=$(find "$mujoco_dir/python/dist" -name "mujoco-*.whl" 2>/dev/null) MUJOCO_PATH="$mujoco_dir/mujoco_install" MUJOCO_PLUGIN_PATH="$mujoco_dir/plugin" pip install --no-deps --force-reinstall "$whl_path" cd "$mujoco_dir/mjx" +pip wheel -w "$mujoco_dir/mjx" --no-deps . pip install --no-deps --force-reinstall . \ No newline at end of file From 532f1fddfb271dc35d7c29b33f3f5cbfc40b55cd Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 18:00:16 -0800 Subject: [PATCH 39/79] fixed bug where same identifier was used for two steps --- .github/workflows/code_checks.yml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/code_checks.yml b/.github/workflows/code_checks.yml index 3d2e00a0..0e1c202e 100644 --- a/.github/workflows/code_checks.yml +++ b/.github/workflows/code_checks.yml @@ -22,7 +22,7 @@ jobs: restore-keys: | ${{ runner.os }}-pip- - name: Download mujoco artifact - id: download-artifact + id: download-artifact-mujoco uses: dawidd6/action-download-artifact@v2 with: workflow: mujoco_nightly.yml @@ -30,7 +30,7 @@ jobs: name: mujoco_wheel path: ${{ github.workspace }} - name: Download mjx artifact - id: download-artifact + id: download-artifact-mjx uses: dawidd6/action-download-artifact@v2 with: workflow: mujoco_nightly.yml From 5b5a4ee997e7f0862670c04ac56cbe348682c01a Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 18:17:21 -0800 Subject: [PATCH 40/79] fixed mjx wheel filepath --- .github/workflows/mujoco_nightly.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml index a3ee4050..389fe471 100644 --- a/.github/workflows/mujoco_nightly.yml +++ b/.github/workflows/mujoco_nightly.yml @@ -69,7 +69,7 @@ jobs: # Store the package as an artifact # the below path is known from the mujoco installation script mujoco_whl_path=$(find $PWD/../mujoco/python/dist -name "mujoco-*.whl") - mjx_whl_path=$(find $PWD/../mujoco/mjx -name "mujoco-*.whl") + mjx_whl_path=$(find $PWD/../mujoco/mjx -name "mujoco_mjx-*.whl") echo "mujoco_path=$(realpath $mujoco_whl_path)" >> $GITHUB_ENV echo "mjx_path=$(realpath $mjx_whl_path)" >> $GITHUB_ENV id: package From 18fdccb6f7d119137db1ca2a227fd0707aab814f Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 19:00:17 -0800 Subject: [PATCH 41/79] updated workflows to run at intended times; pip install new mjx; fixed path unlinking bug in test --- .github/workflows/code_checks.yml | 1 + .github/workflows/mujoco_nightly.yml | 3 --- tests/test_model_io.py | 4 ++-- 3 files changed, 3 insertions(+), 5 deletions(-) diff --git a/.github/workflows/code_checks.yml b/.github/workflows/code_checks.yml index 0e1c202e..c6490503 100644 --- a/.github/workflows/code_checks.yml +++ b/.github/workflows/code_checks.yml @@ -44,6 +44,7 @@ jobs: python -m pip install --upgrade pip bash ./install.sh -d pip install --no-deps --force-reinstall mujoco-*.whl + pip install --no-deps --force-reinstall mujoco_mjx*.whl - name: Run black shell: bash -l {0} run: black --check . diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml index 389fe471..6e060c6d 100644 --- a/.github/workflows/mujoco_nightly.yml +++ b/.github/workflows/mujoco_nightly.yml @@ -3,9 +3,6 @@ name: Build Nightly MuJoCo Release on: schedule: - cron: "0 5 * * *" # runs at 5AM every day - push: - pull_request: - branches: [main] jobs: build-and-package: diff --git a/tests/test_model_io.py b/tests/test_model_io.py index 4d084904..9d4940f1 100644 --- a/tests/test_model_io.py +++ b/tests/test_model_io.py @@ -53,7 +53,7 @@ def test_save_xml(): # saving a URDF as XML + verifying it loads into mjx save_model_xml(ROOT + "/models/pendulum/pendulum.urdf") assert load_mjx_model_and_data_from_file("pendulum.xml") - Path.unlink("pendulum.xml") # deleting test file + Path("pendulum.xml").unlink() # deleting test file def test_force_float(): @@ -83,7 +83,7 @@ def test_force_float(): f.write(dummy_xml_string) model2 = _modify_robot_float_base("_temp.xml") - Path.unlink("_temp.xml") + Path("_temp.xml").unlink() combined2 = "\t".join(get_joint_names(model2)) assert "freejoint" in combined2 From e5f01ce033fee90c59f41b8433c7aa7c52e1582c Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 19:06:32 -0800 Subject: [PATCH 42/79] bugfix: missed a problematic unlink call --- ambersim/utils/io_utils.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ambersim/utils/io_utils.py b/ambersim/utils/io_utils.py index 2f045ac9..6aa56caf 100644 --- a/ambersim/utils/io_utils.py +++ b/ambersim/utils/io_utils.py @@ -85,7 +85,7 @@ def load_mj_model_from_file( output_name = "/".join(str(filepath).split("/")[:-1]) + "/_temp_xml_model.xml" save_model_xml(filepath, output_name=output_name) mj_model = _modify_robot_float_base(output_name) - Path.unlink(output_name) + Path(output_name).unlink() else: mj_model = _modify_robot_float_base(filepath) else: From 5ee2ffb4d3797aac729b0cb76d70967c71d929be Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 21:54:42 -0800 Subject: [PATCH 43/79] expose mujoco git hash option to installation scripts --- install.sh | 20 ++++++++++------- install_mj_source.sh | 53 ++++++++++++++++++++++++++------------------ 2 files changed, 43 insertions(+), 30 deletions(-) diff --git a/install.sh b/install.sh index c297f336..d8b1cd47 100755 --- a/install.sh +++ b/install.sh @@ -7,26 +7,30 @@ set -e dev=false source=false -while getopts ds flag -do +while getopts dsh: flag; do case "${flag}" in - d) dev=true;; - s) source=true;; + d) dev=true;; # Install development dependencies + s) source=true;; # Install MuJoCo from source + h) hash=${OPTARG};; # Hash of the MuJoCo commit to install esac done # Install regular or development dependencies if [ "$dev" = true ] ; then echo "[NOTE] Installing development dependencies..." - pip install --upgrade --upgrade-strategy eager -e .[all] --find-links https://storage.googleapis.com/jax-releases/jax_cuda_releases.html --find-links https://download.pytorch.org/whl/cu118 + pip install --upgrade --upgrade-strategy only-if-needed -e .[all] \ + --find-links https://storage.googleapis.com/jax-releases/jax_cuda_releases.html \ + --find-links https://download.pytorch.org/whl/cu118 pre-commit autoupdate pre-commit install else echo "[NOTE] Installing non-developer dependencies..." - pip install --upgrade --upgrade-strategy -e . --default-timeout=100 future --find-links https://storage.googleapis.com/jax-releases/jax_cuda_releases.html --find-links https://download.pytorch.org/whl/cu118 + pip install --upgrade --upgrade-strategy only-if-needed -e . --default-timeout=100 future \ + --find-links https://storage.googleapis.com/jax-releases/jax_cuda_releases.html \ + --find-links https://download.pytorch.org/whl/cu118 fi # Checking whether to install mujoco from source -if [[ "$source" = true ]] ; then - bash install_mj_source.sh +if [ "$source" = true ] ; then + bash install_mj_source.sh -h "$hash" fi diff --git a/install_mj_source.sh b/install_mj_source.sh index e4170acc..85f8a987 100755 --- a/install_mj_source.sh +++ b/install_mj_source.sh @@ -1,4 +1,11 @@ #!/bin/bash + +while getopts h: flag; do + case "${flag}" in + h) hash=${OPTARG};; # Hash of the MuJoCo commit to install + esac +done + echo -e "\n[NOTE] Installing mujoco from source..." # the script directory and mujoco directory @@ -10,9 +17,9 @@ LATEST_GIT_HASH=$(git ls-remote https://github.com/google-deepmind/mujoco HEAD | if [ -d "$mujoco_dir/python/dist" ]; then tar_path=$(find "$mujoco_dir/python/dist" -name "mujoco-*${LATEST_GIT_HASH}.tar.gz" 2>/dev/null) whl_path=$(find "$mujoco_dir/python/dist" -name "mujoco-*.whl" 2>/dev/null) + if [ -f "$tar_path" ]; then echo -e "[NOTE] Found cached mujoco tar.gz file..." - # if wheel exists, install from wheel if [ -f "$whl_path" ]; then echo -e "[NOTE] Wheel found! Installing from wheel..." cd "$mujoco_dir/python/dist" @@ -37,48 +44,50 @@ if [ -d "$mujoco_dir/python/dist" ]; then fi # Check if CMake and a compiler are installed -if ! command -v cmake &> /dev/null; then - echo "CMake is not installed. Please install CMake before proceeding." - exit 1 -fi +command -v cmake &> /dev/null || { echo "CMake is not installed. Please install CMake before proceeding."; exit 1; } +command -v g++ &> /dev/null || { echo "C++ compiler is not available. Please install a C++ compiler before proceeding."; exit 1; } -if ! command -v g++ &> /dev/null; then - echo "C++ compiler is not available. Please install a C++ compiler before proceeding." - exit 1 -fi # Clone the Mujoco repo to the directory above where this script is located # If it exists already, then just git pull new changes if [ -d "$mujoco_dir" ]; then echo "Mujoco exists already - running git pull to update it!" - (cd "$mujoco_dir" && git pull origin main) + cd "$mujoco_dir" + git pull origin main + if [ ! -z "$hash" ]; then + echo "Checking out with provided commit hash!" + git checkout "$hash" + fi else + echo "Mujoco does not exist - cloning it!" git clone https://github.com/google-deepmind/mujoco.git "$mujoco_dir" + if [ ! -z "$hash" ]; then + echo "Checking out to provided hash!" + (cd "$mujoco_dir" && git checkout "$hash") + fi fi # Configure and build export MAKEFLAGS="-j$(nproc)" # allow the max number of processors when building cd "$mujoco_dir" -SAVED_GIT_HASH=$(git rev-parse HEAD) # getting the git hash -cmake . -cmake --build . +if [ -z "$hash" ]; then + SAVED_GIT_HASH=$(git rev-parse HEAD) # getting the git hash +else + SAVED_GIT_HASH="$hash" +fi +cmake . && cmake --build . # Install Mujoco -cmake . -DCMAKE_INSTALL_PREFIX="./mujoco_install" -cmake --install . +cmake . -DCMAKE_INSTALL_PREFIX="./mujoco_install" && cmake --install . # Generate source distribution required for Python bindings cd "$mujoco_dir/python" ./make_sdist.sh tar_path=$(find "$mujoco_dir/python/dist" -name 'mujoco-*.tar.gz' 2>/dev/null) -# Renaming the tar file to append the commit hash -old_name=$(basename "$tar_path") -old_prefix="${old_name%%.tar.gz}" -new_prefix="${old_prefix}-${SAVED_GIT_HASH}" -new_name="${new_prefix}.tar.gz" -new_tar_path="$(dirname "$tar_path")/$new_name" -mv "$tar_path" "$new_tar_path" # renames the tar file to have the git hash in it +# Renaming the tar file by appending the commit hash +new_tar_path="$(dirname "$tar_path")/$(basename "$tar_path" .tar.gz)-$SAVED_GIT_HASH.tar.gz" +mv "$tar_path" "$new_tar_path" # manually building wheel so we can cache it cd "$mujoco_dir/python/dist" From ad39148b884339ccd99a3e0c64e6b999f81a113b Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 22:04:57 -0800 Subject: [PATCH 44/79] added check_artifact and search_artifact flags to artifact retrieval action - should only download most recent artifact --- .github/workflows/code_checks.yml | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/.github/workflows/code_checks.yml b/.github/workflows/code_checks.yml index c6490503..fa3deab1 100644 --- a/.github/workflows/code_checks.yml +++ b/.github/workflows/code_checks.yml @@ -27,6 +27,8 @@ jobs: with: workflow: mujoco_nightly.yml workflow_conclusion: success + check_artifacts: true + search_artifacts: true name: mujoco_wheel path: ${{ github.workspace }} - name: Download mjx artifact @@ -35,6 +37,8 @@ jobs: with: workflow: mujoco_nightly.yml workflow_conclusion: success + check_artifacts: true + search_artifacts: true name: mjx_wheel path: ${{ github.workspace }} - name: Install dependencies From 74b2b16bbba24422ab4272095557554522b9baf7 Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 22:12:42 -0800 Subject: [PATCH 45/79] modify the mujoco nightly build workflow to run when ready to review as well --- .github/workflows/mujoco_nightly.yml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml index 6e060c6d..0bd71d43 100644 --- a/.github/workflows/mujoco_nightly.yml +++ b/.github/workflows/mujoco_nightly.yml @@ -3,6 +3,9 @@ name: Build Nightly MuJoCo Release on: schedule: - cron: "0 5 * * *" # runs at 5AM every day + pull_request: + branches: [main] + types: [ready_for_review] jobs: build-and-package: From e26c70bd6bd0a2e78f8aa259856154c27848b97f Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 22:18:31 -0800 Subject: [PATCH 46/79] trigger code check workflow after nightly build workflow completes --- .github/workflows/code_checks.yml | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/.github/workflows/code_checks.yml b/.github/workflows/code_checks.yml index fa3deab1..673bd79b 100644 --- a/.github/workflows/code_checks.yml +++ b/.github/workflows/code_checks.yml @@ -5,6 +5,10 @@ on: branches: [main] pull_request: branches: [main] + workflow_run: + workflows: ["Build Nightly MuJoCo Release"] + types: + - completed permissions: contents: read From 3f1b2cb9b36b12593b3aa547f1386020d52bb45a Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 22:23:32 -0800 Subject: [PATCH 47/79] added missing id to conda cache action that was preventing conditional environment updates --- .github/workflows/mujoco_nightly.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml index 0bd71d43..bdeba644 100644 --- a/.github/workflows/mujoco_nightly.yml +++ b/.github/workflows/mujoco_nightly.yml @@ -45,6 +45,7 @@ jobs: key: ${{ runner.os }}-conda-${{ env.CACHE_NUMBER }}-${{ hashFiles('environment.yml') }} + id: cache - name: Update environment run: mamba env update -n ambersim -f environment.yml From 7dc31f2beddb09a8a3cd7894ccc511d3f75d1b23 Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 22:49:33 -0800 Subject: [PATCH 48/79] run the composition of the nightly build + code checks when ready for review --- .github/workflows/mujoco_nightly.yml | 10 ++-------- .../workflows/mujoco_nightly_and_code_checks.yml | 16 ++++++++++++++++ 2 files changed, 18 insertions(+), 8 deletions(-) create mode 100644 .github/workflows/mujoco_nightly_and_code_checks.yml diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml index bdeba644..ca97bb8f 100644 --- a/.github/workflows/mujoco_nightly.yml +++ b/.github/workflows/mujoco_nightly.yml @@ -3,9 +3,6 @@ name: Build Nightly MuJoCo Release on: schedule: - cron: "0 5 * * *" # runs at 5AM every day - pull_request: - branches: [main] - types: [ready_for_review] jobs: build-and-package: @@ -17,14 +14,11 @@ jobs: - name: Free Up GitHub Actions Ubuntu Runner Disk Space 🔧 uses: jlumbroso/free-disk-space@main with: - # This might remove tools that are actually needed, if set to "true" but frees about 6 GB - tool-cache: false - - # All of these default to true, but feel free to set to "false" if necessary for your workflow + tool-cache: false # might have useful/necessary stuff android: true dotnet: true haskell: true - large-packages: true + large-packages: false # doesn't save that much space relatively, takes long to run swap-storage: true # for caching the conda env diff --git a/.github/workflows/mujoco_nightly_and_code_checks.yml b/.github/workflows/mujoco_nightly_and_code_checks.yml new file mode 100644 index 00000000..16143fc4 --- /dev/null +++ b/.github/workflows/mujoco_nightly_and_code_checks.yml @@ -0,0 +1,16 @@ +name: mujoco_nightly_and_code_checks + +on: + pull_request: + branches: [main] + types: [ready_for_review] + +jobs: + first: + name: Build MuJoCo Nightly Release + uses: ./.github/workflows/mujoco_nightly.yml + + second: + name: Code Checks + needs: first + uses: ./.github/workflows/code_checks.yml \ No newline at end of file From 46568e6532006eb8e41dbf10627a205a85a019fa Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 22:58:52 -0800 Subject: [PATCH 49/79] added workflow_call to make workflows reusable --- .github/workflows/code_checks.yml | 5 +---- .github/workflows/mujoco_nightly.yml | 1 + 2 files changed, 2 insertions(+), 4 deletions(-) diff --git a/.github/workflows/code_checks.yml b/.github/workflows/code_checks.yml index 673bd79b..0f9deb6d 100644 --- a/.github/workflows/code_checks.yml +++ b/.github/workflows/code_checks.yml @@ -5,10 +5,7 @@ on: branches: [main] pull_request: branches: [main] - workflow_run: - workflows: ["Build Nightly MuJoCo Release"] - types: - - completed + workflow_call: permissions: contents: read diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml index ca97bb8f..8f49192d 100644 --- a/.github/workflows/mujoco_nightly.yml +++ b/.github/workflows/mujoco_nightly.yml @@ -3,6 +3,7 @@ name: Build Nightly MuJoCo Release on: schedule: - cron: "0 5 * * *" # runs at 5AM every day + workflow_call: jobs: build-and-package: From 0996ab0104a9bebd970eea09169687831d19911b Mon Sep 17 00:00:00 2001 From: alberthli Date: Fri, 10 Nov 2023 23:25:46 -0800 Subject: [PATCH 50/79] minor: README edit --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index ec294bc1..439b55d5 100644 --- a/README.md +++ b/README.md @@ -51,7 +51,7 @@ pip show mujoco-mjx ### Abridged Dev Guidelines Development on this code will be controlled via code review. To facilitate this, please follow these guidelines: * keep your pull requests small so that it's practical to human review them; -* try to create _draft pull requests_ instead of regular ones and request reviews from relevant people only when ready - our CI runs only when a pull request is marked "ready for review," so this saves a lot of unnecessary CI runs; +* try to create _draft pull requests_ instead of regular ones and request reviews from relevant people only when ready - we rebuild `mujoco` from source and run the branch tests when this happens; * write tests as you go (and if you are reviewing, suggest missing tests); * write docstrings for public classes and methods, even if it's just a one-liner; * before committing, make sure you locally pass all tests by running `pytest` in the repo root; From 0db0864f31ebf5ffba754ebfb825a4934d06e36f Mon Sep 17 00:00:00 2001 From: alberthli Date: Sat, 11 Nov 2023 11:18:36 -0800 Subject: [PATCH 51/79] append git commit hash to end of artifact name to distinguish builds; change schedule time to 4:53AM to avoid high load on the hour --- .github/workflows/code_checks.yml | 6 ++++-- .github/workflows/mujoco_nightly.yml | 14 +++++++++----- 2 files changed, 13 insertions(+), 7 deletions(-) diff --git a/.github/workflows/code_checks.yml b/.github/workflows/code_checks.yml index 0f9deb6d..21507f71 100644 --- a/.github/workflows/code_checks.yml +++ b/.github/workflows/code_checks.yml @@ -30,7 +30,8 @@ jobs: workflow_conclusion: success check_artifacts: true search_artifacts: true - name: mujoco_wheel + name_is_regexp: true + name: "mujoco_wheel-*" path: ${{ github.workspace }} - name: Download mjx artifact id: download-artifact-mjx @@ -40,7 +41,8 @@ jobs: workflow_conclusion: success check_artifacts: true search_artifacts: true - name: mjx_wheel + name_is_regexp: true + name: "mjx_wheel-*" path: ${{ github.workspace }} - name: Install dependencies working-directory: ${{ github.workspace }} diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml index 8f49192d..5b1dae38 100644 --- a/.github/workflows/mujoco_nightly.yml +++ b/.github/workflows/mujoco_nightly.yml @@ -2,7 +2,7 @@ name: Build Nightly MuJoCo Release on: schedule: - - cron: "0 5 * * *" # runs at 5AM every day + - cron: "53 4 * * *" # runs at 4:53AM every day - avoid high load on the hour workflow_call: jobs: @@ -62,24 +62,28 @@ jobs: python -m pip install --upgrade pip ./install_mj_source.sh - # Store the package as an artifact - # the below path is known from the mujoco installation script + # Saving the wheels to respective paths mujoco_whl_path=$(find $PWD/../mujoco/python/dist -name "mujoco-*.whl") mjx_whl_path=$(find $PWD/../mujoco/mjx -name "mujoco_mjx-*.whl") echo "mujoco_path=$(realpath $mujoco_whl_path)" >> $GITHUB_ENV echo "mjx_path=$(realpath $mjx_whl_path)" >> $GITHUB_ENV + + # Appending the relevant git commit hash to the artifact name + LATEST_GIT_HASH=$(git ls-remote https://github.com/google-deepmind/mujoco HEAD | awk '{ print $1}') + echo "mujoco_name=mujoco_wheel-${LATEST_GIT_HASH}" >> $GITHUB_ENV + echo "mjx_name=mjx_wheel-${LATEST_GIT_HASH}" >> $GITHUB_ENV id: package - name: Upload mujoco artifact uses: actions/upload-artifact@v3 with: - name: mujoco_wheel + name: ${{ env.mujoco_name }} path: ${{ env.mujoco_path }} retention-days: 7 - name: Upload mjx artifact uses: actions/upload-artifact@v3 with: - name: mjx_wheel + name: ${{ env.mjx_name }} path: ${{ env.mjx_path }} retention-days: 7 \ No newline at end of file From 937145484914fe1af663228bfbe1f060ce2853bf Mon Sep 17 00:00:00 2001 From: alberthli Date: Sat, 11 Nov 2023 11:45:38 -0800 Subject: [PATCH 52/79] conditional caching for nightly builds + download artifact from run ids --- .github/workflows/code_checks.yml | 15 ++++++++++-- .github/workflows/mujoco_nightly.yml | 34 ++++++++++++++++++++++++++++ 2 files changed, 47 insertions(+), 2 deletions(-) diff --git a/.github/workflows/code_checks.yml b/.github/workflows/code_checks.yml index 21507f71..f963eb03 100644 --- a/.github/workflows/code_checks.yml +++ b/.github/workflows/code_checks.yml @@ -22,12 +22,23 @@ jobs: key: ${{ runner.os }}-${{ hashFiles('pyproject.toml') }} restore-keys: | ${{ runner.os }}-pip- + + # get the most recent run ID associated with mujoco nightly + - name: Get Recent Run ID + id: get_run_id + run: | + response=$(curl -s -H "Authorization: Bearer ${{ secrets.GITHUB_TOKEN }}" \ + "https://api.github.com/repos/${{ github.repository }}/actions/workflows/mujoco_nightly.yml/runs") + echo "::set-output name=run_id::$(echo "$response" | jq -r '.workflow_runs[0].id')" + - name: Print Recent Run ID + run: echo "[DEBUG] Most recent run ID: ${{ steps.get_run_id.outputs.run_id }}" + - name: Download mujoco artifact id: download-artifact-mujoco uses: dawidd6/action-download-artifact@v2 with: workflow: mujoco_nightly.yml - workflow_conclusion: success + run_id: ${{ steps.get_run_id.outputs.run_id }}" check_artifacts: true search_artifacts: true name_is_regexp: true @@ -38,7 +49,7 @@ jobs: uses: dawidd6/action-download-artifact@v2 with: workflow: mujoco_nightly.yml - workflow_conclusion: success + run_id: ${{ steps.get_run_id.outputs.run_id }}" check_artifacts: true search_artifacts: true name_is_regexp: true diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml index 5b1dae38..f74780f0 100644 --- a/.github/workflows/mujoco_nightly.yml +++ b/.github/workflows/mujoco_nightly.yml @@ -46,6 +46,39 @@ jobs: mamba env update -n ambersim -f environment.yml if: steps.cache.outputs.cache-hit != 'true' + # download previously built mujoco artifact to check version + - name: Download mujoco artifact + id: download-artifact-mujoco + uses: dawidd6/action-download-artifact@v2 + with: + workflow: mujoco_nightly.yml + workflow_conclusion: success + check_artifacts: true + search_artifacts: true + name_is_regexp: true + name: "mujoco_wheel-*" + path: ${{ github.workspace }} + + - name: Build pre-check + shell: bash -l {0} + run: | + # Checks the git hash of the cached files vs. the most recent one + LATEST_GIT_HASH=$(git ls-remote https://github.com/google-deepmind/mujoco HEAD | awk '{ print $1}') + + filename=$(find ${{ github.workspace }} -type f -name "mujoco_wheel-*.whl" -print -quit) + echo "[DEBUG] filename: $filename" + + if [ -n "$filename" ]; then + # if the file name exists, extract the git hash and compare to upstream mujoco + CACHED_GIT_HASH=$(echo "$filename" | awk -F'mujoco_wheel-' '{print $2}' | awk -F'.' '{print $1}') + if [ "$LATEST_GIT_HASH" = "$CACHED_GIT_HASH" ]; then + echo "Cached wheel matches most recent one - skipping build! Hash: $CACHED_GIT_HASH" + exit 0 + fi + else + echo "No cached wheels found - building new ones!" + fi + # mujoco build + install - name: Create and Store Wheel shell: bash -l {0} @@ -70,6 +103,7 @@ jobs: # Appending the relevant git commit hash to the artifact name LATEST_GIT_HASH=$(git ls-remote https://github.com/google-deepmind/mujoco HEAD | awk '{ print $1}') + echo "[DEBUG] LATEST_GIT_HASH: $LATEST_GIT_HASH" echo "mujoco_name=mujoco_wheel-${LATEST_GIT_HASH}" >> $GITHUB_ENV echo "mjx_name=mjx_wheel-${LATEST_GIT_HASH}" >> $GITHUB_ENV id: package From fc0bfa1216c99b0b67919a724c8f2fde21b97e5f Mon Sep 17 00:00:00 2001 From: alberthli Date: Sat, 11 Nov 2023 11:46:36 -0800 Subject: [PATCH 53/79] minor: syntax error --- .github/workflows/code_checks.yml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/.github/workflows/code_checks.yml b/.github/workflows/code_checks.yml index f963eb03..246fe274 100644 --- a/.github/workflows/code_checks.yml +++ b/.github/workflows/code_checks.yml @@ -31,7 +31,8 @@ jobs: "https://api.github.com/repos/${{ github.repository }}/actions/workflows/mujoco_nightly.yml/runs") echo "::set-output name=run_id::$(echo "$response" | jq -r '.workflow_runs[0].id')" - name: Print Recent Run ID - run: echo "[DEBUG] Most recent run ID: ${{ steps.get_run_id.outputs.run_id }}" + run: | + echo "[DEBUG] Most recent run ID: ${{ steps.get_run_id.outputs.run_id }}" - name: Download mujoco artifact id: download-artifact-mujoco From 7d1e50c4a5a4978b20b65217b2f436165d46d101 Mon Sep 17 00:00:00 2001 From: alberthli Date: Sat, 11 Nov 2023 11:58:15 -0800 Subject: [PATCH 54/79] bugfixes for downloading + checking hash --- .github/workflows/code_checks.yml | 4 +-- .github/workflows/mujoco_nightly.yml | 38 +++++++++++++++++++++++++--- 2 files changed, 36 insertions(+), 6 deletions(-) diff --git a/.github/workflows/code_checks.yml b/.github/workflows/code_checks.yml index 246fe274..b212fb1d 100644 --- a/.github/workflows/code_checks.yml +++ b/.github/workflows/code_checks.yml @@ -43,7 +43,7 @@ jobs: check_artifacts: true search_artifacts: true name_is_regexp: true - name: "mujoco_wheel-*" + name: "mujoco_wheel*" path: ${{ github.workspace }} - name: Download mjx artifact id: download-artifact-mjx @@ -54,7 +54,7 @@ jobs: check_artifacts: true search_artifacts: true name_is_regexp: true - name: "mjx_wheel-*" + name: "mjx_wheel*" path: ${{ github.workspace }} - name: Install dependencies working-directory: ${{ github.workspace }} diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml index f74780f0..65e7f815 100644 --- a/.github/workflows/mujoco_nightly.yml +++ b/.github/workflows/mujoco_nightly.yml @@ -46,19 +46,44 @@ jobs: mamba env update -n ambersim -f environment.yml if: steps.cache.outputs.cache-hit != 'true' - # download previously built mujoco artifact to check version + # get the most recent run ID associated with mujoco nightly + - name: Get Most Recent Run ID + id: get_run_id + run: | + response=$(curl -s -H "Authorization: Bearer ${{ secrets.GITHUB_TOKEN }}" \ + "https://api.github.com/repos/${{ github.repository }}/actions/workflows/mujoco_nightly.yml/runs") + echo "::set-output name=run_id::$(echo "$response" | jq -r '.workflow_runs[0].id')" + - name: Print Recent Run ID + run: | + echo "[DEBUG] Most recent run ID: ${{ steps.get_run_id.outputs.run_id }}" + + # download previously built mujoco and mjx artifacts - name: Download mujoco artifact id: download-artifact-mujoco uses: dawidd6/action-download-artifact@v2 with: workflow: mujoco_nightly.yml - workflow_conclusion: success + run_id: ${{ steps.get_run_id.outputs.run_id }}" + check_artifacts: true + search_artifacts: true + name_is_regexp: true + name: "mujoco_wheel*" + if_no_artifact_found: warn + path: ${{ github.workspace }} + - name: Download mjx artifact + id: download-artifact-mjx + uses: dawidd6/action-download-artifact@v2 + with: + workflow: mujoco_nightly.yml + run_id: ${{ steps.get_run_id.outputs.run_id }}" check_artifacts: true search_artifacts: true name_is_regexp: true - name: "mujoco_wheel-*" + name: "mjx_wheel*" + if_no_artifact_found: warn path: ${{ github.workspace }} + # checks whether to rebuild or not - name: Build pre-check shell: bash -l {0} run: | @@ -73,10 +98,14 @@ jobs: CACHED_GIT_HASH=$(echo "$filename" | awk -F'mujoco_wheel-' '{print $2}' | awk -F'.' '{print $1}') if [ "$LATEST_GIT_HASH" = "$CACHED_GIT_HASH" ]; then echo "Cached wheel matches most recent one - skipping build! Hash: $CACHED_GIT_HASH" - exit 0 + echo "skip_build=true" >> $GITHUB_ENV + else + echo "Cached wheel is outdated - building new ones! Old Hash: $CACHED_GIT_HASH" + echo "skip_build=true" >> $GITHUB_ENV fi else echo "No cached wheels found - building new ones!" + echo "skip_build=false" >> $GITHUB_ENV fi # mujoco build + install @@ -107,6 +136,7 @@ jobs: echo "mujoco_name=mujoco_wheel-${LATEST_GIT_HASH}" >> $GITHUB_ENV echo "mjx_name=mjx_wheel-${LATEST_GIT_HASH}" >> $GITHUB_ENV id: package + if: env.skip_build != 'true' - name: Upload mujoco artifact uses: actions/upload-artifact@v3 From 7012c2f8bea45f5aba528a49eafec6e58c7824a4 Mon Sep 17 00:00:00 2001 From: alberthli Date: Sat, 11 Nov 2023 12:18:24 -0800 Subject: [PATCH 55/79] weird bugs regarding not downloading correctly or regexp not working --- .github/workflows/code_checks.yml | 4 --- .github/workflows/mujoco_nightly.yml | 38 ++++++++++++++++++++-------- 2 files changed, 27 insertions(+), 15 deletions(-) diff --git a/.github/workflows/code_checks.yml b/.github/workflows/code_checks.yml index b212fb1d..08bb1196 100644 --- a/.github/workflows/code_checks.yml +++ b/.github/workflows/code_checks.yml @@ -40,8 +40,6 @@ jobs: with: workflow: mujoco_nightly.yml run_id: ${{ steps.get_run_id.outputs.run_id }}" - check_artifacts: true - search_artifacts: true name_is_regexp: true name: "mujoco_wheel*" path: ${{ github.workspace }} @@ -51,8 +49,6 @@ jobs: with: workflow: mujoco_nightly.yml run_id: ${{ steps.get_run_id.outputs.run_id }}" - check_artifacts: true - search_artifacts: true name_is_regexp: true name: "mjx_wheel*" path: ${{ github.workspace }} diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml index 65e7f815..c509267b 100644 --- a/.github/workflows/mujoco_nightly.yml +++ b/.github/workflows/mujoco_nightly.yml @@ -16,11 +16,11 @@ jobs: uses: jlumbroso/free-disk-space@main with: tool-cache: false # might have useful/necessary stuff - android: true - dotnet: true - haskell: true + android: true # removes 14GB very quickly + dotnet: false # removes a lot of space, but unnecessary here. skip to save time. + haskell: false # removes a lot of space, but unnecessary here. skip to save time. large-packages: false # doesn't save that much space relatively, takes long to run - swap-storage: true + swap-storage: false # removes a lot of space, but unnecessary here. skip to save time. # for caching the conda env # see: https://github.com/conda-incubator/setup-miniconda#caching-environments @@ -47,15 +47,31 @@ jobs: if: steps.cache.outputs.cache-hit != 'true' # get the most recent run ID associated with mujoco nightly - - name: Get Most Recent Run ID - id: get_run_id + - name: Get Recent Run ID for mujoco_nightly.yml + id: get_run_id_workflow1 run: | response=$(curl -s -H "Authorization: Bearer ${{ secrets.GITHUB_TOKEN }}" \ "https://api.github.com/repos/${{ github.repository }}/actions/workflows/mujoco_nightly.yml/runs") - echo "::set-output name=run_id::$(echo "$response" | jq -r '.workflow_runs[0].id')" - - name: Print Recent Run ID + echo "::set-output name=run_id_workflow1::$(echo "$response" | jq -r '.workflow_runs[0].id')" + + - name: Get Recent Run ID for mujoco_nightly_and_code_checks.yml + id: get_run_id_workflow2 + run: | + response=$(curl -s -H "Authorization: Bearer ${{ secrets.GITHUB_TOKEN }}" \ + "https://api.github.com/repos/${{ github.repository }}/actions/workflows/mujoco_nightly_and_code_checks.yml/runs") + echo "::set-output name=run_id_workflow2::$(echo "$response" | jq -r '.workflow_runs[0].id')" + + - name: Compare Run IDs run: | - echo "[DEBUG] Most recent run ID: ${{ steps.get_run_id.outputs.run_id }}" + run_id_workflow1="${{ steps.get_run_id_workflow1.outputs.run_id }}" + run_id_workflow2="${{ steps.get_run_id_workflow2.outputs.run_id }}" + + if [ "$run_id_workflow1" -gt "$run_id_workflow2" ]; then + most_recent_run_id="$run_id_workflow1" + else + most_recent_run_id="$run_id_workflow2" + fi + echo "run_id=$most_recent_run_id" >> $GITHUB_ENV # download previously built mujoco and mjx artifacts - name: Download mujoco artifact @@ -63,7 +79,7 @@ jobs: uses: dawidd6/action-download-artifact@v2 with: workflow: mujoco_nightly.yml - run_id: ${{ steps.get_run_id.outputs.run_id }}" + run_id: ${{ env.run_id }}" check_artifacts: true search_artifacts: true name_is_regexp: true @@ -75,7 +91,7 @@ jobs: uses: dawidd6/action-download-artifact@v2 with: workflow: mujoco_nightly.yml - run_id: ${{ steps.get_run_id.outputs.run_id }}" + run_id: ${{ env.run_id }}" check_artifacts: true search_artifacts: true name_is_regexp: true From d2ae3699d2ca4f83176a5ad9051c1704549e93c1 Mon Sep 17 00:00:00 2001 From: alberthli Date: Sat, 11 Nov 2023 12:26:52 -0800 Subject: [PATCH 56/79] fixed stray quotation mark that might have been causing a bug --- .github/workflows/code_checks.yml | 4 ++-- .github/workflows/mujoco_nightly.yml | 12 ++++-------- 2 files changed, 6 insertions(+), 10 deletions(-) diff --git a/.github/workflows/code_checks.yml b/.github/workflows/code_checks.yml index 08bb1196..84eaf955 100644 --- a/.github/workflows/code_checks.yml +++ b/.github/workflows/code_checks.yml @@ -39,7 +39,7 @@ jobs: uses: dawidd6/action-download-artifact@v2 with: workflow: mujoco_nightly.yml - run_id: ${{ steps.get_run_id.outputs.run_id }}" + run_id: ${{ steps.get_run_id.outputs.run_id }} name_is_regexp: true name: "mujoco_wheel*" path: ${{ github.workspace }} @@ -48,7 +48,7 @@ jobs: uses: dawidd6/action-download-artifact@v2 with: workflow: mujoco_nightly.yml - run_id: ${{ steps.get_run_id.outputs.run_id }}" + run_id: ${{ steps.get_run_id.outputs.run_id }} name_is_regexp: true name: "mjx_wheel*" path: ${{ github.workspace }} diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml index c509267b..d3958761 100644 --- a/.github/workflows/mujoco_nightly.yml +++ b/.github/workflows/mujoco_nightly.yml @@ -79,11 +79,9 @@ jobs: uses: dawidd6/action-download-artifact@v2 with: workflow: mujoco_nightly.yml - run_id: ${{ env.run_id }}" - check_artifacts: true - search_artifacts: true - name_is_regexp: true + run_id: ${{ env.run_id }} name: "mujoco_wheel*" + name_is_regexp: true if_no_artifact_found: warn path: ${{ github.workspace }} - name: Download mjx artifact @@ -91,11 +89,9 @@ jobs: uses: dawidd6/action-download-artifact@v2 with: workflow: mujoco_nightly.yml - run_id: ${{ env.run_id }}" - check_artifacts: true - search_artifacts: true - name_is_regexp: true + run_id: ${{ env.run_id }} name: "mjx_wheel*" + name_is_regexp: true if_no_artifact_found: warn path: ${{ github.workspace }} From a595bdb3fdd13f1a4dadc2ac5948d82648c8e8f5 Mon Sep 17 00:00:00 2001 From: alberthli Date: Sat, 11 Nov 2023 12:53:42 -0800 Subject: [PATCH 57/79] big debugging run --- .github/workflows/code_checks.yml | 34 ++++---- .github/workflows/mujoco_nightly.yml | 86 ++++++++++++------- .../mujoco_nightly_and_code_checks.yml | 6 +- 3 files changed, 75 insertions(+), 51 deletions(-) diff --git a/.github/workflows/code_checks.yml b/.github/workflows/code_checks.yml index 84eaf955..de605f0e 100644 --- a/.github/workflows/code_checks.yml +++ b/.github/workflows/code_checks.yml @@ -24,42 +24,46 @@ jobs: ${{ runner.os }}-pip- # get the most recent run ID associated with mujoco nightly - - name: Get Recent Run ID - id: get_run_id - run: | - response=$(curl -s -H "Authorization: Bearer ${{ secrets.GITHUB_TOKEN }}" \ - "https://api.github.com/repos/${{ github.repository }}/actions/workflows/mujoco_nightly.yml/runs") - echo "::set-output name=run_id::$(echo "$response" | jq -r '.workflow_runs[0].id')" - - name: Print Recent Run ID - run: | - echo "[DEBUG] Most recent run ID: ${{ steps.get_run_id.outputs.run_id }}" + # - name: Get Recent Run ID + # id: get_run_id + # run: | + # response=$(curl -s -H "Authorization: Bearer ${{ secrets.GITHUB_TOKEN }}" \ + # "https://api.github.com/repos/${{ github.repository }}/actions/workflows/mujoco_nightly.yml/runs") + # echo "::set-output name=run_id::$(echo "$response" | jq -r '.workflow_runs[0].id')" + # - name: Print Recent Run ID + # run: | + # echo "[DEBUG] Most recent run ID: ${{ steps.get_run_id.outputs.run_id }}" - name: Download mujoco artifact id: download-artifact-mujoco uses: dawidd6/action-download-artifact@v2 with: workflow: mujoco_nightly.yml - run_id: ${{ steps.get_run_id.outputs.run_id }} + # run_id: ${{ steps.get_run_id.outputs.run_id }} name_is_regexp: true - name: "mujoco_wheel*" + name: "mujoco_wheel-*" path: ${{ github.workspace }} + check_artifacts: true + search_artifacts: true - name: Download mjx artifact id: download-artifact-mjx uses: dawidd6/action-download-artifact@v2 with: workflow: mujoco_nightly.yml - run_id: ${{ steps.get_run_id.outputs.run_id }} + # run_id: ${{ steps.get_run_id.outputs.run_id }} name_is_regexp: true - name: "mjx_wheel*" + name: "mjx_wheel-*" path: ${{ github.workspace }} + check_artifacts: true + search_artifacts: true - name: Install dependencies working-directory: ${{ github.workspace }} shell: bash -l {0} run: | python -m pip install --upgrade pip bash ./install.sh -d - pip install --no-deps --force-reinstall mujoco-*.whl - pip install --no-deps --force-reinstall mujoco_mjx*.whl + pip install --no-deps --force-reinstall mujoco_wheel/mujoco-*.whl + pip install --no-deps --force-reinstall mjx_wheel/mujoco_mjx-*.whl - name: Run black shell: bash -l {0} run: black --check . diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml index d3958761..32c8daa0 100644 --- a/.github/workflows/mujoco_nightly.yml +++ b/.github/workflows/mujoco_nightly.yml @@ -4,6 +4,9 @@ on: schedule: - cron: "53 4 * * *" # runs at 4:53AM every day - avoid high load on the hour workflow_call: + pull_request: # [DEBUG] + branches: [main] + types: [ready_for_review] jobs: build-and-package: @@ -47,31 +50,33 @@ jobs: if: steps.cache.outputs.cache-hit != 'true' # get the most recent run ID associated with mujoco nightly - - name: Get Recent Run ID for mujoco_nightly.yml - id: get_run_id_workflow1 - run: | - response=$(curl -s -H "Authorization: Bearer ${{ secrets.GITHUB_TOKEN }}" \ - "https://api.github.com/repos/${{ github.repository }}/actions/workflows/mujoco_nightly.yml/runs") - echo "::set-output name=run_id_workflow1::$(echo "$response" | jq -r '.workflow_runs[0].id')" - - - name: Get Recent Run ID for mujoco_nightly_and_code_checks.yml - id: get_run_id_workflow2 - run: | - response=$(curl -s -H "Authorization: Bearer ${{ secrets.GITHUB_TOKEN }}" \ - "https://api.github.com/repos/${{ github.repository }}/actions/workflows/mujoco_nightly_and_code_checks.yml/runs") - echo "::set-output name=run_id_workflow2::$(echo "$response" | jq -r '.workflow_runs[0].id')" - - - name: Compare Run IDs - run: | - run_id_workflow1="${{ steps.get_run_id_workflow1.outputs.run_id }}" - run_id_workflow2="${{ steps.get_run_id_workflow2.outputs.run_id }}" - - if [ "$run_id_workflow1" -gt "$run_id_workflow2" ]; then - most_recent_run_id="$run_id_workflow1" - else - most_recent_run_id="$run_id_workflow2" - fi - echo "run_id=$most_recent_run_id" >> $GITHUB_ENV + # - name: Get Recent Run ID for mujoco_nightly.yml + # id: get_run_id_workflow1 + # run: | + # response=$(curl -s -H "Authorization: Bearer ${{ secrets.GITHUB_TOKEN }}" \ + # "https://api.github.com/repos/${{ github.repository }}/actions/workflows/mujoco_nightly.yml/runs") + # echo "::set-output name=run_id_workflow1::$(echo "$response" | jq -r '.workflow_runs[0].id')" + # echo "[DEBUG] Most recent run ID for mujoco_nightly.yml: ${{ steps.get_run_id_workflow1.outputs.run_id }}" + + # - name: Get Recent Run ID for mujoco_nightly_and_code_checks.yml + # id: get_run_id_workflow2 + # run: | + # response=$(curl -s -H "Authorization: Bearer ${{ secrets.GITHUB_TOKEN }}" \ + # "https://api.github.com/repos/${{ github.repository }}/actions/workflows/mujoco_nightly_and_code_checks.yml/runs") + # echo "::set-output name=run_id_workflow2::$(echo "$response" | jq -r '.workflow_runs[0].id')" + # echo "[DEBUG] Most recent run ID for mujoco_nightly_and_code_checks.yml: ${{ steps.get_run_id_workflow2.outputs.run_id }}" + + # - name: Compare Run IDs + # run: | + # run_id_workflow1="${{ steps.get_run_id_workflow1.outputs.run_id }}" + # run_id_workflow2="${{ steps.get_run_id_workflow2.outputs.run_id }}" + + # if [ "$run_id_workflow1" -gt "$run_id_workflow2" ]; then + # most_recent_run_id="$run_id_workflow1" + # else + # most_recent_run_id="$run_id_workflow2" + # fi + # echo "run_id=$most_recent_run_id" >> $GITHUB_ENV # download previously built mujoco and mjx artifacts - name: Download mujoco artifact @@ -79,21 +84,25 @@ jobs: uses: dawidd6/action-download-artifact@v2 with: workflow: mujoco_nightly.yml - run_id: ${{ env.run_id }} - name: "mujoco_wheel*" + # run_id: ${{ steps.get_run_id.outputs.run_id }} name_is_regexp: true - if_no_artifact_found: warn + name: "mujoco_wheel-*" path: ${{ github.workspace }} + check_artifacts: true + search_artifacts: true + if_no_artifact_found: warn - name: Download mjx artifact id: download-artifact-mjx uses: dawidd6/action-download-artifact@v2 with: workflow: mujoco_nightly.yml - run_id: ${{ env.run_id }} - name: "mjx_wheel*" + # run_id: ${{ steps.get_run_id.outputs.run_id }} name_is_regexp: true - if_no_artifact_found: warn + name: "mjx_wheel-*" path: ${{ github.workspace }} + check_artifacts: true + search_artifacts: true + if_no_artifact_found: warn # checks whether to rebuild or not - name: Build pre-check @@ -102,8 +111,10 @@ jobs: # Checks the git hash of the cached files vs. the most recent one LATEST_GIT_HASH=$(git ls-remote https://github.com/google-deepmind/mujoco HEAD | awk '{ print $1}') - filename=$(find ${{ github.workspace }} -type f -name "mujoco_wheel-*.whl" -print -quit) - echo "[DEBUG] filename: $filename" + mujoco_whl_path=$(find ${{ github.workspace }} -type f -name "mujoco_wheel-*.whl" -print -quit) + mjx_whl_path=$(find ${{ github.workspace }} -type f -name "mujoco_wheel-*.whl" -print -quit) + echo "[DEBUG] mujoco_whl_path: $mujoco_whl_path" + echo "[DEBUG] mjx_whl_path: $mjx_whl_path" if [ -n "$filename" ]; then # if the file name exists, extract the git hash and compare to upstream mujoco @@ -111,6 +122,14 @@ jobs: if [ "$LATEST_GIT_HASH" = "$CACHED_GIT_HASH" ]; then echo "Cached wheel matches most recent one - skipping build! Hash: $CACHED_GIT_HASH" echo "skip_build=true" >> $GITHUB_ENV + + # names of the wheels + echo "mujoco_name=mujoco_wheel-${LATEST_GIT_HASH}" >> $GITHUB_ENV + echo "mjx_name=mjx_wheel-${LATEST_GIT_HASH}" >> $GITHUB_ENV + + # paths to the wheels + echo "mujoco_path=$(realpath $mujoco_whl_path)" >> $GITHUB_ENV + echo "mjx_path=$(realpath $mjx_whl_path)" >> $GITHUB_ENV else echo "Cached wheel is outdated - building new ones! Old Hash: $CACHED_GIT_HASH" echo "skip_build=true" >> $GITHUB_ENV @@ -150,6 +169,7 @@ jobs: id: package if: env.skip_build != 'true' + # [TODO] if skip_build, then reupload the cached artifacts - name: Upload mujoco artifact uses: actions/upload-artifact@v3 with: diff --git a/.github/workflows/mujoco_nightly_and_code_checks.yml b/.github/workflows/mujoco_nightly_and_code_checks.yml index 16143fc4..b2619ad3 100644 --- a/.github/workflows/mujoco_nightly_and_code_checks.yml +++ b/.github/workflows/mujoco_nightly_and_code_checks.yml @@ -1,9 +1,9 @@ name: mujoco_nightly_and_code_checks on: - pull_request: - branches: [main] - types: [ready_for_review] + # pull_request: + # branches: [main] + # types: [ready_for_review] jobs: first: From 21bb4a999e05e4c68f6f2f98bd27c9d4157a885f Mon Sep 17 00:00:00 2001 From: alberthli Date: Sat, 11 Nov 2023 13:02:46 -0800 Subject: [PATCH 58/79] hopefully better find functionality for getting cached wheels --- .github/workflows/mujoco_nightly.yml | 4 +-- .../mujoco_nightly_and_code_checks.yml | 26 +++++++++---------- 2 files changed, 15 insertions(+), 15 deletions(-) diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml index 32c8daa0..a384429e 100644 --- a/.github/workflows/mujoco_nightly.yml +++ b/.github/workflows/mujoco_nightly.yml @@ -111,8 +111,8 @@ jobs: # Checks the git hash of the cached files vs. the most recent one LATEST_GIT_HASH=$(git ls-remote https://github.com/google-deepmind/mujoco HEAD | awk '{ print $1}') - mujoco_whl_path=$(find ${{ github.workspace }} -type f -name "mujoco_wheel-*.whl" -print -quit) - mjx_whl_path=$(find ${{ github.workspace }} -type f -name "mujoco_wheel-*.whl" -print -quit) + mujoco_whl_path=$(find ${{ github.workspace }} -name "mujoco_wheel-*.whl" -print -quit) + mjx_whl_path=$(find ${{ github.workspace }} -name "mujoco_wheel-*.whl" -print -quit) echo "[DEBUG] mujoco_whl_path: $mujoco_whl_path" echo "[DEBUG] mjx_whl_path: $mjx_whl_path" diff --git a/.github/workflows/mujoco_nightly_and_code_checks.yml b/.github/workflows/mujoco_nightly_and_code_checks.yml index b2619ad3..8fa06327 100644 --- a/.github/workflows/mujoco_nightly_and_code_checks.yml +++ b/.github/workflows/mujoco_nightly_and_code_checks.yml @@ -1,16 +1,16 @@ -name: mujoco_nightly_and_code_checks +# name: mujoco_nightly_and_code_checks -on: - # pull_request: - # branches: [main] - # types: [ready_for_review] +# on: +# pull_request: +# branches: [main] +# types: [ready_for_review] -jobs: - first: - name: Build MuJoCo Nightly Release - uses: ./.github/workflows/mujoco_nightly.yml +# jobs: +# first: +# name: Build MuJoCo Nightly Release +# uses: ./.github/workflows/mujoco_nightly.yml - second: - name: Code Checks - needs: first - uses: ./.github/workflows/code_checks.yml \ No newline at end of file +# second: +# name: Code Checks +# needs: first +# uses: ./.github/workflows/code_checks.yml \ No newline at end of file From c5a3a9d9b6b3f23da6ae442752fbe42a43ab81cc Mon Sep 17 00:00:00 2001 From: alberthli Date: Sat, 11 Nov 2023 13:08:34 -0800 Subject: [PATCH 59/79] try again with searching for file --- .github/workflows/mujoco_nightly.yml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml index a384429e..a6f91fbe 100644 --- a/.github/workflows/mujoco_nightly.yml +++ b/.github/workflows/mujoco_nightly.yml @@ -111,8 +111,8 @@ jobs: # Checks the git hash of the cached files vs. the most recent one LATEST_GIT_HASH=$(git ls-remote https://github.com/google-deepmind/mujoco HEAD | awk '{ print $1}') - mujoco_whl_path=$(find ${{ github.workspace }} -name "mujoco_wheel-*.whl" -print -quit) - mjx_whl_path=$(find ${{ github.workspace }} -name "mujoco_wheel-*.whl" -print -quit) + mujoco_whl_path=$(find ${{ github.workspace }}/mujoco_wheel -name "mujoco_wheel-*.whl") + mjx_whl_path=$(find ${{ github.workspace }}/mjx_wheel -name "mujoco_wheel-*.whl") echo "[DEBUG] mujoco_whl_path: $mujoco_whl_path" echo "[DEBUG] mjx_whl_path: $mjx_whl_path" From e3997550e6f533a06b41d59f614299309438d0b0 Mon Sep 17 00:00:00 2001 From: alberthli Date: Sat, 11 Nov 2023 13:16:35 -0800 Subject: [PATCH 60/79] fix find command again --- .github/workflows/mujoco_nightly.yml | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml index a6f91fbe..a8394157 100644 --- a/.github/workflows/mujoco_nightly.yml +++ b/.github/workflows/mujoco_nightly.yml @@ -111,10 +111,8 @@ jobs: # Checks the git hash of the cached files vs. the most recent one LATEST_GIT_HASH=$(git ls-remote https://github.com/google-deepmind/mujoco HEAD | awk '{ print $1}') - mujoco_whl_path=$(find ${{ github.workspace }}/mujoco_wheel -name "mujoco_wheel-*.whl") - mjx_whl_path=$(find ${{ github.workspace }}/mjx_wheel -name "mujoco_wheel-*.whl") - echo "[DEBUG] mujoco_whl_path: $mujoco_whl_path" - echo "[DEBUG] mjx_whl_path: $mjx_whl_path" + mujoco_whl_path=$(find ${{ github.workspace }} -name "mujoco-*.whl") + mjx_whl_path=$(find ${{ github.workspace }} -name "mujoco_mjx-*.whl") if [ -n "$filename" ]; then # if the file name exists, extract the git hash and compare to upstream mujoco From 6b06288e636e1955445793e6667045990c196273 Mon Sep 17 00:00:00 2001 From: alberthli Date: Sat, 11 Nov 2023 13:22:48 -0800 Subject: [PATCH 61/79] wrong variable name fixed --- .github/workflows/mujoco_nightly.yml | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml index a8394157..9d576984 100644 --- a/.github/workflows/mujoco_nightly.yml +++ b/.github/workflows/mujoco_nightly.yml @@ -114,9 +114,14 @@ jobs: mujoco_whl_path=$(find ${{ github.workspace }} -name "mujoco-*.whl") mjx_whl_path=$(find ${{ github.workspace }} -name "mujoco_mjx-*.whl") - if [ -n "$filename" ]; then + echo "[DEBUG] LATEST_GIT_HASH: $LATEST_GIT_HASH" + echo "[DEBUG] mujoco_whl_path: $mujoco_whl_path" + echo "[DEBUG] mjx_whl_path: $mjx_whl_path" + + if [ -n "$mujoco_whl_path" ]; then # if the file name exists, extract the git hash and compare to upstream mujoco - CACHED_GIT_HASH=$(echo "$filename" | awk -F'mujoco_wheel-' '{print $2}' | awk -F'.' '{print $1}') + CACHED_GIT_HASH=$(echo "$mujoco_whl_path" | awk -F'mujoco-' '{print $2}' | awk -F'.' '{print NF>1?$NF:$(NF-1)}') + echo "[DEBUG] CACHED_GIT_HASH: $CACHED_GIT_HASH" if [ "$LATEST_GIT_HASH" = "$CACHED_GIT_HASH" ]; then echo "Cached wheel matches most recent one - skipping build! Hash: $CACHED_GIT_HASH" echo "skip_build=true" >> $GITHUB_ENV From 959fcc8ce9ca110623ff28ee53328dfe540100a3 Mon Sep 17 00:00:00 2001 From: alberthli Date: Sat, 11 Nov 2023 13:36:16 -0800 Subject: [PATCH 62/79] try again with extracting the cached hash --- .github/workflows/mujoco_nightly.yml | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml index 9d576984..4e0353ce 100644 --- a/.github/workflows/mujoco_nightly.yml +++ b/.github/workflows/mujoco_nightly.yml @@ -120,8 +120,7 @@ jobs: if [ -n "$mujoco_whl_path" ]; then # if the file name exists, extract the git hash and compare to upstream mujoco - CACHED_GIT_HASH=$(echo "$mujoco_whl_path" | awk -F'mujoco-' '{print $2}' | awk -F'.' '{print NF>1?$NF:$(NF-1)}') - echo "[DEBUG] CACHED_GIT_HASH: $CACHED_GIT_HASH" + CACHED_GIT_HASH=$(echo "$mujoco_whl_path" | grep -oP "mujoco_wheel-\K[^/]+") if [ "$LATEST_GIT_HASH" = "$CACHED_GIT_HASH" ]; then echo "Cached wheel matches most recent one - skipping build! Hash: $CACHED_GIT_HASH" echo "skip_build=true" >> $GITHUB_ENV From 0ce392b8fc8f79b8f9187dc4460b89bf973b6227 Mon Sep 17 00:00:00 2001 From: alberthli Date: Sat, 11 Nov 2023 13:41:05 -0800 Subject: [PATCH 63/79] fixed pip install path --- .github/workflows/code_checks.yml | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/.github/workflows/code_checks.yml b/.github/workflows/code_checks.yml index de605f0e..a46b5861 100644 --- a/.github/workflows/code_checks.yml +++ b/.github/workflows/code_checks.yml @@ -62,8 +62,10 @@ jobs: run: | python -m pip install --upgrade pip bash ./install.sh -d - pip install --no-deps --force-reinstall mujoco_wheel/mujoco-*.whl - pip install --no-deps --force-reinstall mjx_wheel/mujoco_mjx-*.whl + mujoco_whl_path=$(find ${{ github.workspace }} -name "mujoco-*.whl") + mjx_whl_path=$(find ${{ github.workspace }} -name "mujoco_mjx-*.whl") + pip install --no-deps --force-reinstall $mujoco_whl_path + pip install --no-deps --force-reinstall $mjx_whl_path - name: Run black shell: bash -l {0} run: black --check . From 2e610121d469a19334f94e285c8c2641d479bcc6 Mon Sep 17 00:00:00 2001 From: alberthli Date: Sat, 11 Nov 2023 13:42:37 -0800 Subject: [PATCH 64/79] add back reusable workflow --- .../mujoco_nightly_and_code_checks.yml | 26 +++++++++---------- 1 file changed, 13 insertions(+), 13 deletions(-) diff --git a/.github/workflows/mujoco_nightly_and_code_checks.yml b/.github/workflows/mujoco_nightly_and_code_checks.yml index 8fa06327..16143fc4 100644 --- a/.github/workflows/mujoco_nightly_and_code_checks.yml +++ b/.github/workflows/mujoco_nightly_and_code_checks.yml @@ -1,16 +1,16 @@ -# name: mujoco_nightly_and_code_checks +name: mujoco_nightly_and_code_checks -# on: -# pull_request: -# branches: [main] -# types: [ready_for_review] +on: + pull_request: + branches: [main] + types: [ready_for_review] -# jobs: -# first: -# name: Build MuJoCo Nightly Release -# uses: ./.github/workflows/mujoco_nightly.yml +jobs: + first: + name: Build MuJoCo Nightly Release + uses: ./.github/workflows/mujoco_nightly.yml -# second: -# name: Code Checks -# needs: first -# uses: ./.github/workflows/code_checks.yml \ No newline at end of file + second: + name: Code Checks + needs: first + uses: ./.github/workflows/code_checks.yml \ No newline at end of file From f6f968e3dad642ad8ce5f026efbae16016dc448f Mon Sep 17 00:00:00 2001 From: alberthli Date: Sat, 11 Nov 2023 13:50:02 -0800 Subject: [PATCH 65/79] debug: scheduled nightly build --- .github/workflows/mujoco_nightly.yml | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml index 4e0353ce..ece1df94 100644 --- a/.github/workflows/mujoco_nightly.yml +++ b/.github/workflows/mujoco_nightly.yml @@ -2,11 +2,11 @@ name: Build Nightly MuJoCo Release on: schedule: - - cron: "53 4 * * *" # runs at 4:53AM every day - avoid high load on the hour + - cron: "53 21 * * *" # [DEBUG] runs at 1:53PMPST every day - avoid high load on the hour workflow_call: - pull_request: # [DEBUG] - branches: [main] - types: [ready_for_review] + # pull_request: # [DEBUG] + # branches: [main] + # types: [ready_for_review] jobs: build-and-package: From d4483c0d9d2ebaf6d92dc7bf86815da5235ac046 Mon Sep 17 00:00:00 2001 From: alberthli Date: Sat, 11 Nov 2023 13:53:02 -0800 Subject: [PATCH 66/79] conditional mujoco upgrade - only if no wheels were downloaded --- .github/workflows/code_checks.yml | 27 +++++++++++------------- .github/workflows/mujoco_nightly.yml | 31 +--------------------------- 2 files changed, 13 insertions(+), 45 deletions(-) diff --git a/.github/workflows/code_checks.yml b/.github/workflows/code_checks.yml index a46b5861..585c7f1e 100644 --- a/.github/workflows/code_checks.yml +++ b/.github/workflows/code_checks.yml @@ -23,49 +23,46 @@ jobs: restore-keys: | ${{ runner.os }}-pip- - # get the most recent run ID associated with mujoco nightly - # - name: Get Recent Run ID - # id: get_run_id - # run: | - # response=$(curl -s -H "Authorization: Bearer ${{ secrets.GITHUB_TOKEN }}" \ - # "https://api.github.com/repos/${{ github.repository }}/actions/workflows/mujoco_nightly.yml/runs") - # echo "::set-output name=run_id::$(echo "$response" | jq -r '.workflow_runs[0].id')" - # - name: Print Recent Run ID - # run: | - # echo "[DEBUG] Most recent run ID: ${{ steps.get_run_id.outputs.run_id }}" - + # download the cached artifacts - name: Download mujoco artifact id: download-artifact-mujoco uses: dawidd6/action-download-artifact@v2 with: workflow: mujoco_nightly.yml - # run_id: ${{ steps.get_run_id.outputs.run_id }} name_is_regexp: true name: "mujoco_wheel-*" path: ${{ github.workspace }} check_artifacts: true search_artifacts: true + if_no_artifact_found: warn - name: Download mjx artifact id: download-artifact-mjx uses: dawidd6/action-download-artifact@v2 with: workflow: mujoco_nightly.yml - # run_id: ${{ steps.get_run_id.outputs.run_id }} name_is_regexp: true name: "mjx_wheel-*" path: ${{ github.workspace }} check_artifacts: true search_artifacts: true + if_no_artifact_found: warn - name: Install dependencies working-directory: ${{ github.workspace }} shell: bash -l {0} run: | python -m pip install --upgrade pip bash ./install.sh -d + + # upgrade mujoco to be installed from source mujoco_whl_path=$(find ${{ github.workspace }} -name "mujoco-*.whl") mjx_whl_path=$(find ${{ github.workspace }} -name "mujoco_mjx-*.whl") - pip install --no-deps --force-reinstall $mujoco_whl_path - pip install --no-deps --force-reinstall $mjx_whl_path + if [ -n "$mujoco_whl_path" ]; then + pip install --no-deps --force-reinstall $mujoco_whl_path + fi + if [ -n "$mjx_whl_path" ]; then + pip install --no-deps --force-reinstall $mjx_whl_path + fi + - name: Run black shell: bash -l {0} run: black --check . diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml index ece1df94..e0aed802 100644 --- a/.github/workflows/mujoco_nightly.yml +++ b/.github/workflows/mujoco_nightly.yml @@ -2,7 +2,7 @@ name: Build Nightly MuJoCo Release on: schedule: - - cron: "53 21 * * *" # [DEBUG] runs at 1:53PMPST every day - avoid high load on the hour + - cron: "53 21 * * *" # [DEBUG] runs at 1:53PM PST every day - avoid high load on the hour workflow_call: # pull_request: # [DEBUG] # branches: [main] @@ -49,35 +49,6 @@ jobs: mamba env update -n ambersim -f environment.yml if: steps.cache.outputs.cache-hit != 'true' - # get the most recent run ID associated with mujoco nightly - # - name: Get Recent Run ID for mujoco_nightly.yml - # id: get_run_id_workflow1 - # run: | - # response=$(curl -s -H "Authorization: Bearer ${{ secrets.GITHUB_TOKEN }}" \ - # "https://api.github.com/repos/${{ github.repository }}/actions/workflows/mujoco_nightly.yml/runs") - # echo "::set-output name=run_id_workflow1::$(echo "$response" | jq -r '.workflow_runs[0].id')" - # echo "[DEBUG] Most recent run ID for mujoco_nightly.yml: ${{ steps.get_run_id_workflow1.outputs.run_id }}" - - # - name: Get Recent Run ID for mujoco_nightly_and_code_checks.yml - # id: get_run_id_workflow2 - # run: | - # response=$(curl -s -H "Authorization: Bearer ${{ secrets.GITHUB_TOKEN }}" \ - # "https://api.github.com/repos/${{ github.repository }}/actions/workflows/mujoco_nightly_and_code_checks.yml/runs") - # echo "::set-output name=run_id_workflow2::$(echo "$response" | jq -r '.workflow_runs[0].id')" - # echo "[DEBUG] Most recent run ID for mujoco_nightly_and_code_checks.yml: ${{ steps.get_run_id_workflow2.outputs.run_id }}" - - # - name: Compare Run IDs - # run: | - # run_id_workflow1="${{ steps.get_run_id_workflow1.outputs.run_id }}" - # run_id_workflow2="${{ steps.get_run_id_workflow2.outputs.run_id }}" - - # if [ "$run_id_workflow1" -gt "$run_id_workflow2" ]; then - # most_recent_run_id="$run_id_workflow1" - # else - # most_recent_run_id="$run_id_workflow2" - # fi - # echo "run_id=$most_recent_run_id" >> $GITHUB_ENV - # download previously built mujoco and mjx artifacts - name: Download mujoco artifact id: download-artifact-mujoco From 3ae83d2b9fc499360319a9d388f6a999d302020c Mon Sep 17 00:00:00 2001 From: alberthli Date: Sat, 11 Nov 2023 15:01:15 -0800 Subject: [PATCH 67/79] try sharing artifact between two jobs in the same workflow --- .github/workflows/mujoco_nightly.yml | 26 ++++++++----------- .../mujoco_nightly_and_code_checks.yml | 26 +++++++++---------- 2 files changed, 24 insertions(+), 28 deletions(-) diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml index e0aed802..771b2e99 100644 --- a/.github/workflows/mujoco_nightly.yml +++ b/.github/workflows/mujoco_nightly.yml @@ -2,11 +2,11 @@ name: Build Nightly MuJoCo Release on: schedule: - - cron: "53 21 * * *" # [DEBUG] runs at 1:53PM PST every day - avoid high load on the hour + - cron: "53 12 * * *" # runs at 4:53AM PST every day - avoid high load on the hour workflow_call: - # pull_request: # [DEBUG] - # branches: [main] - # types: [ready_for_review] + pull_request: # [DEBUG] + branches: [main] + types: [ready_for_review] jobs: build-and-package: @@ -55,7 +55,6 @@ jobs: uses: dawidd6/action-download-artifact@v2 with: workflow: mujoco_nightly.yml - # run_id: ${{ steps.get_run_id.outputs.run_id }} name_is_regexp: true name: "mujoco_wheel-*" path: ${{ github.workspace }} @@ -67,7 +66,6 @@ jobs: uses: dawidd6/action-download-artifact@v2 with: workflow: mujoco_nightly.yml - # run_id: ${{ steps.get_run_id.outputs.run_id }} name_is_regexp: true name: "mjx_wheel-*" path: ${{ github.workspace }} @@ -85,10 +83,6 @@ jobs: mujoco_whl_path=$(find ${{ github.workspace }} -name "mujoco-*.whl") mjx_whl_path=$(find ${{ github.workspace }} -name "mujoco_mjx-*.whl") - echo "[DEBUG] LATEST_GIT_HASH: $LATEST_GIT_HASH" - echo "[DEBUG] mujoco_whl_path: $mujoco_whl_path" - echo "[DEBUG] mjx_whl_path: $mjx_whl_path" - if [ -n "$mujoco_whl_path" ]; then # if the file name exists, extract the git hash and compare to upstream mujoco CACHED_GIT_HASH=$(echo "$mujoco_whl_path" | grep -oP "mujoco_wheel-\K[^/]+") @@ -96,11 +90,9 @@ jobs: echo "Cached wheel matches most recent one - skipping build! Hash: $CACHED_GIT_HASH" echo "skip_build=true" >> $GITHUB_ENV - # names of the wheels + # save the names and filepaths so we can just re-upload them echo "mujoco_name=mujoco_wheel-${LATEST_GIT_HASH}" >> $GITHUB_ENV echo "mjx_name=mjx_wheel-${LATEST_GIT_HASH}" >> $GITHUB_ENV - - # paths to the wheels echo "mujoco_path=$(realpath $mujoco_whl_path)" >> $GITHUB_ENV echo "mjx_path=$(realpath $mjx_whl_path)" >> $GITHUB_ENV else @@ -142,7 +134,6 @@ jobs: id: package if: env.skip_build != 'true' - # [TODO] if skip_build, then reupload the cached artifacts - name: Upload mujoco artifact uses: actions/upload-artifact@v3 with: @@ -155,4 +146,9 @@ jobs: with: name: ${{ env.mjx_name }} path: ${{ env.mjx_path }} - retention-days: 7 \ No newline at end of file + retention-days: 7 + + test_nightly: + name: Code Checks + needs: build-and-package + uses: ./.github/workflows/code_checks.yml \ No newline at end of file diff --git a/.github/workflows/mujoco_nightly_and_code_checks.yml b/.github/workflows/mujoco_nightly_and_code_checks.yml index 16143fc4..8fa06327 100644 --- a/.github/workflows/mujoco_nightly_and_code_checks.yml +++ b/.github/workflows/mujoco_nightly_and_code_checks.yml @@ -1,16 +1,16 @@ -name: mujoco_nightly_and_code_checks +# name: mujoco_nightly_and_code_checks -on: - pull_request: - branches: [main] - types: [ready_for_review] +# on: +# pull_request: +# branches: [main] +# types: [ready_for_review] -jobs: - first: - name: Build MuJoCo Nightly Release - uses: ./.github/workflows/mujoco_nightly.yml +# jobs: +# first: +# name: Build MuJoCo Nightly Release +# uses: ./.github/workflows/mujoco_nightly.yml - second: - name: Code Checks - needs: first - uses: ./.github/workflows/code_checks.yml \ No newline at end of file +# second: +# name: Code Checks +# needs: first +# uses: ./.github/workflows/code_checks.yml \ No newline at end of file From 1cf1c2156c334c08994e4351e3a3f3c0486d27f4 Mon Sep 17 00:00:00 2001 From: alberthli Date: Sat, 11 Nov 2023 15:08:51 -0800 Subject: [PATCH 68/79] removed two-stage nightly builds, allow mujoco to build when ready for review --- .github/workflows/mujoco_nightly.yml | 9 ++------- .../workflows/mujoco_nightly_and_code_checks.yml | 16 ---------------- 2 files changed, 2 insertions(+), 23 deletions(-) delete mode 100644 .github/workflows/mujoco_nightly_and_code_checks.yml diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml index 771b2e99..dd2d2994 100644 --- a/.github/workflows/mujoco_nightly.yml +++ b/.github/workflows/mujoco_nightly.yml @@ -4,9 +4,9 @@ on: schedule: - cron: "53 12 * * *" # runs at 4:53AM PST every day - avoid high load on the hour workflow_call: - pull_request: # [DEBUG] + pull_request: branches: [main] - types: [ready_for_review] + types: [ready_for_review] # also caches when a PR is ready for review jobs: build-and-package: @@ -147,8 +147,3 @@ jobs: name: ${{ env.mjx_name }} path: ${{ env.mjx_path }} retention-days: 7 - - test_nightly: - name: Code Checks - needs: build-and-package - uses: ./.github/workflows/code_checks.yml \ No newline at end of file diff --git a/.github/workflows/mujoco_nightly_and_code_checks.yml b/.github/workflows/mujoco_nightly_and_code_checks.yml deleted file mode 100644 index 8fa06327..00000000 --- a/.github/workflows/mujoco_nightly_and_code_checks.yml +++ /dev/null @@ -1,16 +0,0 @@ -# name: mujoco_nightly_and_code_checks - -# on: -# pull_request: -# branches: [main] -# types: [ready_for_review] - -# jobs: -# first: -# name: Build MuJoCo Nightly Release -# uses: ./.github/workflows/mujoco_nightly.yml - -# second: -# name: Code Checks -# needs: first -# uses: ./.github/workflows/code_checks.yml \ No newline at end of file From 3e925d6fa2e8172699681af167038a15d27248c3 Mon Sep 17 00:00:00 2001 From: alberthli Date: Sat, 11 Nov 2023 15:30:42 -0800 Subject: [PATCH 69/79] clean up workflows + add some comments --- .github/workflows/code_checks.yml | 9 ++++++--- .github/workflows/mujoco_nightly.yml | 20 ++++++++++++++------ 2 files changed, 20 insertions(+), 9 deletions(-) diff --git a/.github/workflows/code_checks.yml b/.github/workflows/code_checks.yml index 585c7f1e..fba9a1d8 100644 --- a/.github/workflows/code_checks.yml +++ b/.github/workflows/code_checks.yml @@ -5,7 +5,6 @@ on: branches: [main] pull_request: branches: [main] - workflow_call: permissions: contents: read @@ -15,7 +14,10 @@ jobs: runs-on: ubuntu-latest steps: + # checks out ambersim - uses: actions/checkout@v4 + + # checks the cache for pip packages - uses: actions/cache@v3 with: path: ~/.cache/pip @@ -51,9 +53,9 @@ jobs: shell: bash -l {0} run: | python -m pip install --upgrade pip - bash ./install.sh -d + bash ./install.sh -d # -d means dev, don't use -s because we manually install mj/mjx from source here - # upgrade mujoco to be installed from source + # upgrade mujoco to use nightly build mujoco_whl_path=$(find ${{ github.workspace }} -name "mujoco-*.whl") mjx_whl_path=$(find ${{ github.workspace }} -name "mujoco_mjx-*.whl") if [ -n "$mujoco_whl_path" ]; then @@ -63,6 +65,7 @@ jobs: pip install --no-deps --force-reinstall $mjx_whl_path fi + # run all code checks - name: Run black shell: bash -l {0} run: black --check . diff --git a/.github/workflows/mujoco_nightly.yml b/.github/workflows/mujoco_nightly.yml index dd2d2994..18886d2c 100644 --- a/.github/workflows/mujoco_nightly.yml +++ b/.github/workflows/mujoco_nightly.yml @@ -3,7 +3,6 @@ name: Build Nightly MuJoCo Release on: schedule: - cron: "53 12 * * *" # runs at 4:53AM PST every day - avoid high load on the hour - workflow_call: pull_request: branches: [main] types: [ready_for_review] # also caches when a PR is ready for review @@ -13,8 +12,11 @@ jobs: runs-on: ubuntu-latest steps: + # checks out ambersim - name: Checkout code uses: actions/checkout@v4 + + # frees up space in the runner, since there's not enough disk space to build mujoco from source - name: Free Up GitHub Actions Ubuntu Runner Disk Space 🔧 uses: jlumbroso/free-disk-space@main with: @@ -25,7 +27,7 @@ jobs: large-packages: false # doesn't save that much space relatively, takes long to run swap-storage: false # removes a lot of space, but unnecessary here. skip to save time. - # for caching the conda env + # for caching the conda env - re-updates the env every 24 hours just in case # see: https://github.com/conda-incubator/setup-miniconda#caching-environments - name: Setup Mambaforge uses: conda-incubator/setup-miniconda@v2 @@ -34,6 +36,10 @@ jobs: miniforge-version: latest activate-environment: anaconda-client-env use-mamba: true + - name: Get Date + id: get-date + run: echo "today=$(/bin/date -u '+%Y%m%d')" >> $GITHUB_OUTPUT + shell: bash - name: Cache conda uses: actions/cache@v3 env: @@ -41,13 +47,15 @@ jobs: with: path: ${{ env.CONDA }}/envs key: - ${{ runner.os }}-conda-${{ env.CACHE_NUMBER }}-${{ - hashFiles('environment.yml') }} + conda-${{ runner.os }}--${{ runner.arch }}--${{ + steps.get-date.outputs.today }}-${{ + hashFiles('etc/example-environment-caching.yml') }}-${{ env.CACHE_NUMBER + }} id: cache - name: Update environment run: mamba env update -n ambersim -f environment.yml - if: steps.cache.outputs.cache-hit != 'true' + if: steps.cache.outputs.cache-hit != 'true' # only re-initializes the environment if we don't get a cache hit # download previously built mujoco and mjx artifacts - name: Download mujoco artifact @@ -128,12 +136,12 @@ jobs: # Appending the relevant git commit hash to the artifact name LATEST_GIT_HASH=$(git ls-remote https://github.com/google-deepmind/mujoco HEAD | awk '{ print $1}') - echo "[DEBUG] LATEST_GIT_HASH: $LATEST_GIT_HASH" echo "mujoco_name=mujoco_wheel-${LATEST_GIT_HASH}" >> $GITHUB_ENV echo "mjx_name=mjx_wheel-${LATEST_GIT_HASH}" >> $GITHUB_ENV id: package if: env.skip_build != 'true' + # upload the built wheels as artifacts - name: Upload mujoco artifact uses: actions/upload-artifact@v3 with: From 7896095510f7eaa33246664fa04a2a50cc4aebbe Mon Sep 17 00:00:00 2001 From: alberthli Date: Sat, 11 Nov 2023 15:34:40 -0800 Subject: [PATCH 70/79] very minor README update --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 439b55d5..38fafcfe 100644 --- a/README.md +++ b/README.md @@ -51,7 +51,7 @@ pip show mujoco-mjx ### Abridged Dev Guidelines Development on this code will be controlled via code review. To facilitate this, please follow these guidelines: * keep your pull requests small so that it's practical to human review them; -* try to create _draft pull requests_ instead of regular ones and request reviews from relevant people only when ready - we rebuild `mujoco` from source and run the branch tests when this happens; +* try to create _draft pull requests_ instead of regular ones and request reviews from relevant people only when ready - we rebuild `mujoco` from source when this happens; * write tests as you go (and if you are reviewing, suggest missing tests); * write docstrings for public classes and methods, even if it's just a one-liner; * before committing, make sure you locally pass all tests by running `pytest` in the repo root; From 64d2225f473a123d6f55fa54c17ac8affd253ccb Mon Sep 17 00:00:00 2001 From: alberthli Date: Sat, 11 Nov 2023 15:54:19 -0800 Subject: [PATCH 71/79] added additional test to ensure that the actuators in the XML and URDF are the same --- ambersim/utils/introspection_utils.py | 7 +++++++ tests/test_model_io.py | 23 +++++++++++++++++++---- 2 files changed, 26 insertions(+), 4 deletions(-) diff --git a/ambersim/utils/introspection_utils.py b/ambersim/utils/introspection_utils.py index 549b3e14..70bc1971 100644 --- a/ambersim/utils/introspection_utils.py +++ b/ambersim/utils/introspection_utils.py @@ -2,6 +2,13 @@ import mujoco as mj +"""Useful utils for introspecting a mujoco model.""" + + +def get_actuator_names(model: mj.MjModel) -> List[str]: + """Returns a list of all actuator names in a mujoco (NOT mjx) model.""" + return [mj.mj_id2name(model, mj.mjtObj.mjOBJ_ACTUATOR, i) for i in range(model.nu)] + def get_geom_names(model: mj.MjModel) -> List[str]: """Returns a list of all geom names in a mujoco (NOT mjx) model.""" diff --git a/tests/test_model_io.py b/tests/test_model_io.py index 1736033a..f76bba77 100644 --- a/tests/test_model_io.py +++ b/tests/test_model_io.py @@ -11,8 +11,13 @@ from ambersim import ROOT from ambersim.utils._internal_utils import _rmtree from ambersim.utils.conversion_utils import convex_decomposition_file, save_model_xml -from ambersim.utils.introspection_utils import get_joint_names -from ambersim.utils.io_utils import _modify_robot_float_base, load_mjx_model_and_data_from_file +from ambersim.utils.introspection_utils import get_actuator_names, get_joint_names +from ambersim.utils.io_utils import ( + _modify_robot_float_base, + load_mj_model_from_file, + load_mjx_model_and_data_from_file, + mj_to_mjx_model_and_data, +) def test_load_model(): @@ -63,12 +68,22 @@ def test_actuators(): # loading the URDF and checking the number of transmissions it has with open(urdf_filepath, "r") as f: urdf_tree = etree.XML(f.read(), etree.XMLParser(remove_blank_text=True, recover=True)) - num_actuators = len(urdf_tree.findall("transmission")) + transmissions = urdf_tree.findall("transmission") + num_actuators = len(transmissions) # checking that the same file loaded into mjx has the same number of actuators - mjx_model, _ = load_mjx_model_and_data_from_file(urdf_filepath) + mj_model = load_mj_model_from_file(urdf_filepath) + mjx_model, _ = mj_to_mjx_model_and_data(mj_model) assert mjx_model.nu == num_actuators + # checking that each transmission has a corresponding actuator in the XML + # the actuators in the XML are named after the joints they actuate, so we can just check + # the joints in the transmission blocks of the URDF against the XML actuator names + xml_actuator_names = get_actuator_names(mj_model) + xml_actuated_joint_names = sorted([name.replace("_actuator", "") for name in xml_actuator_names]) + urdf_actuated_joint_names = sorted([t.find("joint").get("name") for t in transmissions]) + assert xml_actuated_joint_names == urdf_actuated_joint_names + def test_force_float(): """Tests the functionality of forcing models to have a floating base.""" From 56a1e7d32617a33d02d3f3cf55d2487c09de47ca Mon Sep 17 00:00:00 2001 From: alberthli Date: Sat, 11 Nov 2023 17:02:06 -0800 Subject: [PATCH 72/79] add parsing for mimic joints --- ambersim/utils/introspection_utils.py | 5 +++ ambersim/utils/io_utils.py | 51 +++++++++++++++++++++++++-- models/barrett_hand/bh280.xml | 12 +++++++ models/pendulum/pendulum.urdf | 11 ++++++ models/pendulum/pendulum.xml | 4 +++ tests/test_model_io.py | 28 +++++++++++++-- 6 files changed, 106 insertions(+), 5 deletions(-) diff --git a/ambersim/utils/introspection_utils.py b/ambersim/utils/introspection_utils.py index 70bc1971..4183b856 100644 --- a/ambersim/utils/introspection_utils.py +++ b/ambersim/utils/introspection_utils.py @@ -10,6 +10,11 @@ def get_actuator_names(model: mj.MjModel) -> List[str]: return [mj.mj_id2name(model, mj.mjtObj.mjOBJ_ACTUATOR, i) for i in range(model.nu)] +def get_equality_names(model: mj.MjModel) -> List[str]: + """Returns a list of all equality constraint names in a mujoco (NOT mjx) model.""" + return [mj.mj_id2name(model, mj.mjtObj.mjOBJ_EQUALITY, i) for i in range(model.neq)] + + def get_geom_names(model: mj.MjModel) -> List[str]: """Returns a list of all geom names in a mujoco (NOT mjx) model.""" return [mj.mj_id2name(model, mj.mjtObj.mjOBJ_GEOM, i) for i in range(model.ngeom)] diff --git a/ambersim/utils/io_utils.py b/ambersim/utils/io_utils.py index df8f60ec..ff9ee5d7 100644 --- a/ambersim/utils/io_utils.py +++ b/ambersim/utils/io_utils.py @@ -36,8 +36,7 @@ def _add_actuators(urdf_filepath: Union[str, Path], xml_filepath: Union[str, Pat # checking whether the XML has an actuator section already if xml_tree.find("actuator") is None: - actuator = etree.Element("actuator") - xml_tree.append(actuator) + xml_tree.append(etree.Element("actuator")) # getting transmission info from URDF and loading it into the XML actuators = xml_tree.find("actuator") @@ -70,6 +69,53 @@ def _add_actuators(urdf_filepath: Union[str, Path], xml_filepath: Union[str, Pat f.write(etree.tostring(xml_tree, pretty_print=True)) +def _add_mimics(urdf_filepath: Union[str, Path], xml_filepath: Union[str, Path]) -> None: + """Takes a URDF and a corresponding XML derived from it and adds mimic joints to the XML. + + This util is necessary because mujoco doesn't automatically add equality constraints for mimic joints. + + Args: + urdf_filepath: A path to a URDF file. + xml_filepath: A path to an XML file. + """ + # parsing URDF + # the recover=True keyword parses even after encountering invalid namespaces + # this is useful when, e.g., we have drake:declare_convex, which is not a valid namespace + with open(urdf_filepath, "r") as f: + urdf_tree = etree.XML(f.read(), etree.XMLParser(remove_blank_text=True, recover=True)) + + # parsing XML + with open(xml_filepath, "r") as f: + xml_tree = etree.XML(f.read(), etree.XMLParser(remove_blank_text=True)) + + # checking whether the XML has an equality section already + if xml_tree.find("equality") is None: + xml_tree.append(etree.Element("equality")) + + # getting mimic info from URDF and loading it into the XML + equality = xml_tree.find("equality") + for joint in urdf_tree.xpath("//joint[mimic]"): + joint1 = joint.get("name") # the joint that mimics + mimic = joint.find("mimic") # the mimic element + joint2 = mimic.get("joint") # the joint to mimic + multiplier = mimic.get("multiplier") if mimic.get("multiplier") is not None else 1 + offset = mimic.get("offset") if mimic.get("offset") is not None else 0 + + # adding the mimic joint + etree.SubElement( + equality, + "joint", + name=f"{joint1}_{joint2}_equality", + joint1=joint1, + joint2=joint2, + polycoef=f"{offset} {multiplier} 0 0 0", + ) + + # resaving the XML + with open(xml_filepath, "wb") as f: + f.write(etree.tostring(xml_tree, pretty_print=True)) + + def _modify_robot_float_base(filepath: Union[str, Path]) -> mj.MjModel: """Modifies a robot to have a floating base if it doesn't already.""" # loading current robot @@ -130,6 +176,7 @@ def load_mj_model_from_file( output_path = "/".join(str(filepath).split("/")[:-1]) + "/_temp_xml_model.xml" save_model_xml(filepath, output_path=output_path) _add_actuators(filepath, output_path) + _add_mimics(filepath, output_path) temp_output_path = True elif is_xml: output_path = filepath diff --git a/models/barrett_hand/bh280.xml b/models/barrett_hand/bh280.xml index 0e9a8e04..60240018 100644 --- a/models/barrett_hand/bh280.xml +++ b/models/barrett_hand/bh280.xml @@ -186,4 +186,16 @@ + + + + + + + + + + + + diff --git a/models/pendulum/pendulum.urdf b/models/pendulum/pendulum.urdf index a6fef884..9f16dd3a 100644 --- a/models/pendulum/pendulum.urdf +++ b/models/pendulum/pendulum.urdf @@ -43,4 +43,15 @@ + + transmission_interface/SimpleTransmission + + hardware_interface/PositionJointInterface + + + hardware_interface/PositionJointInterface + 1 + 1 + + \ No newline at end of file diff --git a/models/pendulum/pendulum.xml b/models/pendulum/pendulum.xml index 32c0b50c..92430d45 100644 --- a/models/pendulum/pendulum.xml +++ b/models/pendulum/pendulum.xml @@ -12,4 +12,8 @@ + + + + diff --git a/tests/test_model_io.py b/tests/test_model_io.py index f76bba77..ae323211 100644 --- a/tests/test_model_io.py +++ b/tests/test_model_io.py @@ -11,7 +11,7 @@ from ambersim import ROOT from ambersim.utils._internal_utils import _rmtree from ambersim.utils.conversion_utils import convex_decomposition_file, save_model_xml -from ambersim.utils.introspection_utils import get_actuator_names, get_joint_names +from ambersim.utils.introspection_utils import get_actuator_names, get_equality_names, get_joint_names from ambersim.utils.io_utils import ( _modify_robot_float_base, load_mj_model_from_file, @@ -73,8 +73,7 @@ def test_actuators(): # checking that the same file loaded into mjx has the same number of actuators mj_model = load_mj_model_from_file(urdf_filepath) - mjx_model, _ = mj_to_mjx_model_and_data(mj_model) - assert mjx_model.nu == num_actuators + assert mj_model.nu == num_actuators # checking that each transmission has a corresponding actuator in the XML # the actuators in the XML are named after the joints they actuate, so we can just check @@ -85,6 +84,29 @@ def test_actuators(): assert xml_actuated_joint_names == urdf_actuated_joint_names +def test_mimics(): + """Tests that mimic joints are added as equality constraints when converting from URDF to XML.""" + for urdf_filepath in Path(ROOT + "/models").rglob("*.urdf"): + # loading the URDF and checking the number of mimic joints it has + with open(urdf_filepath, "r") as f: + urdf_tree = etree.XML(f.read(), etree.XMLParser(remove_blank_text=True, recover=True)) + mimics = urdf_tree.xpath("//joint[mimic]") + num_mimics = len(mimics) + + # checking that the same file loaded into mjx has the same number of equality constraints + mj_model = load_mj_model_from_file(urdf_filepath) + assert mj_model.neq == num_mimics + + # checking that each mimic joint has a corresponding equality constraint in the XML + xml_equality_names = get_equality_names(mj_model) + for joint in urdf_tree.xpath("//joint[mimic]"): + joint1 = joint.get("name") # the joint that mimics + mimic = joint.find("mimic") # the mimic element + joint2 = mimic.get("joint") # the joint to mimic + eq_name = f"{joint1}_{joint2}_equality" + assert eq_name in xml_equality_names + + def test_force_float(): """Tests the functionality of forcing models to have a floating base.""" # case 1: model's first body has a joint, add a freejoint with dummy body From c6c59304581cfa9f8097fe08c70fef7885cc126d Mon Sep 17 00:00:00 2001 From: alberthli Date: Sat, 11 Nov 2023 17:34:22 -0800 Subject: [PATCH 73/79] for now, temporarily comment out the joint equality constraints in the barrett hand xml, since they weren't supported in the original mjx release --- models/barrett_hand/bh280.xml | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/models/barrett_hand/bh280.xml b/models/barrett_hand/bh280.xml index 60240018..0c422304 100644 --- a/models/barrett_hand/bh280.xml +++ b/models/barrett_hand/bh280.xml @@ -192,10 +192,12 @@ - + + From 37fd3e2a616dd2a3f29bfde68860e4a8a9d4928f Mon Sep 17 00:00:00 2001 From: alberthli Date: Sat, 11 Nov 2023 21:13:33 -0800 Subject: [PATCH 74/79] update pendulum to have capsules, add back in equality constraints for barrett hand --- models/barrett_hand/bh280.xml | 6 ++---- models/pendulum/pendulum.urdf | 16 +++++++++++----- models/pendulum/pendulum.xml | 17 ++++++++++------- 3 files changed, 23 insertions(+), 16 deletions(-) diff --git a/models/barrett_hand/bh280.xml b/models/barrett_hand/bh280.xml index 0c422304..60240018 100644 --- a/models/barrett_hand/bh280.xml +++ b/models/barrett_hand/bh280.xml @@ -192,12 +192,10 @@ - - + diff --git a/models/pendulum/pendulum.urdf b/models/pendulum/pendulum.urdf index 9f16dd3a..b1f0454d 100644 --- a/models/pendulum/pendulum.urdf +++ b/models/pendulum/pendulum.urdf @@ -10,8 +10,14 @@ - + + + + + + + @@ -19,19 +25,19 @@ - + - + - + @@ -40,7 +46,7 @@ - + diff --git a/models/pendulum/pendulum.xml b/models/pendulum/pendulum.xml index 92430d45..fa962023 100644 --- a/models/pendulum/pendulum.xml +++ b/models/pendulum/pendulum.xml @@ -2,13 +2,16 @@ - - - - - - - + + + + + + + From 0a91327c0bc3a6cddd5a8b1bf5ee3df89e92aa80 Mon Sep 17 00:00:00 2001 From: alberthli Date: Sat, 11 Nov 2023 21:51:05 -0800 Subject: [PATCH 75/79] commented out equality-constrained joints for now, since mjx is still bugged out on them --- ambersim/utils/io_utils.py | 2 +- models/barrett_hand/bh280.xml | 5 ++-- tests/test_model_io.py | 46 ++++++++++++++++++----------------- 3 files changed, 28 insertions(+), 25 deletions(-) diff --git a/ambersim/utils/io_utils.py b/ambersim/utils/io_utils.py index ff9ee5d7..a438775c 100644 --- a/ambersim/utils/io_utils.py +++ b/ambersim/utils/io_utils.py @@ -176,7 +176,7 @@ def load_mj_model_from_file( output_path = "/".join(str(filepath).split("/")[:-1]) + "/_temp_xml_model.xml" save_model_xml(filepath, output_path=output_path) _add_actuators(filepath, output_path) - _add_mimics(filepath, output_path) + # _add_mimics(filepath, output_path) # TODO(ahl): uncomment when eq cons on joints are supported temp_output_path = True elif is_xml: output_path = filepath diff --git a/models/barrett_hand/bh280.xml b/models/barrett_hand/bh280.xml index 60240018..817fc65d 100644 --- a/models/barrett_hand/bh280.xml +++ b/models/barrett_hand/bh280.xml @@ -192,10 +192,11 @@ - + + diff --git a/tests/test_model_io.py b/tests/test_model_io.py index ae323211..4a9c0c7d 100644 --- a/tests/test_model_io.py +++ b/tests/test_model_io.py @@ -48,7 +48,8 @@ def test_load_model(): def test_all_models(): """Tests the loading of all models in the repo.""" - filepaths = (p.resolve() for p in Path(ROOT + "/models").glob("**/*") if p.suffix in {".urdf", ".xml"}) + # filepaths = (p.resolve() for p in Path(ROOT + "/models").glob("**/*") if p.suffix in {".urdf", ".xml"}) + filepaths = (p.resolve() for p in Path(ROOT + "/models").glob("**/*") if p.suffix in {".xml"}) for filepath in filepaths: assert load_mjx_model_and_data_from_file(filepath) assert load_mjx_model_and_data_from_file(filepath, force_float=True) @@ -84,27 +85,28 @@ def test_actuators(): assert xml_actuated_joint_names == urdf_actuated_joint_names -def test_mimics(): - """Tests that mimic joints are added as equality constraints when converting from URDF to XML.""" - for urdf_filepath in Path(ROOT + "/models").rglob("*.urdf"): - # loading the URDF and checking the number of mimic joints it has - with open(urdf_filepath, "r") as f: - urdf_tree = etree.XML(f.read(), etree.XMLParser(remove_blank_text=True, recover=True)) - mimics = urdf_tree.xpath("//joint[mimic]") - num_mimics = len(mimics) - - # checking that the same file loaded into mjx has the same number of equality constraints - mj_model = load_mj_model_from_file(urdf_filepath) - assert mj_model.neq == num_mimics - - # checking that each mimic joint has a corresponding equality constraint in the XML - xml_equality_names = get_equality_names(mj_model) - for joint in urdf_tree.xpath("//joint[mimic]"): - joint1 = joint.get("name") # the joint that mimics - mimic = joint.find("mimic") # the mimic element - joint2 = mimic.get("joint") # the joint to mimic - eq_name = f"{joint1}_{joint2}_equality" - assert eq_name in xml_equality_names +# TODO(ahl): uncomment when equality-constrained joints are supported properly +# def test_mimics(): +# """Tests that mimic joints are added as equality constraints when converting from URDF to XML.""" +# for urdf_filepath in Path(ROOT + "/models").rglob("*.urdf"): +# # loading the URDF and checking the number of mimic joints it has +# with open(urdf_filepath, "r") as f: +# urdf_tree = etree.XML(f.read(), etree.XMLParser(remove_blank_text=True, recover=True)) +# mimics = urdf_tree.xpath("//joint[mimic]") +# num_mimics = len(mimics) + +# # checking that the same file loaded into mjx has the same number of equality constraints +# mj_model = load_mj_model_from_file(urdf_filepath) +# assert mj_model.neq == num_mimics + +# # checking that each mimic joint has a corresponding equality constraint in the XML +# xml_equality_names = get_equality_names(mj_model) +# for joint in urdf_tree.xpath("//joint[mimic]"): +# joint1 = joint.get("name") # the joint that mimics +# mimic = joint.find("mimic") # the mimic element +# joint2 = mimic.get("joint") # the joint to mimic +# eq_name = f"{joint1}_{joint2}_equality" +# assert eq_name in xml_equality_names def test_force_float(): From 430e78ad15eff0f7f0524b70d9de93c9157f5215 Mon Sep 17 00:00:00 2001 From: alberthli Date: Sat, 11 Nov 2023 22:00:57 -0800 Subject: [PATCH 76/79] changed comments to be about merging #21 instead of mistaken mjx bug --- ambersim/utils/io_utils.py | 2 +- models/barrett_hand/bh280.xml | 2 +- models/pendulum/pendulum.urdf | 16 +++++----------- models/pendulum/pendulum.xml | 17 +++++++---------- tests/test_model_io.py | 2 +- 5 files changed, 15 insertions(+), 24 deletions(-) diff --git a/ambersim/utils/io_utils.py b/ambersim/utils/io_utils.py index a438775c..22844f48 100644 --- a/ambersim/utils/io_utils.py +++ b/ambersim/utils/io_utils.py @@ -176,7 +176,7 @@ def load_mj_model_from_file( output_path = "/".join(str(filepath).split("/")[:-1]) + "/_temp_xml_model.xml" save_model_xml(filepath, output_path=output_path) _add_actuators(filepath, output_path) - # _add_mimics(filepath, output_path) # TODO(ahl): uncomment when eq cons on joints are supported + # _add_mimics(filepath, output_path) # TODO(ahl): uncomment when we merge #21 temp_output_path = True elif is_xml: output_path = filepath diff --git a/models/barrett_hand/bh280.xml b/models/barrett_hand/bh280.xml index 817fc65d..02aaefe5 100644 --- a/models/barrett_hand/bh280.xml +++ b/models/barrett_hand/bh280.xml @@ -192,7 +192,7 @@ - + @@ -25,19 +19,19 @@ - + - + - + @@ -46,7 +40,7 @@ - + diff --git a/models/pendulum/pendulum.xml b/models/pendulum/pendulum.xml index fa962023..92430d45 100644 --- a/models/pendulum/pendulum.xml +++ b/models/pendulum/pendulum.xml @@ -2,16 +2,13 @@ - - - - - - - + + + + + + + diff --git a/tests/test_model_io.py b/tests/test_model_io.py index 4a9c0c7d..2a069029 100644 --- a/tests/test_model_io.py +++ b/tests/test_model_io.py @@ -85,7 +85,7 @@ def test_actuators(): assert xml_actuated_joint_names == urdf_actuated_joint_names -# TODO(ahl): uncomment when equality-constrained joints are supported properly +# TODO(ahl): uncomment when we merge #21. # def test_mimics(): # """Tests that mimic joints are added as equality constraints when converting from URDF to XML.""" # for urdf_filepath in Path(ROOT + "/models").rglob("*.urdf"): From be6521473168ac5761109eed7fdbde4411d85bd8 Mon Sep 17 00:00:00 2001 From: alberthli Date: Sat, 11 Nov 2023 22:03:19 -0800 Subject: [PATCH 77/79] remove stray commented code --- tests/test_model_io.py | 1 - 1 file changed, 1 deletion(-) diff --git a/tests/test_model_io.py b/tests/test_model_io.py index 2a069029..26f95f57 100644 --- a/tests/test_model_io.py +++ b/tests/test_model_io.py @@ -48,7 +48,6 @@ def test_load_model(): def test_all_models(): """Tests the loading of all models in the repo.""" - # filepaths = (p.resolve() for p in Path(ROOT + "/models").glob("**/*") if p.suffix in {".urdf", ".xml"}) filepaths = (p.resolve() for p in Path(ROOT + "/models").glob("**/*") if p.suffix in {".xml"}) for filepath in filepaths: assert load_mjx_model_and_data_from_file(filepath) From ffc5a95166125bc686605e72459fbc8b841d46d9 Mon Sep 17 00:00:00 2001 From: alberthli Date: Sun, 12 Nov 2023 14:11:07 -0800 Subject: [PATCH 78/79] fixed adding the floating base joint + test random translations and rotations of it --- ambersim/utils/pin_utils.py | 9 +++++---- tests/test_kin_dyn.py | 17 +++++++++++++---- 2 files changed, 18 insertions(+), 8 deletions(-) diff --git a/ambersim/utils/pin_utils.py b/ambersim/utils/pin_utils.py index 2fdb8023..fb1a5a57 100644 --- a/ambersim/utils/pin_utils.py +++ b/ambersim/utils/pin_utils.py @@ -104,6 +104,7 @@ def mjx_qpos_to_pin(qpos_mjx: jax.Array, mjx_model: mjx.Model, mj2pin: List[int] startidx = mjx_model.jnt_qposadr[mj_idx] if jnt_type == 0: # FREE, 7-dimensional + # pinocchio uses the (x, y, z, w) convention _qpos_pin.append(qpos_mjx[startidx : startidx + 3]) quat_wxyz = qpos_mjx[startidx + 3 : startidx + 7] quat_xyzw = np.concatenate((quat_wxyz[1:], quat_wxyz[:1])) @@ -126,12 +127,12 @@ def mjx_qvel_to_pin(qvel_mjx: jax.Array, mjx_model: mjx.Model, mj2pin: List[int] Notice that there is one less coordinate for rotational velocities compared to quaternion coordinates. Args: - qvel_mjx: The mjx joint velocities. - mjx_model: The mjx model. - mj2pin: The mapping from mujoco joint order to pinocchio joint order. + qvel_mjx: The mjx joint velocities. + mjx_model: The mjx model. + mj2pin: The mapping from mujoco joint order to pinocchio joint order. Returns: - qvel_pin: The pinocchio joint velocities. + qvel_pin: The pinocchio joint velocities. """ qvel_mjx = np.array(qvel_mjx) _qvel_pin = [] diff --git a/tests/test_kin_dyn.py b/tests/test_kin_dyn.py index 802c50bf..1c911671 100644 --- a/tests/test_kin_dyn.py +++ b/tests/test_kin_dyn.py @@ -39,8 +39,8 @@ def shared_variables(): mj_joint_names = get_joint_names(mj_model) # loading pinocchio models - pin_model = pin.buildModelFromUrdf(urdf_path) - pin_model.addJoint(0, pin.JointModelFreeFlyer(), pin.SE3.Identity(), "freejoint") + pin_model = pin.buildModelFromUrdf(urdf_path, pin.JointModelFreeFlyer()) + pin_model.names[1] = "freejoint" # by default, adding a joint above names it "root_joint", so we rename it pin_data = pin_model.createData() pin_joint_names = list(pin_model.names) @@ -54,8 +54,17 @@ def shared_variables(): _qpos_mj.append([np.random.randn()]) # arbitrary else: # floating base state convention: (translation[x, y, z], quat[w, x, y, z]) - # TODO(ahl): also randomize rotation - _qpos_mj.append([np.random.randn(), np.random.randn(), np.random.randn(), 1.0, 0.0, 0.0, 0.0]) + _translation = np.random.randn(3) + _uvw = np.random.rand(3) + _quat = np.array( + [ + np.sqrt(1.0 - _uvw[0]) * np.sin(2 * np.pi * _uvw[1]), + np.sqrt(1.0 - _uvw[0]) * np.cos(2 * np.pi * _uvw[1]), + np.sqrt(_uvw[0]) * np.sin(2 * np.pi * _uvw[2]), + np.sqrt(_uvw[0]) * np.cos(2 * np.pi * _uvw[2]), + ] + ) # uniformly random quaternion: stackoverflow.com/a/44031492 + _qpos_mj.append(np.concatenate((_translation, _quat))) qpos_mjx = jnp.array(np.concatenate(_qpos_mj)) qpos_pin = mjx_qpos_to_pin(qpos_mjx, mjx_model, mj2pin) # accounts for potentially different joint ordering From 5a382347a8888c8dcbeba99189f6d00f929d4294 Mon Sep 17 00:00:00 2001 From: alberthli Date: Mon, 13 Nov 2023 09:54:12 -0800 Subject: [PATCH 79/79] [dirty] set up for dynamics test, need to figure out underactuated mimic joints in pinocchio --- tests/test_kin_dyn.py | 23 ++++++++++++++--------- 1 file changed, 14 insertions(+), 9 deletions(-) diff --git a/tests/test_kin_dyn.py b/tests/test_kin_dyn.py index 1c911671..02c8ddad 100644 --- a/tests/test_kin_dyn.py +++ b/tests/test_kin_dyn.py @@ -72,6 +72,11 @@ def shared_variables(): # qvel_mjx = jnp.array(np.random.randn(mjx_model.nv)) # qvel_pin = mjx_qvel_to_pin(qvel_mjx, mjx_model, mj2pin) # accounts for potentially different joint ordering + # # setting dummy torques + # qtau_mjx = jnp.array(np.random.randn(mjx_model.nu)) + # # [TODO] figure out how to deal with mimic joints in pinocchio + # breakpoint() + # return shared variables return ( mj_model, @@ -145,14 +150,14 @@ def test_fk(shared_variables): # def test_fd(shared_variables): # """Tests forward dynamics.""" -# # mj_model, mjx_model, mjx_data, mj_joint_names, pin_model, pin_data, pin_joint_names, qpos_mjx, qpos_pin, mj2pin, pin2mj = shared_variables +# mj_model, mjx_model, mjx_data, mj_joint_names, pin_model, pin_data, pin_joint_names, qpos_mjx, qpos_pin, mj2pin, pin2mj = shared_variables -# # # running FD test -# # -# # dv_mjx = np.array(mjx_data.qacc) +# # running FD test +# dv_mjx = np.array(mjx_data.qacc) +# mjx_data = mjx.forward(mjx_model, mjx_data.replace(qpos=qpos_mjx)) -# # M = pin.crba(pin_model, pin_data, qpos_pin)mjx_data = mjx.forward(mjx_model, mjx_data.replace(qpos=qpos_mjx)) -# # qvel_pin = np.zeros(pin_model.nv) # [TODO] make this more exotic -# # zero_accel = np.zeros(pin_model.nv) -# # tau0 = pin.rnea(pin_model, pin_data, qpos_pin, qvel_pin, zero_accel) -# # # [TODO] add applied forces tau to pinocchio and mjx for the test, check about gravity +# M = pin.crba(pin_model, pin_data, qpos_pin) +# qvel_pin = np.zeros(pin_model.nv) # [TODO] make this more exotic +# zero_accel = np.zeros(pin_model.nv) +# tau0 = pin.rnea(pin_model, pin_data, qpos_pin, qvel_pin, zero_accel) +# # [TODO] add applied forces tau to pinocchio and mjx for the test, check about gravity