Skip to content

Commit

Permalink
Merge branch 'main' into ce
Browse files Browse the repository at this point in the history
  • Loading branch information
erez-tom authored Feb 13, 2024
2 parents 6aa2db8 + 4384ef0 commit ed9e635
Show file tree
Hide file tree
Showing 5 changed files with 31 additions and 27 deletions.
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
.vs/
# Exclude temporary folders
*.egg-info/
.eggs/
build/
build_cmake/
# Exclude macOS folder attributes
Expand Down
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -110,7 +110,7 @@ We provide a simple Python API for MJPC. This API is still experimental and expe
- [direct.py](python/mujoco_mpc/direct.py) for available methods for direct optimization.

## Installing via Pip
The MJPC Python module can be installed with:
First, build MJPC (see above), then the MJPC Python module can be installed with:
```sh
python "${MUJOCO_MPC_ROOT}/python/${API}.py" install
```
Expand Down
34 changes: 17 additions & 17 deletions python/mujoco_mpc/agent_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ class AgentTest(parameterized.TestCase):
def test_set_task_parameters(self):
model_path = (
pathlib.Path(__file__).parent.parent.parent
/ "mjpc/tasks/cartpole/task.xml"
/ "build/mjpc/tasks/cartpole/task.xml"
)
model = mujoco.MjModel.from_xml_path(str(model_path))
with agent_lib.Agent(task_id="Cartpole", model=model) as agent:
Expand All @@ -56,7 +56,7 @@ def test_set_task_parameters(self):
def test_set_subprocess_working_dir(self):
model_path = (
pathlib.Path(__file__).parent.parent.parent
/ "mjpc/tasks/cartpole/task.xml"
/ "build/mjpc/tasks/cartpole/task.xml"
)
model = mujoco.MjModel.from_xml_path(str(model_path))

Expand All @@ -76,7 +76,7 @@ def test_set_subprocess_working_dir(self):
def test_step_env_with_planner(self):
model_path = (
pathlib.Path(__file__).parent.parent.parent
/ "mjpc/tasks/particle/task_timevarying.xml"
/ "build/mjpc/tasks/particle/task_timevarying.xml"
)
model = mujoco.MjModel.from_xml_path(str(model_path))
data = mujoco.MjData(model)
Expand Down Expand Up @@ -109,7 +109,7 @@ def test_step_env_with_planner(self):
def test_env_initialized_to_home_keyframe(self):
model_path = (
pathlib.Path(__file__).parent.parent.parent
/ "mjpc/tasks/quadruped/task_flat.xml"
/ "build/mjpc/tasks/quadruped/task_flat.xml"
)
model = mujoco.MjModel.from_xml_path(str(model_path))

Expand All @@ -126,7 +126,7 @@ def test_action_averaging_doesnt_change_state(self, nominal):
# out physics, but the API should be implemented not to mutate the state
model_path = (
pathlib.Path(__file__).parent.parent.parent
/ "mjpc/tasks/cartpole/task.xml"
/ "build/mjpc/tasks/cartpole/task.xml"
)
model = mujoco.MjModel.from_xml_path(str(model_path))
data = mujoco.MjData(model)
Expand Down Expand Up @@ -161,7 +161,7 @@ def test_action_averaging_improves_control(self):
# expect action averaging to be a bit better
model_path = (
pathlib.Path(__file__).parent.parent.parent
/ "mjpc/tasks/cartpole/task.xml"
/ "build/mjpc/tasks/cartpole/task.xml"
)
model = mujoco.MjModel.from_xml_path(str(model_path))
data = mujoco.MjData(model)
Expand Down Expand Up @@ -213,7 +213,7 @@ def test_stepping_on_agent_side(self):
"""Test an alternative way of stepping the physics, on the agent side."""
model_path = (
pathlib.Path(__file__).parent.parent.parent
/ "mjpc/tasks/cartpole/task.xml"
/ "build/mjpc/tasks/cartpole/task.xml"
)
model = mujoco.MjModel.from_xml_path(str(model_path))
data = mujoco.MjData(model)
Expand Down Expand Up @@ -246,7 +246,7 @@ def test_stepping_on_agent_side(self):
def test_set_cost_weights(self):
model_path = (
pathlib.Path(__file__).parent.parent.parent
/ "mjpc/tasks/cartpole/task.xml"
/ "build/mjpc/tasks/cartpole/task.xml"
)
model = mujoco.MjModel.from_xml_path(str(model_path))

