Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ else()
include(FetchContent)

# Detect architecture
set(MUJOCO_VERSION "3.3.4")
set(MUJOCO_VERSION "3.4.0")
if(CMAKE_SYSTEM_PROCESSOR MATCHES "x86_64|AMD64")
set(CPU_ARCH "x86_64")
elseif(CMAKE_SYSTEM_PROCESSOR MATCHES "aarch64|arm64")
Expand Down
10 changes: 5 additions & 5 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,16 +1,16 @@
# MuJoCo ros2_control Simulation

This package contains a ros2_control system interface for the [MuJoCo Simulator](https://mujoco.readthedocs.io/en/3.3.4/overview.html).
This package contains a ros2_control system interface for the [MuJoCo Simulator](https://mujoco.readthedocs.io/en/3.4.0/overview.html).
It was originally written for simulating robot hardware in NASA Johnson's [iMETRO facility](https://ntrs.nasa.gov/citations/20230015485).

The system interface wraps MuJoCo's [Simulate App](https://github.com/google-deepmind/mujoco/tree/3.3.4/simulate) to provide included functionality.
The system interface wraps MuJoCo's [Simulate App](https://github.com/google-deepmind/mujoco/tree/3.4.0/simulate) to provide included functionality.
Because the app is not bundled as a library, we compile it directly from a local install of MuJoCo.

Parts of this library are also based on the MoveIt [mujoco_ros2_control](https://github.com/moveit/mujoco_ros2_control) package.

## Installation

This interface has only been tested against ROS 2 jazzy and MuJoCo `3.3.4`.
This interface has only been tested against ROS 2 jazzy and MuJoCo `3.4.0`.
It should also be compatible with kilted and rolling, but we do not actively maintain those.
We assume all required ROS dependencies have been installed either manually or with `rosdep`.

Expand All @@ -21,10 +21,10 @@ However, a local install of MuJoCo can be used to build the application by setti

```bash
# The tested version
MUJOCO_VERSION=3.3.4
MUJOCO_VERSION=3.4.0

# Wherever it was installed and extracted on your machine
MUJOCO_INSTALL_DIR=/opt/mujoco/mujoco-3.3.4
MUJOCO_INSTALL_DIR=/opt/mujoco/mujoco-3.4.0
```

From there the library can be compiled with `colcon build ...`, as normal.
Expand Down
2 changes: 1 addition & 1 deletion docker/Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ FROM ros:${ROS_DISTRO} AS mujoco_ros
SHELL ["/bin/bash", "-o", "pipefail", "-c"]

# Defaults for the MuJoCo install, CPU_ARCH may be set to aarch64 for arm cpus
ARG MUJOCO_VERSION=3.3.4
ARG MUJOCO_VERSION=3.4.0
ARG CPU_ARCH=x86_64

ARG DEBIAN_FRONTEND=noninteractive
Expand Down
4 changes: 2 additions & 2 deletions pixi.toml
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ LDFLAGS = "-L${CONDA_PREFIX}/lib -Wl,-rpath,${CONDA_PREFIX}/lib"
CXXFLAGS = "-fuse-ld=mold"

# The default location for mujoco
MUJOCO_DIR="${PIXI_PROJECT_ROOT}/mujoco/mujoco-3.3.4"
MUJOCO_DIR="${PIXI_PROJECT_ROOT}/mujoco/mujoco-3.4.0"

[tasks]
# Setup tasks
Expand Down Expand Up @@ -63,4 +63,4 @@ ros-jazzy-rviz2 = "*"
[pypi-dependencies]
xacro = ">=2.1.1, <3"
obj2mjcf = ">=0.0.25"
mujoco = "==3.3.4"
mujoco = "==3.4.0"
2 changes: 1 addition & 1 deletion src/mujoco_cameras.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -225,7 +225,7 @@ void MujocoCameras::update()
for (auto& camera : cameras_)
{
// Fix non-linear projections in the depth image and flip the data.
// https://github.com/google-deepmind/mujoco/blob/3.3.4/python/mujoco/renderer.py#L190
// https://github.com/google-deepmind/mujoco/blob/3.4.0/python/mujoco/renderer.py#L190
for (uint32_t h = 0; h < camera.height; h++)
{
for (uint32_t w = 0; w < camera.width; w++)
Expand Down
9 changes: 8 additions & 1 deletion src/mujoco_system_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1721,8 +1721,15 @@ void MujocoSystemInterface::PhysicsLoop()
sim_->measured_slowdown = std::chrono::duration<double>(elapsedCPU).count() / elapsedSim;
measured = true;
}
// inject noise
// inject noise
// Use mjVERSION_HEADER and if it is greater than 337 then do one thing or another
// Needed due to
// https://github.com/google-deepmind/mujoco/commit/401bf431b8b0fe6e0a619412a607b5135dc4ded4#diff-3dc22ceeebd71304c41d349c6d273bda172ea88ff49c772dbdcf51b9b19bbd33R2943
#if mjVERSION_HEADER < 337
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Forgive my ignorance here, should we just enforce that the header version match exactly what we expect in the CMakeLists.txt file? Would that make this conditional go away?

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Sure, but this allows people to go back to the older version and they don't have to touch the code to know what to fix. So, I would say it is better to have it handled also in the code

sim_->InjectNoise();
#else
sim_->InjectNoise(-1);
#endif

// Copy data to the control
mju_copy(mj_data_->ctrl, mj_data_control_->ctrl, mj_model_->nu);
Expand Down
Loading