Expand All @@ -271,7 +271,7 @@ def test_set_cost_weights(self):
def test_get_cost_weights(self):
model_path = (
pathlib.Path(__file__).parent.parent.parent
/ "mjpc/tasks/cartpole/task.xml"
/ "build/mjpc/tasks/cartpole/task.xml"
)
model = mujoco.MjModel.from_xml_path(str(model_path))

Expand Down Expand Up @@ -310,7 +310,7 @@ def test_get_cost_weights(self):
def test_set_state_with_lists(self):
model_path = (
pathlib.Path(__file__).parent.parent.parent
/ "mjpc/tasks/particle/task_timevarying.xml"
/ "build/mjpc/tasks/particle/task_timevarying.xml"
)
model = mujoco.MjModel.from_xml_path(str(model_path))
data = mujoco.MjData(model)
Expand All @@ -330,7 +330,7 @@ def test_set_state_with_lists(self):
def test_get_set_default_mode(self):
model_path = (
pathlib.Path(__file__).parent.parent.parent
/ "mjpc/tasks/cartpole/task.xml"
/ "build/mjpc/tasks/cartpole/task.xml"
)
model = mujoco.MjModel.from_xml_path(str(model_path))
with agent_lib.Agent(task_id="Cartpole", model=model) as agent:
Expand All @@ -341,7 +341,7 @@ def test_get_set_default_mode(self):
def test_get_set_mode(self):
model_path = (
pathlib.Path(__file__).parent.parent.parent
/ "mjpc/tasks/quadruped/task_flat.xml"
/ "build/mjpc/tasks/quadruped/task_flat.xml"
)
model = mujoco.MjModel.from_xml_path(str(model_path))
with agent_lib.Agent(task_id="Quadruped Flat", model=model) as agent:
Expand All @@ -352,7 +352,7 @@ def test_get_set_mode(self):
def test_get_all_modes(self):
model_path = (
pathlib.Path(__file__).parent.parent.parent
/ "mjpc/tasks/quadruped/task_flat.xml"
/ "build/mjpc/tasks/quadruped/task_flat.xml"
)
model = mujoco.MjModel.from_xml_path(str(model_path))
with agent_lib.Agent(task_id="Quadruped Flat", model=model) as agent:
Expand All @@ -365,7 +365,7 @@ def test_get_all_modes(self):
def test_set_mode_error(self):
model_path = (
pathlib.Path(__file__).parent.parent.parent
/ "mjpc/tasks/quadruped/task_flat.xml"
/ "build/mjpc/tasks/quadruped/task_flat.xml"
)
model = mujoco.MjModel.from_xml_path(str(model_path))
with agent_lib.Agent(task_id="Quadruped Flat", model=model) as agent:
Expand All @@ -374,7 +374,7 @@ def test_set_mode_error(self):
def test_set_task_parameters_from_another_agent(self):
model_path = (
pathlib.Path(__file__).parent.parent.parent
/ "mjpc/tasks/cartpole/task.xml"
/ "build/mjpc/tasks/cartpole/task.xml"
)
model = mujoco.MjModel.from_xml_path(str(model_path))
with agent_lib.Agent(task_id="Cartpole", model=model) as agent:
Expand All @@ -393,7 +393,7 @@ def test_set_task_parameters_from_another_agent(self):
def test_best_trajectory(self):
model_path = (
pathlib.Path(__file__).parent.parent.parent
/ "mjpc/tasks/particle/task_timevarying.xml"
/ "build/mjpc/tasks/particle/task_timevarying.xml"
)
model = mujoco.MjModel.from_xml_path(str(model_path))
data = mujoco.MjData(model)
Expand All @@ -418,7 +418,7 @@ def test_best_trajectory(self):
def test_set_mocap(self):
model_path = (
pathlib.Path(__file__).parent.parent.parent
/ "mjpc/tasks/particle/task_timevarying.xml"
/ "build/mjpc/tasks/particle/task_timevarying.xml"
)
model = mujoco.MjModel.from_xml_path(str(model_path))
with agent_lib.Agent(task_id="ParticleFixed", model=model) as agent:
Expand Down
18 changes: 10 additions & 8 deletions python/mujoco_mpc/ui_agent_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ def test_stepping_on_agent_side(self):
"""Test an alternative way of stepping the physics, on the agent side."""
model_path = (
pathlib.Path(__file__).parent.parent.parent
/ "mjpc/tasks/cartpole/task.xml"
/ "build/mjpc/tasks/cartpole/task.xml"
)
model = mujoco.MjModel.from_xml_path(str(model_path))
data = mujoco.MjData(model)
Expand All @@ -67,7 +67,9 @@ def test_stepping_on_agent_side(self):
data.qvel = state.qvel
data.act = state.act
data.mocap_pos = np.array(state.mocap_pos).reshape(data.mocap_pos.shape)
data.mocap_quat = np.array(state.mocap_quat).reshape(data.mocap_quat.shape)
data.mocap_quat = np.array(state.mocap_quat).reshape(
data.mocap_quat.shape
)
data.userdata = np.array(state.userdata).reshape(data.userdata.shape)
observations.append(get_observation(model, data))

Expand All @@ -79,7 +81,7 @@ def test_stepping_on_agent_side(self):
def test_set_cost_weights(self):
model_path = (
pathlib.Path(__file__).parent.parent.parent
/ "mjpc/tasks/cartpole/task.xml"
/ "build/mjpc/tasks/cartpole/task.xml"
)
model = mujoco.MjModel.from_xml_path(str(model_path))

Expand Down Expand Up @@ -109,7 +111,7 @@ def test_set_cost_weights(self):
def test_get_cost_weights(self):
model_path = (
pathlib.Path(__file__).parent.parent.parent
/ "mjpc/tasks/cartpole/task.xml"
/ "build/mjpc/tasks/cartpole/task.xml"
)
model = mujoco.MjModel.from_xml_path(str(model_path))

Expand Down Expand Up @@ -141,7 +143,7 @@ def test_get_cost_weights(self):
def test_set_state_with_lists(self):
model_path = (
pathlib.Path(__file__).parent.parent.parent
/ "mjpc/tasks/particle/task_timevarying.xml"
/ "build/mjpc/tasks/particle/task_timevarying.xml"
)
model = mujoco.MjModel.from_xml_path(str(model_path))
data = mujoco.MjData(model)
Expand All @@ -161,7 +163,7 @@ def test_set_state_with_lists(self):
def test_set_get_mode(self):
model_path = (
pathlib.Path(__file__).parent.parent.parent
/ "mjpc/tasks/cartpole/task.xml"
/ "build/mjpc/tasks/cartpole/task.xml"
)
model = mujoco.MjModel.from_xml_path(str(model_path))
with self.get_agent(task_id="Cartpole", model=model) as agent:
Expand All @@ -184,7 +186,7 @@ def test_get_all_modes(self):
def test_get_set_mode(self):
model_path = (
pathlib.Path(__file__).parent.parent.parent
/ "mjpc/tasks/quadruped/task_flat.xml"
/ "build/mjpc/tasks/quadruped/task_flat.xml"
)
model = mujoco.MjModel.from_xml_path(str(model_path))
with self.get_agent(task_id="Quadruped Flat", model=model) as agent:
Expand All @@ -195,7 +197,7 @@ def test_get_set_mode(self):
def test_set_mode_error(self):
model_path = (
pathlib.Path(__file__).parent.parent.parent
/ "mjpc/tasks/quadruped/task_flat.xml"
/ "build/mjpc/tasks/quadruped/task_flat.xml"
)
model = mujoco.MjModel.from_xml_path(str(model_path))
with self.get_agent(task_id="Quadruped Flat", model=model) as agent:
Expand Down
3 changes: 2 additions & 1 deletion python/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -149,7 +149,8 @@ def finalize_options(self):
self.set_undefined_options("build_ext", ("build_lib", "build_lib"))

def run(self):
mjpc_tasks_path = Path(__file__).parent.parent / "mjpc" / "tasks"
mjpc_tasks_path = Path(__file__).parent.parent / "build" / "mjpc" / "tasks"
assert mjpc_tasks_path.exists(), "Build MJPC before installing Python API"
source_paths = (
tuple(mjpc_tasks_path.rglob("*.xml"))
+ tuple(mjpc_tasks_path.rglob("*.png"))
Expand Down

0 comments on commit ed9e635

Please sign in to comment.